rosinterface.cpp 6.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280
  1. /*
  2. * Copyright 2015-2019 Autoware Foundation. All rights reserved.
  3. *
  4. * Licensed under the Apache License, Version 2.0 (the "License");
  5. * you may not use this file except in compliance with the License.
  6. * You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. *
  10. * Unless required by applicable law or agreed to in writing, software
  11. * distributed under the License is distributed on an "AS IS" BASIS,
  12. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. * See the License for the specific language governing permissions and
  14. * limitations under the License.
  15. */
  16. #include "rosinterface/rosinterface.h"
  17. //using namespace RobotSDK;
  18. bool ROSInterfaceBase::initflag=0;
  19. ROSInterfaceBase::ROSInterfaceBase(QObject *parent)
  20. : QObject(parent)
  21. {
  22. if(!initflag)
  23. {
  24. QStringList arguments=QApplication::instance()->arguments();
  25. int argc=1;
  26. QString NodeName;
  27. if(arguments.size()>1)
  28. {
  29. NodeName=arguments[1];
  30. }
  31. else
  32. {
  33. NodeName=QFileInfo(arguments[0]).baseName();
  34. }
  35. char *argv=NodeName.toUtf8().data();
  36. ros::init(argc,&argv,NodeName.toStdString());
  37. initflag=1;
  38. }
  39. nh=new ros::NodeHandle;
  40. }
  41. ROSInterfaceBase::~ROSInterfaceBase()
  42. {
  43. if(nh!=NULL)
  44. {
  45. if(nh->ok())
  46. {
  47. nh->shutdown();
  48. }
  49. delete nh;
  50. nh=NULL;
  51. }
  52. }
  53. ROSSubBase::ROSSubBase(int QueryInterval, QObject *parent)
  54. : ROSInterfaceBase(parent)
  55. {
  56. nh->setCallbackQueue(&queue);
  57. timer=new QTimer(this);
  58. timer->setInterval(QueryInterval);
  59. connect(timer,SIGNAL(timeout()),this,SLOT(receiveMessageSlot()));
  60. connect(this,SIGNAL(startReceiveSignal()),timer,SLOT(start()));
  61. connect(this,SIGNAL(stopReceiveSignal()),timer,SLOT(stop()));
  62. connect(this,SIGNAL(resetQueryIntervalSignal(int)),timer,SLOT(start(int)));
  63. receiveflag=0;
  64. emit startReceiveSignal();
  65. }
  66. ROSSubBase::~ROSSubBase()
  67. {
  68. receiveflag=0;
  69. emit stopReceiveSignal();
  70. disconnect(timer,SIGNAL(timeout()),this,SLOT(receiveMessageSlot()));
  71. disconnect(this,SIGNAL(startReceiveSignal()),timer,SLOT(start()));
  72. disconnect(this,SIGNAL(stopReceiveSignal()),timer,SLOT(stop()));
  73. delete timer;
  74. }
  75. void ROSSubBase::startReceiveSlot()
  76. {
  77. lock.lockForWrite();
  78. receiveflag=1;
  79. clearMessage();
  80. lock.unlock();
  81. }
  82. void ROSSubBase::stopReceiveSlot()
  83. {
  84. lock.lockForWrite();
  85. receiveflag=0;
  86. lock.unlock();
  87. }
  88. void ROSSubBase::receiveMessageSlot()
  89. {
  90. if(ros::ok()&&nh->ok())
  91. {
  92. receiveMessage(queue.callOne(ros::WallDuration(0)));
  93. }
  94. }
  95. void ROSSubBase::receiveMessage(ros::CallbackQueue::CallOneResult result)
  96. {
  97. if(receiveflag)
  98. {
  99. switch(result)
  100. {
  101. case ros::CallbackQueue::Called:
  102. emit receiveMessageSignal();
  103. break;
  104. case ros::CallbackQueue::TryAgain:
  105. case ros::CallbackQueue::Disabled:
  106. case ros::CallbackQueue::Empty:
  107. default:
  108. break;
  109. }
  110. }
  111. return;
  112. }
  113. ROSTFPub::ROSTFPub(QString childFrameID, QString frameID, QObject *parent)
  114. : ROSInterfaceBase(parent)
  115. {
  116. childframeid=childFrameID;
  117. frameid=frameID;
  118. }
  119. bool ROSTFPub::sendTF(tf::Transform &transform)
  120. {
  121. br.sendTransform(tf::StampedTransform(transform,ros::Time::now(),frameid.toStdString(),childframeid.toStdString()));
  122. return 1;
  123. }
  124. QString ROSTFPub::getChildFrameID()
  125. {
  126. return childframeid;
  127. }
  128. void ROSTFPub::resetChildFrameID(QString childFrameID)
  129. {
  130. childframeid=childFrameID;
  131. }
  132. QString ROSTFPub::getFrameID()
  133. {
  134. return frameid;
  135. }
  136. void ROSTFPub::resetFrameID(QString frameID)
  137. {
  138. frameid=frameID;
  139. }
  140. ROSTFSub::ROSTFSub(QString destinationFrame, QString originalFrame, int QueryInterval, QObject *parent)
  141. : ROSInterfaceBase(parent)
  142. {
  143. destinationframe=destinationFrame;
  144. originalframe=originalFrame;
  145. timer=new QTimer(this);
  146. timer->setInterval(QueryInterval);
  147. connect(timer,SIGNAL(timeout()),this,SLOT(receiveTFSlot()));
  148. connect(this,SIGNAL(startReceiveSignal()),timer,SLOT(start()));
  149. connect(this,SIGNAL(stopReceiveSignal()),timer,SLOT(stop()));
  150. connect(this,SIGNAL(resetQueryIntervalSignal(int)),timer,SLOT(start(int)));
  151. receiveflag=0;
  152. lastflag=0;
  153. emit startReceiveSignal();
  154. }
  155. ROSTFSub::~ROSTFSub()
  156. {
  157. receiveflag=0;
  158. lastflag=0;
  159. emit stopReceiveSignal();
  160. disconnect(timer,SIGNAL(timeout()),this,SLOT(receiveTFSlot()));
  161. disconnect(this,SIGNAL(startReceiveSignal()),timer,SLOT(start()));
  162. disconnect(this,SIGNAL(stopReceiveSignal()),timer,SLOT(stop()));
  163. delete timer;
  164. }
  165. void ROSTFSub::startReceiveSlot()
  166. {
  167. lock.lockForWrite();
  168. receiveflag=1;
  169. lastflag=0;
  170. clearTFs();
  171. lock.unlock();
  172. }
  173. void ROSTFSub::stopReceiveSlot()
  174. {
  175. lock.lockForWrite();
  176. receiveflag=0;
  177. lastflag=0;
  178. lock.unlock();
  179. }
  180. void ROSTFSub::receiveTFSlot()
  181. {
  182. if(ros::ok()&&receiveflag)
  183. {
  184. lock.lockForWrite();
  185. tf::StampedTransform transform;
  186. try
  187. {
  188. listener.lookupTransform(destinationframe.toStdString(),originalframe.toStdString(),ros::Time(0),transform);
  189. }
  190. catch(tf::TransformException & ex)
  191. {
  192. //qDebug()<<QString(ex.what());
  193. lock.unlock();
  194. return;
  195. }
  196. if(!lastflag||lasttf.stamp_.sec!=transform.stamp_.sec||lasttf.stamp_.nsec!=transform.stamp_.nsec)
  197. {
  198. tfs.push_back(transform);
  199. lasttf=transform;
  200. lastflag=1;
  201. lock.unlock();
  202. emit receiveTFSignal();
  203. }
  204. else
  205. {
  206. lock.unlock();
  207. }
  208. }
  209. }
  210. void ROSTFSub::clearTFs()
  211. {
  212. tfs.clear();
  213. }
  214. bool ROSTFSub::getTF(tf::StampedTransform & transform)
  215. {
  216. lock.lockForWrite();
  217. bool flag=0;
  218. if(receiveflag&&!tfs.isEmpty())
  219. {
  220. transform=tfs.front();
  221. tfs.pop_front();
  222. flag=1;
  223. }
  224. lock.unlock();
  225. return flag;
  226. }
  227. QString ROSTFSub::getDestinationFrame()
  228. {
  229. return destinationframe;
  230. }
  231. void ROSTFSub::resetDestinationFrame(QString destinationFrame)
  232. {
  233. lock.lockForWrite();
  234. destinationframe=destinationFrame;
  235. lock.unlock();
  236. }
  237. QString ROSTFSub::getOriginalFrame()
  238. {
  239. return originalframe;
  240. }
  241. void ROSTFSub::resetOriginalFrame(QString orignalFrame)
  242. {
  243. lock.lockForWrite();
  244. originalframe=orignalFrame;
  245. lock.unlock();
  246. }
  247. void ROSTFSub::resetQueryInterval(int QueryInterval)
  248. {
  249. emit resetQueryIntervalSignal(QueryInterval);
  250. }