ddynamic_reconfigure_auto_update_test.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 
4 using namespace ddynamic_reconfigure;
5 
6 int main(int argc, char **argv)
7 {
8  ros::init(argc, argv, "fake_dynamic_reconfigure");
9 
10  ros::NodeHandle nh("fake_dyanmic_reconfigure");
11 
12  double value = 0;
13 
14  DDynamicReconfigure ddr_1(ros::NodeHandle(nh, "ddr1"));
15  ddr_1.RegisterVariable(&value, "value");
16  ddr_1.PublishServicesTopics();
17 
18  DDynamicReconfigure ddr_2(ros::NodeHandle(nh, "ddr2"));
19  ddr_2.RegisterVariable(&value, "value");
20  ddr_2.PublishServicesTopics();
21 
22  while (nh.ok())
23  {
24  ros::spinOnce();
25  ROS_INFO_STREAM(value);
26  ros::Duration(0.1).sleep();
27  }
28 }
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...
int main(int argc, char **argv)
#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