Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
ros::NodeHandle Class Reference

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. More...
 
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. More...
 
Publisher advertise (AdvertiseOptions &ops)
 Advertise a topic, with full range of AdvertiseOptions. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
template<class MReq , class MRes >
ServiceServer advertiseService (const std::string &service, bool(*srv_func)(MReq &, MRes &))
 Advertise a service, version for bare function. More...
 
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. More...
 
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. More...
 
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. More...
 
ServiceServer advertiseService (AdvertiseServiceOptions &ops)
 Advertise a service, with full range of AdvertiseServiceOptions. More...
 
template<class T >
SteadyTimer createSteadyTimer (WallDuration period, void(T::*callback)(const SteadyTimerEvent &), 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. More...
 
template<class T >
SteadyTimer createSteadyTimer (WallDuration period, void(T::*callback)(const SteadyTimerEvent &), 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. More...
 
SteadyTimer createSteadyTimer (WallDuration period, const SteadyTimerCallback &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. More...
 
SteadyTimer createSteadyTimer (SteadyTimerOptions &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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
bool deleteParam (const std::string &key) const
 Delete a parameter from the parameter server. More...
 
CallbackQueueInterfacegetCallbackQueue () const
 Returns the callback queue associated with this NodeHandle. If none has been explicitly set, returns the global queue. More...
 
const std::string & getNamespace () const
 Returns the namespace associated with this NodeHandle. More...
 
bool getParam (const std::string &key, std::string &s) const
 Get a string value from the parameter server. More...
 
bool getParam (const std::string &key, double &d) const
 Get a double value from the parameter server. More...
 
bool getParam (const std::string &key, float &f) const
 Get a float value from the parameter server. More...
 
bool getParam (const std::string &key, int &i) const
 Get an integer value from the parameter server. More...
 
bool getParam (const std::string &key, bool &b) const
 Get a boolean value from the parameter server. More...
 
bool getParam (const std::string &key, XmlRpc::XmlRpcValue &v) const
 Get an arbitrary XML/RPC value from the parameter server. More...
 
bool getParam (const std::string &key, std::vector< std::string > &vec) const
 Get a string vector value from the parameter server. More...
 
bool getParam (const std::string &key, std::vector< double > &vec) const
 Get a double vector value from the parameter server. More...
 
bool getParam (const std::string &key, std::vector< float > &vec) const
 Get a float vector value from the parameter server. More...
 
bool getParam (const std::string &key, std::vector< int > &vec) const
 Get an int vector value from the parameter server. More...
 
bool getParam (const std::string &key, std::vector< bool > &vec) const
 Get a boolean vector value from the parameter server. More...
 
bool getParam (const std::string &key, std::map< std::string, std::string > &map) const
 Get a string map value from the parameter server. More...
 
bool getParam (const std::string &key, std::map< std::string, double > &map) const
 Get a double map value from the parameter server. More...
 
bool getParam (const std::string &key, std::map< std::string, float > &map) const
 Get a float map value from the parameter server. More...
 
bool getParam (const std::string &key, std::map< std::string, int > &map) const
 Get an int map value from the parameter server. More...
 
bool getParam (const std::string &key, std::map< std::string, bool > &map) const
 Get a boolean map value from the parameter server. More...
 
bool getParamCached (const std::string &key, std::string &s) const
 Get a string value from the parameter server, with local caching. More...
 
bool getParamCached (const std::string &key, double &d) const
 Get a double value from the parameter server, with local caching. More...
 
bool getParamCached (const std::string &key, float &f) const
 Get a float value from the parameter server, with local caching. More...
 
bool getParamCached (const std::string &key, int &i) const
 Get an integer value from the parameter server, with local caching. More...
 
bool getParamCached (const std::string &key, bool &b) const
 Get a boolean value from the parameter server, with local caching. More...
 
bool getParamCached (const std::string &key, XmlRpc::XmlRpcValue &v) const
 Get an arbitrary XML/RPC value from the parameter server, with local caching. More...
 
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. More...
 
bool getParamCached (const std::string &key, std::vector< double > &vec) const
 Get a double vector value from the parameter server, with local caching. More...
 
bool getParamCached (const std::string &key, std::vector< float > &vec) const
 Get a float vector value from the parameter server, with local caching. More...
 
bool getParamCached (const std::string &key, std::vector< int > &vec) const
 Get a int vector value from the parameter server, with local caching. More...
 
bool getParamCached (const std::string &key, std::vector< bool > &vec) const
 Get a bool vector value from the parameter server, with local caching. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
bool getParamNames (std::vector< std::string > &keys) const
 Get the keys for all the parameters in the parameter server. More...
 
const std::string & getUnresolvedNamespace () const
 Returns the namespace associated with this NodeHandle as it was passed in (before it was resolved) More...
 
bool hasParam (const std::string &key) const
 Check whether a parameter exists on the parameter server. More...
 
 NodeHandle (const std::string &ns=std::string(), const M_string &remappings=M_string())
 Constructor. More...
 
 NodeHandle (const NodeHandle &rhs)
 Copy constructor. More...
 
 NodeHandle (const NodeHandle &parent, const std::string &ns)
 Parent constructor. More...
 
 NodeHandle (const NodeHandle &parent, const std::string &ns, const M_string &remappings)
 Parent constructor. More...
 
bool ok () const
 Check whether it's time to exit. More...
 
NodeHandleoperator= (const NodeHandle &rhs)
 
template<typename T >
bool param (const std::string &param_name, T &param_val, const T &default_val) const
 Assign value from parameter server, with default. More...
 
template<typename T >
param (const std::string &param_name, const T &default_val)
 Return value from parameter server, or default if unavailable. More...
 
std::string resolveName (const std::string &name, bool remap=true) const
 Resolves a name into a fully-qualified name. More...
 
bool searchParam (const std::string &key, std::string &result) const
 Search up the tree for a parameter with a given key. More...
 
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. More...
 
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. More...
 
ServiceClient serviceClient (ServiceClientOptions &ops)
 Create a client for a service, version with full range of ServiceClientOptions. More...
 
void setCallbackQueue (CallbackQueueInterface *queue)
 Set the default callback queue to be used by this NodeHandle. More...
 
void setParam (const std::string &key, const XmlRpc::XmlRpcValue &v) const
 Set an arbitrary XML/RPC value on the parameter server. More...
 
void setParam (const std::string &key, const std::string &s) const
 Set a string value on the parameter server. More...
 
void setParam (const std::string &key, const char *s) const
 Set a string value on the parameter server. More...
 
void setParam (const std::string &key, double d) const
 Set a double value on the parameter server. More...
 
void setParam (const std::string &key, int i) const
 Set an integer value on the parameter server. More...
 
void setParam (const std::string &key, bool b) const
 Set a boolean value on the parameter server. More...
 
void setParam (const std::string &key, const std::vector< std::string > &vec) const
 Set a string vector value on the parameter server. More...
 
void setParam (const std::string &key, const std::vector< double > &vec) const
 Set a double vector value on the parameter server. More...
 
void setParam (const std::string &key, const std::vector< float > &vec) const
 Set a float vector value on the parameter server. More...
 
void setParam (const std::string &key, const std::vector< int > &vec) const
 Set a int vector value on the parameter server. More...
 
void setParam (const std::string &key, const std::vector< bool > &vec) const
 Set a bool vector value on the parameter server. More...
 
void setParam (const std::string &key, const std::map< std::string, std::string > &map) const
 Set a string vector value on the parameter server. More...
 
void setParam (const std::string &key, const std::map< std::string, double > &map) const
 Set a double vector value on the parameter server. More...
 
void setParam (const std::string &key, const std::map< std::string, float > &map) const
 Set a float vector value on the parameter server. More...
 
void setParam (const std::string &key, const std::map< std::string, int > &map) const
 Set a int vector value on the parameter server. More...
 
void setParam (const std::string &key, const std::map< std::string, bool > &map) const
 Set a bool vector value on the parameter server. More...
 
void shutdown ()
 Shutdown every handle created through this NodeHandle. More...
 
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. More...
 
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 More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
Subscriber subscribe (SubscribeOptions &ops)
 Subscribe to a topic, version with full range of SubscribeOptions. More...
 
 ~NodeHandle ()
 Destructor. More...
 

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

CallbackQueueInterfacecallback_queue_
 
NodeHandleBackingCollectioncollection_
 
std::string namespace_
 
bool ok_
 
M_string remappings_
 
std::string unresolved_namespace_
 
M_string unresolved_remappings_
 

Detailed Description

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 87 of file node_handle.h.

Constructor & Destructor Documentation

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.

Parameters
nsNamespace 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/"
remappingsRemappings for this NodeHandle.
Exceptions
InvalidNameExceptionif the namespace is not a valid graph resource name

Definition at line 73 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 115 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.

Exceptions
InvalidNameExceptionif the namespace is not a valid graph resource name

Definition at line 89 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.

Exceptions
InvalidNameExceptionif the namespace is not a valid graph resource name

Definition at line 101 of file node_handle.cpp.

ros::NodeHandle::~NodeHandle ( )

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 127 of file node_handle.cpp.

Member Function Documentation

template<class M >
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);

Parameters
topicTopic to advertise on
queue_sizeMaximum 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
Returns
On success, a Publisher that, when it goes out of scope, will automatically release a reference on this advertisement. On failure, an empty Publisher.
Exceptions
InvalidNameExceptionIf 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 249 of file node_handle.h.

template<class M >
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));
 \param topic Topic to advertise on

 \param queue_size Maximum number of outgoing messages to be queued for delivery to subscribers

 \param connect_cb Function to call when a subscriber connects

 \param disconnect_cb (optional) Function to call when a subscriber disconnects

 \param 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.
 \param latch (optional) If true, the last message published on this topic will be saved and sent to new subscribers when they connect
 \return On success, a Publisher that, when it goes out of scope, will automatically release a reference
 on this advertisement.  On failure, an empty Publisher which can be checked with:
ros::NodeHandle nodeHandle;
ros::publisher pub = nodeHandle.advertise<std_msgs::Empty>("my_topic", 1, (ros::SubscriberStatusCallback)callback);
if (pub)  // Enter if publisher is valid
{
...
}
Exceptions
InvalidNameExceptionIf the topic name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 315 of file node_handle.h.

Publisher ros::NodeHandle::advertise ( AdvertiseOptions ops)

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)

