29 #ifndef ROSCPP_NODE_HANDLE_H
30 #define ROSCPP_NODE_HANDLE_H
32 #include "ros/forwards.h"
33 #include "ros/publisher.h"
34 #include "ros/subscriber.h"
35 #include "ros/service_server.h"
36 #include "ros/service_client.h"
37 #include "ros/timer.h"
39 #include "ros/wall_timer.h"
40 #include "ros/advertise_options.h"
41 #include "ros/advertise_service_options.h"
42 #include "ros/subscribe_options.h"
43 #include "ros/service_client_options.h"
44 #include "ros/timer_options.h"
45 #include "ros/wall_timer_options.h"
46 #include "ros/spinner.h"
52 #include <xmlrpcpp/XmlRpcValue.h>
57 class NodeHandleBackingCollection;
215 std::string resolveName(
const std::string&
name,
bool remap =
true)
const;
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, std::bind(fp, obj, std::placeholders::_1));
412 template<
class M,
class T>
417 ops.template initByFullCallbackType<M>(topic,
queue_size, std::bind(fp, obj, std::placeholders::_1));
464 template<
class M,
class T>
466 void(T::*fp)(
const std::shared_ptr<M const>&), T* obj,
470 ops.template init<M>(topic,
queue_size, std::bind(fp, obj, std::placeholders::_1));
474 template<
class M,
class T>
476 void(T::*fp)(
const std::shared_ptr<M const>&)
const, T* obj,
480 ops.template init<M>(topic,
queue_size, std::bind(fp, obj, std::placeholders::_1));
528 template<
class M,
class T>
533 ops.template initByFullCallbackType<M>(topic,
queue_size, std::bind(fp, obj.get(), std::placeholders::_1));
539 template<
class M,
class T>
544 ops.template initByFullCallbackType<M>(topic,
queue_size, std::bind(fp, obj.get(), std::placeholders::_1));
593 template<
class M,
class T>
595 void(T::*fp)(
const std::shared_ptr<M const>&),
599 ops.template init<M>(topic,
queue_size, std::bind(fp, obj.get(), std::placeholders::_1));
604 template<
class M,
class T>
606 void(T::*fp)(
const std::shared_ptr<M const>&)
const,
610 ops.template init<M>(topic,
queue_size, std::bind(fp, obj.get(), std::placeholders::_1));
659 ops.template initByFullCallbackType<M>(topic,
queue_size, fp);
798 template<
class M,
class C>
878 template<
class T,
class MReq,
class MRes>
882 ops.template init<MReq, MRes>(service, std::bind(srv_func, obj, std::placeholders::_1, std::placeholders::_2));
923 template<
class T,
class MReq,
class MRes>
927 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, std::bind(srv_func, obj, std::placeholders::_1));
969 template<
class T,
class MReq,
class MRes>
973 ops.template init<MReq, MRes>(service, std::bind(srv_func, obj.get(), std::placeholders::_1, std::placeholders::_2));
1016 template<
class T,
class MReq,
class MRes>
1020 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, std::bind(srv_func, obj.get(), std::placeholders::_1));
1060 template<
class MReq,
class MRes>
1064 ops.template init<MReq, MRes>(service, srv_func);
1103 template<
class MReq,
class MRes>
1107 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, srv_func);
1144 template<
class MReq,
class MRes>
1149 ops.template init<MReq, MRes>(service,
callback);
1194 ops.template initBySpecType<S>(service,
callback);
1239 template<
class MReq,
class MRes>
1244 ops.template init<MReq, MRes>(service_name, persistent, header_values);
1259 template<
class Service>
1264 ops.template init<Service>(service_name, persistent, header_values);
1293 template<
class Handler,
class Obj>
1314 bool oneshot =
false,
bool autostart =
true)
const
1316 return createTimer(period, std::bind(
callback, obj, std::placeholders::_1), oneshot, autostart);
1334 bool oneshot =
false,
bool autostart =
true)
const
1336 return createTimer(period, std::bind(
callback, obj, std::placeholders::_1), oneshot, autostart);
1356 bool oneshot =
false,
bool autostart =
true)
const
1362 return createTimer(ops);
1378 bool autostart =
true)
const;
1411 bool oneshot =
false,
bool autostart =
true)
const
1413 return createWallTimer(period, std::bind(
callback, obj, std::placeholders::_1), oneshot, autostart);
1433 const std::shared_ptr<T>& obj,
1434 bool oneshot =
false,
bool autostart =
true)
const
1440 return createWallTimer(ops);
1456 bool oneshot =
false,
bool autostart =
true)
const;
1483 void setParam(
const std::string& key,
const std::string& s)
const;
1490 void setParam(
const std::string& key,
const char* s)
const;
1497 void setParam(
const std::string& key,
double d)
const;
1504 void setParam(
const std::string& key,
int i)
const;
1511 void setParam(
const std::string& key,
bool b)
const;
1519 void setParam(
const std::string& key,
const std::vector<std::string>& vec)
const;
1526 void setParam(
const std::string& key,
const std::vector<double>& vec)
const;
1533 void setParam(
const std::string& key,
const std::vector<float>& vec)
const;
1540 void setParam(
const std::string& key,
const std::vector<int>& vec)
const;
1547 void setParam(
const std::string& key,
const std::vector<bool>& vec)
const;
1555 void setParam(
const std::string& key,
const std::map<std::string, std::string>& map)
const;
1562 void setParam(
const std::string& key,
const std::map<std::string, double>& map)
const;
1569 void setParam(
const std::string& key,
const std::map<std::string, float>& map)
const;
1576 void setParam(
const std::string& key,
const std::map<std::string, int>& map)
const;
1583 void setParam(
const std::string& key,
const std::map<std::string, bool>& map)
const;
1593 bool getParam(
const std::string& key, std::string& s)
const;
1604 bool getParam(
const std::string& key,
double& d)
const;
1615 bool getParam(
const std::string& key,
float& f)
const;
1626 bool getParam(
const std::string& key,
int& i)
const;
1637 bool getParam(
const std::string& key,
bool& b)
const;
1660 bool getParam(
const std::string& key, std::vector<std::string>& vec)
const;
1671 bool getParam(
const std::string& key, std::vector<double>& vec)
const;
1682 bool getParam(
const std::string& key, std::vector<float>& vec)
const;
1693 bool getParam(
const std::string& key, std::vector<int>& vec)
const;
1704 bool getParam(
const std::string& key, std::vector<bool>& vec)
const;
1716 bool getParam(
const std::string& key, std::map<std::string, std::string>& map)
const;
1727 bool getParam(
const std::string& key, std::map<std::string, double>& map)
const;
1738 bool getParam(
const std::string& key, std::map<std::string, float>& map)
const;
1749 bool getParam(
const std::string& key, std::map<std::string, int>& map)
const;
1760 bool getParam(
const std::string& key, std::map<std::string, bool>& map)
const;
1777 bool getParamCached(
const std::string& key, std::string& s)
const;
1791 bool getParamCached(
const std::string& key,
double& d)
const;
1805 bool getParamCached(
const std::string& key,
float& f)
const;
1819 bool getParamCached(
const std::string& key,
int& i)
const;
1833 bool getParamCached(
const std::string& key,
bool& b)
const;
1862 bool getParamCached(
const std::string& key, std::vector<std::string>& vec)
const;
1876 bool getParamCached(
const std::string& key, std::vector<double>& vec)
const;
1890 bool getParamCached(
const std::string& key, std::vector<float>& vec)
const;
1904 bool getParamCached(
const std::string& key, std::vector<int>& vec)
const;
1918 bool getParamCached(
const std::string& key, std::vector<bool>& vec)
const;
1933 bool getParamCached(
const std::string& key, std::map<std::string, std::string>& map)
const;
1947 bool getParamCached(
const std::string& key, std::map<std::string, double>& map)
const;
1961 bool getParamCached(
const std::string& key, std::map<std::string, float>& map)
const;
1975 bool getParamCached(
const std::string& key, std::map<std::string, int>& map)
const;
1989 bool getParamCached(
const std::string& key, std::map<std::string, bool>& map)
const;
1998 bool hasParam(
const std::string& key)
const;
2011 bool searchParam(
const std::string& key, std::string& result)
const;
2019 bool deleteParam(
const std::string& key)
const;
2040 template<
typename T>
2041 bool param(
const std::string& param_name, T& param_val,
const T& default_val)
const
2043 if (hasParam(param_name))
2045 if (getParam(param_name, param_val))
2051 param_val = default_val;
2073 template<
typename T>
2074 T
param(
const std::string& param_name,
const T& default_val)
2077 param(param_name, param_val, default_val);
2103 void construct(
const std::string& ns,
bool validate_name);
2106 void initRemappings(
const M_string& remappings);
2108 std::string remapName(
const std::string&
name)
const;
2124 #endif // ROSCPP_NODE_HANDLE_H