Go to the documentation of this file.
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");
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] ==
'/')
402 bool oneshot,
bool autostart)
const
433 bool oneshot,
bool autostart)
const
464 bool oneshot,
bool autostart)
const
497 NodeHandleBackingCollection::V_SubImpl::iterator it =
collection_->
subs_.begin();
498 NodeHandleBackingCollection::V_SubImpl::iterator end =
collection_->
subs_.end();
499 for (; it != end; ++it)
511 NodeHandleBackingCollection::V_PubImpl::iterator it =
collection_->
pubs_.begin();
512 NodeHandleBackingCollection::V_PubImpl::iterator end =
collection_->
pubs_.end();
513 for (; it != end; ++it)
525 NodeHandleBackingCollection::V_SrvImpl::iterator it =
collection_->
srvs_.begin();
526 NodeHandleBackingCollection::V_SrvImpl::iterator end =
collection_->
srvs_.end();
527 for (; it != end; ++it)
541 for (; it != end; ++it)
792 std::string remapped = key;
797 remapped = it->second;
std::string topic
The topic to publish on.
const ROSCPP_DECL std::string & getNamespace()
Returns the namespace of the current node.
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
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...
bool persistent
Whether or not the connection should persist.
boost::function< void(const TimerEvent &)> TimerCallback
bool g_node_started_by_nh
Encapsulates all options available for starting a timer.
TopicManagerPtr keep_alive_topic_manager
WallDuration period
The period to call the callback at.
std::string remapName(const std::string &name) const
void construct(const std::string &ns, bool validate_name)
NodeHandle(const std::string &ns=std::string(), const M_string &remappings=M_string())
Constructor.
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::vector< Publisher::ImplWPtr > V_PubImpl
std::string topic
Topic to subscribe to.
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.
std::vector< ServiceClient::ImplWPtr > V_SrvCImpl
bool deleteParam(const std::string &key) const
Delete a parameter from the parameter server.
ROSCPP_DECL std::string clean(const std::string &name)
Cleans a graph resource name: removes double slashes, trailing slash.
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
SubscriberStatusCallback connect_cb
The function to call when a subscriber connects to this topic.
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
NodeHandle & operator=(const NodeHandle &rhs)
static const ServiceManagerPtr & instance()
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...
SubscriberStatusCallback disconnect_cb
The function to call when a subscriber disconnects from this topic.
WallDuration period
The period to call the callback at.
std::vector< ServiceServer::ImplWPtr > V_SrvImpl
std::string datatype
The datatype of the message published on this topic (eg. "std_msgs/String")
WallTimerCallback callback
The callback to call.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
boost::function< void(const WallTimerEvent &)> WallTimerCallback
std::string unresolved_namespace_
ROSCPP_DECL bool validate(const std::string &name, std::string &error)
Validate a name against the name spec.
Encapsulates all options available for creating a Publisher.
ROSCPP_DECL bool ok()
Check whether it's time to exit.
ROSCPP_DECL bool del(const std::string &key)
Delete a parameter from the parameter server.
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
Resolve a graph resource name into a fully qualified graph resource name.
TimerCallback callback
The callback to call.
Manages a timer callback.
void start()
Start the timer. Does nothing if the timer is already started.
Manages a wall-clock timer callback.
std::string resolveName(const std::string &name, bool remap=true) const
Resolves a name into a fully-qualified name.
Encapsulates all options available for starting a timer.
CallbackQueueInterface * callback_queue_
ROSCPP_DECL bool getCached(const std::string &key, std::string &s)
Get a string value from the parameter server, with local caching.
M_string header
Extra key/value pairs to add to the connection header.
ServiceManagerPtr keep_alive_service_manager
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
bool latch
Whether or not this publication should "latch". A latching publication will automatically send out th...
M_string unresolved_remappings_
Encapsulates all options available for creating a ServiceClient.
bool searchParam(const std::string &key, std::string &result) const
Search up the tree for a parameter with a given key.
ROSCPP_DECL bool isInitialized()
Returns whether or not ros::init() has been called.
bool hasParam(const std::string &key) const
Check whether a parameter exists on the parameter server.
Provides a handle-based interface to service client connections.
Encapsulates all options available for creating a ServiceServer.
roscpp's interface for creating subscribers, publishers, etc.
ROSCPP_DECL std::string remap(const std::string &name)
Apply remappings to a name.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Advertise a topic, simple version.
ROSCPP_DECL bool isStarted()
Returns whether or not the node has been started through ros::start()
SteadyTimerCallback callback
The callback to call.
Manages an advertisement on a specific topic.
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
Set an arbitrary XML/RPC value on the parameter server.
void setCallbackQueue(CallbackQueueInterface *queue)
Set the default callback queue to be used by this NodeHandle.
bool getParam(const std::string &key, std::string &s) const
Get a string value from the parameter server.
Duration period
The period to call the callback at.
bool getParamCached(const std::string &key, std::string &s) const
Get a string value from the parameter server, with local caching.
boost::mutex g_nh_refcount_mutex
std::vector< Subscriber::ImplWPtr > V_SubImpl
boost::function< void(const SteadyTimerEvent &)> SteadyTimerCallback
std::string service
Service name.
std::string md5sum
Service md5sum.
ROSCPP_DECL void start()
Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc lo...
bool ok() const
Check whether it's time to exit.
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
Append one name to another.
Encapsulates all options available for creating a Subscriber.
bool getParamNames(std::vector< std::string > &keys) const
Get the keys for all the parameters in the parameter server.
void start()
Start the timer. Does nothing if the timer is already started.
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
static const TopicManagerPtr & instance()
void initRemappings(const M_string &remappings)
ROSCPP_DECL bool get(const std::string &key, std::string &s)
Get a string value from the parameter server.
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.
boost::function< void(const SubscriberLinkPtr &)> getLastMessageCallback()
Thrown when an invalid graph resource name is specified to any roscpp function.
Encapsulates all options available for starting a timer.
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
Get the list of all the parameters in the server.
std::string md5sum
The md5sum of the message datatype published on this topic.
ROSCPP_DECL void spin()
Enter simple event loop.
Manages an service advertisement.
ROSCPP_DECL bool has(const std::string &key)
Check whether a parameter exists on the parameter server.
const std::string & getNamespace() const
Returns the namespace associated with this NodeHandle.
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.
Manages an subscription callback on a specific topic.
void shutdown()
Shutdown every handle created through this NodeHandle.
VoidConstPtr tracked_object
An object whose destruction will prevent the callbacks associated with this advertisement from being ...
Manages a steady-clock timer callback.
Abstract interface for a queue used to handle all callbacks within roscpp.
std::string service
Service to connect to.
NodeHandleBackingCollection * collection_
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
Returns a pointer to the global default callback queue.
std::map< std::string, std::string > M_string
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
Set an arbitrary XML/RPC value on the parameter server.
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...
roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
, Jacob Perron
autogenerated on Sat Sep 14 2024 02:59:35