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

Implementation of a ThreadedStream that receives rc_visard's dynamics protobuf messages and re-publishes them as ros messages. More...

#include <protobuf2ros_stream.h>

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

Public Member Functions

 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

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

Implementation of a ThreadedStream that receives rc_visard's dynamics protobuf messages and re-publishes them as ros messages.

The ros topic is the dynamics stream name; the ros message type is determined by the protobuf message type of the dynamics stream.

Definition at line 51 of file protobuf2ros_stream.h.

Constructor & Destructor Documentation

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

Definition at line 54 of file protobuf2ros_stream.h.

Member Function Documentation

bool rc::Protobuf2RosStream::startReceivingAndPublishingAsRos ( )
overrideprotectedvirtual
Returns
true, if stopped without fails

Implements rc::ThreadedStream.

Reimplemented in rc::DynamicsStream, and rc::PoseStream.

Definition at line 52 of file protobuf2ros_stream.cc.

Member Data Documentation

const std::string rc::Protobuf2RosStream::_tfPrefix
protected

Definition at line 63 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 Wed Mar 20 2019 07:55:49