Parameters
opsAdvertise options to use
Returns
On success, a Publisher that, when it goes out of scope, will automatically release a reference on this advertisement. On failure, an empty Publisher which can be checked with:
ros::NodeHandle nodeHandle;
ros::AdvertiseOptions ops;
...
ros::publisher pub = nodeHandle.advertise(ops);
if (pub)  // Enter if publisher is valid
{
...
}
 \throws InvalidNameException If the topic name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 285 of file node_handle.cpp.

template<class T , class MReq , class MRes >
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);
 \param service Service name to advertise on
 \param srv_func Member function pointer to call when a message has arrived
 \param obj Object to call srv_func on
 \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
 On failure, an empty ServiceServer which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf 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 879 of file node_handle.h.

template<class T , class MReq , class MRes >
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);
 \param service Service name to advertise on
 \param srv_func Member function pointer to call when a message has arrived
 \param obj Object to call srv_func on
 \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
 On failure, an empty ServiceServer which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf 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 924 of file node_handle.h.

template<class T , class MReq , class MRes >
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);
 \param service Service name to advertise on
 \param srv_func Member function pointer to call when a message has arrived
 \param 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).
 \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
 On failure, an empty ServiceServer which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the service name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 970 of file node_handle.h.

template<class T , class MReq , class MRes >
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);
 \param service Service name to advertise on
 \param srv_func Member function pointer to call when a message has arrived
 \param 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).
 \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
 On failure, an empty ServiceServer which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the service name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 1017 of file node_handle.h.

