Public Types | Public Member Functions | Private Member Functions | List of all members
robot_activity::resource::ManagedSubscriber Class Reference

Implementation of Managed class for ros::Subscriber. More...

#include <managed_subscriber.h>

Inheritance diagram for robot_activity::resource::ManagedSubscriber:
Inheritance graph
[legend]

Public Types

template<class Message >
using MessageCallback = boost::function< void(Message)>
 Typedef for ROS subscriber callbacks. More...
 
- Public Types inherited from robot_activity::resource::Managed< ManagedSubscriber, ros::Subscriber >
typedef std::shared_ptr< Managed< ManagedSubscriber, ros::Subscriber > > SharedPtr
 

Public Member Functions

template<class Message >
LazyAcquirer makeLazyAcquirer (const std::string &topic, uint32_t queue_size, const MessageCallback< Message > &callback, const ros::VoidConstPtr &tracked_object=ros::VoidConstPtr(), const ros::TransportHints &transport_hints=ros::TransportHints()) const
 Creates a function that when called subscribes to a ROS topic. More...
 
template<class M , class T >
LazyAcquirer makeLazyAcquirer (const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const ros::TransportHints &transport_hints=ros::TransportHints()) const
 Creates a function that when called subscribes to a ROS topic. More...
 
template<class M , class T >
LazyAcquirer makeLazyAcquirer (const std::string &topic, uint32_t queue_size, void(T::*fp)(M) const, T *obj, const ros::TransportHints &transport_hints=ros::TransportHints()) const
 Creates a function that when called subscribes to a ROS topic. More...
 
template<class M , class T >
LazyAcquirer makeLazyAcquirer (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const ros::TransportHints &transport_hints=ros::TransportHints()) const
 Creates a function that when called subscribes to a ROS topic. More...
 
template<class M , class T >
LazyAcquirer makeLazyAcquirer (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &) const, T *obj, const ros::TransportHints &transport_hints=ros::TransportHints()) const
 Creates a function that when called subscribes to a ROS topic. More...
 
template<class M , class T >
LazyAcquirer makeLazyAcquirer (const std::string &topic, uint32_t queue_size, void(T::*fp)(M), const boost::shared_ptr< T > &obj, const ros::TransportHints &transport_hints=ros::TransportHints()) const
 Creates a function that when called subscribes to a ROS topic. More...
 
template<class M , class T >
LazyAcquirer makeLazyAcquirer (const std::string &topic, uint32_t queue_size, void(T::*fp)(M) const, const boost::shared_ptr< T > &obj, const ros::TransportHints &transport_hints=ros::TransportHints()) const
 Creates a function that when called subscribes to a ROS topic. More...
 
template<class M , class T >
LazyAcquirer makeLazyAcquirer (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), const boost::shared_ptr< T > &obj, const ros::TransportHints &transport_hints=ros::TransportHints()) const
 Creates a function that when called subscribes to a ROS topic. More...
 
template<class M , class T >
LazyAcquirer makeLazyAcquirer (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &) const, const boost::shared_ptr< T > &obj, const ros::TransportHints &transport_hints=ros::TransportHints()) const
 Creates a function that when called subscribes to a ROS topic. More...
 
template<class M >
LazyAcquirer makeLazyAcquirer (const std::string &topic, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints()) const
 Creates a function that when called subscribes to a ROS topic. More...
 
template<class M >
LazyAcquirer makeLazyAcquirer (const std::string &topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr< M const > &), const ros::TransportHints &transport_hints=ros::TransportHints()) const
 Creates a function that when called subscribes to a ROS topic. More...
 
void shutdown ()
 Shutdowns the ROS subscriber. More...
 
void subscribe (const ros::NodeHandlePtr &node_handle)
 Subscribes to a ROS topic given a node handle. More...
 
- Public Member Functions inherited from robot_activity::resource::Managed< ManagedSubscriber, ros::Subscriber >
void acquire (const ros::NodeHandlePtr &node_handle)
 Acquires the resource if it's not already acquired. More...
 
 Managed ()=delete
 Default empty constructor is deleted. More...
 
 Managed (Args &&...args)
 Variadic constructor. More...
 
void pause ()
 Pauses the resource. More...
 
void release ()
 Releases the resource if it's already acquired. shutdown() method in case of ros::Subscriber and ros::ServiceServer. More...
 
void resume ()
 Resumes the resource. More...
 
 ~Managed ()
 Destructor. More...
 

Private Member Functions

template<class Message >
MessageCallback< Message > wrapMessageCallback (const MessageCallback< Message > &callback) const
 Wraps the message callback. More...
 

Additional Inherited Members

- Protected Types inherited from robot_activity::resource::Managed< ManagedSubscriber, ros::Subscriber >
typedef std::function< ros::Subscriber(const ros::NodeHandlePtr &)> LazyAcquirer
 
