dd_server.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
4 #include <ddynamic_reconfigure/TutorialParams.h>
5 
14 using namespace ddynamic_reconfigure;
15 using namespace ros;
16 using namespace ddynamic_reconfigure;
17 
18 bool paramService(TutorialParams::Request& req, TutorialParams::Response& res, DDynamicReconfigure& dd) {
19  res.int_param = dd.get("int_param").toInt();
20  res.double_param = dd.get("double_param").toDouble();
21  res.str_param = dd.get("str_param").toString();
22  res.enum_param = dd.get("enum_param").toInt();
23  return true;
24 }
25 
26 void callback(const DDMap& map, int) {
27  ROS_INFO("Reconfigure Request: %d %f %s %s %ld",
28  get(map, "int_param").toInt(),
29  get(map, "double_param").toDouble(),
30  get(map, "str_param").toString().c_str(),
31  get(map, "bool_param").toBool() ? "True" : "False",
32  map.size());
33 }
34 
35 int main(int argc, char **argv) {
36  // ROS init stage
37  init(argc, argv, "dd_server");
38  NodeHandle nh;
39 
40  // DDynamic setup stage
41  DDynamicReconfigure dd(nh);
42  dd.add(new DDInt("int_param", 0, "An Integer parameter", 0, 50, 100));
43  dd.add(new DDDouble("double_param", 0, "A double parameter", .5, 0, 1));
44  dd.add(new DDString("str_param", 0, "A string parameter", "Hello World"));
45  dd.add(new DDBool("bool_param", 0, "A Boolean parameter", true));
46  map<string, int> dict;
47  dict["Small"] = 0;
48  dict["Medium"] = 1;
49  dict["Large"] = 2;
50  dict["ExtraLarge"] = 3;
51  dd.add(new DDEnum("enum_param", 0, "A size parameter which is edited via an enum", 1, dict));
52  dd.start(callback);
53 
54  // Actual Server Node code
55  ROS_INFO("Spinning node");
56  function<bool(TutorialParams::Request &, TutorialParams::Response &)> f = bind(paramService, _1, _2, dd);
57  ServiceServer checkParam = nh.advertiseService("get_params", f);
58  MultiThreadedSpinner spinner(2);
59  spinner.spin();
60  return 0;
61 }
62 
f
Value get(const char *name)
a tool people who use this API can use to find the value given within the param map.
a boolean implementation of the parameter. These are used to handle true/false values, or bit quantities if needed. In ROS, booleans are handled as u-bytes (u-int8), so be careful with these!
Definition: dd_bool_param.h:16
int main(int argc, char **argv)
Definition: dd_server.cpp:35
void init(const M_string &remappings)
void callback(const DDMap &map, int)
Definition: dd_server.cpp:26
map< string, DDPtr > DDMap
int toInt() const
converts the stored value into an integer.
Definition: dd_value.h:97
The DDynamicReconfigure class is the main class responsible for keeping track of parameters basic pro...
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
an integer enum implementation of the parameter. This is an extension to the int parameter, which allows creating string aliases for certain (if not all) numbers available.
Definition: dd_enum_param.h:19
#define ROS_INFO(...)
bool paramService(TutorialParams::Request &req, TutorialParams::Response &res, DDynamicReconfigure &dd)
Definition: dd_server.cpp:18
a double implementation of the parameter. This is used to handle double-precision floating point numb...
virtual void spin(CallbackQueue *queue=0)
virtual void start()
starts the server and config, without having any callback.
double toDouble() const
converts the stored value into a double.
Definition: dd_value.h:133
virtual void add(DDPtr param)
adds a parameter to the list, allowing it to be generated.
a string implementation of the parameter. This is used to handle strings of characters of variable le...
string toString() const
converts the stored value into a string.
Definition: dd_value.h:116
an integer implementation of the parameter. This is used to 32 bit signed integral numbers...
Definition: dd_int_param.h:17


ddynamic_reconfigure
Author(s): Noam Dori
autogenerated on Thu May 16 2019 02:46:37