template<class MReq , class MRes >
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);
 \param service Service name to advertise on
 \param srv_func function pointer to call when a message has arrived
 \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
 On failure, an empty ServiceServer which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the service name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 1061 of file node_handle.h.

template<class MReq , class MRes >
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);
 \param service Service name to advertise on
 \param srv_func function pointer to call when a message has arrived
 \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
 On failure, an empty ServiceServer which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the service name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 1104 of file node_handle.h.

template<class MReq , class MRes >
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).

Parameters
serviceService name to advertise on
callbackCallback to call when the service is called
tracked_objectA 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.
Returns
On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service. On failure, an empty ServiceServer which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the service name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 1145 of file node_handle.h.

template<class S >
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).

Parameters
serviceService name to advertise on
callbackCallback to call when the service is called
tracked_objectA 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.
Returns
On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service. On failure, an empty ServiceServer which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the service name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 1190 of file node_handle.h.

ServiceServer ros::NodeHandle::advertiseService ( AdvertiseServiceOptions ops)

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

Parameters
opsAdvertise options
Returns
On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service. On failure, an empty ServiceServer which can be checked with:
AdvertiseServiceOptions ops;
...
ros::NodeHandle nodeHandle;
ros::ServiceServer service = nodeHandle.advertiseService(ops);
if (service)  // Enter if advertised service is valid
{
...
}
Exceptions
InvalidNameExceptionIf the service name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 348 of file node_handle.cpp.

