#include <protobuf2ros_stream.h>
Public Member Functions | |
Protobuf2RosStream (rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix) | |
Protected Member Functions | |
virtual bool | startReceivingAndPublishingAsRos () override |
Protected Attributes | |
const std::string | _tfPrefix |
Implementation of a ThreadedStream that receives rc_visard's dynamics protobuf messages and re-publishes them as ros messages
The ros topic is the dynamics stream name; the ros message type is determined by the protobuf message type of the dynamics stream.
Definition at line 54 of file protobuf2ros_stream.h.
rc::Protobuf2RosStream::Protobuf2RosStream | ( | rc::dynamics::RemoteInterface::Ptr | rcdIface, |
const std::string & | stream, | ||
ros::NodeHandle & | nh, | ||
const std::string & | frame_id_prefix | ||
) | [inline] |
Definition at line 57 of file protobuf2ros_stream.h.
bool rc::Protobuf2RosStream::startReceivingAndPublishingAsRos | ( | ) | [override, protected, virtual] |
Implements rc::ThreadedStream.
Reimplemented in rc::PoseStream.
Definition at line 53 of file protobuf2ros_stream.cc.
const std::string rc::Protobuf2RosStream::_tfPrefix [protected] |
Definition at line 66 of file protobuf2ros_stream.h.