Implementation of a ThreadedStream that receives rc_visard's dynamics protobuf messages and re-publishes them as ros messages. More...
#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) | |
Public Member Functions inherited from rc::ThreadedStream | |
void | join () |
const std::string & | name () const |
const std::atomic_bool & | requested () const |
void | start () |
void | stop () |
const std::atomic_bool & | succeeded () const |
Protected Member Functions | |
virtual bool | startReceivingAndPublishingAsRos () override |
Protected Member Functions inherited from rc::ThreadedStream | |
ThreadedStream (rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh) | |
virtual void | work () |
Protected Attributes | |
const std::string | _tfPrefix |
Protected Attributes inherited from rc::ThreadedStream | |
Manager::Ptr | _manager |
ros::NodeHandle | _nh |
rc::dynamics::RemoteInterface::Ptr | _rcdyn |
std::atomic_bool | _requested |
std::atomic_bool | _stop |
std::string | _stream |
std::atomic_bool | _success |
std::thread | _thread |
Additional Inherited Members | |
Public Types inherited from rc::ThreadedStream | |
typedef std::shared_ptr< ThreadedStream > | Ptr |
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 51 of file protobuf2ros_stream.h.
|
inline |
Definition at line 54 of file protobuf2ros_stream.h.
|
overrideprotectedvirtual |
Implements rc::ThreadedStream.
Reimplemented in rc::DynamicsStream, and rc::PoseStream.
Definition at line 52 of file protobuf2ros_stream.cc.
|
protected |
Definition at line 63 of file protobuf2ros_stream.h.