- Protected Member Functions inherited from robot_activity::resource::Managed< ManagedSubscriber, ros::Subscriber >
LazyAcquirer makeLazyAcquirer (Args &&...args) const
 Lazily acquires a resource. More...
 
- Protected Attributes inherited from robot_activity::resource::Managed< ManagedSubscriber, ros::Subscriber >
std::atomic< bool > acquired_
 Atomic flag specifing whether the resource is acquired or not. More...
 
LazyAcquirer lazy_acquirer_
 Function that will acquire the resource upon calling with a node handle. More...
 
std::atomic< bool > paused_
 Atomic flag specifing whether the resource is paused or not. More...
 
ros::Subscriber resource_
 The actual resource controlled by this class. More...
 

Detailed Description

Implementation of Managed class for ros::Subscriber.

Adds additional functionality to ros::Subscriber resource by wrapping it. The subsciber can be shutdowned, subscribed and paused. Shutting down has the same effect as in ROS, while subscribing does not require any arguments, since they are passed in the inherited constructor. Pausing the service, will cause the callback to return immediately without any execution.

Definition at line 71 of file managed_subscriber.h.

Member Typedef Documentation

template<class Message >
using robot_activity::resource::ManagedSubscriber::MessageCallback = boost::function<void(Message)>

Typedef for ROS subscriber callbacks.

Template Parameters
Callbackargument - Message type

Definition at line 125 of file managed_subscriber.h.

Member Function Documentation

template<class Message >
LazyAcquirer robot_activity::resource::ManagedSubscriber::makeLazyAcquirer ( const std::string &  topic,
uint32_t  queue_size,
const MessageCallback< Message > &  callback,
const ros::VoidConstPtr tracked_object = ros::VoidConstPtr(),
const ros::TransportHints transport_hints = ros::TransportHints() 
) const
inline

Creates a function that when called subscribes to a ROS topic.

Returns a lambda, which given a node handle will subscribe to a ROS topic. This lambda is called during subscribe call and the result is assigned as the managed resource, which in this case is the ros::Subscriber

Parameters
topicName of the ROS topic to subscribe to
queue_sizeSubscriber's queue size, 0 signifies an infinite queue
callbackSubscriber callback specified as boost::function accepting one argument - message type
tracked_objectObject to be tracked, whose destruction will terminate the subscriber
transport_hintsOptions describing the ROS subscriber
Template Parameters
MessageMessage type
Returns
Lambda, which return a ros::Subscriber

Definition at line 145 of file managed_subscriber.h.

template<class M , class T >
LazyAcquirer robot_activity::resource::ManagedSubscriber::makeLazyAcquirer ( const std::string &  topic,
uint32_t  queue_size,
void(T::*)(M)  fp,
T *  obj,
const ros::TransportHints transport_hints = ros::TransportHints() 
) const
inline

Creates a function that when called subscribes to a ROS topic.

Returns a lambda, which given a node handle will subscribe to a ROS topic. This lambda is called during subscribe call and the result is assigned as the managed resource, which in this case is the ros::Subscriber

Parameters
topicName of the ROS topic to subscribe to
queue_sizeSubscriber's queue size, 0 signifies an infinite queue
fpSubscriber callback specified as a pointer to a member function
objRaw pointer to an object used when calling the member function.
transport_hintsOptions describing the ROS subscriber
Template Parameters
MMessage type
TObject type on which the member function is called
Returns
Lambda, which return a ros::Subscriber

Definition at line 181 of file managed_subscriber.h.

template<class M , class T >
LazyAcquirer robot_activity::resource::ManagedSubscriber::makeLazyAcquirer ( const std::string &  topic,
uint32_t  queue_size,
void(T::*)(M) const  fp,
T *  obj,
const ros::TransportHints transport_hints = ros::TransportHints() 
) const
inline

Creates a function that when called subscribes to a ROS topic.

Returns a lambda, which given a node handle will subscribe to a ROS topic. This lambda is called during subscribe call and the result is assigned as the managed resource, which in this case is the ros::Subscriber

Parameters
topicName of the ROS topic to subscribe to
queue_sizeSubscriber's queue size, 0 signifies an infinite queue
fpSubscriber callback specified as a pointer to a member const function
objRaw pointer to an object used when calling the member function
transport_hintsOptions describing the ROS subscriber
Template Parameters
MMessage type
TObject type on which the member function is called
Returns
Lambda, which return a ros::Subscriber

Definition at line 207 of file managed_subscriber.h.

template<class M , class T >
LazyAcquirer robot_activity::resource::ManagedSubscriber::makeLazyAcquirer ( const std::string &  topic,
uint32_t  queue_size,
void(T::*)(const boost::shared_ptr< M const > &)  fp,
T *  obj,
const ros::TransportHints transport_hints = ros::TransportHints() 
) const
inline

