rtt_rostopic_ros_msg_transporter.hpp
Go to the documentation of this file.
1 /***************************************************************************
2  tag: Ruben Smits Tue Nov 16 09:18:49 CET 2010 ros_msg_transporter.hpp
3 
4  ros_msg_transporter.hpp - description
5  -------------------
6  begin : Tue November 16 2010
7  copyright : (C) 2010 Ruben Smits
8  email : first.last@mech.kuleuven.be
9 
10  ***************************************************************************
11  * This library is free software; you can redistribute it and/or *
12  * modify it under the terms of the GNU Lesser General Public *
13  * License as published by the Free Software Foundation; either *
14  * version 2.1 of the License, or (at your option) any later version. *
15  * *
16  * This library is distributed in the hope that it will be useful, *
17  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
18  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU *
19  * Lesser General Public License for more details. *
20  * *
21  * You should have received a copy of the GNU Lesser General Public *
22  * License along with this library; if not, write to the Free Software *
23  * Foundation, Inc., 59 Temple Place, *
24  * Suite 330, Boston, MA 02111-1307 USA *
25  * *
26  ***************************************************************************/
27 
28 
29 // Copyright (C) 2010 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
30 
31 // Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
32 // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
33 
34 // This library is free software; you can redistribute it and/or
35 // modify it under the terms of the GNU Lesser General Public
36 // License as published by the Free Software Foundation; either
37 // version 2.1 of the License, or (at your option) any later version.
38 
39 // This library is distributed in the hope that it will be useful,
40 // but WITHOUT ANY WARRANTY; without even the implied warranty of
41 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
42 // Lesser General Public License for more details.
43 
44 // You should have received a copy of the GNU Lesser General Public
45 // License along with this library; if not, write to the Free Software
46 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
47 
48 
49 #ifndef __RTT_ROSCOMM_ROS_MSG_TRANSPORTER_HPP_
50 #define __RTT_ROSCOMM_ROS_MSG_TRANSPORTER_HPP_
51 
52 #include <rtt/rtt-config.h>
54 #include <rtt/Port.hpp>
55 #include <rtt/TaskContext.hpp>
57 #include <ros/ros.h>
58 
60 
61 #ifndef RTT_VERSION_GTE
62  #define RTT_VERSION_GTE(major,minor,patch) \
63  ((RTT_VERSION_MAJOR > major) || (RTT_VERSION_MAJOR == major && \
64  (RTT_VERSION_MINOR > minor) || (RTT_VERSION_MINOR == minor && \
65  (RTT_VERSION_PATCH >= patch))))
66 #endif
67 
68 namespace rtt_roscomm {
69 
74  template <typename T>
76  {
77  typedef T OrocosType;
78  typedef T RosType;
79  static const RosType &toRos(const OrocosType &t) { return t; }
80  static const OrocosType &fromRos(const RosType &t) { return t; }
81  };
82 
86  template<typename T>
88  {
90  typedef typename adapter::RosType RosType;
91 
92  char hostname[1024];
93  std::string topicname;
99 
101 
102  public:
103 
115  ros_node(),
116  ros_node_private("~")
117  {
118  if ( policy.name_id.empty() ){
119  std::stringstream namestr;
120  gethostname(hostname, sizeof(hostname));
121 
122  if (port->getInterface() && port->getInterface()->getOwner()) {
123  namestr << hostname<<'/' << port->getInterface()->getOwner()->getName()
124  << '/' << port->getName() << '/'<<this << '/' << getpid();
125  } else {
126  namestr << hostname<<'/' << port->getName() << '/'<<this << '/' << getpid();
127  }
128  policy.name_id = namestr.str();
129  }
130  topicname=policy.name_id;
131  RTT::Logger::In in(topicname);
132 
133  if (port->getInterface() && port->getInterface()->getOwner()) {
134  RTT::log(RTT::Debug)<<"Creating ROS publisher for port "<<port->getInterface()->getOwner()->getName()<<"."<<port->getName()<<" on topic "<<policy.name_id<<RTT::endlog();
135  } else {
136  RTT::log(RTT::Debug)<<"Creating ROS publisher for port "<<port->getName()<<" on topic "<<policy.name_id<<RTT::endlog();
137  }
138 
139  // Handle private names
140  if(topicname.length() > 1 && topicname.at(0) == '~') {
141  ros_pub = ros_node_private.advertise<RosType>(policy.name_id.substr(1), policy.size > 0 ? policy.size : 1, policy.init); // minimum 1
142  } else {
143  ros_pub = ros_node.advertise<RosType>(policy.name_id, policy.size > 0 ? policy.size : 1, policy.init); // minimum 1
144  }
146  act->addPublisher( this );
147  }
148 
150  RTT::Logger::In in(topicname);
151 // RTT::log(RTT::Debug) << "Destroying RosPubChannelElement" << RTT::endlog();
152  act->removePublisher( this );
153  }
154 
160  virtual bool inputReady() {
161  return true;
162  }
163 
164  virtual bool isRemoteElement() const {
165  return true;
166  }
167 
168  virtual std::string getElementName() const {
169  return "RosPubChannelElement";
170  }
171 
172  virtual std::string getRemoteURI() const {
173  return ros_pub.getTopic();
174  }
175 
183 #if RTT_VERSION_GTE(2,8,99)
184  virtual RTT::WriteStatus data_sample(typename RTT::base::ChannelElement<T>::param_t sample)
185  {
186  this->sample = sample;
187  return RTT::WriteSuccess;
188  }
189 #else
191  {
192  this->sample = sample;
193  return true;
194  }
195 #endif
196 
202  bool signal(){
203  //RTT::Logger::In in(topicname);
204  //RTT::log(RTT::Debug) << "Requesting publish" << RTT::endlog();
205  return act->trigger();
206  }
207 
208  void publish(){
209  // this read should always succeed since signal() means 'data available in a data element'.
210  typename RTT::base::ChannelElement<T>::shared_ptr input = this->getInput();
211  while( input && (input->read(sample,false) == RTT::NewData) )
212  write(sample);
213  }
214 
215 #if RTT_VERSION_GTE(2,8,99)
217 #else
219 #endif
220  {
221  ros_pub.publish(adapter::toRos(sample));
222 #if RTT_VERSION_GTE(2,8,99)
223  return RTT::WriteSuccess;
224 #else
225  return true;
226 #endif
227  }
228 
229  };
230 
234  template<typename T>
236  {
238  typedef typename adapter::RosType RosType;
239 
240  std::string topicname;
244 
245  public:
256  ros_node(),
257  ros_node_private("~")
258  {
259  topicname=policy.name_id;
260  RTT::Logger::In in(topicname);
261  if (port->getInterface() && port->getInterface()->getOwner()) {
262  RTT::log(RTT::Debug)<<"Creating ROS subscriber for port "<<port->getInterface()->getOwner()->getName()<<"."<<port->getName()<<" on topic "<<policy.name_id<<RTT::endlog();
263  } else {
264  RTT::log(RTT::Debug)<<"Creating ROS subscriber for port "<<port->getName()<<" on topic "<<policy.name_id<<RTT::endlog();
265  }
266  if(topicname.length() > 1 && topicname.at(0) == '~') {
267  ros_sub = ros_node_private.subscribe(policy.name_id.substr(1), policy.size > 0 ? policy.size : 1, &RosSubChannelElement::newData, this); // minimum queue_size 1
268  } else {
269  ros_sub = ros_node.subscribe(policy.name_id, policy.size > 0 ? policy.size : 1, &RosSubChannelElement::newData, this); // minimum queue_size 1
270  }
271  }
272 
274  RTT::Logger::In in(topicname);
275 // RTT::log(RTT::Debug)<<"Destroying RosSubChannelElement"<<RTT::endlog();
276  }
277 
278  virtual bool inputReady() {
279  return true;
280  }
281 
282  virtual bool isRemoteElement() const {
283  return true;
284  }
285 
286  virtual std::string getElementName() const {
287  return "RosSubChannelElement";
288  }
289 
290  virtual std::string getRemoteURI() const {
291  return ros_sub.getTopic();
292  }
293 
299  void newData(const RosType& msg){
300  typename RTT::base::ChannelElement<T>::shared_ptr output = this->getOutput();
301  if (output)
302  output->write(adapter::fromRos(msg));
303  }
304  };
305 
306  template <class T>
308  {
311 
312  // Pull semantics are not supported by the ROS message transport.
313  if (policy.pull) {
314  RTT::log(RTT::Error) << "Pull connections are not supported by the ROS message transport." << RTT::endlog();
316  }
317 
318  // Check if this node is initialized
319  if (!ros::ok()) {
320  RTT::log(RTT::Error) << "Cannot create ROS message transport because the node is not initialized or already shutting down. Did you import package rtt_rosnode before?" << RTT::endlog();
322  }
323 
324  if (is_sender){
325  channel = new RosPubChannelElement<T>(port, policy);
326 
327  if (policy.type == RTT::ConnPolicy::UNBUFFERED){
328  RTT::log(RTT::Debug) << "Creating unbuffered publisher connection for port " << port->getName() << ". This may not be real-time safe!" << RTT::endlog();
329  return channel;
330  }
331 
332  RTT::base::ChannelElementBase::shared_ptr buf = RTT::internal::ConnFactory::buildDataStorage<T>(policy);
334 #if RTT_VERSION_GTE(2,8,99)
335  buf->connectTo(channel);
336 #else
337  buf->setOutput(channel);
338 #endif
339  return buf;
340 
341  } else {
342  channel = new RosSubChannelElement<T>(port, policy);
343 
344 #if !RTT_VERSION_GTE(2,8,99)
345  RTT::base::ChannelElementBase::shared_ptr buf = RTT::internal::ConnFactory::buildDataStorage<T>(policy);
347  channel->setOutput(buf);
348 #endif
349  }
350 
351  return channel;
352  }
353  };
354 }
355 #endif
boost::call_traits< T >::param_type param_t
boost::intrusive_ptr< ChannelElement< T > > shared_ptr
void publish(const boost::shared_ptr< M > &message) const
WriteSuccess
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
const std::string & getName() const
static const OrocosType & fromRos(const RosType &t)
RTT::base::ChannelElement< T >::value_t sample
RosPubChannelElement(RTT::base::PortInterface *port, const RTT::ConnPolicy &policy)
bool write(typename RTT::base::ChannelElement< T >::param_t sample)
DataFlowInterface * getInterface() const
RosPublishActivity::shared_ptr act
We must cache the RosPublishActivity object.
virtual RTT::base::ChannelElementBase::shared_ptr createStream(RTT::base::PortInterface *port, const RTT::ConnPolicy &policy, bool is_sender) const
std::string getTopic() const
ROSCPP_DECL bool ok()
static const RosType & toRos(const OrocosType &t)
virtual FlowStatus read(reference_t sample, bool copy_old_data=true)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
RosSubChannelElement(RTT::base::PortInterface *port, const RTT::ConnPolicy &policy)
boost::intrusive_ptr< ChannelElementBase > shared_ptr
virtual bool data_sample(typename RTT::base::ChannelElement< T >::param_t sample)
virtual WriteStatus write(param_t sample)
std::string getTopic() const
std::string name_id
static Logger & log()
static Logger::LogFunction endlog()
WriteStatus
static const int UNBUFFERED
virtual const std::string & getName() const
TaskContext * getOwner() const


rtt_roscomm
Author(s): Ruben Smits, Jonathan Bohren
autogenerated on Sat Jun 8 2019 18:05:17