#include <ThreadedStream.h>
Classes | |
class | Manager |
Public Types | |
typedef std::shared_ptr < ThreadedStream > | Ptr |
Public Member Functions | |
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 ()=0 |
ThreadedStream (rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh) | |
virtual void | work () |
Protected Attributes | |
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 |
Convenience classes to implement and manage different types of data streams in separate threads.
Intended use: 1 - create a manager 2 - create different types of threaded streams 3 - add them to the manager 4 - start the threads 5 - let the threaded streams to their work and supervise their state 6 - stop the threads and join them 7 - destroy manager (Re-use after joining some threads is not intended!!!)
Definition at line 61 of file ThreadedStream.h.
typedef std::shared_ptr<ThreadedStream> rc::ThreadedStream::Ptr |
Definition at line 64 of file ThreadedStream.h.
rc::ThreadedStream::ThreadedStream | ( | rc::dynamics::RemoteInterface::Ptr | rcdIface, |
const std::string & | stream, | ||
ros::NodeHandle & | nh | ||
) | [protected] |
Definition at line 43 of file ThreadedStream.cc.
void rc::ThreadedStream::join | ( | ) |
Definition at line 62 of file ThreadedStream.cc.
const std::string& rc::ThreadedStream::name | ( | ) | const [inline] |
Definition at line 96 of file ThreadedStream.h.
const std::atomic_bool& rc::ThreadedStream::requested | ( | ) | const [inline] |
Definition at line 97 of file ThreadedStream.h.
void rc::ThreadedStream::start | ( | ) |
Definition at line 49 of file ThreadedStream.cc.
virtual bool rc::ThreadedStream::startReceivingAndPublishingAsRos | ( | ) | [protected, pure virtual] |
Implemented in rc::PoseStream, and rc::Protobuf2RosStream.
void rc::ThreadedStream::stop | ( | ) |
Definition at line 57 of file ThreadedStream.cc.
const std::atomic_bool& rc::ThreadedStream::succeeded | ( | ) | const [inline] |
Definition at line 98 of file ThreadedStream.h.
void rc::ThreadedStream::work | ( | ) | [protected, virtual] |
Definition at line 68 of file ThreadedStream.cc.
Manager::Ptr rc::ThreadedStream::_manager [protected] |
Definition at line 114 of file ThreadedStream.h.
ros::NodeHandle rc::ThreadedStream::_nh [protected] |
Definition at line 118 of file ThreadedStream.h.
rc::dynamics::RemoteInterface::Ptr rc::ThreadedStream::_rcdyn [protected] |
Definition at line 116 of file ThreadedStream.h.
std::atomic_bool rc::ThreadedStream::_requested [protected] |
Definition at line 111 of file ThreadedStream.h.
std::atomic_bool rc::ThreadedStream::_stop [protected] |
Definition at line 111 of file ThreadedStream.h.
std::string rc::ThreadedStream::_stream [protected] |
Definition at line 117 of file ThreadedStream.h.
std::atomic_bool rc::ThreadedStream::_success [protected] |
Definition at line 111 of file ThreadedStream.h.
std::thread rc::ThreadedStream::_thread [protected] |
Definition at line 113 of file ThreadedStream.h.