49 #include <boost/thread.hpp> 62 typedef std::vector<ServiceServer::ImplWPtr>
V_SrvImpl;
63 typedef std::vector<Subscriber::ImplWPtr>
V_SubImpl;
82 std::string tilde_resolved_ns;
83 if (!ns.empty() && ns[0] ==
'~')
86 tilde_resolved_ns = ns;
156 ROS_FATAL(
"You must call ros::init() before creating the first NodeHandle");
173 boost::mutex::scoped_lock lock(g_nh_refcount_mutex);
177 g_node_started_by_nh =
true;
188 boost::mutex::scoped_lock lock(g_nh_refcount_mutex);
192 if (g_nh_refcount == 0 && g_node_started_by_nh)
201 M_string::const_iterator it = remappings.begin();
202 M_string::const_iterator end = remappings.end();
203 for (; it != end; ++it)
205 const std::string& from = it->first;
206 const std::string& to = it->second;
224 M_string::const_iterator it =
remappings_.find(resolved);
254 std::string
final = name;
258 std::stringstream ss;
259 ss <<
"Using ~ names with NodeHandle methods is not allowed. If you want to use private names with the NodeHandle ";
260 ss <<
"interface, construct a NodeHandle using a private name as its namespace. e.g. ";
261 ss <<
"ros::NodeHandle nh(\"~\"); ";
262 ss <<
"nh.getParam(\"my_private_name\");";
263 ss <<
" (name = [" << name <<
"])";
266 else if (
final[0] ==
'/')
397 bool oneshot,
bool autostart)
const 428 bool oneshot,
bool autostart)
const 459 bool oneshot,
bool autostart)
const 492 NodeHandleBackingCollection::V_SubImpl::iterator it =
collection_->
subs_.begin();
493 NodeHandleBackingCollection::V_SubImpl::iterator end =
collection_->
subs_.end();
494 for (; it != end; ++it)
506 NodeHandleBackingCollection::V_PubImpl::iterator it =
collection_->
pubs_.begin();
507 NodeHandleBackingCollection::V_PubImpl::iterator end =
collection_->
pubs_.end();
508 for (; it != end; ++it)
520 NodeHandleBackingCollection::V_SrvImpl::iterator it =
collection_->
srvs_.begin();
521 NodeHandleBackingCollection::V_SrvImpl::iterator end =
collection_->
srvs_.end();
522 for (; it != end; ++it)
536 for (; it != end; ++it)
787 std::string remapped = key;
792 remapped = it->second;
SubscriberStatusCallback connect_cb
The function to call when a subscriber connects to this topic.
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
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.
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
Get the list of all the parameters in the server.
Manages an subscription callback on a specific topic.
Encapsulates all options available for creating a ServiceClient.
void start()
Start the timer. Does nothing if the timer is already started.
NodeHandle & operator=(const NodeHandle &rhs)
ROSCPP_DECL void start()
Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc lo...
std::vector< ServiceServer::ImplWPtr > V_SrvImpl
std::string md5sum
Service md5sum.
SubscriberStatusCallback disconnect_cb
The function to call when a subscriber disconnects from this topic.
std::string service
Service name.
boost::function< void(const TimerEvent &)> TimerCallback
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.
bool getParamCached(const std::string &key, std::string &s) const
Get a string value from the parameter server, with local caching.
NodeHandle(const std::string &ns=std::string(), const M_string &remappings=M_string())
Constructor.
bool deleteParam(const std::string &key) const
Delete a parameter from the parameter server.
Encapsulates all options available for starting a timer.
std::string resolveName(const std::string &name, bool remap=true) const
Resolves a name into a fully-qualified name.
WallTimerCallback callback
The callback to call.
std::vector< ServiceClient::ImplWPtr > V_SrvCImpl
ROSCPP_DECL bool isInitialized()
Returns whether or not ros::init() has been called.
std::vector< Publisher::ImplWPtr > V_PubImpl
CallbackQueueInterface * callback_queue_
void construct(const std::string &ns, bool validate_name)
std::string unresolved_namespace_
void start()
Start the timer. Does nothing if the timer is already started.
SteadyTimerCallback callback
The callback to call.
ROSCPP_DECL bool validate(const std::string &name, std::string &error)
Validate a name against the name spec.
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
TopicManagerPtr keep_alive_topic_manager
ServiceManagerPtr keep_alive_service_manager
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
Resolve a graph resource name into a fully qualified graph resource name.
ROSCPP_DECL std::string clean(const std::string &name)
Cleans a graph resource name: removes double slashes, trailing slash.
Abstract interface for a queue used to handle all callbacks within roscpp.
Encapsulates all options available for creating a Publisher.
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.
WallDuration period
The period to call the callback at.
static const ServiceManagerPtr & instance()
Encapsulates all options available for creating a ServiceServer.
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
Returns a pointer to the global default callback queue.
std::map< std::string, std::string > M_string
std::string service
Service to connect to.
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
Set an arbitrary XML/RPC value on the parameter server.
ROSCPP_DECL std::string remap(const std::string &name)
Apply remappings to a name.
void start()
Start the timer. Does nothing if the timer is already started.
SubscriptionCallbackHelperPtr helper
Helper object used to get create messages and call callbacks.
ROSCPP_DECL const std::string & getNamespace()
Returns the namespace of the current node.
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...
VoidConstPtr tracked_object
An object whose destruction will prevent the callbacks associated with this advertisement from being ...
M_string unresolved_remappings_
ROSCPP_DECL bool get(const std::string &key, std::string &s)
Get a string value from the parameter server.
Encapsulates all options available for creating a Subscriber.
boost::mutex g_nh_refcount_mutex
bool searchParam(const std::string &key, std::string &result) const
Search up the tree for a parameter with a given key.
bool persistent
Whether or not the connection should persist.
void setCallbackQueue(CallbackQueueInterface *queue)
Set the default callback queue to be used by this NodeHandle.
roscpp's interface for creating subscribers, publishers, etc.
boost::function< void(const SteadyTimerEvent &)> SteadyTimerCallback
ROSCPP_DECL bool ok()
Check whether it's time to exit.
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 fu...
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
TimerCallback callback
The callback to call.
const std::string & getNamespace() const
Returns the namespace associated with this NodeHandle.
std::string datatype
The datatype of the message published on this topic (eg. "std_msgs/String")
Encapsulates all options available for starting a timer.
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...
WallDuration period
The period to call the callback at.
ROSCPP_DECL bool has(const std::string &key)
Check whether a parameter exists on the parameter server.
bool getParamNames(std::vector< std::string > &keys) const
Get the keys for all the parameters in the parameter server.
std::vector< Subscriber::ImplWPtr > V_SubImpl
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Advertise a topic, simple version.
ROSCPP_DECL void spin()
Enter simple event loop.
Manages an advertisement on a specific topic.
ROSCPP_DECL bool getCached(const std::string &key, std::string &s)
Get a string value from the parameter server, with local caching.
std::string md5sum
The md5sum of the message datatype published on this topic.
Manages a steady-clock timer callback.
void initRemappings(const M_string &remappings)
bool g_node_started_by_nh
ROSCPP_DECL bool del(const std::string &key)
Delete a parameter from the parameter server.
boost::function< void(const WallTimerEvent &)> WallTimerCallback
ROSCPP_DECL bool isStarted()
Returns whether or not the node has been started through ros::start()
Manages an service advertisement.
Duration period
The period to call the callback at.
Thrown when an invalid graph resource name is specified to any roscpp function.
bool getParam(const std::string &key, std::string &s) const
Get a string value from the parameter server.
void shutdown()
Shutdown every handle created through this NodeHandle.
std::string topic
The topic to publish on.
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
Append one name to another.
Manages a timer callback.
Provides a handle-based interface to service client connections.
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
bool ok() const
Check whether it's time to exit.
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
bool hasParam(const std::string &key) const
Check whether a parameter exists on the parameter server.
std::string topic
Topic to subscribe to.
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
Search up the tree for a parameter with a given key.
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
Set an arbitrary XML/RPC value on the parameter server.
Manages a wall-clock timer callback.
std::string remapName(const std::string &name) const
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
NodeHandleBackingCollection * collection_
Encapsulates all options available for starting a timer.
M_string header
Extra key/value pairs to add to the connection header.
static const TopicManagerPtr & instance()