#include <rtt_rostopic_ros_msg_transporter.hpp>

| Public Member Functions | |
| virtual bool | data_sample (typename RTT::base::ChannelElement< T >::param_t sample) | 
| virtual bool | inputReady () | 
| void | publish () | 
| RosPubChannelElement (RTT::base::PortInterface *port, const RTT::ConnPolicy &policy) | |
| bool | signal () | 
| bool | write (typename RTT::base::ChannelElement< T >::param_t sample) | 
| ~RosPubChannelElement () | |
| Private Types | |
| typedef RosMessageAdapter< T > | adapter | 
| typedef adapter::RosType | RosType | 
| Private Attributes | |
| RosPublishActivity::shared_ptr | act | 
| We must cache the RosPublishActivity object. | |
| char | hostname [1024] | 
| ros::NodeHandle | ros_node | 
| ros::NodeHandle | ros_node_private | 
| ros::Publisher | ros_pub | 
| RTT::base::ChannelElement< T > ::value_t | sample | 
| std::string | topicname | 
A ChannelElement implementation to publish data over a ros topic
Definition at line 87 of file rtt_rostopic_ros_msg_transporter.hpp.
| typedef RosMessageAdapter<T> rtt_roscomm::RosPubChannelElement< T >::adapter  [private] | 
Definition at line 89 of file rtt_rostopic_ros_msg_transporter.hpp.
| typedef adapter::RosType rtt_roscomm::RosPubChannelElement< T >::RosType  [private] | 
Definition at line 90 of file rtt_rostopic_ros_msg_transporter.hpp.
| rtt_roscomm::RosPubChannelElement< T >::RosPubChannelElement | ( | RTT::base::PortInterface * | port, | 
| const RTT::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 114 of file rtt_rostopic_ros_msg_transporter.hpp.
| rtt_roscomm::RosPubChannelElement< T >::~RosPubChannelElement | ( | ) |  [inline] | 
Definition at line 149 of file rtt_rostopic_ros_msg_transporter.hpp.
| virtual bool rtt_roscomm::RosPubChannelElement< T >::data_sample | ( | typename RTT::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 178 of file rtt_rostopic_ros_msg_transporter.hpp.
| virtual bool rtt_roscomm::RosPubChannelElement< T >::inputReady | ( | ) |  [inline, virtual] | 
Function to see if the ChannelElement is ready to receive inputs
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 160 of file rtt_rostopic_ros_msg_transporter.hpp.
| void rtt_roscomm::RosPubChannelElement< T >::publish | ( | ) |  [inline, virtual] | 
Publish all data in the channel to a ROS topic.
Implements rtt_roscomm::RosPublisher.
Definition at line 196 of file rtt_rostopic_ros_msg_transporter.hpp.
| bool rtt_roscomm::RosPubChannelElement< T >::signal | ( | ) |  [inline, virtual] | 
signal from the port that new data is availabe to publish
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 190 of file rtt_rostopic_ros_msg_transporter.hpp.
| bool rtt_roscomm::RosPubChannelElement< T >::write | ( | typename RTT::base::ChannelElement< T >::param_t | sample | ) |  [inline] | 
Definition at line 206 of file rtt_rostopic_ros_msg_transporter.hpp.
| RosPublishActivity::shared_ptr rtt_roscomm::RosPubChannelElement< T >::act  [private] | 
We must cache the RosPublishActivity object.
Definition at line 98 of file rtt_rostopic_ros_msg_transporter.hpp.
| char rtt_roscomm::RosPubChannelElement< T >::hostname[1024]  [private] | 
Definition at line 92 of file rtt_rostopic_ros_msg_transporter.hpp.
| ros::NodeHandle rtt_roscomm::RosPubChannelElement< T >::ros_node  [private] | 
Definition at line 94 of file rtt_rostopic_ros_msg_transporter.hpp.
| ros::NodeHandle rtt_roscomm::RosPubChannelElement< T >::ros_node_private  [private] | 
Definition at line 95 of file rtt_rostopic_ros_msg_transporter.hpp.
| ros::Publisher rtt_roscomm::RosPubChannelElement< T >::ros_pub  [private] | 
Definition at line 96 of file rtt_rostopic_ros_msg_transporter.hpp.
| RTT::base::ChannelElement<T>::value_t rtt_roscomm::RosPubChannelElement< T >::sample  [private] | 
Definition at line 100 of file rtt_rostopic_ros_msg_transporter.hpp.
| std::string rtt_roscomm::RosPubChannelElement< T >::topicname  [private] | 
Definition at line 93 of file rtt_rostopic_ros_msg_transporter.hpp.