#include <ros_msg_transporter.hpp>
Public Member Functions | |
virtual bool | inputReady () |
void | newData (const T &msg) |
RosSubChannelElement (base::PortInterface *port, const ConnPolicy &policy) | |
~RosSubChannelElement () | |
Private Attributes | |
ros::NodeHandle | ros_node |
ros::Subscriber | ros_sub |
Definition at line 176 of file ros_msg_transporter.hpp.
ros_integration::RosSubChannelElement< T >::RosSubChannelElement | ( | base::PortInterface * | port, |
const ConnPolicy & | policy | ||
) | [inline] |
Contructor of to create ROS subscriber ChannelElement, it will subscribe to a topic with the name given by the policy.name_id
port | port for which we will create a the ROS publisher |
policy | connection policy containing the topic name and buffer size |
Definition at line 191 of file ros_msg_transporter.hpp.
ros_integration::RosSubChannelElement< T >::~RosSubChannelElement | ( | ) | [inline] |
Definition at line 202 of file ros_msg_transporter.hpp.
virtual bool ros_integration::RosSubChannelElement< T >::inputReady | ( | ) | [inline, virtual] |
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 205 of file ros_msg_transporter.hpp.
void ros_integration::RosSubChannelElement< T >::newData | ( | const T & | msg | ) | [inline] |
Callback function for the ROS subscriber, it will trigger the ChannelElement's signal function
msg | The received message |
Definition at line 213 of file ros_msg_transporter.hpp.
ros::NodeHandle ros_integration::RosSubChannelElement< T >::ros_node [private] |
Definition at line 178 of file ros_msg_transporter.hpp.
ros::Subscriber ros_integration::RosSubChannelElement< T >::ros_sub [private] |
Definition at line 179 of file ros_msg_transporter.hpp.