Specific implementation for roboception::msgs::Frame messages that publishes received messages not only as ros StampedPoses but also on tf if desired. More...
#include <protobuf2ros_stream.h>
Public Member Functions | |
PoseAndTFStream (rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix, bool tfEnabled) | |
![]() | |
Protobuf2RosStream (rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix) | |
![]() | |
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 | checkRosPublishersUsed () override |
virtual void | initRosPublishers () override |
virtual void | publishToRos (std::shared_ptr<::google::protobuf::Message > pbMsg) override |
![]() | |
virtual bool | startReceivingAndPublishingAsRos () override |
![]() | |
ThreadedStream (rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh) | |
virtual void | work () |
Protected Attributes | |
std::shared_ptr< tf::TransformBroadcaster > | _tf_pub |
bool | _tfEnabled |
![]() | |
std::shared_ptr< Protobuf2RosPublisher > | _rosPublisher |
const std::string | _tfPrefix |
![]() | |
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 | |
![]() | |
typedef std::shared_ptr< ThreadedStream > | Ptr |
Specific implementation for roboception::msgs::Frame messages that 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 82 of file protobuf2ros_stream.h.
|
inline |
Definition at line 85 of file protobuf2ros_stream.h.
|
overrideprotectedvirtual |
Reimplemented from rc::Protobuf2RosStream.
Definition at line 215 of file protobuf2ros_stream.cc.
|
overrideprotectedvirtual |
Reimplemented from rc::Protobuf2RosStream.
Definition at line 209 of file protobuf2ros_stream.cc.
|
overrideprotectedvirtual |
Reimplemented from rc::Protobuf2RosStream.
Definition at line 220 of file protobuf2ros_stream.cc.
|
protected |
Definition at line 104 of file protobuf2ros_stream.h.
|
protected |
Definition at line 105 of file protobuf2ros_stream.h.