void ros::NodeHandle::construct ( const std::string &  ns,
bool  validate_name 
)
private

Definition at line 148 of file node_handle.cpp.

template<class T >
SteadyTimer ros::NodeHandle::createSteadyTimer ( WallDuration  period,
void(T::*)(const SteadyTimerEvent &)  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.

Parameters
periodThe period at which to call the callback
callbackThe method to call
objThe object to call the method on
oneshotIf true, this timer will only fire once
autostartIf true (default), return timer that is already started

Definition at line 1489 of file node_handle.h.

template<class T >
SteadyTimer ros::NodeHandle::createSteadyTimer ( WallDuration  period,
void(T::*)(const SteadyTimerEvent &)  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.

Parameters
periodThe period at which to call the callback
callbackThe method to call
objThe 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).
oneshotIf true, this timer will only fire once

Definition at line 1511 of file node_handle.h.

SteadyTimer ros::NodeHandle::createSteadyTimer ( WallDuration  period,
const SteadyTimerCallback 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.

Parameters
periodThe period at which to call the callback
callbackThe function to call
oneshotIf true, this timer will only fire once

Definition at line 454 of file node_handle.cpp.

SteadyTimer ros::NodeHandle::createSteadyTimer ( SteadyTimerOptions 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.

Parameters
opsThe options to use when creating the timer

Definition at line 465 of file node_handle.cpp.

template<class Handler , class Obj >
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.

Parameters
rThe rate at which to call the callback
callbackThe method to call
objThe object to call the method on
oneshotIf true, this timer will only fire once
autostartIf true (default), return timer that is already started

Definition at line 1294 of file node_handle.h.

template<class T >
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.

Parameters
periodThe period at which to call the callback
callbackThe method to call
objThe object to call the method on
oneshotIf true, this timer will only fire once
autostartIf true (default), return timer that is already started

Definition at line 1313 of file node_handle.h.

template<class T >
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.

Parameters
periodThe period at which to call the callback
callbackThe method to call
objThe object to call the method on
oneshotIf true, this timer will only fire once
autostartIf true (default), return timer that is already started

Definition at line 1333 of file node_handle.h.

template<class T >
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.

Parameters
periodThe period at which to call the callback
callbackThe method to call
objThe 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).
oneshotIf true, this timer will only fire once
autostartIf true (default), return timer that is already started

Definition at line 1355 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.

Parameters
periodThe period at which to call the callback
callbackThe function to call
oneshotIf true, this timer will only fire once
autostartIf true (default), return timer that is already started

Definition at line 392 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.

Parameters
opsThe options to use when creating the timer

Definition at line 403 of file node_handle.cpp.

template<class T >
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.

Parameters
periodThe period at which to call the callback
callbackThe method to call
objThe object to call the method on
oneshotIf true, this timer will only fire once
autostartIf true (default), return timer that is already started

Definition at line 1410 of file node_handle.h.

template<class T >
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.

Parameters
periodThe period at which to call the callback
callbackThe method to call
objThe 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).
oneshotIf true, this timer will only fire once

Definition at line 1432 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.

Parameters
periodThe period at which to call the callback
callbackThe function to call
oneshotIf true, this timer will only fire once

Definition at line 423 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.

Parameters
opsThe options to use when creating the timer

Definition at line 434 of file node_handle.cpp.

bool ros::NodeHandle::deleteParam ( const std::string &  key) const

Delete a parameter from the parameter server.

Parameters
keyThe key to delete.
Returns
true if the deletion succeeded, false otherwise.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 623 of file node_handle.cpp.

void ros::NodeHandle::destruct ( )
private

Definition at line 180 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 183 of file node_handle.h.

const std::string& ros::NodeHandle::getNamespace ( ) const
inline

Returns the namespace associated with this NodeHandle.

Definition at line 191 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]sStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 638 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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]dStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf 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,
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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]fStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 648 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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]iStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 653 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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]bStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 658 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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]vStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 633 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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]vecStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf 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::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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]vecStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf 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::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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]vecStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 672 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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]vecStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 676 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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]vecStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 680 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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]mapStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 685 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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]mapStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 689 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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]mapStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf 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::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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]mapStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 697 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().

