#include <rtt_rostopic_ros_msg_transporter.hpp>

Private Types | |
| typedef RosMessageAdapter< T > | adapter |
| typedef adapter::RosType | RosType |
Private Attributes | |
| RosPublishActivity::shared_ptr | act |
| We must cache the RosPublishActivity object. More... | |
| 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 |
Additional Inherited Members | |
Public Types inherited from RTT::base::ChannelElement< T > | |
| typedef boost::call_traits< T >::param_type | param_t |
| typedef boost::call_traits< T >::reference | reference_t |
| typedef boost::intrusive_ptr< ChannelElement< T > > | shared_ptr |
| typedef T | value_t |
Public Types inherited from RTT::base::ChannelElementBase | |
| typedef boost::intrusive_ptr< ChannelElementBase > | shared_ptr |
Static Public Member Functions inherited from RTT::base::ChannelElementBase | |
| static ChannelElement< T > * | narrow (ChannelElementBase *e) |
Protected Member Functions inherited from RTT::base::ChannelElementBase | |
| virtual bool | addInput (shared_ptr const &input) |
| virtual bool | addOutput (shared_ptr const &output, bool mandatory=true) |
| void | deref () |
| void | ref () |
| virtual void | removeInput (shared_ptr const &input) |
| virtual void | removeOutput (shared_ptr const &output) |
Protected Attributes inherited from RTT::base::ChannelElementBase | |
| shared_ptr | input |
| RTT::os::SharedMutex | input_lock |
| shared_ptr | output |
| RTT::os::SharedMutex | output_lock |
A ChannelElement implementation to publish data over a ros topic
Definition at line 87 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 89 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 90 of file rtt_rostopic_ros_msg_transporter.hpp.
|
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.
|
inline |
Definition at line 149 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inlinevirtual |
Create a data sample, this could be used to allocate the necessary memory
| sample |
Definition at line 190 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inlinevirtual |
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 168 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inlinevirtual |
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 172 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inlinevirtual |
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.
|
inlinevirtual |
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 164 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inlinevirtual |
Publish all data in the channel to a ROS topic.
Implements rtt_roscomm::RosPublisher.
Definition at line 208 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inlinevirtual |
signal from the port that new data is availabe to publish
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 202 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inline |
Definition at line 218 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
We must cache the RosPublishActivity object.
Definition at line 98 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 92 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 94 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 95 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 96 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 100 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 93 of file rtt_rostopic_ros_msg_transporter.hpp.