Creates a function that when called subscribes to a ROS topic.

Returns a lambda, which given a node handle will subscribe to a ROS topic. This lambda is called during subscribe call and the result is assigned as the managed resource, which in this case is the ros::Subscriber

Parameters
topicName of the ROS topic to subscribe to
queue_sizeSubscriber's queue size, 0 signifies an infinite queue
fpSubscriber callback specified as a pointer to a member function, which accepts a boost::shared_ptr to a const message
objRaw pointer to an object used when calling the member function.
transport_hintsOptions describing the ROS subscriber
Template Parameters
MMessage type
TObject type on which the member function is called
Returns
Lambda, which return a ros::Subscriber

Definition at line 234 of file managed_subscriber.h.

template<class M , class T >
LazyAcquirer robot_activity::resource::ManagedSubscriber::makeLazyAcquirer ( const std::string &  topic,
uint32_t  queue_size,
void(T::*)(const boost::shared_ptr< M const > &) const  fp,
T *  obj,
const ros::TransportHints transport_hints = ros::TransportHints() 
) const
inline

Creates a function that when called subscribes to a ROS topic.

Returns a lambda, which given a node handle will subscribe to a ROS topic. This lambda is called during subscribe call and the result is assigned as the managed resource, which in this case is the ros::Subscriber

Parameters
topicName of the ROS topic to subscribe to
queue_sizeSubscriber's queue size, 0 signifies an infinite queue
fpSubscriber callback specified as a pointer to a const member function, which accepts a boost::shared_ptr to a const message
objRaw pointer to an object used when calling the member function.
transport_hintsOptions describing the ROS subscriber
Template Parameters
MMessage type
TObject type on which the member function is called
Returns
Lambda, which return a ros::Subscriber

Definition at line 264 of file managed_subscriber.h.

template<class M , class T >
LazyAcquirer robot_activity::resource::ManagedSubscriber::makeLazyAcquirer ( const std::string &  topic,
uint32_t  queue_size,
void(T::*)(M)  fp,
const boost::shared_ptr< T > &  obj,
const ros::TransportHints transport_hints = ros::TransportHints() 
) const
inline

Creates a function that when called subscribes to a ROS topic.

Returns a lambda, which given a node handle will subscribe to a ROS topic. This lambda is called during subscribe call and the result is assigned as the managed resource, which in this case is the ros::Subscriber

Parameters
topicName of the ROS topic to subscribe to
queue_sizeSubscriber's queue size, 0 signifies an infinite queue
fpSubscriber callback specified as a pointer to a member function, which accepts a message
objBoost shared pointer to an object used when calling the member function. Destruction of this object causes subscriber to shutdown.
transport_hintsOptions describing the ROS subscriber
Template Parameters
MMessage type
TObject type on which the member function is called
Returns
Lambda, which return a ros::Subscriber

Definition at line 296 of file managed_subscriber.h.

template<class M , class T >
LazyAcquirer robot_activity::resource::ManagedSubscriber::makeLazyAcquirer ( const std::string &  topic,
uint32_t  queue_size,
void(T::*)(M) const  fp,
const boost::shared_ptr< T > &  obj,
const ros::TransportHints transport_hints = ros::TransportHints() 
) const
inline

Creates a function that when called subscribes to a ROS topic.

Returns a lambda, which given a node handle will subscribe to a ROS topic. This lambda is called during subscribe call and the result is assigned as the managed resource, which in this case is the ros::Subscriber

Parameters
topicName of the ROS topic to subscribe to
queue_sizeSubscriber's queue size, 0 signifies an infinite queue
fpSubscriber callback specified as a pointer to a const member function, which accepts a message
objBoost shared pointer to an object used when calling the member function. Destruction of this object causes subscriber to shutdown.
transport_hintsOptions describing the ROS subscriber
Template Parameters
MMessage type
TObject type on which the member function is called
Returns
Lambda, which return a ros::Subscriber

Definition at line 328 of file managed_subscriber.h.

template<class M , class T >
LazyAcquirer robot_activity::resource::ManagedSubscriber::makeLazyAcquirer ( const std::string &  topic,
uint32_t  queue_size,
void(T::*)(const boost::shared_ptr< M const > &)  fp,
const boost::shared_ptr< T > &  obj,
const ros::TransportHints transport_hints = ros::TransportHints() 
) const
inline

Creates a function that when called subscribes to a ROS topic.

Returns a lambda, which given a node handle will subscribe to a ROS topic. This lambda is called during subscribe call and the result is assigned as the managed resource, which in this case is the ros::Subscriber