Parameters
keyThe key to be used in the parameter server's dictionary
[out]mapStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 701 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]sStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf 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,
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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]dStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 716 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]fStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 721 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]iStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 726 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]bStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 731 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]vStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 706 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]vecStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf 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::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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]vecStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf 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::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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]vecStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 744 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]vecStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 748 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]vecStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 752 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]mapStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 757 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]mapStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 761 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]mapStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 765 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]mapStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 769 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.

Parameters
keyThe key to be used in the parameter server's dictionary
[out]mapStorage for the retrieved value.
Returns
true if the parameter value was retrieved, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 773 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.

Parameters
keysThe keys retrieved.
Returns
true if the query succeeded, false otherwise.

Definition at line 628 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 197 of file node_handle.h.

bool ros::NodeHandle::hasParam ( const std::string &  key) const

Check whether a parameter exists on the parameter server.

Parameters
keyThe key to check.
Returns
true if the parameter exists, false otherwise
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 618 of file node_handle.cpp.

void ros::NodeHandle::initRemappings ( const M_string remappings)
private

Definition at line 194 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

Returns
true if we're still OK, false if it's time to exit

Definition at line 794 of file node_handle.cpp.

NodeHandle & ros::NodeHandle::operator= ( const NodeHandle rhs)

Definition at line 132 of file node_handle.cpp.

template<typename T >
bool 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.

Parameters
param_nameThe key to be searched on the parameter server.
[out]param_valStorage for the retrieved value.
default_valValue to use if the server doesn't contain this parameter.
Returns
true if the parameter was retrieved from the server, false otherwise.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 2120 of file node_handle.h.

template<typename T >
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.

Parameters
param_nameThe key to be searched on the parameter server.
default_valValue to return if the server doesn't contain this parameter.
Returns
The parameter value retrieved from the parameter server, or default_val if unavailable.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name.

Definition at line 2153 of file node_handle.h.

std::string ros::NodeHandle::remapName ( const std::string &  name) const
private

Definition at line 215 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.

Parameters
nameName to remap
remapWhether to apply name-remapping rules
Returns
Resolved name.
Exceptions
InvalidNameExceptionIf the name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 231 of file node_handle.cpp.

std::string ros::NodeHandle::resolveName ( const std::string &  name,
bool  remap,
no_validate   
) const
private

Definition at line 243 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.

Parameters
keythe parameter to search for
[out]resultthe found value (if any)
Returns
true if the parameter was found, false otherwise.

Definition at line 778 of file node_handle.cpp.

template<class MReq , class MRes >
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.

Parameters
service_nameThe name of the service to connect to
persistentWhether 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_valuesKey/value pairs you'd like to send along in the connection handshake
Exceptions
InvalidNameExceptionIf the service name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 1240 of file node_handle.h.

template<class Service >
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.

Parameters
service_nameThe name of the service to connect to
persistentWhether 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_valuesKey/value pairs you'd like to send along in the connection handshake
Exceptions
InvalidNameExceptionIf the service name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 1260 of file node_handle.h.

ServiceClient ros::NodeHandle::serviceClient ( ServiceClientOptions ops)

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.

Parameters
opsThe options for this service client
Exceptions
InvalidNameExceptionIf the service name begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 378 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 210 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.

Parameters
keyThe key to be used in the parameter server's dictionary
vThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 546 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.

Parameters
keyThe key to be used in the parameter server's dictionary
sThe value to be inserted.
Exceptions
InvalidNameExceptionIf 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 char *  s 
) const

Set a string value on the parameter server.

Parameters
keyThe key to be used in the parameter server's dictionary
sThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 556 of file node_handle.cpp.

void ros::NodeHandle::setParam ( const std::string &  key,
double  d 
) const

Set a double value on the parameter server.

Parameters
keyThe key to be used in the parameter server's dictionary
dThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 561 of file node_handle.cpp.

