Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
rc::PoseAndTFStream Class Reference

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>

Inheritance diagram for rc::PoseAndTFStream:
Inheritance graph
[legend]

Public Member Functions

 PoseAndTFStream (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 checkRosPublishersUsed () override
 
virtual void initRosPublishers () override
 
virtual void publishToRos (std::shared_ptr<::google::protobuf::Message > pbMsg) override
 
- Protected Member Functions inherited from rc::Protobuf2RosStream
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

std::shared_ptr< tf::TransformBroadcaster_tf_pub
 
bool _tfEnabled
 
- Protected Attributes inherited from rc::Protobuf2RosStream
std::shared_ptr< Protobuf2RosPublisher_rosPublisher
 
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< ThreadedStreamPtr
 

Detailed Description

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.

Constructor & Destructor Documentation

rc::PoseAndTFStream::PoseAndTFStream ( rc::dynamics::RemoteInterface::Ptr  rcdIface,
const std::string &  stream,
ros::NodeHandle nh,
const std::string &  frame_id_prefix,
bool  tfEnabled 
)
inline

Definition at line 85 of file protobuf2ros_stream.h.

Member Function Documentation

bool rc::PoseAndTFStream::checkRosPublishersUsed ( )
overrideprotectedvirtual

Reimplemented from rc::Protobuf2RosStream.

Definition at line 215 of file protobuf2ros_stream.cc.

void rc::PoseAndTFStream::initRosPublishers ( )
overrideprotectedvirtual

Reimplemented from rc::Protobuf2RosStream.

Definition at line 209 of file protobuf2ros_stream.cc.

void rc::PoseAndTFStream::publishToRos ( std::shared_ptr<::google::protobuf::Message >  pbMsg)
overrideprotectedvirtual

Reimplemented from rc::Protobuf2RosStream.

Definition at line 220 of file protobuf2ros_stream.cc.

Member Data Documentation

std::shared_ptr<tf::TransformBroadcaster> rc::PoseAndTFStream::_tf_pub
protected

Definition at line 104 of file protobuf2ros_stream.h.

bool rc::PoseAndTFStream::_tfEnabled
protected

Definition at line 105 of file protobuf2ros_stream.h.


The documentation for this class was generated from the following files:


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Sat Feb 13 2021 03:42:55