roscpp's interface for creating subscribers, publishers, etc. More...
#include <node_handle.h>
Classes | |
struct | no_validate |
Public Member Functions | |
template<class M > | |
Publisher | advertise (const std::string &topic, uint32_t queue_size, bool latch=false) |
Advertise a topic, simple version. | |
template<class M > | |
Publisher | advertise (const std::string &topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb=SubscriberStatusCallback(), const VoidConstPtr &tracked_object=VoidConstPtr(), bool latch=false) |
Advertise a topic, with most of the available options, including subscriber status callbacks. | |
Publisher | advertise (AdvertiseOptions &ops) |
Advertise a topic, with full range of AdvertiseOptions. | |
template<class T , class MReq , class MRes > | |
ServiceServer | advertiseService (const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj) |
Advertise a service, version for class member function with bare pointer. | |
template<class T , class MReq , class MRes > | |
ServiceServer | advertiseService (const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), T *obj) |
Advertise a service, version for class member function with bare pointer using ros::ServiceEvent as the callback parameter type. | |
template<class T , class MReq , class MRes > | |
ServiceServer | advertiseService (const std::string &service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr< T > &obj) |
Advertise a service, version for class member function with shared_ptr. | |
template<class T , class MReq , class MRes > | |
ServiceServer | advertiseService (const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), const boost::shared_ptr< T > &obj) |
Advertise a service, version for class member function with shared_ptr using ros::ServiceEvent as the callback parameter type. | |
template<class MReq , class MRes > | |
ServiceServer | advertiseService (const std::string &service, bool(*srv_func)(MReq &, MRes &)) |
Advertise a service, version for bare function. | |
template<class MReq , class MRes > | |
ServiceServer | advertiseService (const std::string &service, bool(*srv_func)(ServiceEvent< MReq, MRes > &)) |
Advertise a service, version for bare function using ros::ServiceEvent as the callback parameter type. | |
template<class MReq , class MRes > | |
ServiceServer | advertiseService (const std::string &service, const boost::function< bool(MReq &, MRes &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr()) |
Advertise a service, version for arbitrary boost::function object. | |
template<class S > | |
ServiceServer | advertiseService (const std::string &service, const boost::function< bool(S &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr()) |
Advertise a service, version for arbitrary boost::function object using ros::ServiceEvent as the callback parameter type. | |
ServiceServer | advertiseService (AdvertiseServiceOptions &ops) |
Advertise a service, with full range of AdvertiseServiceOptions. | |
template<class Handler , class Obj > | |
Timer | createTimer (Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const |
Create a timer which will call a callback at the specified rate. This variant takes a class member function, and a bare pointer to the object to call the method on. | |
template<class T > | |
Timer | createTimer (Duration period, void(T::*callback)(const TimerEvent &) const, T *obj, bool oneshot=false, bool autostart=true) const |
Create a timer which will call a callback at the specified rate. This variant takes a class member function, and a bare pointer to the object to call the method on. | |
template<class T > | |
Timer | createTimer (Duration period, void(T::*callback)(const TimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const |
Create a timer which will call a callback at the specified rate. This variant takes a class member function, and a bare pointer to the object to call the method on. | |
template<class T > | |
Timer | createTimer (Duration period, void(T::*callback)(const TimerEvent &), const boost::shared_ptr< T > &obj, bool oneshot=false, bool autostart=true) const |
Create a timer which will call a callback at the specified rate. This variant takes a class member function, and a shared pointer to the object to call the method on. | |
Timer | createTimer (Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const |
Create a timer which will call a callback at the specified rate. This variant takes anything that can be bound to a Boost.Function, including a bare function. | |
Timer | createTimer (TimerOptions &ops) const |
Create a timer which will call a callback at the specified rate. This variant allows the full range of TimerOptions. | |
template<class T > | |
WallTimer | createWallTimer (WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const |
Create a timer which will call a callback at the specified rate, using wall time to determine when to call the callback instead of ROS time. This variant takes a class member function, and a bare pointer to the object to call the method on. | |
template<class T > | |
WallTimer | createWallTimer (WallDuration period, void(T::*callback)(const WallTimerEvent &), const boost::shared_ptr< T > &obj, bool oneshot=false, bool autostart=true) const |
Create a timer which will call a callback at the specified rate, using wall time to determine when to call the callback instead of ROS time. This variant takes a class member function, and a shared pointer to the object to call the method on. | |
WallTimer | createWallTimer (WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const |
Create a timer which will call a callback at the specified rate, using wall time to determine when to call the callback instead of ROS time. This variant takes anything that can be bound to a Boost.Function, including a bare function. | |
WallTimer | createWallTimer (WallTimerOptions &ops) const |
Create a timer which will call a callback at the specified rate, using wall time to determine when to call the callback instead of ROS time. This variant allows the full range of TimerOptions. | |
bool | deleteParam (const std::string &key) const |
Delete a parameter from the parameter server. | |
CallbackQueueInterface * | getCallbackQueue () const |
Returns the callback queue associated with this NodeHandle. If none has been explicitly set, returns the global queue. | |
const std::string & | getNamespace () const |
Returns the namespace associated with this NodeHandle. | |
bool | getParam (const std::string &key, std::string &s) const |
Get a string value from the parameter server. | |
bool | getParam (const std::string &key, double &d) const |
Get a double value from the parameter server. | |
bool | getParam (const std::string &key, float &f) const |
Get a float value from the parameter server. | |
bool | getParam (const std::string &key, int &i) const |
Get an integer value from the parameter server. | |
bool | getParam (const std::string &key, bool &b) const |
Get a boolean value from the parameter server. | |
bool | getParam (const std::string &key, XmlRpc::XmlRpcValue &v) const |
Get an arbitrary XML/RPC value from the parameter server. | |
bool | getParam (const std::string &key, std::vector< std::string > &vec) const |
Get a string vector value from the parameter server. | |
bool | getParam (const std::string &key, std::vector< double > &vec) const |
Get a double vector value from the parameter server. | |
bool | getParam (const std::string &key, std::vector< float > &vec) const |
Get a float vector value from the parameter server. | |
bool | getParam (const std::string &key, std::vector< int > &vec) const |
Get an int vector value from the parameter server. | |
bool | getParam (const std::string &key, std::vector< bool > &vec) const |
Get a boolean vector value from the parameter server. | |
bool | getParam (const std::string &key, std::map< std::string, std::string > &map) const |
Get a string map value from the parameter server. | |
bool | getParam (const std::string &key, std::map< std::string, double > &map) const |
Get a double map value from the parameter server. | |
bool | getParam (const std::string &key, std::map< std::string, float > &map) const |
Get a float map value from the parameter server. | |
bool | getParam (const std::string &key, std::map< std::string, int > &map) const |
Get an int map value from the parameter server. | |
bool | getParam (const std::string &key, std::map< std::string, bool > &map) const |
Get a boolean map value from the parameter server. | |
bool | getParamCached (const std::string &key, std::string &s) const |
Get a string value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, double &d) const |
Get a double value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, float &f) const |
Get a float value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, int &i) const |
Get an integer value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, bool &b) const |
Get a boolean value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, XmlRpc::XmlRpcValue &v) const |
Get an arbitrary XML/RPC value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, std::vector< std::string > &vec) const |
Get a std::string vector value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, std::vector< double > &vec) const |
Get a double vector value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, std::vector< float > &vec) const |
Get a float vector value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, std::vector< int > &vec) const |
Get a int vector value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, std::vector< bool > &vec) const |
Get a bool vector value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, std::map< std::string, std::string > &map) const |
Get a string->std::string map value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, std::map< std::string, double > &map) const |
Get a string->double map value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, std::map< std::string, float > &map) const |
Get a string->float map value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, std::map< std::string, int > &map) const |
Get a string->int map value from the parameter server, with local caching. | |
bool | getParamCached (const std::string &key, std::map< std::string, bool > &map) const |
Get a string->bool map value from the parameter server, with local caching. | |
bool | getParamNames (std::vector< std::string > &keys) const |
Get the keys for all the parameters in the parameter server. | |
const std::string & | getUnresolvedNamespace () const |
Returns the namespace associated with this NodeHandle as it was passed in (before it was resolved) | |
bool | hasParam (const std::string &key) const |
Check whether a parameter exists on the parameter server. | |
NodeHandle (const std::string &ns=std::string(), const M_string &remappings=M_string()) | |
Constructor. | |
NodeHandle (const NodeHandle &rhs) | |
Copy constructor. | |
NodeHandle (const NodeHandle &parent, const std::string &ns) | |
Parent constructor. | |
NodeHandle (const NodeHandle &parent, const std::string &ns, const M_string &remappings) | |
Parent constructor. | |
bool | ok () const |
Check whether it's time to exit. | |
NodeHandle & | operator= (const NodeHandle &rhs) |
template<typename T > | |
void | param (const std::string ¶m_name, T ¶m_val, const T &default_val) const |
Assign value from parameter server, with default. | |
template<typename T > | |
T | param (const std::string ¶m_name, const T &default_val) |
Return value from parameter server, or default if unavailable. | |
std::string | resolveName (const std::string &name, bool remap=true) const |
Resolves a name into a fully-qualified name. | |
bool | searchParam (const std::string &key, std::string &result) const |
Search up the tree for a parameter with a given key. | |
template<class MReq , class MRes > | |
ServiceClient | serviceClient (const std::string &service_name, bool persistent=false, const M_string &header_values=M_string()) |
Create a client for a service, version templated on two message types. | |
template<class Service > | |
ServiceClient | serviceClient (const std::string &service_name, bool persistent=false, const M_string &header_values=M_string()) |
Create a client for a service, version templated on service type. | |
ServiceClient | serviceClient (ServiceClientOptions &ops) |
Create a client for a service, version with full range of ServiceClientOptions. | |
void | setCallbackQueue (CallbackQueueInterface *queue) |
Set the default callback queue to be used by this NodeHandle. | |
void | setParam (const std::string &key, const XmlRpc::XmlRpcValue &v) const |
Set an arbitrary XML/RPC value on the parameter server. | |
void | setParam (const std::string &key, const std::string &s) const |
Set a string value on the parameter server. | |
void | setParam (const std::string &key, const char *s) const |
Set a string value on the parameter server. | |
void | setParam (const std::string &key, double d) const |
Set a double value on the parameter server. | |
void | setParam (const std::string &key, int i) const |
Set an integer value on the parameter server. | |
void | setParam (const std::string &key, bool b) const |
Set a boolean value on the parameter server. | |
void | setParam (const std::string &key, const std::vector< std::string > &vec) const |
Set a string vector value on the parameter server. | |
void | setParam (const std::string &key, const std::vector< double > &vec) const |
Set a double vector value on the parameter server. | |
void | setParam (const std::string &key, const std::vector< float > &vec) const |
Set a float vector value on the parameter server. | |
void | setParam (const std::string &key, const std::vector< int > &vec) const |
Set a int vector value on the parameter server. | |
void | setParam (const std::string &key, const std::vector< bool > &vec) const |
Set a bool vector value on the parameter server. | |
void | setParam (const std::string &key, const std::map< std::string, std::string > &map) const |
Set a string vector value on the parameter server. | |
void | setParam (const std::string &key, const std::map< std::string, double > &map) const |
Set a double vector value on the parameter server. | |
void | setParam (const std::string &key, const std::map< std::string, float > &map) const |
Set a float vector value on the parameter server. | |
void | setParam (const std::string &key, const std::map< std::string, int > &map) const |
Set a int vector value on the parameter server. | |
void | setParam (const std::string &key, const std::map< std::string, bool > &map) const |
Set a bool vector value on the parameter server. | |
void | shutdown () |
Shutdown every handle created through this NodeHandle. | |
template<class M , class T > | |
Subscriber | subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints()) |
Subscribe to a topic, version for class member function with bare pointer. | |
template<class M , class T > | |
Subscriber | subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M) const, T *obj, const TransportHints &transport_hints=TransportHints()) |
and the const version | |
template<class M , class T > | |
Subscriber | subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const TransportHints &transport_hints=TransportHints()) |
Subscribe to a topic, version for class member function with bare pointer. | |
template<class M , class T > | |
Subscriber | subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &) const, T *obj, const TransportHints &transport_hints=TransportHints()) |
template<class M , class T > | |
Subscriber | subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints()) |
Subscribe to a topic, version for class member function with shared_ptr. | |
template<class M , class T > | |
Subscriber | subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M) const, const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints()) |
template<class M , class T > | |
Subscriber | subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints()) |
Subscribe to a topic, version for class member function with shared_ptr. | |
template<class M , class T > | |
Subscriber | subscribe (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 TransportHints &transport_hints=TransportHints()) |
template<class M > | |
Subscriber | subscribe (const std::string &topic, uint32_t queue_size, void(*fp)(M), const TransportHints &transport_hints=TransportHints()) |
Subscribe to a topic, version for bare function. | |
template<class M > | |
Subscriber | subscribe (const std::string &topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr< M const > &), const TransportHints &transport_hints=TransportHints()) |
Subscribe to a topic, version for bare function. | |
template<class M > | |
Subscriber | subscribe (const std::string &topic, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints()) |
Subscribe to a topic, version for arbitrary boost::function object. | |
template<class M , class C > | |
Subscriber | subscribe (const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints()) |
Subscribe to a topic, version for arbitrary boost::function object. | |
Subscriber | subscribe (SubscribeOptions &ops) |
Subscribe to a topic, version with full range of SubscribeOptions. | |
~NodeHandle () | |
Destructor. | |
Private Member Functions | |
void | construct (const std::string &ns, bool validate_name) |
void | destruct () |
void | initRemappings (const M_string &remappings) |
std::string | remapName (const std::string &name) const |
std::string | resolveName (const std::string &name, bool remap, no_validate) const |
Private Attributes | |
CallbackQueueInterface * | callback_queue_ |
NodeHandleBackingCollection * | collection_ |
std::string | namespace_ |
bool | ok_ |
M_string | remappings_ |
std::string | unresolved_namespace_ |
M_string | unresolved_remappings_ |
roscpp's interface for creating subscribers, publishers, etc.
This class is used for writing nodes. It provides a RAII interface to this process' node, in that when the first NodeHandle is created, it instantiates everything necessary for this node, and when the last NodeHandle goes out of scope it shuts down the node.
NodeHandle uses reference counting internally, and copying a NodeHandle is very lightweight.
You must call one of the ros::init functions prior to instantiating this class.
The most widely used methods are:
Definition at line 86 of file node_handle.h.
ros::NodeHandle::NodeHandle | ( | const std::string & | ns = std::string() , |
const M_string & | remappings = M_string() |
||
) |
Constructor.
When a NodeHandle is constructed, it checks to see if the global node state has already been started. If so, it increments a global reference count. If not, it starts the node with ros::start() and sets the reference count to 1.
ns | Namespace for this NodeHandle. This acts in addition to any namespace assigned to this ROS node. eg. If the node's namespace is "/a" and the namespace passed in here is "b", all topics/services/parameters will be prefixed with "/a/b/" |
remappings | Remappings for this NodeHandle. |
InvalidNameException | if the namespace is not a valid graph resource name |
Definition at line 71 of file node_handle.cpp.
ros::NodeHandle::NodeHandle | ( | const NodeHandle & | rhs | ) |
Copy constructor.
When a NodeHandle is copied, it inherits the namespace of the NodeHandle being copied, and increments the reference count of the global node state by 1.
Definition at line 113 of file node_handle.cpp.
ros::NodeHandle::NodeHandle | ( | const NodeHandle & | parent, |
const std::string & | ns | ||
) |
Parent constructor.
This version of the constructor takes a "parent" NodeHandle. If the passed "ns" is relative (does not start with a slash), it is equivalent to calling:
NodeHandle child(parent.getNamespace() + "/" + ns);
If the passed "ns" is absolute (does start with a slash), it is equivalent to calling:
NodeHandle child(ns);
When a NodeHandle is copied, it inherits the namespace of the NodeHandle being copied, and increments the reference count of the global node state by 1.
InvalidNameException | if the namespace is not a valid graph resource name |
Definition at line 87 of file node_handle.cpp.
ros::NodeHandle::NodeHandle | ( | const NodeHandle & | parent, |
const std::string & | ns, | ||
const M_string & | remappings | ||
) |
Parent constructor.
This version of the constructor takes a "parent" NodeHandle. If the passed "ns" is relative (does not start with a slash), it is equivalent to calling:
NodeHandle child(parent.getNamespace() + "/" + ns, remappings);
If the passed "ns" is absolute (does start with a slash), it is equivalent to calling:
NodeHandle child(ns, remappings);
This version also lets you pass in name remappings that are specific to this NodeHandle
When a NodeHandle is copied, it inherits the namespace of the NodeHandle being copied, and increments the reference count of the global node state by 1.
InvalidNameException | if the namespace is not a valid graph resource name |
Definition at line 99 of file node_handle.cpp.
Destructor.
When a NodeHandle is destroyed, it decrements a global reference count by 1, and if the reference count is now 0, shuts down the node.
Definition at line 125 of file node_handle.cpp.
Publisher ros::NodeHandle::advertise | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
bool | latch = false |
||
) | [inline] |
Advertise a topic, simple version.
This call connects to the master to publicize that the node will be publishing messages on the given topic. This method returns a Publisher that allows you to publish a message on this topic.
This version of advertise is a templated convenience function, and can be used like so
ros::Publisher pub = handle.advertise<std_msgs::Empty>("my_topic", 1);
topic | Topic to advertise on |
queue_size | Maximum number of outgoing messages to be queued for delivery to subscribers |
latch | (optional) If true, the last message published on this topic will be saved and sent to new subscribers when they connect |
InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name, or is an otherwise invalid graph resource name |
Definition at line 248 of file node_handle.h.
Publisher ros::NodeHandle::advertise | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
const SubscriberStatusCallback & | connect_cb, | ||
const SubscriberStatusCallback & | disconnect_cb = SubscriberStatusCallback() , |
||
const VoidConstPtr & | tracked_object = VoidConstPtr() , |
||
bool | latch = false |
||
) | [inline] |
Advertise a topic, with most of the available options, including subscriber status callbacks.
This call connects to the master to publicize that the node will be publishing messages on the given topic. This method returns a Publisher that allows you to publish a message on this topic.
This version of advertise allows you to pass functions to be called when new subscribers connect and disconnect. With bare functions it can be used like so:
void connectCallback(const ros::SingleSubscriberPublisher& pub) { // Do something } handle.advertise<std_msgs::Empty>("my_topic", 1, (ros::SubscriberStatusCallback)connectCallback);
With class member functions it can be used with boost::bind:
void MyClass::connectCallback(const ros::SingleSubscriberPublisher& pub) { // Do something } MyClass my_class; ros::Publisher pub = handle.advertise<std_msgs::Empty>("my_topic", 1, boost::bind(&MyClass::connectCallback, my_class, _1));
topic | Topic to advertise on |
queue_size | Maximum number of outgoing messages to be queued for delivery to subscribers |
connect_cb | Function to call when a subscriber connects |
disconnect_cb | (optional) Function to call when a subscriber disconnects |
tracked_object | (optional) A shared pointer to an object to track for these callbacks. If set, the a weak_ptr will be created to this object, and if the reference count goes to 0 the subscriber callbacks will not get called. Note that setting this will cause a new reference to be added to the object before the callback, and for it to go out of scope (and potentially be deleted) in the code path (and therefore thread) that the callback is invoked from. |
latch | (optional) If true, the last message published on this topic will be saved and sent to new subscribers when they connect |
ros::NodeHandle nodeHandle; ros::publisher pub = nodeHandle.advertise<std_msgs::Empty>("my_topic", 1, (ros::SubscriberStatusCallback)callback); if (pub) // Enter if publisher is valid { ... }
InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 314 of file node_handle.h.
Advertise a topic, with full range of AdvertiseOptions.
This call connects to the master to publicize that the node will be publishing messages on the given topic. This method returns a Publisher that allows you to publish a message on this topic.
This is an advanced version advertise() that exposes all options (through the AdvertiseOptions structure)
ops | Advertise options to use |
ros::NodeHandle nodeHandle; ros::AdvertiseOptions ops; ... ros::publisher pub = nodeHandle.advertise(ops); if (pub) // Enter if publisher is valid { ... }
InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 283 of file node_handle.cpp.
ServiceServer ros::NodeHandle::advertiseService | ( | const std::string & | service, |
bool(T::*)(MReq &, MRes &) | srv_func, | ||
T * | obj | ||
) | [inline] |
Advertise a service, version for class member function with bare pointer.
This call connects to the master to publicize that the node will be offering an RPC service with the given name.
This is a convenience function for using member functions, and can be used like so:
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response) { return true; } Foo foo_object; ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callback, &foo_object);
service | Service name to advertise on |
srv_func | Member function pointer to call when a message has arrived |
obj | Object to call srv_func on |
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response) { return true; } ros::NodeHandle nodeHandle; Foo foo_object; ros::ServiceServer service = nodeHandle.advertiseService("my_service", &Foo::callback, &foo_object); if (service) // Enter if advertised service is valid { ... }
InvalidNameException | If the service name begins with a tilde, or is an otherwise invalid graph resource name, or is an otherwise invalid graph resource name |
Definition at line 878 of file node_handle.h.
ServiceServer ros::NodeHandle::advertiseService | ( | const std::string & | service, |
bool(T::*)(ServiceEvent< MReq, MRes > &) | srv_func, | ||
T * | obj | ||
) | [inline] |
Advertise a service, version for class member function with bare pointer using ros::ServiceEvent as the callback parameter type.
This call connects to the master to publicize that the node will be offering an RPC service with the given name.
This is a convenience function for using member functions, and can be used like so:
bool Foo::callback(ros::ServiceEvent<std_srvs::Empty::Request, std_srvs::Empty::Response>& event) { return true; } Foo foo_object; ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callback, &foo_object);
service | Service name to advertise on |
srv_func | Member function pointer to call when a message has arrived |
obj | Object to call srv_func on |
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response) { return true; } ros::NodeHandle nodeHandle; Foo foo_object; ros::ServiceServer service = nodeHandle.advertiseService("my_service", &Foo::callback, &foo_object); if (service) // Enter if advertised service is valid { ... }
InvalidNameException | If the service name begins with a tilde, or is an otherwise invalid graph resource name, or is an otherwise invalid graph resource name |
Definition at line 923 of file node_handle.h.
ServiceServer ros::NodeHandle::advertiseService | ( | const std::string & | service, |
bool(T::*)(MReq &, MRes &) | srv_func, | ||
const boost::shared_ptr< T > & | obj | ||
) | [inline] |
Advertise a service, version for class member function with shared_ptr.
This call connects to the master to publicize that the node will be offering an RPC service with the given name.
This is a convenience function for using member functions on shared pointers, and can be used like so:
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response) { return true; } boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>()); ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callback, foo_object);
service | Service name to advertise on |
srv_func | Member function pointer to call when a message has arrived |
obj | Object to call srv_func on. Since this is a shared_ptr, it will automatically be tracked with a weak_ptr, and if the object is deleted the service callback will stop being called (and therefore will not crash). |
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response) { return true; } ros::NodeHandle nodeHandle; Foo foo_object; ros::ServiceServer service = nodeHandle.advertiseService("my_service", &Foo::callback, &foo_object); if (service) // Enter if advertised service is valid { ... }
InvalidNameException | If the service name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 969 of file node_handle.h.
ServiceServer ros::NodeHandle::advertiseService | ( | const std::string & | service, |
bool(T::*)(ServiceEvent< MReq, MRes > &) | srv_func, | ||
const boost::shared_ptr< T > & | obj | ||
) | [inline] |
Advertise a service, version for class member function with shared_ptr using ros::ServiceEvent as the callback parameter type.
This call connects to the master to publicize that the node will be offering an RPC service with the given name.
This is a convenience function for using member functions on shared pointers, and can be used like so:
bool Foo::callback(ros::ServiceEvent<std_srvs::Empty, std_srvs::Empty>& event) { return true; } boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>()); ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callback, foo_object);
service | Service name to advertise on |
srv_func | Member function pointer to call when a message has arrived |
obj | Object to call srv_func on. Since this is a shared_ptr, it will automatically be tracked with a weak_ptr, and if the object is deleted the service callback will stop being called (and therefore will not crash). |
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response) { return true; } ros::NodeHandle nodeHandle; Foo foo_object; ros::ServiceServer service = nodeHandle.advertiseService("my_service", &Foo::callback, &foo_object); if (service) // Enter if advertised service is valid { ... }
InvalidNameException | If the service name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 1016 of file node_handle.h.
ServiceServer ros::NodeHandle::advertiseService | ( | const std::string & | service, |
bool(*)(MReq &, MRes &) | srv_func | ||
) | [inline] |
Advertise a service, version for bare function.
This call connects to the master to publicize that the node will be offering an RPC service with the given name.
This is a convenience function for using bare functions, and can be used like so:
bool callback(std_srvs::Empty& request, std_srvs::Empty& response) { return true; } ros::ServiceServer service = handle.advertiseService("my_service", callback);
service | Service name to advertise on |
srv_func | function pointer to call when a message has arrived |
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response) { return true; } ros::NodeHandle nodeHandle; Foo foo_object; ros::ServiceServer service = nodeHandle.advertiseService("my_service", callback); if (service) // Enter if advertised service is valid { ... }
InvalidNameException | If the service name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 1060 of file node_handle.h.
ServiceServer ros::NodeHandle::advertiseService | ( | const std::string & | service, |
bool(*)(ServiceEvent< MReq, MRes > &) | srv_func | ||
) | [inline] |
Advertise a service, version for bare function using ros::ServiceEvent as the callback parameter type.
This call connects to the master to publicize that the node will be offering an RPC service with the given name.
This is a convenience function for using bare functions, and can be used like so:
bool callback(ros::ServiceEvent<std_srvs::Empty, std_srvs::Empty>& event) { return true; } ros::ServiceServer service = handle.advertiseService("my_service", callback);
service | Service name to advertise on |
srv_func | function pointer to call when a message has arrived |
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response) { return true; } ros::NodeHandle nodeHandle; Foo foo_object; ros::ServiceServer service = nodeHandle.advertiseService("my_service", callback); if (service) // Enter if advertised service is valid { ... }
InvalidNameException | If the service name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 1103 of file node_handle.h.
ServiceServer ros::NodeHandle::advertiseService | ( | const std::string & | service, |
const boost::function< bool(MReq &, MRes &)> & | callback, | ||
const VoidConstPtr & | tracked_object = VoidConstPtr() |
||
) | [inline] |
Advertise a service, version for arbitrary boost::function object.
This call connects to the master to publicize that the node will be offering an RPC service with the given name.
This version of advertiseService allows non-class functions, as well as functor objects and boost::bind (along with anything else boost::function supports).
service | Service name to advertise on |
callback | Callback to call when the service is called |
tracked_object | A shared pointer to an object to track for these callbacks. If set, the a weak_ptr will be created to this object, and if the reference count goes to 0 the subscriber callbacks will not get called. Note that setting this will cause a new reference to be added to the object before the callback, and for it to go out of scope (and potentially be deleted) in the code path (and therefore thread) that the callback is invoked from. |
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response) { return true; } ros::NodeHandle nodeHandle; Foo foo_object; ros::ServiceServer service = nodeHandle.advertiseService("my_service", callback); if (service) // Enter if advertised service is valid { ... }
InvalidNameException | If the service name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 1144 of file node_handle.h.
ServiceServer ros::NodeHandle::advertiseService | ( | const std::string & | service, |
const boost::function< bool(S &)> & | callback, | ||
const VoidConstPtr & | tracked_object = VoidConstPtr() |
||
) | [inline] |
Advertise a service, version for arbitrary boost::function object using ros::ServiceEvent as the callback parameter type.
Note that the template parameter S is the full event type, e.g. ros::ServiceEvent<Req, Res>
This call connects to the master to publicize that the node will be offering an RPC service with the given name.
This version of advertiseService allows non-class functions, as well as functor objects and boost::bind (along with anything else boost::function supports).
service | Service name to advertise on |
callback | Callback to call when the service is called |
tracked_object | A shared pointer to an object to track for these callbacks. If set, the a weak_ptr will be created to this object, and if the reference count goes to 0 the subscriber callbacks will not get called. Note that setting this will cause a new reference to be added to the object before the callback, and for it to go out of scope (and potentially be deleted) in the code path (and therefore thread) that the callback is invoked from. |
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response) { return true; } ros::NodeHandle nodeHandle; Foo foo_object; ros::ServiceServer service = nodeHandle.advertiseService("my_service", callback); if (service) // Enter if advertised service is valid { ... }
InvalidNameException | If the service name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 1189 of file node_handle.h.
Advertise a service, with full range of AdvertiseServiceOptions.
This call connects to the master to publicize that the node will be offering an RPC service with the given name.
This version of advertiseService allows the full set of options, exposed through the AdvertiseServiceOptions class
ops | Advertise options |
AdvertiseServiceOptions ops; ... ros::NodeHandle nodeHandle; ros::ServiceServer service = nodeHandle.advertiseService(ops); if (service) // Enter if advertised service is valid { ... }
InvalidNameException | If the service name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 346 of file node_handle.cpp.
void ros::NodeHandle::construct | ( | const std::string & | ns, |
bool | validate_name | ||
) | [private] |
Definition at line 146 of file node_handle.cpp.
Timer ros::NodeHandle::createTimer | ( | Rate | r, |
Handler | h, | ||
Obj | o, | ||
bool | oneshot = false , |
||
bool | autostart = true |
||
) | const [inline] |
Create a timer which will call a callback at the specified rate. This variant takes a class member function, and a bare pointer to the object to call the method on.
When the Timer (and all copies of it) returned goes out of scope, the timer will automatically be stopped, and the callback will no longer be called.
r | The rate at which to call the callback |
callback | The method to call |
obj | The object to call the method on |
oneshot | If true, this timer will only fire once |
autostart | If true (default), return timer that is already started |
Definition at line 1293 of file node_handle.h.
Timer ros::NodeHandle::createTimer | ( | Duration | period, |
void(T::*)(const TimerEvent &) const | callback, | ||
T * | obj, | ||
bool | oneshot = false , |
||
bool | autostart = true |
||
) | const [inline] |
Create a timer which will call a callback at the specified rate. This variant takes a class member function, and a bare pointer to the object to call the method on.
When the Timer (and all copies of it) returned goes out of scope, the timer will automatically be stopped, and the callback will no longer be called.
period | The period at which to call the callback |
callback | The method to call |
obj | The object to call the method on |
oneshot | If true, this timer will only fire once |
autostart | If true (default), return timer that is already started |
Definition at line 1312 of file node_handle.h.
Timer ros::NodeHandle::createTimer | ( | Duration | period, |
void(T::*)(const TimerEvent &) | callback, | ||
T * | obj, | ||
bool | oneshot = false , |
||
bool | autostart = true |
||
) | const [inline] |
Create a timer which will call a callback at the specified rate. This variant takes a class member function, and a bare pointer to the object to call the method on.
When the Timer (and all copies of it) returned goes out of scope, the timer will automatically be stopped, and the callback will no longer be called.
period | The period at which to call the callback |
callback | The method to call |
obj | The object to call the method on |
oneshot | If true, this timer will only fire once |
autostart | If true (default), return timer that is already started |
Definition at line 1332 of file node_handle.h.
Timer ros::NodeHandle::createTimer | ( | Duration | period, |
void(T::*)(const TimerEvent &) | callback, | ||
const boost::shared_ptr< T > & | obj, | ||
bool | oneshot = false , |
||
bool | autostart = true |
||
) | const [inline] |
Create a timer which will call a callback at the specified rate. This variant takes a class member function, and a shared pointer to the object to call the method on.
When the Timer (and all copies of it) returned goes out of scope, the timer will automatically be stopped, and the callback will no longer be called.
period | The period at which to call the callback |
callback | The method to call |
obj | The object to call the method on. Since this is a shared pointer, the object will automatically be tracked with a weak_ptr so that if it is deleted before the Timer goes out of scope the callback will no longer be called (and therefore will not crash). |
oneshot | If true, this timer will only fire once |
autostart | If true (default), return timer that is already started |
Definition at line 1354 of file node_handle.h.
Timer ros::NodeHandle::createTimer | ( | Duration | period, |
const TimerCallback & | callback, | ||
bool | oneshot = false , |
||
bool | autostart = true |
||
) | const |
Create a timer which will call a callback at the specified rate. This variant takes anything that can be bound to a Boost.Function, including a bare function.
When the Timer (and all copies of it) returned goes out of scope, the timer will automatically be stopped, and the callback will no longer be called.
period | The period at which to call the callback |
callback | The function to call |
oneshot | If true, this timer will only fire once |
autostart | If true (default), return timer that is already started |
Definition at line 390 of file node_handle.cpp.
Timer ros::NodeHandle::createTimer | ( | TimerOptions & | ops | ) | const |
Create a timer which will call a callback at the specified rate. This variant allows the full range of TimerOptions.
When the Timer (and all copies of it) returned goes out of scope, the timer will automatically be stopped, and the callback will no longer be called.
ops | The options to use when creating the timer |
Definition at line 401 of file node_handle.cpp.
WallTimer ros::NodeHandle::createWallTimer | ( | WallDuration | period, |
void(T::*)(const WallTimerEvent &) | callback, | ||
T * | obj, | ||
bool | oneshot = false , |
||
bool | autostart = true |
||
) | const [inline] |
Create a timer which will call a callback at the specified rate, using wall time to determine when to call the callback instead of ROS time. This variant takes a class member function, and a bare pointer to the object to call the method on.
When the Timer (and all copies of it) returned goes out of scope, the timer will automatically be stopped, and the callback will no longer be called.
period | The period at which to call the callback |
callback | The method to call |
obj | The object to call the method on |
oneshot | If true, this timer will only fire once |
autostart | If true (default), return timer that is already started |
Definition at line 1409 of file node_handle.h.
WallTimer ros::NodeHandle::createWallTimer | ( | WallDuration | period, |
void(T::*)(const WallTimerEvent &) | callback, | ||
const boost::shared_ptr< T > & | obj, | ||
bool | oneshot = false , |
||
bool | autostart = true |
||
) | const [inline] |
Create a timer which will call a callback at the specified rate, using wall time to determine when to call the callback instead of ROS time. This variant takes a class member function, and a shared pointer to the object to call the method on.
When the Timer (and all copies of it) returned goes out of scope, the timer will automatically be stopped, and the callback will no longer be called.
period | The period at which to call the callback |
callback | The method to call |
obj | The object to call the method on. Since this is a shared pointer, the object will automatically be tracked with a weak_ptr so that if it is deleted before the Timer goes out of scope the callback will no longer be called (and therefore will not crash). |
oneshot | If true, this timer will only fire once |
Definition at line 1431 of file node_handle.h.
WallTimer ros::NodeHandle::createWallTimer | ( | WallDuration | period, |
const WallTimerCallback & | callback, | ||
bool | oneshot = false , |
||
bool | autostart = true |
||
) | const |
Create a timer which will call a callback at the specified rate, using wall time to determine when to call the callback instead of ROS time. This variant takes anything that can be bound to a Boost.Function, including a bare function.
When the Timer (and all copies of it) returned goes out of scope, the timer will automatically be stopped, and the callback will no longer be called.
period | The period at which to call the callback |
callback | The function to call |
oneshot | If true, this timer will only fire once |
Definition at line 421 of file node_handle.cpp.
WallTimer ros::NodeHandle::createWallTimer | ( | WallTimerOptions & | ops | ) | const |
Create a timer which will call a callback at the specified rate, using wall time to determine when to call the callback instead of ROS time. This variant allows the full range of TimerOptions.
When the Timer (and all copies of it) returned goes out of scope, the timer will automatically be stopped, and the callback will no longer be called.
ops | The options to use when creating the timer |
Definition at line 432 of file node_handle.cpp.
bool ros::NodeHandle::deleteParam | ( | const std::string & | key | ) | const |
Delete a parameter from the parameter server.
key | The key to delete. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 590 of file node_handle.cpp.
void ros::NodeHandle::destruct | ( | ) | [private] |
Definition at line 178 of file node_handle.cpp.
CallbackQueueInterface* ros::NodeHandle::getCallbackQueue | ( | ) | const [inline] |
Returns the callback queue associated with this NodeHandle. If none has been explicitly set, returns the global queue.
Definition at line 182 of file node_handle.h.
const std::string& ros::NodeHandle::getNamespace | ( | ) | const [inline] |
Returns the namespace associated with this NodeHandle.
Definition at line 190 of file node_handle.h.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
std::string & | s | ||
) | const |
Get a string value from the parameter server.
key | The key to be used in the parameter server's dictionary | |
[out] | s | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 605 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
double & | d | ||
) | const |
Get a double value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | d | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 610 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
float & | f | ||
) | const |
Get a float value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | f | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 615 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
int & | i | ||
) | const |
Get an integer value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | i | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 620 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
bool & | b | ||
) | const |
Get a boolean value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | b | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 625 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
XmlRpc::XmlRpcValue & | v | ||
) | const |
Get an arbitrary XML/RPC value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | v | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 600 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
std::vector< std::string > & | vec | ||
) | const |
Get a string vector value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | vec | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 631 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
std::vector< double > & | vec | ||
) | const |
Get a double vector value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | vec | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 635 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
std::vector< float > & | vec | ||
) | const |
Get a float vector value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | vec | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 639 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
std::vector< int > & | vec | ||
) | const |
Get an int vector value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | vec | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 643 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
std::vector< bool > & | vec | ||
) | const |
Get a boolean vector value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | vec | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 647 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
std::map< std::string, std::string > & | map | ||
) | const |
Get a string map value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | map | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 652 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
std::map< std::string, double > & | map | ||
) | const |
Get a double map value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | map | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 656 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
std::map< std::string, float > & | map | ||
) | const |
Get a float map value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | map | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 660 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
std::map< std::string, int > & | map | ||
) | const |
Get an int map value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | map | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 664 of file node_handle.cpp.
bool ros::NodeHandle::getParam | ( | const std::string & | key, |
std::map< std::string, bool > & | map | ||
) | const |
Get a boolean map value from the parameter server.
If you want to provide a default value in case the key does not exist use param().
key | The key to be used in the parameter server's dictionary | |
[out] | map | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 668 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
std::string & | s | ||
) | const |
Get a string value from the parameter server, with local caching.
If you want to provide a default value in case the key does not exist use param().
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | s | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 678 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
double & | d | ||
) | const |
Get a double value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | d | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 683 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
float & | f | ||
) | const |
Get a float value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | f | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 688 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
int & | i | ||
) | const |
Get an integer value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | i | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 693 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
bool & | b | ||
) | const |
Get a boolean value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | b | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 698 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
XmlRpc::XmlRpcValue & | v | ||
) | const |
Get an arbitrary XML/RPC value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | v | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 673 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
std::vector< std::string > & | vec | ||
) | const |
Get a std::string vector value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | vec | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 703 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
std::vector< double > & | vec | ||
) | const |
Get a double vector value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | vec | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 707 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
std::vector< float > & | vec | ||
) | const |
Get a float vector value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | vec | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 711 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
std::vector< int > & | vec | ||
) | const |
Get a int vector value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | vec | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 715 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
std::vector< bool > & | vec | ||
) | const |
Get a bool vector value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | vec | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 719 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
std::map< std::string, std::string > & | map | ||
) | const |
Get a string->std::string map value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | map | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 724 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
std::map< std::string, double > & | map | ||
) | const |
Get a string->double map value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | map | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 728 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
std::map< std::string, float > & | map | ||
) | const |
Get a string->float map value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | map | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 732 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
std::map< std::string, int > & | map | ||
) | const |
Get a string->int map value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | map | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 736 of file node_handle.cpp.
bool ros::NodeHandle::getParamCached | ( | const std::string & | key, |
std::map< std::string, bool > & | map | ||
) | const |
Get a string->bool map value from the parameter server, with local caching.
This method will cache parameters locally, and subscribe for updates from the parameter server. Once the parameter is retrieved for the first time no subsequent getCached() calls with the same key will query the master -- they will instead look up in the local cache.
key | The key to be used in the parameter server's dictionary | |
[out] | map | Storage for the retrieved value. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 740 of file node_handle.cpp.
bool ros::NodeHandle::getParamNames | ( | std::vector< std::string > & | keys | ) | const |
Get the keys for all the parameters in the parameter server.
keys | The keys retrieved. |
Definition at line 595 of file node_handle.cpp.
const std::string& ros::NodeHandle::getUnresolvedNamespace | ( | ) | const [inline] |
Returns the namespace associated with this NodeHandle as it was passed in (before it was resolved)
Definition at line 196 of file node_handle.h.
bool ros::NodeHandle::hasParam | ( | const std::string & | key | ) | const |
Check whether a parameter exists on the parameter server.
key | The key to check. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 585 of file node_handle.cpp.
void ros::NodeHandle::initRemappings | ( | const M_string & | remappings | ) | [private] |
Definition at line 192 of file node_handle.cpp.
bool ros::NodeHandle::ok | ( | ) | const |
Check whether it's time to exit.
This method checks to see if both ros::ok() is true and shutdown() has not been called on this NodeHandle, to see whether it's yet time to exit. ok() is false once either ros::shutdown() or NodeHandle::shutdown() have been called
Definition at line 761 of file node_handle.cpp.
NodeHandle & ros::NodeHandle::operator= | ( | const NodeHandle & | rhs | ) |
Definition at line 130 of file node_handle.cpp.
void ros::NodeHandle::param | ( | const std::string & | param_name, |
T & | param_val, | ||
const T & | default_val | ||
) | const [inline] |
Assign value from parameter server, with default.
This method tries to retrieve the indicated parameter value from the parameter server, storing the result in param_val. If the value cannot be retrieved from the server, default_val is used instead.
param_name | The key to be searched on the parameter server. | |
[out] | param_val | Storage for the retrieved value. |
default_val | Value to use if the server doesn't contain this parameter. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 2039 of file node_handle.h.
T ros::NodeHandle::param | ( | const std::string & | param_name, |
const T & | default_val | ||
) | [inline] |
Return value from parameter server, or default if unavailable.
This method tries to retrieve the indicated parameter value from the parameter server. If the parameter cannot be retrieved, default_val
is returned instead.
param_name | The key to be searched on the parameter server. |
default_val | Value to return if the server doesn't contain this parameter. |
default_val
if unavailable.InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name. |
Definition at line 2071 of file node_handle.h.
std::string ros::NodeHandle::remapName | ( | const std::string & | name | ) | const [private] |
Definition at line 213 of file node_handle.cpp.
std::string ros::NodeHandle::resolveName | ( | const std::string & | name, |
bool | remap = true |
||
) | const |
Resolves a name into a fully-qualified name.
Resolves a name into a fully qualified name, eg. "blah" => "/namespace/blah". By default also applies any matching name-remapping rules (which were usually supplied on the command line at startup) to the given name, returning the resulting remapped name.
name | Name to remap |
remap | Whether to apply name-remapping rules |
InvalidNameException | If the name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 229 of file node_handle.cpp.
std::string ros::NodeHandle::resolveName | ( | const std::string & | name, |
bool | remap, | ||
no_validate | |||
) | const [private] |
Definition at line 241 of file node_handle.cpp.
bool ros::NodeHandle::searchParam | ( | const std::string & | key, |
std::string & | result | ||
) | const |
Search up the tree for a parameter with a given key.
This function parameter server's searchParam feature to search up the tree for a parameter. For example, if the parameter server has a parameter [/a/b] and you're in the namespace [/a/c/d], searching for the parameter "b" will yield [/a/b]. If [/a/c/d/b] existed, that parameter would be returned instead.
key | the parameter to search for | |
[out] | result | the found value (if any) |
Definition at line 745 of file node_handle.cpp.
ServiceClient ros::NodeHandle::serviceClient | ( | const std::string & | service_name, |
bool | persistent = false , |
||
const M_string & | header_values = M_string() |
||
) | [inline] |
Create a client for a service, version templated on two message types.
When the last handle reference of a persistent connection is cleared, the connection will automatically close.
service_name | The name of the service to connect to |
persistent | Whether this connection should persist. Persistent services keep the connection to the remote host active so that subsequent calls will happen faster. In general persistent services are discouraged, as they are not as robust to node failure as non-persistent services. |
header_values | Key/value pairs you'd like to send along in the connection handshake |
InvalidNameException | If the service name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 1239 of file node_handle.h.
ServiceClient ros::NodeHandle::serviceClient | ( | const std::string & | service_name, |
bool | persistent = false , |
||
const M_string & | header_values = M_string() |
||
) | [inline] |
Create a client for a service, version templated on service type.
When the last handle reference of a persistent connection is cleared, the connection will automatically close.
service_name | The name of the service to connect to |
persistent | Whether this connection should persist. Persistent services keep the connection to the remote host active so that subsequent calls will happen faster. In general persistent services are discouraged, as they are not as robust to node failure as non-persistent services. |
header_values | Key/value pairs you'd like to send along in the connection handshake |
InvalidNameException | If the service name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 1259 of file node_handle.h.
Create a client for a service, version with full range of ServiceClientOptions.
When the last handle reference of a persistent connection is cleared, the connection will automatically close.
ops | The options for this service client |
InvalidNameException | If the service name begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 376 of file node_handle.cpp.
void ros::NodeHandle::setCallbackQueue | ( | CallbackQueueInterface * | queue | ) |
Set the default callback queue to be used by this NodeHandle.
Setting this will cause any callbacks from advertisements/subscriptions/services/etc. to happen through the use of the specified queue. NULL (the default) causes the global queue (serviced by ros::spin() and ros::spinOnce()) to be used.
Definition at line 208 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const XmlRpc::XmlRpcValue & | v | ||
) | const |
Set an arbitrary XML/RPC value on the parameter server.
key | The key to be used in the parameter server's dictionary |
v | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 513 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const std::string & | s | ||
) | const |
Set a string value on the parameter server.
key | The key to be used in the parameter server's dictionary |
s | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 518 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const char * | s | ||
) | const |
Set a string value on the parameter server.
key | The key to be used in the parameter server's dictionary |
s | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 523 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
double | d | ||
) | const |
Set a double value on the parameter server.
key | The key to be used in the parameter server's dictionary |
d | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 528 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
int | i | ||
) | const |
Set an integer value on the parameter server.
key | The key to be used in the parameter server's dictionary |
i | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 533 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
bool | b | ||
) | const |
Set a boolean value on the parameter server.
key | The key to be used in the parameter server's dictionary |
b | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 538 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const std::vector< std::string > & | vec | ||
) | const |
Set a string vector value on the parameter server.
key | The key to be used in the parameter server's dictionary |
vec | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 543 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const std::vector< double > & | vec | ||
) | const |
Set a double vector value on the parameter server.
key | The key to be used in the parameter server's dictionary |
vec | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 547 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const std::vector< float > & | vec | ||
) | const |
Set a float vector value on the parameter server.
key | The key to be used in the parameter server's dictionary |
vec | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 551 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const std::vector< int > & | vec | ||
) | const |
Set a int vector value on the parameter server.
key | The key to be used in the parameter server's dictionary |
vec | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 555 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const std::vector< bool > & | vec | ||
) | const |
Set a bool vector value on the parameter server.
key | The key to be used in the parameter server's dictionary |
vec | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 559 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const std::map< std::string, std::string > & | map | ||
) | const |
Set a string vector value on the parameter server.
key | The key to be used in the parameter server's dictionary |
map | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 564 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const std::map< std::string, double > & | map | ||
) | const |
Set a double vector value on the parameter server.
key | The key to be used in the parameter server's dictionary |
map | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 568 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const std::map< std::string, float > & | map | ||
) | const |
Set a float vector value on the parameter server.
key | The key to be used in the parameter server's dictionary |
map | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 572 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const std::map< std::string, int > & | map | ||
) | const |
Set a int vector value on the parameter server.
key | The key to be used in the parameter server's dictionary |
map | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 576 of file node_handle.cpp.
void ros::NodeHandle::setParam | ( | const std::string & | key, |
const std::map< std::string, bool > & | map | ||
) | const |
Set a bool vector value on the parameter server.
key | The key to be used in the parameter server's dictionary |
map | The value to be inserted. |
InvalidNameException | If the parameter key begins with a tilde, or is an otherwise invalid graph resource name |
Definition at line 580 of file node_handle.cpp.
void ros::NodeHandle::shutdown | ( | ) |
Shutdown every handle created through this NodeHandle.
This method will unadvertise every topic and service advertisement, and unsubscribe every subscription created through this NodeHandle.
Definition at line 452 of file node_handle.cpp.
Subscriber ros::NodeHandle::subscribe | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
void(T::*)(M) | fp, | ||
T * | obj, | ||
const TransportHints & | transport_hints = TransportHints() |
||
) | [inline] |
Subscribe to a topic, version for class member function with bare pointer.
This method connects to the master to register interest in a given topic. The node will automatically be connected with publishers on this topic. On each message receipt, fp is invoked and passed a shared pointer to the message received. This message should not be changed in place, as it is shared with any other subscriptions to this topic.
This version of subscribe is a convenience function for using member functions, and can be used like so:
void Foo::callback(const std_msgs::Empty::ConstPtr& message) { } Foo foo_object; ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, &foo_object);
M | [template] M here is the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&), not the message type, and should almost always be deduced |
topic | Topic to subscribe to |
queue_size | Number of incoming messages to queue up for processing (messages in excess of this queue capacity will be discarded). |
fp | Member function pointer to call when a message has arrived |
obj | Object to call fp on |
transport_hints | a TransportHints structure which defines various transport-related options |
ros::NodeHandle nodeHandle; void Foo::callback(const std_msgs::Empty::ConstPtr& message) {} boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>()); ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object); if (sub) // Enter if subscriber is valid { ... }
InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name |
ConflictingSubscriptionException | If this node is already subscribed to the same topic with a different datatype |
Definition at line 401 of file node_handle.h.
Subscriber ros::NodeHandle::subscribe | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
void(T::*)(M) const | fp, | ||
T * | obj, | ||
const TransportHints & | transport_hints = TransportHints() |
||
) | [inline] |
and the const version
Definition at line 412 of file node_handle.h.
Subscriber ros::NodeHandle::subscribe | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
void(T::*)(const boost::shared_ptr< M const > &) | fp, | ||
T * | obj, | ||
const TransportHints & | transport_hints = TransportHints() |
||
) | [inline] |
Subscribe to a topic, version for class member function with bare pointer.
This method connects to the master to register interest in a given topic. The node will automatically be connected with publishers on this topic. On each message receipt, fp is invoked and passed a shared pointer to the message received. This message should not be changed in place, as it is shared with any other subscriptions to this topic.
This version of subscribe is a convenience function for using member functions, and can be used like so:
void Foo::callback(const std_msgs::Empty::ConstPtr& message) { } Foo foo_object; ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, &foo_object);
M | [template] M here is the message type |
topic | Topic to subscribe to |
queue_size | Number of incoming messages to queue up for processing (messages in excess of this queue capacity will be discarded). |
fp | Member function pointer to call when a message has arrived |
obj | Object to call fp on |
transport_hints | a TransportHints structure which defines various transport-related options |
ros::NodeHandle nodeHandle; void Foo::callback(const std_msgs::Empty::ConstPtr& message) {} boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>()); ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object); if (sub) // Enter if subscriber is valid { ... }
InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name |
ConflictingSubscriptionException | If this node is already subscribed to the same topic with a different datatype |
Definition at line 464 of file node_handle.h.
Subscriber ros::NodeHandle::subscribe | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
void(T::*)(const boost::shared_ptr< M const > &) const | fp, | ||
T * | obj, | ||
const TransportHints & | transport_hints = TransportHints() |
||
) | [inline] |
Definition at line 474 of file node_handle.h.
Subscriber ros::NodeHandle::subscribe | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
void(T::*)(M) | fp, | ||
const boost::shared_ptr< T > & | obj, | ||
const TransportHints & | transport_hints = TransportHints() |
||
) | [inline] |
Subscribe to a topic, version for class member function with shared_ptr.
This method connects to the master to register interest in a given topic. The node will automatically be connected with publishers on this topic. On each message receipt, fp is invoked and passed a shared pointer to the message received. This message should not be changed in place, as it is shared with any other subscriptions to this topic.
This version of subscribe is a convenience function for using member functions on a shared_ptr:
void Foo::callback(const std_msgs::Empty::ConstPtr& message) { } boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>()); ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object);
M | [template] M here is the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&), not the message type, and should almost always be deduced |
topic | Topic to subscribe to |
queue_size | Number of incoming messages to queue up for processing (messages in excess of this queue capacity will be discarded). |
fp | Member function pointer to call when a message has arrived |
obj | Object to call fp on. Since this is a shared pointer, the object will automatically be tracked with a weak_ptr so that if it is deleted before the Subscriber goes out of scope the callback will no longer be called (and therefore will not crash). |
transport_hints | a TransportHints structure which defines various transport-related options |
ros::NodeHandle nodeHandle; void Foo::callback(const std_msgs::Empty::ConstPtr& message) {} boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>()); ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object); if (sub) // Enter if subscriber is valid { ... }
InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name |
ConflictingSubscriptionException | If this node is already subscribed to the same topic with a different datatype |
Definition at line 528 of file node_handle.h.
Subscriber ros::NodeHandle::subscribe | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
void(T::*)(M) const | fp, | ||
const boost::shared_ptr< T > & | obj, | ||
const TransportHints & | transport_hints = TransportHints() |
||
) | [inline] |
Definition at line 539 of file node_handle.h.
Subscriber ros::NodeHandle::subscribe | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
void(T::*)(const boost::shared_ptr< M const > &) | fp, | ||
const boost::shared_ptr< T > & | obj, | ||
const TransportHints & | transport_hints = TransportHints() |
||
) | [inline] |
Subscribe to a topic, version for class member function with shared_ptr.
This method connects to the master to register interest in a given topic. The node will automatically be connected with publishers on this topic. On each message receipt, fp is invoked and passed a shared pointer to the message received. This message should not be changed in place, as it is shared with any other subscriptions to this topic.
This version of subscribe is a convenience function for using member functions on a shared_ptr:
void Foo::callback(const std_msgs::Empty::ConstPtr& message) { } boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>()); ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object);
M | [template] M here is the message type |
topic | Topic to subscribe to |
queue_size | Number of incoming messages to queue up for processing (messages in excess of this queue capacity will be discarded). |
fp | Member function pointer to call when a message has arrived |
obj | Object to call fp on. Since this is a shared pointer, the object will automatically be tracked with a weak_ptr so that if it is deleted before the Subscriber goes out of scope the callback will no longer be called (and therefore will not crash). |
transport_hints | a TransportHints structure which defines various transport-related options |
ros::NodeHandle nodeHandle; void Foo::callback(const std_msgs::Empty::ConstPtr& message) {} boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>()); ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object); if (sub) // Enter if subscriber is valid { ... }
InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name |
ConflictingSubscriptionException | If this node is already subscribed to the same topic with a different datatype |
Definition at line 593 of file node_handle.h.
Subscriber ros::NodeHandle::subscribe | ( | 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 TransportHints & | transport_hints = TransportHints() |
||
) | [inline] |
Definition at line 604 of file node_handle.h.
Subscriber ros::NodeHandle::subscribe | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
void(*)(M) | fp, | ||
const TransportHints & | transport_hints = TransportHints() |
||
) | [inline] |
Subscribe to a topic, version for bare function.
This method connects to the master to register interest in a given topic. The node will automatically be connected with publishers on this topic. On each message receipt, fp is invoked and passed a shared pointer to the message received. This message should not be changed in place, as it is shared with any other subscriptions to this topic.
This version of subscribe is a convenience function for using bare functions, and can be used like so:
void callback(const std_msgs::Empty::ConstPtr& message) { } ros::Subscriber sub = handle.subscribe("my_topic", 1, callback);
M | [template] M here is the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&), not the message type, and should almost always be deduced |
topic | Topic to subscribe to |
queue_size | Number of incoming messages to queue up for processing (messages in excess of this queue capacity will be discarded). |
fp | Function pointer to call when a message has arrived |
transport_hints | a TransportHints structure which defines various transport-related options |
void callback(const std_msgs::Empty::ConstPtr& message){...} ros::NodeHandle nodeHandle; ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, callback); if (sub) // Enter if subscriber is valid { ... }
InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name |
ConflictingSubscriptionException | If this node is already subscribed to the same topic with a different datatype |
Definition at line 655 of file node_handle.h.
Subscriber ros::NodeHandle::subscribe | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
void(*)(const boost::shared_ptr< M const > &) | fp, | ||
const TransportHints & | transport_hints = TransportHints() |
||
) | [inline] |
Subscribe to a topic, version for bare function.
This method connects to the master to register interest in a given topic. The node will automatically be connected with publishers on this topic. On each message receipt, fp is invoked and passed a shared pointer to the message received. This message should not be changed in place, as it is shared with any other subscriptions to this topic.
This version of subscribe is a convenience function for using bare functions, and can be used like so:
void callback(const std_msgs::Empty::ConstPtr& message) { } ros::Subscriber sub = handle.subscribe("my_topic", 1, callback);
M | [template] M here is the message type |
topic | Topic to subscribe to |
queue_size | Number of incoming messages to queue up for processing (messages in excess of this queue capacity will be discarded). |
fp | Function pointer to call when a message has arrived |
transport_hints | a TransportHints structure which defines various transport-related options |
void callback(const std_msgs::Empty::ConstPtr& message){...} ros::NodeHandle nodeHandle; ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, callback); if (sub) // Enter if subscriber is valid { ... }
InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name |
ConflictingSubscriptionException | If this node is already subscribed to the same topic with a different datatype |
Definition at line 703 of file node_handle.h.
Subscriber ros::NodeHandle::subscribe | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
const boost::function< void(const boost::shared_ptr< M const > &)> & | callback, | ||
const VoidConstPtr & | tracked_object = VoidConstPtr() , |
||
const TransportHints & | transport_hints = TransportHints() |
||
) | [inline] |
Subscribe to a topic, version for arbitrary boost::function object.
This method connects to the master to register interest in a given topic. The node will automatically be connected with publishers on this topic. On each message receipt, callback is invoked and passed a shared pointer to the message received. This message should not be changed in place, as it is shared with any other subscriptions to this topic.
This version of subscribe allows anything bindable to a boost::function object
M | [template] M here is the message type |
topic | Topic to subscribe to |
queue_size | Number of incoming messages to queue up for processing (messages in excess of this queue capacity will be discarded). |
callback | Callback to call when a message has arrived |
tracked_object | A shared pointer to an object to track for these callbacks. If set, the a weak_ptr will be created to this object, and if the reference count goes to 0 the subscriber callbacks will not get called. Note that setting this will cause a new reference to be added to the object before the callback, and for it to go out of scope (and potentially be deleted) in the code path (and therefore thread) that the callback is invoked from. |
transport_hints | a TransportHints structure which defines various transport-related options |
void callback(const std_msgs::Empty::ConstPtr& message){...} ros::NodeHandle nodeHandle; ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, callback); if (sub) // Enter if subscriber is valid { ... }
InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name |
ConflictingSubscriptionException | If this node is already subscribed to the same topic with a different datatype |
Definition at line 749 of file node_handle.h.
Subscriber ros::NodeHandle::subscribe | ( | const std::string & | topic, |
uint32_t | queue_size, | ||
const boost::function< void(C)> & | callback, | ||
const VoidConstPtr & | tracked_object = VoidConstPtr() , |
||
const TransportHints & | transport_hints = TransportHints() |
||
) | [inline] |
Subscribe to a topic, version for arbitrary boost::function object.
This method connects to the master to register interest in a given topic. The node will automatically be connected with publishers on this topic. On each message receipt, callback is invoked and passed a shared pointer to the message received. This message should not be changed in place, as it is shared with any other subscriptions to this topic.
This version of subscribe allows anything bindable to a boost::function object
M | [template] the message type |
C | [template] the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&) |
topic | Topic to subscribe to |
queue_size | Number of incoming messages to queue up for processing (messages in excess of this queue capacity will be discarded). |
callback | Callback to call when a message has arrived |
tracked_object | A shared pointer to an object to track for these callbacks. If set, the a weak_ptr will be created to this object, and if the reference count goes to 0 the subscriber callbacks will not get called. Note that setting this will cause a new reference to be added to the object before the callback, and for it to go out of scope (and potentially be deleted) in the code path (and therefore thread) that the callback is invoked from. |
transport_hints | a TransportHints structure which defines various transport-related options |
void callback(const std_msgs::Empty::ConstPtr& message){...} ros::NodeHandle nodeHandle; ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, callback); if (sub) // Enter if subscriber is valid { ... }
InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name |
ConflictingSubscriptionException | If this node is already subscribed to the same topic with a different datatype |
Definition at line 798 of file node_handle.h.
Subscribe to a topic, version with full range of SubscribeOptions.
This method connects to the master to register interest in a given topic. The node will automatically be connected with publishers on this topic. On each message receipt, fp is invoked and passed a shared pointer to the message received. This message should not be changed in place, as it is shared with any other subscriptions to this topic.
This version of subscribe allows the full range of options, exposed through the SubscribeOptions class
ops | Subscribe options |
SubscribeOptions ops; ... ros::NodeHandle nodeHandle; ros::Subscriber sub = nodeHandle.subscribe(ops); if (sub) // Enter if subscriber is valid { ... }
InvalidNameException | If the topic name begins with a tilde, or is an otherwise invalid graph resource name |
ConflictingSubscriptionException | If this node is already subscribed to the same topic with a different datatype |
Definition at line 316 of file node_handle.cpp.
Definition at line 2112 of file node_handle.h.
Definition at line 2114 of file node_handle.h.
std::string ros::NodeHandle::namespace_ [private] |
Definition at line 2107 of file node_handle.h.
bool ros::NodeHandle::ok_ [private] |
Definition at line 2116 of file node_handle.h.
M_string ros::NodeHandle::remappings_ [private] |
Definition at line 2109 of file node_handle.h.
std::string ros::NodeHandle::unresolved_namespace_ [private] |
Definition at line 2108 of file node_handle.h.
Definition at line 2110 of file node_handle.h.