#include <rtt_rostopic_ros_msg_transporter.hpp>
Private Types | |
typedef RosMessageAdapter< T > | adapter |
typedef adapter::RosType | RosType |
Private Attributes | |
ros::NodeHandle | ros_node |
ros::NodeHandle | ros_node_private |
ros::Subscriber | ros_sub |
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 subscribe to data over a ros topic
Definition at line 235 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 237 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 238 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inline |
Contructor of to create ROS subscriber ChannelElement, it will subscribe to a topic with the name given by the policy.name_id
port | port for which we will create a the ROS publisher |
policy | connection policy containing the topic name and buffer size |
Definition at line 255 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inline |
Definition at line 273 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inlinevirtual |
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 286 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inlinevirtual |
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 290 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inlinevirtual |
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 278 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inlinevirtual |
Reimplemented from RTT::base::ChannelElementBase.
Definition at line 282 of file rtt_rostopic_ros_msg_transporter.hpp.
|
inline |
Callback function for the ROS subscriber, it will trigger the ChannelElement's signal function
msg | The received message |
Definition at line 299 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 241 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 242 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 243 of file rtt_rostopic_ros_msg_transporter.hpp.
|
private |
Definition at line 240 of file rtt_rostopic_ros_msg_transporter.hpp.