4 #include <ddynamic_reconfigure/TutorialParams.h> 19 res.int_param = dd.
get(
"int_param").
toInt();
20 res.double_param = dd.
get(
"double_param").
toDouble();
22 res.enum_param = dd.
get(
"enum_param").
toInt();
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",
35 int main(
int argc,
char **argv) {
37 init(argc, argv,
"dd_server");
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;
50 dict[
"ExtraLarge"] = 3;
51 dd.
add(
new DDEnum(
"enum_param", 0,
"A size parameter which is edited via an enum", 1, dict));
56 function<bool(TutorialParams::Request &, TutorialParams::Response &)>
f = bind(
paramService, _1, _2, dd);
int main(int argc, char **argv)
void init(const M_string &remappings)
void callback(const DDMap &map, int)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool paramService(TutorialParams::Request &req, TutorialParams::Response &res, DDynamicReconfigure &dd)
virtual void spin(CallbackQueue *queue=0)