#include <ros_msg_transporter.hpp>
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 () |
bool | write (typename base::ChannelElement< T >::param_t sample) |
~RosPubChannelElement () | |
Private Attributes | |
RosPublishActivity::shared_ptr | act |
We must cache the RosPublishActivity object. | |
char | hostname [1024] |
ros::NodeHandle | ros_node |
ros::Publisher | ros_pub |
base::ChannelElement< T >::value_t | sample |
std::string | topicname |
A ChannelElement implementation to publish data over a ros topic
Definition at line 70 of file ros_msg_transporter.hpp.
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
port | port for which we will create a the ROS publisher |
policy | connection policy containing the topic name and buffer size |
Definition at line 93 of file ros_msg_transporter.hpp.
ros_integration::RosPubChannelElement< T >::~RosPubChannelElement | ( | ) | [inline] |
Definition at line 121 of file ros_msg_transporter.hpp.
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
sample |
Definition at line 143 of file ros_msg_transporter.hpp.
virtual bool ros_integration::RosPubChannelElement< T >::inputReady | ( | ) | [inline, virtual] |
Function to see if the ChannelElement is ready to receive inputs
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 132 of file ros_msg_transporter.hpp.
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 160 of file ros_msg_transporter.hpp.
bool ros_integration::RosPubChannelElement< T >::signal | ( | ) | [inline, virtual] |
signal from the port that new data is availabe to publish
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 154 of file ros_msg_transporter.hpp.
bool ros_integration::RosPubChannelElement< T >::write | ( | typename base::ChannelElement< T >::param_t | sample | ) | [inline] |
Definition at line 167 of file ros_msg_transporter.hpp.
RosPublishActivity::shared_ptr ros_integration::RosPubChannelElement< T >::act [private] |
We must cache the RosPublishActivity object.
Definition at line 77 of file ros_msg_transporter.hpp.
char ros_integration::RosPubChannelElement< T >::hostname[1024] [private] |
Definition at line 72 of file ros_msg_transporter.hpp.
ros::NodeHandle ros_integration::RosPubChannelElement< T >::ros_node [private] |
Definition at line 74 of file ros_msg_transporter.hpp.
ros::Publisher ros_integration::RosPubChannelElement< T >::ros_pub [private] |
Definition at line 75 of file ros_msg_transporter.hpp.
base::ChannelElement<T>::value_t ros_integration::RosPubChannelElement< T >::sample [private] |
Definition at line 79 of file ros_msg_transporter.hpp.
std::string ros_integration::RosPubChannelElement< T >::topicname [private] |
Definition at line 73 of file ros_msg_transporter.hpp.