Parameters
topicName of the ROS topic to subscribe to
queue_sizeSubscriber's queue size, 0 signifies an infinite queue
fpSubscriber callback specified as a pointer to a member function, which accepts a boost::shared_ptr to a const message
objBoost shared pointer to an object used when calling the member function. Destruction of this object causes subscriber to shutdown.
transport_hintsOptions describing the ROS subscriber
Template Parameters
MMessage type
TObject type on which the member function is called
Returns
Lambda, which return a ros::Subscriber

Definition at line 360 of file managed_subscriber.h.

template<class M , class T >
LazyAcquirer robot_activity::resource::ManagedSubscriber::makeLazyAcquirer ( const std::string &  topic,
uint32_t  queue_size,
void(T::*)(const boost::shared_ptr< M const > &) const  fp,
const boost::shared_ptr< T > &  obj,
const ros::TransportHints transport_hints = ros::TransportHints() 
) const
inline

Creates a function that when called subscribes to a ROS topic.

Returns a lambda, which given a node handle will subscribe to a ROS topic. This lambda is called during subscribe call and the result is assigned as the managed resource, which in this case is the ros::Subscriber

Parameters
topicName of the ROS topic to subscribe to
queue_sizeSubscriber's queue size, 0 signifies an infinite queue
fpSubscriber callback specified as a pointer to a const member function, which accepts a boost::shared_ptr to a const message
objBoost shared pointer to an object used when calling the member function. Destruction of this object causes subscriber to shutdown.
transport_hintsOptions describing the ROS subscriber
Template Parameters
MMessage type
TObject type on which the member function is called
Returns
Lambda, which return a ros::Subscriber

Definition at line 393 of file managed_subscriber.h.

template<class M >
LazyAcquirer robot_activity::resource::ManagedSubscriber::makeLazyAcquirer ( const std::string &  topic,
uint32_t  queue_size,
void(*)(M)  fp,
const ros::TransportHints transport_hints = ros::TransportHints() 
) const
inline

Creates a function that when called subscribes to a ROS topic.

Returns a lambda, which given a node handle will subscribe to a ROS topic. This lambda is called during subscribe call and the result is assigned as the managed resource, which in this case is the ros::Subscriber

Parameters
topicName of the ROS topic to subscribe to
queue_sizeSubscriber's queue size, 0 signifies an infinite queue
fpSubscriber callback specified as a pointer to a function
transport_hintsOptions describing the ROS subscriber
Template Parameters
MMessage type
TObject type on which the member function is called
Returns
Lambda, which return a ros::Subscriber

Definition at line 422 of file managed_subscriber.h.

template<class M >
LazyAcquirer robot_activity::resource::ManagedSubscriber::makeLazyAcquirer ( const std::string &  topic,
uint32_t  queue_size,
void(*)(const boost::shared_ptr< M const > &)  fp,
const ros::TransportHints transport_hints = ros::TransportHints() 
) const
inline

Creates a function that when called subscribes to a ROS topic.

Returns a lambda, which given a node handle will subscribe to a ROS topic. This lambda is called during subscribe call and the result is assigned as the managed resource, which in this case is the ros::Subscriber

Parameters
topicName of the ROS topic to subscribe to
queue_sizeSubscriber's queue size, 0 signifies an infinite queue
fpSubscriber callback specified as a pointer to a function, which accepts a boost shared pointer to a const message
transport_hintsOptions describing the ROS subscriber
Template Parameters
MMessage type
TObject type on which the member function is called
Returns
Lambda, which return a ros::Subscriber

Definition at line 449 of file managed_subscriber.h.

void robot_activity::resource::ManagedSubscriber::shutdown ( )
inline

Shutdowns the ROS subscriber.

Has the same effect as ros::Subscriber::shutdown function if the topic was subscribed, otherwise does not have any effect

Definition at line 114 of file managed_subscriber.h.

void robot_activity::resource::ManagedSubscriber::subscribe ( const ros::NodeHandlePtr node_handle)
inline

Subscribes to a ROS topic given a node handle.

Since the ROS subsciber is fully desribed upon instantiation, the actual subscribe call only requires a node handle. The function is idempotent and can be called multiple times without any side-effect. The topic can be also re-subscribed after being shutdowned without respecifying arguments describing the subscription.

Parameters
node_handleNode handle required for the actual call to ros::NodeHandle::subscribe embedded inside

Definition at line 103 of file managed_subscriber.h.

template<class Message >
MessageCallback<Message> robot_activity::resource::ManagedSubscriber::wrapMessageCallback ( const MessageCallback< Message > &  callback) const
inlineprivate

Wraps the message callback.

Allows for pausing/resuming the servce by adding a check at run-time. If paused, the service will return immediately.

Parameters
callback[description]
Returns
[description]

Definition at line 496 of file managed_subscriber.h.


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


robot_activity
Author(s): Maciej ZURAD
autogenerated on Mon Jun 10 2019 14:33:22