Specific implementation for roboception::msgs::Dynamics messages. More...
#include <protobuf2ros_stream.h>
Public Member Functions | |
DynamicsStream (rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix) | |
Public Member Functions inherited from rc::Protobuf2RosStream | |
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 () |
Additional Inherited Members | |
Public Types inherited from rc::ThreadedStream | |
typedef std::shared_ptr< ThreadedStream > | Ptr |
Protected Attributes inherited from rc::Protobuf2RosStream | |
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 |
Specific implementation for roboception::msgs::Dynamics messages.
It publishes the different field of the received message as several messages:
Definition at line 94 of file protobuf2ros_stream.h.
|
inline |
Definition at line 97 of file protobuf2ros_stream.h.
|
overrideprotectedvirtual |
Reimplemented from rc::Protobuf2RosStream.
Definition at line 252 of file protobuf2ros_stream.cc.