#include <ros_msg_transporter.hpp>
Public Member Functions | |
| virtual bool | inputReady () |
| void | newData (const T &msg) |
| FlowStatus | read (typename base::ChannelElement< T >::reference_t sample, bool copy_old_data) |
| RosSubChannelElement (base::PortInterface *port, const ConnPolicy &policy) | |
| ~RosSubChannelElement () | |
Private Attributes | |
| bool | init |
| base::DataObjectLockFree< T > | m_msg |
| bool | newdata |
| ros::NodeHandle | ros_node |
| ros::Subscriber | ros_sub |
Definition at line 157 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 174 of file ros_msg_transporter.hpp.
| ros_integration::RosSubChannelElement< T >::~RosSubChannelElement | ( | ) | [inline] |
Definition at line 182 of file ros_msg_transporter.hpp.
| virtual bool ros_integration::RosSubChannelElement< T >::inputReady | ( | ) | [inline, virtual] |
Definition at line 185 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 193 of file ros_msg_transporter.hpp.
| FlowStatus ros_integration::RosSubChannelElement< T >::read | ( | typename base::ChannelElement< T >::reference_t | sample, | |
| bool | copy_old_data | |||
| ) | [inline] |
function that the port will use to get the received data
| sample | object to put the received data into |
Definition at line 207 of file ros_msg_transporter.hpp.
bool ros_integration::RosSubChannelElement< T >::init [private] |
Definition at line 161 of file ros_msg_transporter.hpp.
base::DataObjectLockFree<T> ros_integration::RosSubChannelElement< T >::m_msg [private] |
Definition at line 162 of file ros_msg_transporter.hpp.
bool ros_integration::RosSubChannelElement< T >::newdata [private] |
Definition at line 161 of file ros_msg_transporter.hpp.
ros::NodeHandle ros_integration::RosSubChannelElement< T >::ros_node [private] |
Definition at line 159 of file ros_msg_transporter.hpp.
ros::Subscriber ros_integration::RosSubChannelElement< T >::ros_sub [private] |
Definition at line 160 of file ros_msg_transporter.hpp.