Specific implementation for roboception::msgs::Frame messages. More...
#include <protobuf2ros_stream.h>
Public Member Functions | |
PoseStream (rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix, bool tfEnabled) | |
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 () |
Protected Attributes | |
bool | _tfEnabled |
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 |
Additional Inherited Members | |
Public Types inherited from rc::ThreadedStream | |
typedef std::shared_ptr< ThreadedStream > | Ptr |
Specific implementation for roboception::msgs::Frame messages.
It publishes received messages not only as ros StampedPoses but also on tf if desired.
Again, the resulting ros topic is the dynamics stream name.
Definition at line 72 of file protobuf2ros_stream.h.
|
inline |
Definition at line 75 of file protobuf2ros_stream.h.
|
overrideprotectedvirtual |
Reimplemented from rc::Protobuf2RosStream.
Definition at line 144 of file protobuf2ros_stream.cc.
|
protected |
Definition at line 84 of file protobuf2ros_stream.h.