28 #ifndef ROSCPP_NODE_HANDLE_H 29 #define ROSCPP_NODE_HANDLE_H 50 #include <boost/bind.hpp> 57 class NodeHandleBackingCollection;
215 std::string resolveName(
const std::string& name,
bool remap =
true)
const;
252 ops.template init<M>(topic, queue_size);
254 return advertise(ops);
322 ops.template init<M>(topic, queue_size, connect_cb, disconnect_cb);
325 return advertise(ops);
401 template<
class M,
class T>
406 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, _1));
408 return subscribe(ops);
412 template<
class M,
class T>
417 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, _1));
419 return subscribe(ops);
464 template<
class M,
class T>
470 ops.template init<M>(topic, queue_size, boost::bind(fp, obj, _1));
472 return subscribe(ops);
474 template<
class M,
class T>
480 ops.template init<M>(topic, queue_size, boost::bind(fp, obj, _1));
482 return subscribe(ops);
528 template<
class M,
class T>
533 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
536 return subscribe(ops);
539 template<
class M,
class T>
544 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
547 return subscribe(ops);
593 template<
class M,
class T>
599 ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
602 return subscribe(ops);
604 template<
class M,
class T>
610 ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
613 return subscribe(ops);
659 ops.template initByFullCallbackType<M>(topic, queue_size, fp);
661 return subscribe(ops);
707 ops.template init<M>(topic, queue_size, fp);
709 return subscribe(ops);
754 ops.template init<M>(topic, queue_size, callback);
757 return subscribe(ops);
798 template<
class M,
class C>
799 Subscriber subscribe(
const std::string& topic, uint32_t queue_size,
const boost::function<
void (C)>& callback,
803 ops.template initByFullCallbackType<C>(topic, queue_size, callback);
806 return subscribe(ops);
878 template<
class T,
class MReq,
class MRes>
882 ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj, _1, _2));
883 return advertiseService(ops);
923 template<
class T,
class MReq,
class MRes>
927 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj, _1));
928 return advertiseService(ops);
969 template<
class T,
class MReq,
class MRes>
973 ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj.get(), _1, _2));
975 return advertiseService(ops);
1016 template<
class T,
class MReq,
class MRes>
1020 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj.get(), _1));
1022 return advertiseService(ops);
1060 template<
class MReq,
class MRes>
1064 ops.template init<MReq, MRes>(service, srv_func);
1065 return advertiseService(ops);
1103 template<
class MReq,
class MRes>
1107 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, srv_func);
1108 return advertiseService(ops);
1144 template<
class MReq,
class MRes>
1149 ops.template init<MReq, MRes>(service, callback);
1151 return advertiseService(ops);
1194 ops.template initBySpecType<S>(service, callback);
1196 return advertiseService(ops);
1239 template<
class MReq,
class MRes>
1244 ops.template init<MReq, MRes>(service_name, persistent, header_values);
1245 return serviceClient(ops);
1259 template<
class Service>
1264 ops.template init<Service>(service_name, persistent, header_values);
1265 return serviceClient(ops);
1293 template<
class Handler,
class Obj>
1314 bool oneshot =
false,
bool autostart =
true)
const 1316 return createTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
1334 bool oneshot =
false,
bool autostart =
true)
const 1336 return createTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
1356 bool oneshot =
false,
bool autostart =
true)
const 1358 TimerOptions ops(period, boost::bind(callback, obj.get(), _1), 0);
1362 return createTimer(ops);
1378 bool autostart =
true)
const;
1411 bool oneshot =
false,
bool autostart =
true)
const 1413 return createWallTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
1434 bool oneshot =
false,
bool autostart =
true)
const 1440 return createWallTimer(ops);
1456 bool oneshot =
false,
bool autostart =
true)
const;
1490 bool oneshot =
false,
bool autostart =
true)
const 1492 return createSteadyTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
1513 bool oneshot =
false,
bool autostart =
true)
const 1519 return createSteadyTimer(ops);
1535 bool oneshot =
false,
bool autostart =
true)
const;
1562 void setParam(
const std::string& key,
const std::string&
s)
const;
1569 void setParam(
const std::string& key,
const char* s)
const;
1576 void setParam(
const std::string& key,
double d)
const;
1583 void setParam(
const std::string& key,
int i)
const;
1590 void setParam(
const std::string& key,
bool b)
const;
1598 void setParam(
const std::string& key,
const std::vector<std::string>& vec)
const;
1605 void setParam(
const std::string& key,
const std::vector<double>& vec)
const;
1612 void setParam(
const std::string& key,
const std::vector<float>& vec)
const;
1619 void setParam(
const std::string& key,
const std::vector<int>& vec)
const;
1626 void setParam(
const std::string& key,
const std::vector<bool>& vec)
const;
1634 void setParam(
const std::string& key,
const std::map<std::string, std::string>& map)
const;
1641 void setParam(
const std::string& key,
const std::map<std::string, double>& map)
const;
1648 void setParam(
const std::string& key,
const std::map<std::string, float>& map)
const;
1655 void setParam(
const std::string& key,
const std::map<std::string, int>& map)
const;
1662 void setParam(
const std::string& key,
const std::map<std::string, bool>& map)
const;
1672 bool getParam(
const std::string& key, std::string& s)
const;
1683 bool getParam(
const std::string& key,
double& d)
const;
1694 bool getParam(
const std::string& key,
float&
f)
const;
1705 bool getParam(
const std::string& key,
int& i)
const;
1716 bool getParam(
const std::string& key,
bool& b)
const;
1739 bool getParam(
const std::string& key, std::vector<std::string>& vec)
const;
1750 bool getParam(
const std::string& key, std::vector<double>& vec)
const;
1761 bool getParam(
const std::string& key, std::vector<float>& vec)
const;
1772 bool getParam(
const std::string& key, std::vector<int>& vec)
const;
1783 bool getParam(
const std::string& key, std::vector<bool>& vec)
const;
1795 bool getParam(
const std::string& key, std::map<std::string, std::string>& map)
const;
1806 bool getParam(
const std::string& key, std::map<std::string, double>& map)
const;
1817 bool getParam(
const std::string& key, std::map<std::string, float>& map)
const;
1828 bool getParam(
const std::string& key, std::map<std::string, int>& map)
const;
1839 bool getParam(
const std::string& key, std::map<std::string, bool>& map)
const;
1856 bool getParamCached(
const std::string& key, std::string& s)
const;
1870 bool getParamCached(
const std::string& key,
double& d)
const;
1884 bool getParamCached(
const std::string& key,
float& f)
const;
1898 bool getParamCached(
const std::string& key,
int& i)
const;
1912 bool getParamCached(
const std::string& key,
bool& b)
const;
1941 bool getParamCached(
const std::string& key, std::vector<std::string>& vec)
const;
1955 bool getParamCached(
const std::string& key, std::vector<double>& vec)
const;
1969 bool getParamCached(
const std::string& key, std::vector<float>& vec)
const;
1983 bool getParamCached(
const std::string& key, std::vector<int>& vec)
const;
1997 bool getParamCached(
const std::string& key, std::vector<bool>& vec)
const;
2012 bool getParamCached(
const std::string& key, std::map<std::string, std::string>& map)
const;
2026 bool getParamCached(
const std::string& key, std::map<std::string, double>& map)
const;
2040 bool getParamCached(
const std::string& key, std::map<std::string, float>& map)
const;
2054 bool getParamCached(
const std::string& key, std::map<std::string, int>& map)
const;
2068 bool getParamCached(
const std::string& key, std::map<std::string, bool>& map)
const;
2077 bool hasParam(
const std::string& key)
const;
2090 bool searchParam(
const std::string& key, std::string& result)
const;
2098 bool deleteParam(
const std::string& key)
const;
2119 template<
typename T>
2120 bool param(
const std::string& param_name, T& param_val,
const T& default_val)
const 2122 if (hasParam(param_name))
2124 if (getParam(param_name, param_val))
2130 param_val = default_val;
2152 template<
typename T>
2153 T
param(
const std::string& param_name,
const T& default_val)
const 2156 param(param_name, param_val, default_val);
2180 std::string resolveName(
const std::string& name,
bool remap,
no_validate)
const;
2182 void construct(
const std::string& ns,
bool validate_name);
2185 void initRemappings(
const M_string& remappings);
2187 std::string remapName(
const std::string& name)
const;
2203 #endif // ROSCPP_NODE_HANDLE_H
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.
const std::string & getUnresolvedNamespace() const
Returns the namespace associated with this NodeHandle as it was passed in (before it was resolved) ...
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
Get the list of all the parameters in the server.
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 fu...
Manages an subscription callback on a specific topic.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
Assign value from parameter server, with default.
Encapsulates all options available for creating a ServiceClient.
boost::shared_ptr< void const > VoidConstPtr
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
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())
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 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())
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.
Encapsulates all options available for starting a timer.
CallbackQueueInterface * callback_queue_
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.
VoidConstPtr tracked_object
An object whose destruction will prevent the callback associated with this service from being called...
std::string unresolved_namespace_
bool latch
Whether or not this publication should "latch". A latching publication will automatically send out th...
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.
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())
VoidConstPtr tracked_object
Abstract interface for a queue used to handle all callbacks within roscpp.
Encapsulates all options available for creating a Publisher.
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.
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.
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.
ServiceServer advertiseService(const std::string &service, bool(*srv_func)(MReq &, MRes &))
Advertise a service, version for bare function.
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.
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...
Provides a way of specifying network transport hints to ros::NodeHandle::subscribe() and someday ros:...
Encapsulates all options available for creating a ServiceServer.
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
Returns a pointer to the global default callback queue.
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 call...
std::map< std::string, std::string > M_string
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.
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...
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 fu...
ROSCPP_DECL std::string remap(const std::string &name)
Apply remappings to a name.
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
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_
Encapsulates all options available for creating a Subscriber.
Duration expectedCycleTime() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Assign value from parameter server, with default.
roscpp's interface for creating subscribers, publishers, etc.
boost::function< void(const SteadyTimerEvent &)> SteadyTimerCallback
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.
ROSCPP_DECL bool ok()
Check whether it's time to exit.
VoidConstPtr tracked_object
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...
const std::string & getNamespace() const
Returns the namespace associated with this NodeHandle.
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.
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...
T param(const std::string ¶m_name, const T &default_val) const
Return value from parameter server, or default if unavailable.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Advertise a topic, simple version.
Manages an advertisement on a specific topic.
TransportHints transport_hints
Hints for transport type and options.
Structure passed as a parameter to the callback invoked by a ros::SteadyTimer.
Event type for services, ros::ServiceEvent<MReq, MRes>& can be used in your callback instead of MReq&...
Manages a steady-clock timer callback.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to a topic, version for arbitrary boost::function object.
Subscriber subscribe(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.
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...
boost::function< void(const WallTimerEvent &)> WallTimerCallback
Manages an service advertisement.
VoidConstPtr tracked_object
An object whose destruction will prevent the callback associated with this subscription.
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...
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...
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...
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 fu...
CallbackQueueInterface * getCallbackQueue() const
Returns the callback queue associated with this NodeHandle. If none has been explicitly set...
Structure passed as a parameter to the callback invoked by a ros::WallTimer.
Structure passed as a parameter to the callback invoked by a ros::Timer.
Manages a wall-clock timer callback.
NodeHandleBackingCollection * collection_
Encapsulates all options available for starting a timer.
VoidConstPtr tracked_object