Manages an subscription callback on a specific topic. More...
#include <subscriber.h>
Classes | |
class | Impl |
Public Member Functions | |
uint32_t | getNumPublishers () const |
Returns the number of publishers this subscriber is connected to. More... | |
std::string | getTopic () const |
operator void * () const | |
bool | operator!= (const Subscriber &rhs) const |
bool | operator< (const Subscriber &rhs) const |
Subscriber & | operator= (const Subscriber &other)=default |
bool | operator== (const Subscriber &rhs) const |
void | shutdown () |
Unsubscribe the callback associated with this Subscriber. More... | |
Subscriber () | |
Subscriber (const Subscriber &rhs) | |
~Subscriber () | |
Private Types | |
typedef boost::shared_ptr< Impl > | ImplPtr |
typedef boost::weak_ptr< Impl > | ImplWPtr |
Private Member Functions | |
Subscriber (const std::string &topic, const NodeHandle &node_handle, const SubscriptionCallbackHelperPtr &helper) | |
Private Attributes | |
ImplPtr | impl_ |
Friends | |
class | NodeHandle |
class | NodeHandleBackingCollection |
Manages an subscription callback on a specific topic.
A Subscriber should always be created through a call to NodeHandle::subscribe(), or copied from one that was. Once all copies of a specific Subscriber go out of scope, the subscription callback associated with that handle will stop being called. Once all Subscriber for a given topic go out of scope the topic will be unsubscribed.
Definition at line 46 of file subscriber.h.
|
private |
Definition at line 108 of file subscriber.h.
|
private |
Definition at line 109 of file subscriber.h.
|
inline |
Definition at line 49 of file subscriber.h.
ros::Subscriber::Subscriber | ( | const Subscriber & | rhs | ) |
Definition at line 70 of file subscriber.cpp.
ros::Subscriber::~Subscriber | ( | ) |
Definition at line 75 of file subscriber.cpp.
|
private |
Definition at line 61 of file subscriber.cpp.
uint32_t ros::Subscriber::getNumPublishers | ( | ) | const |
Returns the number of publishers this subscriber is connected to.
Definition at line 97 of file subscriber.cpp.
std::string ros::Subscriber::getTopic | ( | ) | const |
Definition at line 87 of file subscriber.cpp.
|
inline |
Definition at line 72 of file subscriber.h.
|
inline |
Definition at line 84 of file subscriber.h.
|
inline |
Definition at line 74 of file subscriber.h.
|
default |
|
inline |
Definition at line 79 of file subscriber.h.
void ros::Subscriber::shutdown | ( | ) |
Unsubscribe the callback associated with this Subscriber.
This method usually does not need to be explicitly called, as automatic shutdown happens when all copies of this Subscriber go out of scope
This method overrides the automatic reference counted unsubscribe, and immediately unsubscribes the callback associated with this Subscriber
Definition at line 79 of file subscriber.cpp.
|
friend |
Definition at line 113 of file subscriber.h.
|
friend |
Definition at line 114 of file subscriber.h.
|
private |
Definition at line 111 of file subscriber.h.