test_ddynamic_reconfigure.cpp
Go to the documentation of this file.
2 #include <gmock/gmock.h>
3 #include <future>
4 #include <dynamic_reconfigure/Reconfigure.h>
5 
6 using ::testing::_;
7 using ::testing::Mock;
8 using ::testing::Exactly;
9 
10 using namespace ddynamic_reconfigure;
11 
12 namespace pal
13 {
14 class MockClass
15 {
16 public:
17  MockClass() : double_param_(0.0), int_param_(0), bool_param_(false)
18  {
19  }
20  MOCK_METHOD0(userCallback, void());
21 
22  MOCK_METHOD1(strCallback, void(std::string));
23 
24  MOCK_METHOD1(doubleCallback, void(double));
25 
26  MOCK_METHOD1(intCallback, void(int));
27 
28  MOCK_METHOD1(boolCallback, void(bool));
29  std::string str_param_;
30  double double_param_;
33 };
34 
35 
36 class DDynamicReconfigureTest : public ::testing::Test
37 {
38 public:
39  void cfgCb(const dynamic_reconfigure::ConfigConstPtr& msg)
40  {
41  cfg_msg_ = msg;
42  }
43 
44  void waitForCfg()
45  {
46  cfg_msg_.reset();
47  while (!cfg_msg_.get() && ros::ok())
48  {
49  }
50  }
51 
52  dynamic_reconfigure::ConfigConstPtr cfg_msg_;
53 };
54 
56 {
57  ros::NodeHandle nh("~");
58  DDynamicReconfigure dd(nh);
59  MockClass mock;
60  mock.int_param_ = 0;
61  dd.RegisterVariable(&mock.int_param_, "int_param", -10000, 10000);
62 
64  ros::AsyncSpinner spinner(1);
65  spinner.start();
66 
67  dynamic_reconfigure::Reconfigure srv;
68  dynamic_reconfigure::IntParameter int_param;
69  int_param.name = "int_param";
70  int_param.value = 1234;
71 
72  srv.request.config.ints.push_back(int_param);
73  // This callback willnot block and does nothing, incase it is an auto_update case
75  EXPECT_EQ(0, mock.int_param_);
76  EXPECT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
77  EXPECT_EQ(mock.int_param_, int_param.value);
78 }
79 
80 TEST_F(DDynamicReconfigureTest, basicManualUpdateTest)
81 {
82  ros::NodeHandle nh("~");
83  DDynamicReconfigure dd(nh, false);
84  MockClass mock;
85  mock.int_param_ = 0;
86  dd.RegisterVariable(&mock.int_param_, "int_param", -10000, 10000);
87 
89  ros::AsyncSpinner spinner(1);
90  spinner.start();
91 
92  dynamic_reconfigure::Reconfigure srv;
93  dynamic_reconfigure::IntParameter int_param;
94  int_param.name = "int_param";
95  int_param.value = 1234;
96 
97  srv.request.config.ints.push_back(int_param);
98  EXPECT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
99  // Wait more than the timeout and see that the variable is not updated
100  ros::Duration(3.0).sleep();
101  EXPECT_EQ(mock.int_param_, 0);
102 
103  auto config = std::async([&nh, &srv]() {
104  EXPECT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
105  });
106  // Now wait for 1 sec and then call updateRegisteredVariablesData to update the data of
107  // the variable
108  ros::Duration(1.0).sleep();
110  EXPECT_EQ(mock.int_param_, int_param.value);
111 
112  srv.request.config.ints.back().value = 3214;
113  config = std::async([&nh, &srv]() {
114  EXPECT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
115  });
116  // Now call updateRegisteredVariablesData to update the data of the variable
117  ros::Duration(0.1).sleep();
119  EXPECT_EQ(mock.int_param_, srv.request.config.ints.back().value);
120 }
121 
122 TEST_F(DDynamicReconfigureTest, globalCallbackTest)
123 {
124  ros::NodeHandle nh("~");
125  DDynamicReconfigure dd(nh);
126  MockClass mock;
127  mock.int_param_ = 0;
128  mock.bool_param_ = false;
129  dd.RegisterVariable(&mock.int_param_, "int_param", 0, 100);
130  dd.RegisterVariable(&mock.bool_param_, "bool_param");
131  dd.RegisterVariable(&mock.double_param_, "double_param", -50, 50);
132  dd.setUserCallback(boost::bind(&MockClass::userCallback, &mock));
134  ros::AsyncSpinner spinner(1);
135  spinner.start();
136 
137  EXPECT_CALL(mock, userCallback()).Times(Exactly(1));
138 
139  dynamic_reconfigure::Reconfigure srv;
140  dynamic_reconfigure::IntParameter int_param;
141  int_param.name = "int_param";
142  int_param.value = -1234;
143  srv.request.config.ints.push_back(int_param);
144 
145  dynamic_reconfigure::BoolParameter bool_param;
146  bool_param.name = "bool_param";
147  bool_param.value = true;
148  srv.request.config.bools.push_back(bool_param);
149 
150  dynamic_reconfigure::DoubleParameter double_param;
151  double_param.name = "double_param";
152  double_param.value = 42.4242;
153  srv.request.config.doubles.push_back(double_param);
154 
155  EXPECT_NE(mock.int_param_, int_param.value);
156  EXPECT_FALSE(mock.bool_param_);
157  EXPECT_NE(mock.double_param_, double_param.value);
158  EXPECT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
159  EXPECT_TRUE(mock.bool_param_);
160  EXPECT_EQ(mock.int_param_, int_param.value);
161  EXPECT_NEAR(mock.double_param_, double_param.value, 0.0001);
162 }
163 
165 {
166  ros::NodeHandle nh("~");
167  DDynamicReconfigure dd(nh);
168  MockClass mock;
169  dd.registerVariable<int>("int_param", mock.int_param_,
170  boost::bind(&MockClass::intCallback, &mock, _1));
171  dd.registerVariable<double>("double_param", mock.double_param_,
172  boost::bind(&MockClass::doubleCallback, &mock, _1));
173  dd.registerVariable<bool>("bool_param", mock.bool_param_,
174  boost::bind(&MockClass::boolCallback, &mock, _1));
175  dd.registerVariable<std::string>("str_param", mock.str_param_,
176  boost::bind(&MockClass::strCallback, &mock, _1));
178  ros::AsyncSpinner spinner(1);
179  spinner.start();
180 
181  dynamic_reconfigure::Reconfigure srv;
182  dynamic_reconfigure::IntParameter int_param;
183  int_param.name = "int_param";
184  int_param.value = -1234;
185 
186  dynamic_reconfigure::DoubleParameter double_param;
187  double_param.name = "double_param";
188  double_param.value = 42.4242;
189 
190  dynamic_reconfigure::StrParameter str_param;
191  str_param.name = "str_param";
192  str_param.value = "hello";
193 
194  EXPECT_CALL(mock, intCallback(int_param.value)).Times(Exactly(2));
195  EXPECT_CALL(mock, doubleCallback(double_param.value)).Times(Exactly(1));
196  EXPECT_CALL(mock, boolCallback(_)).Times(Exactly(0));
197  EXPECT_CALL(mock, strCallback("hello")).Times(Exactly(1));
198 
199  srv.request.config.ints.push_back(int_param);
200  EXPECT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
201 
202 
203  srv.request.config.doubles.push_back(double_param);
204  srv.request.config.strs.push_back(str_param);
205  EXPECT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
206 }
207 
208 
209 TEST_F(DDynamicReconfigureTest, pointerCallbackTest)
210 {
211  ros::NodeHandle nh("~");
212  DDynamicReconfigure dd(nh);
213  MockClass mock;
214  dd.registerVariable<int>("int_param", &mock.int_param_,
215  boost::bind(&MockClass::intCallback, &mock, _1));
216  dd.registerVariable<double>("double_param", &mock.double_param_,
217  boost::bind(&MockClass::doubleCallback, &mock, _1));
218  dd.registerVariable<bool>("bool_param", &mock.bool_param_,
219  boost::bind(&MockClass::boolCallback, &mock, _1));
220  dd.registerVariable<std::string>("str_param", &mock.str_param_,
221  boost::bind(&MockClass::strCallback, &mock, _1));
223  ros::AsyncSpinner spinner(1);
224  spinner.start();
225 
226  dynamic_reconfigure::Reconfigure srv;
227  dynamic_reconfigure::IntParameter int_param;
228  int_param.name = "int_param";
229  int_param.value = -1234;
230 
231  dynamic_reconfigure::DoubleParameter double_param;
232  double_param.name = "double_param";
233  double_param.value = 42.4242;
234 
235  dynamic_reconfigure::StrParameter str_param;
236  str_param.name = "str_param";
237  str_param.value = "hello";
238 
239  EXPECT_CALL(mock, intCallback(int_param.value)).Times(Exactly(2));
240  EXPECT_CALL(mock, doubleCallback(double_param.value)).Times(Exactly(1));
241  EXPECT_CALL(mock, boolCallback(_)).Times(Exactly(0));
242  EXPECT_CALL(mock, strCallback("hello")).Times(Exactly(1));
243 
244  srv.request.config.ints.push_back(int_param);
245  EXPECT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
246  EXPECT_EQ(mock.int_param_, int_param.value);
247 
248  srv.request.config.doubles.push_back(double_param);
249  srv.request.config.strs.push_back(str_param);
250  EXPECT_TRUE(ros::service::call(nh.getNamespace() + "/set_parameters", srv));
251  EXPECT_EQ(mock.double_param_, double_param.value);
252  EXPECT_EQ(mock.str_param_, str_param.value);
253 }
255 {
256  ros::NodeHandle nh("foo");
257  ros::AsyncSpinner spinner(1);
258  spinner.start();
259  DDynamicReconfigure dd(nh);
260  int int_param = 0;
261  double double_param = 1.0;
262  std::string str_param = "";
263  std::string second_str_param = "";
264  bool bool_param = false;
265  dd.registerVariable("int_param", &int_param, "");
266  dd.registerVariable("double_param", &double_param, "");
267  dd.registerVariable("str_param", &str_param, "");
268  dd.registerVariable("second_str_param", &second_str_param, "");
269  dd.registerVariable("bool_param", &bool_param, "");
271 
272  ros::Subscriber sub = nh.subscribe<dynamic_reconfigure::Config>(
273  "/foo/parameter_updates", 1, boost::bind(&DDynamicReconfigureTest::cfgCb, this, _1));
274 
275  waitForCfg();
276 
277  ASSERT_EQ(1, cfg_msg_->ints.size());
278  ASSERT_EQ("int_param", cfg_msg_->ints[0].name);
279  ASSERT_EQ(int_param, cfg_msg_->ints[0].value);
280  ASSERT_EQ(1, cfg_msg_->doubles.size());
281  ASSERT_EQ("double_param", cfg_msg_->doubles[0].name);
282  ASSERT_EQ(double_param, cfg_msg_->doubles[0].value);
283  ASSERT_EQ(2, cfg_msg_->strs.size());
284  ASSERT_EQ("str_param", cfg_msg_->strs[0].name);
285  ASSERT_EQ(str_param, cfg_msg_->strs[0].value);
286  ;
287  ASSERT_EQ("second_str_param", cfg_msg_->strs[1].name);
288  ASSERT_EQ(second_str_param, cfg_msg_->strs[1].value);
289  ASSERT_EQ(1, cfg_msg_->bools.size());
290  ASSERT_EQ("bool_param", cfg_msg_->bools[0].name);
291  ASSERT_EQ(bool_param, cfg_msg_->bools[0].value);
292 
293  int_param = 5;
294  double_param = 1e-3;
295  str_param = "changed";
296  bool_param = true;
297 
298  waitForCfg();
299  ASSERT_EQ(1, cfg_msg_->ints.size());
300  ASSERT_EQ("int_param", cfg_msg_->ints[0].name);
301  ASSERT_EQ(int_param, cfg_msg_->ints[0].value);
302  ASSERT_EQ(1, cfg_msg_->doubles.size());
303  ASSERT_EQ("double_param", cfg_msg_->doubles[0].name);
304  ASSERT_EQ(double_param, cfg_msg_->doubles[0].value);
305  ASSERT_EQ(2, cfg_msg_->strs.size());
306  ASSERT_EQ("str_param", cfg_msg_->strs[0].name);
307  ASSERT_EQ(str_param, cfg_msg_->strs[0].value);
308  ;
309  ASSERT_EQ("second_str_param", cfg_msg_->strs[1].name);
310  ASSERT_EQ(second_str_param, cfg_msg_->strs[1].value);
311  ASSERT_EQ(1, cfg_msg_->bools.size());
312  ASSERT_EQ("bool_param", cfg_msg_->bools[0].name);
313  ASSERT_EQ(bool_param, cfg_msg_->bools[0].value);
314 }
315 }
316 
317 
318 int main(int argc, char** argv)
319 {
320  testing::InitGoogleTest(&argc, argv);
321  ros::init(argc, argv, "ddynamic_reconfigure_test");
322  ros::NodeHandle nh;
323 
324  ::testing::InitGoogleMock(&argc, argv);
325 
326  return RUN_ALL_TESTS();
327 }
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
TEST_F(DDynamicReconfigureTest, threadTest)
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
bool call(const std::string &service_name, MReq &req, MRes &res)
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...
virtual void setUserCallback(const UserCallbackType &callback)
setUserCallback An optional callback that will be called whenever a value is changed ...
ROSCPP_DECL bool ok()
const std::string & getNamespace() const
dynamic_reconfigure::ConfigConstPtr cfg_msg_
bool sleep() const
virtual void RegisterVariable(double *variable, std::string id, double min=-100, double max=100)
int main(int argc, char **argv)
virtual void updateRegisteredVariablesData()
updateRegisteredVariablesData - Method to be called to update the registered variable, incase the auto_update is not choosen
void cfgCb(const dynamic_reconfigure::ConfigConstPtr &msg)


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