ros_integration::RosSubChannelElement< T > Class Template Reference

#include <ros_msg_transporter.hpp>

List of all members.

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

Detailed Description

template<typename T>
class ros_integration::RosSubChannelElement< T >

Definition at line 157 of file ros_msg_transporter.hpp.


Constructor & Destructor Documentation

template<typename T>
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

Parameters:
port port for which we will create a the ROS publisher
policy connection policy containing the topic name and buffer size
Returns:
ChannelElement that will publish data to topics

Definition at line 174 of file ros_msg_transporter.hpp.

template<typename T>
ros_integration::RosSubChannelElement< T >::~RosSubChannelElement (  )  [inline]

Definition at line 182 of file ros_msg_transporter.hpp.


Member Function Documentation

template<typename T>
virtual bool ros_integration::RosSubChannelElement< T >::inputReady (  )  [inline, virtual]

Definition at line 185 of file ros_msg_transporter.hpp.

template<typename T>
void ros_integration::RosSubChannelElement< T >::newData ( const T &  msg  )  [inline]

Callback function for the ROS subscriber, it will trigger the ChannelElement's signal function

Parameters:
msg The received message

Definition at line 193 of file ros_msg_transporter.hpp.

template<typename T>
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

Parameters:
sample object to put the received data into
Returns:
FlowStatus for the port

Definition at line 207 of file ros_msg_transporter.hpp.


Member Data Documentation

template<typename T>
bool ros_integration::RosSubChannelElement< T >::init [private]

Definition at line 161 of file ros_msg_transporter.hpp.

template<typename T>
base::DataObjectLockFree<T> ros_integration::RosSubChannelElement< T >::m_msg [private]

Definition at line 162 of file ros_msg_transporter.hpp.

template<typename T>
bool ros_integration::RosSubChannelElement< T >::newdata [private]

Definition at line 161 of file ros_msg_transporter.hpp.

template<typename T>
ros::NodeHandle ros_integration::RosSubChannelElement< T >::ros_node [private]

Definition at line 159 of file ros_msg_transporter.hpp.

template<typename T>
ros::Subscriber ros_integration::RosSubChannelElement< T >::ros_sub [private]

Definition at line 160 of file ros_msg_transporter.hpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Defines


rtt_ros_integration
Author(s): Ruben Smits, ruben.smits@mech.kuleuven.be
autogenerated on Fri Jan 11 09:42:49 2013