void ros::NodeHandle::setParam ( const std::string &  key,
int  i 
) const

Set an integer value on the parameter server.

Parameters
keyThe key to be used in the parameter server's dictionary
iThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 566 of file node_handle.cpp.

void ros::NodeHandle::setParam ( const std::string &  key,
bool  b 
) const

Set a boolean value on the parameter server.

Parameters
keyThe key to be used in the parameter server's dictionary
bThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 571 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.

Parameters
keyThe key to be used in the parameter server's dictionary
vecThe value to be inserted.
Exceptions
InvalidNameExceptionIf 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::vector< double > &  vec 
) const

Set a double vector value on the parameter server.

Parameters
keyThe key to be used in the parameter server's dictionary
vecThe value to be inserted.
Exceptions
InvalidNameExceptionIf 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::setParam ( const std::string &  key,
const std::vector< float > &  vec 
) const

Set a float vector value on the parameter server.

Parameters
keyThe key to be used in the parameter server's dictionary
vecThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 584 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.

Parameters
keyThe key to be used in the parameter server's dictionary
vecThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 588 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.

Parameters
keyThe key to be used in the parameter server's dictionary
vecThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 592 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.

Parameters
keyThe key to be used in the parameter server's dictionary
mapThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 597 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.

Parameters
keyThe key to be used in the parameter server's dictionary
mapThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 601 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.

Parameters
keyThe key to be used in the parameter server's dictionary
mapThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 605 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.

Parameters
keyThe key to be used in the parameter server's dictionary
mapThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 609 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.

Parameters
keyThe key to be used in the parameter server's dictionary
mapThe value to be inserted.
Exceptions
InvalidNameExceptionIf the parameter key begins with a tilde, or is an otherwise invalid graph resource name

Definition at line 613 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 485 of file node_handle.cpp.

template<class M , class T >
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);
 \param M [template] M here is the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&), \b not the message type, and should almost always be deduced
 \param topic Topic to subscribe to
 \param queue_size Number of incoming messages to queue up for
 processing (messages in excess of this queue capacity will be
 discarded).
 \param fp Member function pointer to call when a message has arrived
 \param obj Object to call fp on
 \param transport_hints a TransportHints structure which defines various transport-related options
 \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
 On failure, an empty Subscriber which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the topic name begins with a tilde, or is an otherwise invalid graph resource name
ConflictingSubscriptionExceptionIf this node is already subscribed to the same topic with a different datatype

Definition at line 402 of file node_handle.h.

template<class M , class T >
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 413 of file node_handle.h.

template<class M , class T >
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);
 \param M [template] M here is the message type
 \param topic Topic to subscribe to
 \param queue_size Number of incoming messages to queue up for
 processing (messages in excess of this queue capacity will be
 discarded).
 \param fp Member function pointer to call when a message has arrived
 \param obj Object to call fp on
 \param transport_hints a TransportHints structure which defines various transport-related options
 \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
 On failure, an empty Subscriber which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the topic name begins with a tilde, or is an otherwise invalid graph resource name
ConflictingSubscriptionExceptionIf this node is already subscribed to the same topic with a different datatype

Definition at line 465 of file node_handle.h.

template<class M , class T >
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 475 of file node_handle.h.

template<class M , class T >
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);
 \param M [template] M here is the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&), \b not the message type, and should almost always be deduced
 \param topic Topic to subscribe to
 \param queue_size Number of incoming messages to queue up for
 processing (messages in excess of this queue capacity will be
 discarded).
 \param fp Member function pointer to call when a message has arrived
 \param 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).
 \param transport_hints a TransportHints structure which defines various transport-related options
 \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
 On failure, an empty Subscriber which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the topic name begins with a tilde, or is an otherwise invalid graph resource name
ConflictingSubscriptionExceptionIf this node is already subscribed to the same topic with a different datatype

Definition at line 529 of file node_handle.h.

template<class M , class T >
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 540 of file node_handle.h.

template<class M , class T >
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);
 \param M [template] M here is the message type
 \param topic Topic to subscribe to
 \param queue_size Number of incoming messages to queue up for
 processing (messages in excess of this queue capacity will be
 discarded).
 \param fp Member function pointer to call when a message has arrived
 \param 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).
 \param transport_hints a TransportHints structure which defines various transport-related options
 \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
 On failure, an empty Subscriber which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the topic name begins with a tilde, or is an otherwise invalid graph resource name
