fake_dynamic_reconfigure_server.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 
4 using namespace ddynamic_reconfigure;
5 
15 int main(int argc, char **argv)
16 {
17  ros::init(argc, argv, "fake_dynamic_reconfigure");
18 
19  ros::NodeHandle nh("fake_dyanmic_reconfigure");
20 
21  double double_test = 0.0;
22  double double_range = 2;
23  int int_test = 0;
24  bool bool_test = false;
25  double changing_variable = 0.0;
26  std::string str_test = "";
27  DDynamicReconfigure ddr(nh);
28  DDynamicReconfigure ddr2(ros::NodeHandle(nh, "nh2"));
29  DDynamicReconfigure ddr3(ros::NodeHandle(nh, "nh3"));
30 
31  ddr.RegisterVariable(&double_test, "double_test");
32  ddr.RegisterVariable(&double_range, "double_range_test", 0, 10);
33  ddr.RegisterVariable(&int_test, "int_test");
34  ddr.RegisterVariable(&bool_test, "bool_test");
35  ddr.registerVariable("str_test", &str_test);
36  ddr.RegisterVariable(&changing_variable, "changing_variable");
37 
38  std::map<std::string, int> enum_map = { { "ZERO", 0 }, { "ONE", 1 }, { "ONE_HUNDRED", 100 } };
39  ddr.registerEnumVariable<int>(
40  "enum_int", enum_map["ONE"],
41  [](int new_value) { ROS_INFO_STREAM("Value changed to " << new_value); },
42  "Enum parameter", enum_map, "enum description");
43 
44  std::map<std::string, std::string> str_enum_map = { { "ZERO", "zero" },
45  { "ONE", "one" },
46  { "ONE_HUNDRED", "one hundred" } };
47  ddr.registerEnumVariable<std::string>(
48  "enum_string", str_enum_map["ONE"],
49  [](std::string new_value) { ROS_INFO_STREAM("Value changed to " << new_value); },
50  "Enum parameter", str_enum_map, "enum description");
51 
52  std::map<std::string, double> double_enum_map = { { "ZERO", 0.0 },
53  { "ONE", 1.1 },
54  { "ONE_HUNDRED", 100.001 } };
55  ddr.registerEnumVariable<double>(
56  "enum_double", double_enum_map["ONE"],
57  [](double new_value) { ROS_INFO_STREAM("Value changed to " << new_value); },
58  "Enum parameter", double_enum_map, "enum description");
59 
60 
61  std::map<std::string, bool> bool_enum_map = { { "false", false },
62  { "true", true },
63  { "also true", true } };
64  ddr.registerEnumVariable<bool>(
65  "enum_bool", bool_enum_map["ONE"],
66  [](bool new_value) { ROS_INFO_STREAM("Value changed to " << new_value); },
67  "Enum parameter", bool_enum_map, "enum description");
68 
69  ddr2.RegisterVariable(&double_test, "double_test");
70  ddr2.RegisterVariable(&int_test, "int_test");
71  ddr2.RegisterVariable(&bool_test, "bool_test");
72 
74  ddr2.PublishServicesTopics();
75  ddr3.PublishServicesTopics();
76 
77 
78  ROS_INFO("Spinning node");
79 
80  while (nh.ok())
81  {
82  changing_variable += 0.5;
83  std::cerr << "changing_variable " << changing_variable << std::endl;
84  std::cerr << "double " << double_test << std::endl;
85  std::cerr << "double range" << double_range << std::endl;
86  std::cerr << "int " << int_test << std::endl;
87  std::cerr << "bool " << bool_test << std::endl;
88  std::cerr << "str " << str_test << std::endl;
89  std::cerr << "*********" << std::endl;
90  ros::spinOnce();
91  ros::Duration(1.0).sleep();
92  }
93  return 0;
94 }
void registerVariable(const std::string &name, T *variable, const std::string &description="", T min=getMin< T >(), T max=getMax< T >(), const std::string &group="Default")
registerVariable register a variable to be modified via the dynamic_reconfigure API. When a change is made, it will be reflected in the variable directly
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
The DDynamicReconfigure class allows to use ROS dynamic reconfigure without the need to write a custo...
void registerEnumVariable(const std::string &name, T *variable, const std::string &description="", std::map< std::string, T > enum_dict={}, const std::string &enum_description="", const std::string &group="Default")
int main(int argc, char **argv)
#define ROS_INFO(...)
#define ROS_INFO_STREAM(args)
bool sleep() const
virtual void RegisterVariable(double *variable, std::string id, double min=-100, double max=100)
ROSCPP_DECL void spinOnce()
bool ok() const


ddynamic_reconfigure
Author(s): Hilario Tome
autogenerated on Mon Feb 28 2022 22:12:28