ros_integration::RosPubChannelElement< T > Class Template Reference

#include <ros_msg_transporter.hpp>

Inheritance diagram for ros_integration::RosPubChannelElement< T >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool data_sample (typename base::ChannelElement< T >::param_t sample)
virtual bool inputReady ()
void publish ()
 RosPubChannelElement (base::PortInterface *port, const ConnPolicy &policy)
bool signal ()
 ~RosPubChannelElement ()

Private Attributes

RosPublishActivity::shared_ptr act
 We must cache the RosPublishActivity object.
char hostname [1024]
ros::NodeHandle ros_node
ros::Publisher ros_pub
std::string topicname

Detailed Description

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

A ChannelElement implementation to publish data over a ros topic

Definition at line 68 of file ros_msg_transporter.hpp.


Constructor & Destructor Documentation

template<typename T >
ros_integration::RosPubChannelElement< T >::RosPubChannelElement ( base::PortInterface *  port,
const ConnPolicy &  policy 
) [inline]

Contructor of to create ROS publisher ChannelElement, it will create a topic from the name given by the policy.name_id, if this is empty a default is created as hostname/componentname/portname/pid

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 89 of file ros_msg_transporter.hpp.

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

Definition at line 108 of file ros_msg_transporter.hpp.


Member Function Documentation

template<typename T >
virtual bool ros_integration::RosPubChannelElement< T >::data_sample ( typename base::ChannelElement< T >::param_t  sample  )  [inline, virtual]

Create a data sample, this could be used to allocate the necessary memory, it is not needed in our case

Parameters:
sample 
Returns:
always true

Definition at line 130 of file ros_msg_transporter.hpp.

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

Function to see if the ChannelElement is ready to receive inputs

Returns:
always true in our case

Definition at line 119 of file ros_msg_transporter.hpp.

template<typename T >
void ros_integration::RosPubChannelElement< T >::publish (  )  [inline, virtual]

Publish all data in the channel to a ROS topic.

Implements ros_integration::RosPublisher.

Definition at line 146 of file ros_msg_transporter.hpp.

template<typename T >
bool ros_integration::RosPubChannelElement< T >::signal (  )  [inline]

signal from the port that new data is availabe to publish

Returns:
true if publishing succeeded

Definition at line 140 of file ros_msg_transporter.hpp.


Member Data Documentation

We must cache the RosPublishActivity object.

Definition at line 75 of file ros_msg_transporter.hpp.

template<typename T >
char ros_integration::RosPubChannelElement< T >::hostname[1024] [private]

Definition at line 70 of file ros_msg_transporter.hpp.

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

Definition at line 72 of file ros_msg_transporter.hpp.

template<typename T >
ros::Publisher ros_integration::RosPubChannelElement< T >::ros_pub [private]

Definition at line 73 of file ros_msg_transporter.hpp.

template<typename T >
std::string ros_integration::RosPubChannelElement< T >::topicname [private]

Definition at line 71 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