Go to the documentation of this file.
28 #ifndef ROSCPP_NODE_HANDLE_H
29 #define ROSCPP_NODE_HANDLE_H
55 class NodeHandleBackingCollection;
213 std::string resolveName(
const std::string& name,
bool remap =
true)
const;
250 ops.template init<M>(topic, queue_size);
252 return advertise(ops);
320 ops.template init<M>(topic, queue_size, connect_cb, disconnect_cb);
323 return advertise(ops);
399 template<
class M,
class T>
404 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, boost::placeholders::_1));
406 return subscribe(ops);
410 template<
class M,
class T>
415 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, boost::placeholders::_1));
417 return subscribe(ops);
462 template<
class M,
class T>
468 ops.template init<M>(topic, queue_size, boost::bind(fp, obj, boost::placeholders::_1));
470 return subscribe(ops);
472 template<
class M,
class T>
478 ops.template init<M>(topic, queue_size, boost::bind(fp, obj, boost::placeholders::_1));
480 return subscribe(ops);
526 template<
class M,
class T>
531 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), boost::placeholders::_1));
534 return subscribe(ops);
537 template<
class M,
class T>
542 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), boost::placeholders::_1));
545 return subscribe(ops);
591 template<
class M,
class T>
597 ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), boost::placeholders::_1));
600 return subscribe(ops);
602 template<
class M,
class T>
608 ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), boost::placeholders::_1));
611 return subscribe(ops);
657 ops.template initByFullCallbackType<M>(topic, queue_size, fp);
659 return subscribe(ops);
705 ops.template init<M>(topic, queue_size, fp);
707 return subscribe(ops);
752 ops.template init<M>(topic, queue_size, callback);
755 return subscribe(ops);
796 template<
class M,
class C>
797 Subscriber subscribe(
const std::string& topic, uint32_t queue_size,
const boost::function<
void (C)>& callback,
801 ops.template initByFullCallbackType<C>(topic, queue_size, callback);
804 return subscribe(ops);
876 template<
class T,
class MReq,
class MRes>
880 ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj, boost::placeholders::_1, boost::placeholders::_2));
881 return advertiseService(ops);
921 template<
class T,
class MReq,
class MRes>
925 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj, boost::placeholders::_1));
926 return advertiseService(ops);
967 template<
class T,
class MReq,
class MRes>
971 ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj.get(), boost::placeholders::_1, boost::placeholders::_2));
973 return advertiseService(ops);
1014 template<
class T,
class MReq,
class MRes>
1018 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj.get(), boost::placeholders::_1));
1020 return advertiseService(ops);
1058 template<
class MReq,
class MRes>
1062 ops.template init<MReq, MRes>(service, srv_func);
1063 return advertiseService(ops);
1101 template<
class MReq,
class MRes>
1105 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, srv_func);
1106 return advertiseService(ops);
1142 template<
class MReq,
class MRes>
1147 ops.template init<MReq, MRes>(service, callback);
1149 return advertiseService(ops);
1192 ops.template initBySpecType<S>(service, callback);
1194 return advertiseService(ops);
1237 template<
class MReq,
class MRes>
1242 ops.template init<MReq, MRes>(service_name, persistent, header_values);
1243 return serviceClient(ops);
1257 template<
class Service>
1262 ops.template init<Service>(service_name, persistent, header_values);
1263 return serviceClient(ops);
1291 template<
class Handler,
class Obj>
1312 bool oneshot =
false,
bool autostart =
true)
const
1314 return createTimer(period, boost::bind(callback, obj, boost::placeholders::_1), oneshot, autostart);
1332 bool oneshot =
false,
bool autostart =
true)
const
1334 return createTimer(period, boost::bind(callback, obj, boost::placeholders::_1), oneshot, autostart);
1354 bool oneshot =
false,
bool autostart =
true)
const
1356 TimerOptions ops(period, boost::bind(callback, obj.get(), boost::placeholders::_1), 0);
1360 return createTimer(ops);
1376 bool autostart =
true)
const;
1409 bool oneshot =
false,
bool autostart =
true)
const
1411 return createWallTimer(period, boost::bind(callback, obj, boost::placeholders::_1), oneshot, autostart);
1432 bool oneshot =
false,
bool autostart =
true)
const
1434 WallTimerOptions ops(period, boost::bind(callback, obj.get(), boost::placeholders::_1), 0);
1438 return createWallTimer(ops);
1454 bool oneshot =
false,
bool autostart =
true)
const;
1488 bool oneshot =
false,
bool autostart =
true)
const
1490 return createSteadyTimer(period, boost::bind(callback, obj, boost::placeholders::_1), oneshot, autostart);
1511 bool oneshot =
false,
bool autostart =
true)
const
1513 SteadyTimerOptions ops(period, boost::bind(callback, obj.get(), boost::placeholders::_1), 0);
1517 return createSteadyTimer(ops);
1533 bool oneshot =
false,
bool autostart =
true)
const;
1560 void setParam(
const std::string& key,
const std::string& s)
const;
1567 void setParam(
const std::string& key,
const char* s)
const;
1574 void setParam(
const std::string& key,
double d)
const;
1581 void setParam(
const std::string& key,
int i)
const;
1588 void setParam(
const std::string& key,
bool b)
const;
1596 void setParam(
const std::string& key,
const std::vector<std::string>& vec)
const;
1603 void setParam(
const std::string& key,
const std::vector<double>& vec)
const;
1610 void setParam(
const std::string& key,
const std::vector<float>& vec)
const;
1617 void setParam(
const std::string& key,
const std::vector<int>& vec)
const;
1624 void setParam(
const std::string& key,
const std::vector<bool>& vec)
const;
1632 void setParam(
const std::string& key,
const std::map<std::string, std::string>& map)
const;
1639 void setParam(
const std::string& key,
const std::map<std::string, double>& map)
const;
1646 void setParam(
const std::string& key,
const std::map<std::string, float>& map)
const;
1653 void setParam(
const std::string& key,
const std::map<std::string, int>& map)
const;
1660 void setParam(
const std::string& key,
const std::map<std::string, bool>& map)
const;
1670 bool getParam(
const std::string& key, std::string& s)
const;
1681 bool getParam(
const std::string& key,
double& d)
const;
1692 bool getParam(
const std::string& key,
float& f)
const;
1703 bool getParam(
const std::string& key,
int& i)
const;
1714 bool getParam(
const std::string& key,
bool& b)
const;
1737 bool getParam(
const std::string& key, std::vector<std::string>& vec)
const;
1748 bool getParam(
const std::string& key, std::vector<double>& vec)
const;
1759 bool getParam(
const std::string& key, std::vector<float>& vec)
const;
1770 bool getParam(
const std::string& key, std::vector<int>& vec)
const;
1781 bool getParam(
const std::string& key, std::vector<bool>& vec)
const;
1793 bool getParam(
const std::string& key, std::map<std::string, std::string>& map)
const;
1804 bool getParam(
const std::string& key, std::map<std::string, double>& map)
const;
1815 bool getParam(
const std::string& key, std::map<std::string, float>& map)
const;
1826 bool getParam(
const std::string& key, std::map<std::string, int>& map)
const;
1837 bool getParam(
const std::string& key, std::map<std::string, bool>& map)
const;
1854 bool getParamCached(
const std::string& key, std::string& s)
const;
1868 bool getParamCached(
const std::string& key,
double& d)
const;
1882 bool getParamCached(
const std::string& key,
float& f)
const;
1896 bool getParamCached(
const std::string& key,
int& i)
const;
1910 bool getParamCached(
const std::string& key,
bool& b)
const;
1939 bool getParamCached(
const std::string& key, std::vector<std::string>& vec)
const;
1953 bool getParamCached(
const std::string& key, std::vector<double>& vec)
const;
1967 bool getParamCached(
const std::string& key, std::vector<float>& vec)
const;
1981 bool getParamCached(
const std::string& key, std::vector<int>& vec)
const;
1995 bool getParamCached(
const std::string& key, std::vector<bool>& vec)
const;
2010 bool getParamCached(
const std::string& key, std::map<std::string, std::string>& map)
const;
2024 bool getParamCached(
const std::string& key, std::map<std::string, double>& map)
const;
2038 bool getParamCached(
const std::string& key, std::map<std::string, float>& map)
const;
2052 bool getParamCached(
const std::string& key, std::map<std::string, int>& map)
const;
2066 bool getParamCached(
const std::string& key, std::map<std::string, bool>& map)
const;
2075 bool hasParam(
const std::string& key)
const;
2088 bool searchParam(
const std::string& key, std::string& result)
const;
2096 bool deleteParam(
const std::string& key)
const;
2117 template<
typename T>
2118 bool param(
const std::string& param_name, T& param_val,
const T& default_val)
const
2120 if (hasParam(param_name))
2122 if (getParam(param_name, param_val))
2128 param_val = default_val;
2150 template<
typename T>
2151 T
param(
const std::string& param_name,
const T& default_val)
const
2154 param(param_name, param_val, default_val);
2178 std::string resolveName(
const std::string& name,
bool remap,
no_validate)
const;
2180 void construct(
const std::string& ns,
bool validate_name);
2183 void initRemappings(
const M_string& remappings);
2185 std::string remapName(
const std::string& name)
const;
2201 #endif // ROSCPP_NODE_HANDLE_H
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())
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...
Duration expectedCycleTime() const
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())
boost::function< void(const TimerEvent &)> TimerCallback
Encapsulates all options available for starting a timer.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
Assign value from parameter server, with default.
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...
const std::string & getUnresolvedNamespace() const
Returns the namespace associated with this NodeHandle as it was passed in (before it was resolved)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), T *obj)
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.
TransportHints transport_hints
Hints for transport type and options.
VoidConstPtr tracked_object
An object whose destruction will prevent the callback associated with this service from being called.
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.
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...
Provides a way of specifying network transport hints to ros::NodeHandle::subscribe() and someday ros:...
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Assign value from parameter server, with default.
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
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)
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...
ServiceServer advertiseService(const std::string &service, const boost::function< bool(S &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr())
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
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())
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
VoidConstPtr tracked_object
An object whose destruction will prevent the callback associated with this subscription.
boost::function< void(const WallTimerEvent &)> WallTimerCallback
std::string unresolved_namespace_
Encapsulates all options available for creating a Publisher.
ROSCPP_DECL bool ok()
Check whether it's time to exit.
VoidConstPtr tracked_object
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
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(*fp)(M), const TransportHints &transport_hints=TransportHints())
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...
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr< T > &obj)
Manages a timer callback.
Manages a wall-clock timer callback.
Encapsulates all options available for starting a timer.
CallbackQueueInterface * callback_queue_
ServiceServer advertiseService(const std::string &service, const boost::function< bool(MReq &, MRes &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr())
VoidConstPtr tracked_object
VoidConstPtr tracked_object
bool latch
Whether or not this publication should "latch". A latching publication will automatically send out th...
boost::shared_ptr< void const > VoidConstPtr
M_string unresolved_remappings_
Encapsulates all options available for creating a ServiceClient.
ServiceServer advertiseService(const std::string &service, bool(*srv_func)(MReq &, MRes &))
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...
Provides a handle-based interface to service client connections.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr< M const > &), const TransportHints &transport_hints=TransportHints())
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::SteadyTimer.
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())
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())
Encapsulates all options available for creating a ServiceServer.
roscpp's interface for creating subscribers, publishers, etc.
Structure passed as a parameter to the callback invoked by a ros::Timer.
ROSCPP_DECL std::string remap(const std::string &name)
Apply remappings to a name.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), const boost::shared_ptr< T > &obj)
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.
boost::function< void(const SteadyTimerEvent &)> SteadyTimerCallback
Structure passed as a parameter to the callback invoked by a ros::WallTimer.
Encapsulates all options available for creating a Subscriber.
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())
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())
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...
T param(const std::string ¶m_name, const T &default_val) const
Return value from parameter server, or default if unavailable.
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.
Manages an service advertisement.
const std::string & getNamespace() const
Returns the namespace associated with this NodeHandle.
Manages an subscription callback on a specific topic.
VoidConstPtr tracked_object
An object whose destruction will prevent the callbacks associated with this advertisement from being ...
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())
Manages a steady-clock timer callback.
Abstract interface for a queue used to handle all callbacks within roscpp.
NodeHandleBackingCollection * collection_
ServiceServer advertiseService(const std::string &service, bool(*srv_func)(ServiceEvent< MReq, MRes > &))
Event type for services, ros::ServiceEvent<MReq, MRes>& can be used in your callback instead of MReq&...
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
Returns a pointer to the global default callback queue.
std::map< std::string, std::string > M_string
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