#include <rtt_rostopic_ros_msg_transporter.hpp>
Public Member Functions | |
virtual bool | inputReady () |
void | newData (const RosType &msg) |
RosSubChannelElement (RTT::base::PortInterface *port, const RTT::ConnPolicy &policy) | |
~RosSubChannelElement () | |
Private Types | |
typedef RosMessageAdapter< T > | adapter |
typedef adapter::RosType | RosType |
Private Attributes | |
ros::NodeHandle | ros_node |
ros::NodeHandle | ros_node_private |
ros::Subscriber | ros_sub |
std::string | topicname |
A ChannelElement implementation to subscribe to data over a ros topic
Definition at line 223 of file rtt_rostopic_ros_msg_transporter.hpp.
typedef RosMessageAdapter<T> rtt_roscomm::RosSubChannelElement< T >::adapter [private] |
Definition at line 225 of file rtt_rostopic_ros_msg_transporter.hpp.
typedef adapter::RosType rtt_roscomm::RosSubChannelElement< T >::RosType [private] |
Definition at line 226 of file rtt_rostopic_ros_msg_transporter.hpp.
rtt_roscomm::RosSubChannelElement< T >::RosSubChannelElement | ( | RTT::base::PortInterface * | port, |
const RTT::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 243 of file rtt_rostopic_ros_msg_transporter.hpp.
rtt_roscomm::RosSubChannelElement< T >::~RosSubChannelElement | ( | ) | [inline] |
Definition at line 261 of file rtt_rostopic_ros_msg_transporter.hpp.
virtual bool rtt_roscomm::RosSubChannelElement< T >::inputReady | ( | ) | [inline, virtual] |
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 266 of file rtt_rostopic_ros_msg_transporter.hpp.
void rtt_roscomm::RosSubChannelElement< T >::newData | ( | const RosType & | msg | ) | [inline] |
Callback function for the ROS subscriber, it will trigger the ChannelElement's signal function
msg | The received message |
Definition at line 275 of file rtt_rostopic_ros_msg_transporter.hpp.
ros::NodeHandle rtt_roscomm::RosSubChannelElement< T >::ros_node [private] |
Definition at line 229 of file rtt_rostopic_ros_msg_transporter.hpp.
ros::NodeHandle rtt_roscomm::RosSubChannelElement< T >::ros_node_private [private] |
Definition at line 230 of file rtt_rostopic_ros_msg_transporter.hpp.
ros::Subscriber rtt_roscomm::RosSubChannelElement< T >::ros_sub [private] |
Definition at line 231 of file rtt_rostopic_ros_msg_transporter.hpp.
std::string rtt_roscomm::RosSubChannelElement< T >::topicname [private] |
Definition at line 228 of file rtt_rostopic_ros_msg_transporter.hpp.