ConflictingSubscriptionExceptionIf this node is already subscribed to the same topic with a different datatype

Definition at line 594 of file node_handle.h.

template<class M , class T >
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 605 of file node_handle.h.

template<class M >
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);
 \param M [template] M here is the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&), \b not the message type, and should almost always be deduced
 \param topic Topic to subscribe to
 \param queue_size Number of incoming messages to queue up for
 processing (messages in excess of this queue capacity will be
 discarded).
 \param fp Function pointer to call when a message has arrived
 \param transport_hints a TransportHints structure which defines various transport-related options
 \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
 On failure, an empty Subscriber which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the topic name begins with a tilde, or is an otherwise invalid graph resource name
ConflictingSubscriptionExceptionIf this node is already subscribed to the same topic with a different datatype

Definition at line 656 of file node_handle.h.

template<class M >
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);
 \param M [template] M here is the message type
 \param topic Topic to subscribe to
 \param queue_size Number of incoming messages to queue up for
 processing (messages in excess of this queue capacity will be
 discarded).
 \param fp Function pointer to call when a message has arrived
 \param transport_hints a TransportHints structure which defines various transport-related options
 \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
 On failure, an empty Subscriber which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the topic name begins with a tilde, or is an otherwise invalid graph resource name
ConflictingSubscriptionExceptionIf this node is already subscribed to the same topic with a different datatype

Definition at line 704 of file node_handle.h.

template<class M >
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

Parameters
M[template] M here is the message type
topicTopic to subscribe to
queue_sizeNumber of incoming messages to queue up for processing (messages in excess of this queue capacity will be discarded).
callbackCallback to call when a message has arrived
tracked_objectA 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_hintsa TransportHints structure which defines various transport-related options
Returns
On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic. On failure, an empty Subscriber which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the topic name begins with a tilde, or is an otherwise invalid graph resource name
ConflictingSubscriptionExceptionIf this node is already subscribed to the same topic with a different datatype

Definition at line 750 of file node_handle.h.

template<class M , class C >
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

Parameters
M[template] the message type
C[template] the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&)
topicTopic to subscribe to
queue_sizeNumber of incoming messages to queue up for processing (messages in excess of this queue capacity will be discarded).
callbackCallback to call when a message has arrived
tracked_objectA 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_hintsa TransportHints structure which defines various transport-related options
Returns
On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic. On failure, an empty Subscriber which can be checked with:
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
{
...
}
Exceptions
InvalidNameExceptionIf the topic name begins with a tilde, or is an otherwise invalid graph resource name
ConflictingSubscriptionExceptionIf this node is already subscribed to the same topic with a different datatype

Definition at line 799 of file node_handle.h.

Subscriber ros::NodeHandle::subscribe ( SubscribeOptions ops)

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

Parameters
opsSubscribe options
Returns
On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic. On failure, an empty Subscriber which can be checked with:
SubscribeOptions ops;
...
ros::NodeHandle nodeHandle;
ros::Subscriber sub = nodeHandle.subscribe(ops);
if (sub)  // Enter if subscriber is valid
{
...
}
Exceptions
InvalidNameExceptionIf the topic name begins with a tilde, or is an otherwise invalid graph resource name
ConflictingSubscriptionExceptionIf this node is already subscribed to the same topic with a different datatype

Definition at line 318 of file node_handle.cpp.

Member Data Documentation

CallbackQueueInterface* ros::NodeHandle::callback_queue_
private

Definition at line 2194 of file node_handle.h.

NodeHandleBackingCollection* ros::NodeHandle::collection_
private

Definition at line 2196 of file node_handle.h.

std::string ros::NodeHandle::namespace_
private

Definition at line 2189 of file node_handle.h.

bool ros::NodeHandle::ok_
private

Definition at line 2198 of file node_handle.h.

M_string ros::NodeHandle::remappings_
private

Definition at line 2191 of file node_handle.h.

std::string ros::NodeHandle::unresolved_namespace_
private

Definition at line 2190 of file node_handle.h.

M_string ros::NodeHandle::unresolved_remappings_
private

Definition at line 2192 of file node_handle.h.


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


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Sun Feb 3 2019 03:29:54