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

Specific implementation for roboception::msgs::Dynamics messages. More...

#include <protobuf2ros_stream.h>

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

Public Member Functions

 DynamicsStream (rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix, bool publishImu2CamAsTf)
 
- 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< ros::Publisher_pub_markers
 
std::shared_ptr< ros::Publisher_pub_odom
 
bool _publishImu2CamAsTf
 
bool _publishVisualizationMarkers
 
std::shared_ptr< tf::TransformBroadcaster_tf_pub
 
- 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::Dynamics messages.

It publishes the different field of the received message as several messages:

Definition at line 115 of file protobuf2ros_stream.h.

Constructor & Destructor Documentation

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

Definition at line 118 of file protobuf2ros_stream.h.

Member Function Documentation

bool rc::DynamicsStream::checkRosPublishersUsed ( )
overrideprotectedvirtual

Reimplemented from rc::Protobuf2RosStream.

Definition at line 261 of file protobuf2ros_stream.cc.

void rc::DynamicsStream::initRosPublishers ( )
overrideprotectedvirtual

Reimplemented from rc::Protobuf2RosStream.

Definition at line 239 of file protobuf2ros_stream.cc.

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

Reimplemented from rc::Protobuf2RosStream.

Definition at line 266 of file protobuf2ros_stream.cc.

Member Data Documentation

std::shared_ptr<ros::Publisher> rc::DynamicsStream::_pub_markers
protected

Definition at line 138 of file protobuf2ros_stream.h.

std::shared_ptr<ros::Publisher> rc::DynamicsStream::_pub_odom
protected

Definition at line 137 of file protobuf2ros_stream.h.

bool rc::DynamicsStream::_publishImu2CamAsTf
protected

Definition at line 140 of file protobuf2ros_stream.h.

bool rc::DynamicsStream::_publishVisualizationMarkers
protected

Definition at line 140 of file protobuf2ros_stream.h.

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

Definition at line 139 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