123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280 |
- /*
- * Copyright 2015-2019 Autoware Foundation. All rights reserved.
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
- #include "rosinterface/rosinterface.h"
- //using namespace RobotSDK;
- bool ROSInterfaceBase::initflag=0;
- ROSInterfaceBase::ROSInterfaceBase(QObject *parent)
- : QObject(parent)
- {
- if(!initflag)
- {
- QStringList arguments=QApplication::instance()->arguments();
- int argc=1;
- QString NodeName;
- if(arguments.size()>1)
- {
- NodeName=arguments[1];
- }
- else
- {
- NodeName=QFileInfo(arguments[0]).baseName();
- }
- char *argv=NodeName.toUtf8().data();
- ros::init(argc,&argv,NodeName.toStdString());
- initflag=1;
- }
- nh=new ros::NodeHandle;
- }
- ROSInterfaceBase::~ROSInterfaceBase()
- {
- if(nh!=NULL)
- {
- if(nh->ok())
- {
- nh->shutdown();
- }
- delete nh;
- nh=NULL;
- }
- }
- ROSSubBase::ROSSubBase(int QueryInterval, QObject *parent)
- : ROSInterfaceBase(parent)
- {
- nh->setCallbackQueue(&queue);
- timer=new QTimer(this);
- timer->setInterval(QueryInterval);
- connect(timer,SIGNAL(timeout()),this,SLOT(receiveMessageSlot()));
- connect(this,SIGNAL(startReceiveSignal()),timer,SLOT(start()));
- connect(this,SIGNAL(stopReceiveSignal()),timer,SLOT(stop()));
- connect(this,SIGNAL(resetQueryIntervalSignal(int)),timer,SLOT(start(int)));
- receiveflag=0;
- emit startReceiveSignal();
- }
- ROSSubBase::~ROSSubBase()
- {
- receiveflag=0;
- emit stopReceiveSignal();
- disconnect(timer,SIGNAL(timeout()),this,SLOT(receiveMessageSlot()));
- disconnect(this,SIGNAL(startReceiveSignal()),timer,SLOT(start()));
- disconnect(this,SIGNAL(stopReceiveSignal()),timer,SLOT(stop()));
- delete timer;
- }
- void ROSSubBase::startReceiveSlot()
- {
- lock.lockForWrite();
- receiveflag=1;
- clearMessage();
- lock.unlock();
- }
- void ROSSubBase::stopReceiveSlot()
- {
- lock.lockForWrite();
- receiveflag=0;
- lock.unlock();
- }
- void ROSSubBase::receiveMessageSlot()
- {
- if(ros::ok()&&nh->ok())
- {
- receiveMessage(queue.callOne(ros::WallDuration(0)));
- }
- }
- void ROSSubBase::receiveMessage(ros::CallbackQueue::CallOneResult result)
- {
- if(receiveflag)
- {
- switch(result)
- {
- case ros::CallbackQueue::Called:
- emit receiveMessageSignal();
- break;
- case ros::CallbackQueue::TryAgain:
- case ros::CallbackQueue::Disabled:
- case ros::CallbackQueue::Empty:
- default:
- break;
- }
- }
- return;
- }
- ROSTFPub::ROSTFPub(QString childFrameID, QString frameID, QObject *parent)
- : ROSInterfaceBase(parent)
- {
- childframeid=childFrameID;
- frameid=frameID;
- }
- bool ROSTFPub::sendTF(tf::Transform &transform)
- {
- br.sendTransform(tf::StampedTransform(transform,ros::Time::now(),frameid.toStdString(),childframeid.toStdString()));
- return 1;
- }
- QString ROSTFPub::getChildFrameID()
- {
- return childframeid;
- }
- void ROSTFPub::resetChildFrameID(QString childFrameID)
- {
- childframeid=childFrameID;
- }
- QString ROSTFPub::getFrameID()
- {
- return frameid;
- }
- void ROSTFPub::resetFrameID(QString frameID)
- {
- frameid=frameID;
- }
- ROSTFSub::ROSTFSub(QString destinationFrame, QString originalFrame, int QueryInterval, QObject *parent)
- : ROSInterfaceBase(parent)
- {
- destinationframe=destinationFrame;
- originalframe=originalFrame;
- timer=new QTimer(this);
- timer->setInterval(QueryInterval);
- connect(timer,SIGNAL(timeout()),this,SLOT(receiveTFSlot()));
- connect(this,SIGNAL(startReceiveSignal()),timer,SLOT(start()));
- connect(this,SIGNAL(stopReceiveSignal()),timer,SLOT(stop()));
- connect(this,SIGNAL(resetQueryIntervalSignal(int)),timer,SLOT(start(int)));
- receiveflag=0;
- lastflag=0;
- emit startReceiveSignal();
- }
- ROSTFSub::~ROSTFSub()
- {
- receiveflag=0;
- lastflag=0;
- emit stopReceiveSignal();
- disconnect(timer,SIGNAL(timeout()),this,SLOT(receiveTFSlot()));
- disconnect(this,SIGNAL(startReceiveSignal()),timer,SLOT(start()));
- disconnect(this,SIGNAL(stopReceiveSignal()),timer,SLOT(stop()));
- delete timer;
- }
- void ROSTFSub::startReceiveSlot()
- {
- lock.lockForWrite();
- receiveflag=1;
- lastflag=0;
- clearTFs();
- lock.unlock();
- }
- void ROSTFSub::stopReceiveSlot()
- {
- lock.lockForWrite();
- receiveflag=0;
- lastflag=0;
- lock.unlock();
- }
- void ROSTFSub::receiveTFSlot()
- {
- if(ros::ok()&&receiveflag)
- {
- lock.lockForWrite();
- tf::StampedTransform transform;
- try
- {
- listener.lookupTransform(destinationframe.toStdString(),originalframe.toStdString(),ros::Time(0),transform);
- }
- catch(tf::TransformException & ex)
- {
- //qDebug()<<QString(ex.what());
- lock.unlock();
- return;
- }
- if(!lastflag||lasttf.stamp_.sec!=transform.stamp_.sec||lasttf.stamp_.nsec!=transform.stamp_.nsec)
- {
- tfs.push_back(transform);
- lasttf=transform;
- lastflag=1;
- lock.unlock();
- emit receiveTFSignal();
- }
- else
- {
- lock.unlock();
- }
- }
- }
- void ROSTFSub::clearTFs()
- {
- tfs.clear();
- }
- bool ROSTFSub::getTF(tf::StampedTransform & transform)
- {
- lock.lockForWrite();
- bool flag=0;
- if(receiveflag&&!tfs.isEmpty())
- {
- transform=tfs.front();
- tfs.pop_front();
- flag=1;
- }
- lock.unlock();
- return flag;
- }
- QString ROSTFSub::getDestinationFrame()
- {
- return destinationframe;
- }
- void ROSTFSub::resetDestinationFrame(QString destinationFrame)
- {
- lock.lockForWrite();
- destinationframe=destinationFrame;
- lock.unlock();
- }
- QString ROSTFSub::getOriginalFrame()
- {
- return originalframe;
- }
- void ROSTFSub::resetOriginalFrame(QString orignalFrame)
- {
- lock.lockForWrite();
- originalframe=orignalFrame;
- lock.unlock();
- }
- void ROSTFSub::resetQueryInterval(int QueryInterval)
- {
- emit resetQueryIntervalSignal(QueryInterval);
- }
|