Implementation of Managed class for ros::Subscriber. More...
#include <managed_subscriber.h>
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
void | shutdown () |
Shutdowns the ROS subscriber. | |
void | subscribe (const ros::NodeHandlePtr &node_handle) |
Subscribes to a ROS topic given a node handle. | |
Private Member Functions | |
template<class Message > | |
MessageCallback< Message > | wrapMessageCallback (const MessageCallback< Message > &callback) const |
Wraps the message callback. |
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.
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
topic | Name of the ROS topic to subscribe to |
queue_size | Subscriber's queue size, 0 signifies an infinite queue |
callback | Subscriber callback specified as boost::function accepting one argument - message type |
tracked_object | Object to be tracked, whose destruction will terminate the subscriber |
transport_hints | Options describing the ROS subscriber |
Message | Message type |
Definition at line 145 of file managed_subscriber.h.
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
topic | Name of the ROS topic to subscribe to |
queue_size | Subscriber's queue size, 0 signifies an infinite queue |
fp | Subscriber callback specified as a pointer to a member function |
obj | Raw pointer to an object used when calling the member function. |
transport_hints | Options describing the ROS subscriber |
M | Message type |
T | Object type on which the member function is called |
Definition at line 181 of file managed_subscriber.h.
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
topic | Name of the ROS topic to subscribe to |
queue_size | Subscriber's queue size, 0 signifies an infinite queue |
fp | Subscriber callback specified as a pointer to a member const function |
obj | Raw pointer to an object used when calling the member function |
transport_hints | Options describing the ROS subscriber |
M | Message type |
T | Object type on which the member function is called |
Definition at line 207 of file managed_subscriber.h.
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
topic | Name of the ROS topic to subscribe to |
queue_size | Subscriber's queue size, 0 signifies an infinite queue |
fp | Subscriber callback specified as a pointer to a member function, which accepts a boost::shared_ptr to a const message |
obj | Raw pointer to an object used when calling the member function. |
transport_hints | Options describing the ROS subscriber |
M | Message type |
T | Object type on which the member function is called |
Definition at line 234 of file managed_subscriber.h.
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
topic | Name of the ROS topic to subscribe to |
queue_size | Subscriber's queue size, 0 signifies an infinite queue |
fp | Subscriber callback specified as a pointer to a const member function, which accepts a boost::shared_ptr to a const message |
obj | Raw pointer to an object used when calling the member function. |
transport_hints | Options describing the ROS subscriber |
M | Message type |
T | Object type on which the member function is called |
Definition at line 264 of file managed_subscriber.h.
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
topic | Name of the ROS topic to subscribe to |
queue_size | Subscriber's queue size, 0 signifies an infinite queue |
fp | Subscriber callback specified as a pointer to a member function, which accepts a message |
obj | Boost shared pointer to an object used when calling the member function. Destruction of this object causes subscriber to shutdown. |
transport_hints | Options describing the ROS subscriber |
M | Message type |
T | Object type on which the member function is called |
Definition at line 296 of file managed_subscriber.h.
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
topic | Name of the ROS topic to subscribe to |
queue_size | Subscriber's queue size, 0 signifies an infinite queue |
fp | Subscriber callback specified as a pointer to a const member function, which accepts a message |
obj | Boost shared pointer to an object used when calling the member function. Destruction of this object causes subscriber to shutdown. |
transport_hints | Options describing the ROS subscriber |
M | Message type |
T | Object type on which the member function is called |
Definition at line 328 of file managed_subscriber.h.
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
topic | Name of the ROS topic to subscribe to |
queue_size | Subscriber's queue size, 0 signifies an infinite queue |
fp | Subscriber callback specified as a pointer to a member function, which accepts a boost::shared_ptr to a const message |
obj | Boost shared pointer to an object used when calling the member function. Destruction of this object causes subscriber to shutdown. |
transport_hints | Options describing the ROS subscriber |
M | Message type |
T | Object type on which the member function is called |
Definition at line 360 of file managed_subscriber.h.
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
topic | Name of the ROS topic to subscribe to |
queue_size | Subscriber's queue size, 0 signifies an infinite queue |
fp | Subscriber callback specified as a pointer to a const member function, which accepts a boost::shared_ptr to a const message |
obj | Boost shared pointer to an object used when calling the member function. Destruction of this object causes subscriber to shutdown. |
transport_hints | Options describing the ROS subscriber |
M | Message type |
T | Object type on which the member function is called |
Definition at line 393 of file managed_subscriber.h.
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
topic | Name of the ROS topic to subscribe to |
queue_size | Subscriber's queue size, 0 signifies an infinite queue |
fp | Subscriber callback specified as a pointer to a function |
transport_hints | Options describing the ROS subscriber |
M | Message type |
T | Object type on which the member function is called |
Definition at line 422 of file managed_subscriber.h.
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
topic | Name of the ROS topic to subscribe to |
queue_size | Subscriber's queue size, 0 signifies an infinite queue |
fp | Subscriber callback specified as a pointer to a function, which accepts a boost shared pointer to a const message |
transport_hints | Options describing the ROS subscriber |
M | Message type |
T | Object type on which the member function is called |
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.
node_handle | Node handle required for the actual call to ros::NodeHandle::subscribe embedded inside |
Definition at line 103 of file managed_subscriber.h.
MessageCallback<Message> robot_activity::resource::ManagedSubscriber::wrapMessageCallback | ( | const MessageCallback< Message > & | callback | ) | const [inline, private] |
Wraps the message callback.
Allows for pausing/resuming the servce by adding a check at run-time. If paused, the service will return immediately.
callback | [description] |
Definition at line 496 of file managed_subscriber.h.