dd_server.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <ddynamic_reconfigure/ddynamic_reconfigure.h>
00003 #include <ddynamic_reconfigure/param/dd_all_params.h>
00004 #include <ddynamic_reconfigure/TutorialParams.h>
00005 
00014 using namespace ddynamic_reconfigure;
00015 using namespace ros;
00016 using namespace ddynamic_reconfigure;
00017 
00018 bool paramService(TutorialParams::Request& req, TutorialParams::Response& res, DDynamicReconfigure& dd) {
00019     res.int_param = dd.get("int_param").toInt();
00020     res.double_param = dd.get("double_param").toDouble();
00021     res.str_param = dd.get("str_param").toString();
00022     res.enum_param = dd.get("enum_param").toInt();
00023     return true;
00024 }
00025 
00026 void callback(const DDMap& map, int) {
00027     ROS_INFO("Reconfigure Request: %d %f %s %s %ld",
00028             get(map, "int_param").toInt(),
00029             get(map, "double_param").toDouble(),
00030             get(map, "str_param").toString().c_str(),
00031             get(map, "bool_param").toBool() ? "True" : "False",
00032             map.size());
00033 }
00034 
00035 int main(int argc, char **argv) {
00036     // ROS init stage
00037     init(argc, argv, "dd_server");
00038     NodeHandle nh;
00039 
00040     // DDynamic setup stage
00041     DDynamicReconfigure dd(nh);
00042     dd.add(new DDInt("int_param", 0, "An Integer parameter", 0, 50, 100));
00043     dd.add(new DDDouble("double_param", 0, "A double parameter", .5, 0, 1));
00044     dd.add(new DDString("str_param", 0, "A string parameter", "Hello World"));
00045     dd.add(new DDBool("bool_param", 0, "A Boolean parameter", true));
00046     map<string, int> dict;
00047         dict["Small"] = 0;
00048         dict["Medium"] = 1;
00049         dict["Large"] = 2;
00050         dict["ExtraLarge"] = 3;
00051     dd.add(new DDEnum("enum_param", 0, "A size parameter which is edited via an enum", 1, dict));
00052     dd.start(callback);
00053 
00054     // Actual Server Node code
00055     ROS_INFO("Spinning node");
00056     function<bool(TutorialParams::Request &, TutorialParams::Response &)> f = bind(paramService, _1, _2, dd);
00057     ServiceServer checkParam = nh.advertiseService("get_params", f);
00058     MultiThreadedSpinner spinner(2);
00059     spinner.spin();
00060     return 0;
00061 }
00062 


ddynamic_reconfigure
Author(s): Noam Dori
autogenerated on Wed May 15 2019 04:39:27