rtt_dynamic_reconfigure_tests.cpp
Go to the documentation of this file.
1 /*
2  * (C) 2014, Intermodalics BVBA
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  * 1. Redistributions of source code must retain the above copyright
8  * notice, this list of conditions and the following disclaimer.
9  * 2. Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * 3. Neither the name of the copyright holder nor the names of its contributors
13  * may be used to endorse or promote products derived from this software
14  * without specific prior written permission.
15  *
16  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
17  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
18  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
19  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
20  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
21  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
22  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
24  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
25  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
26  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #define RTT_STATIC
31 
34 #include <gtest/gtest.h>
35 
37 #include <rtt/Logger.hpp>
38 
40 #include <rtt/os/main.h>
41 
43 #include <rtt/OperationCaller.hpp>
44 
45 #include <dynamic_reconfigure/ConfigDescription.h>
46 #include <dynamic_reconfigure/config_tools.h>
47 
48 #include <rtt_dynamic_reconfigure_tests/TestConfig.h>
49 #include "test_component.hpp"
50 
51 using namespace rtt_dynamic_reconfigure;
52 using namespace rtt_dynamic_reconfigure_tests;
53 
54 class DynamicReconfigureTest : public ::testing::Test
55 {
56 public:
58 
59  // virtual void SetUp() {}
60  // virtual void TearDown() {}
61 };
62 
63 static const dynamic_reconfigure::Group *getGroup(const dynamic_reconfigure::ConfigDescription::_groups_type *groups, const std::string &name)
64 {
65  if (!groups) return 0;
66  for(dynamic_reconfigure::ConfigDescription::_groups_type::const_iterator it = groups->begin(); it != groups->end(); ++it) {
67  if (it->name == name) return &(*it);
68  }
69  return 0;
70 }
71 
72 static const dynamic_reconfigure::ParamDescription *getParamDescription(const dynamic_reconfigure::Group *group, const std::string &name)
73 {
74  if (!group) return 0;
75  for(dynamic_reconfigure::Group::_parameters_type::const_iterator it = group->parameters.begin(); it != group->parameters.end(); ++it) {
76  if (it->name == name) return &(*it);
77  }
78  return 0;
79 }
80 
81 TEST_F(DynamicReconfigureTest, ConfigDescription)
82 {
83  // load test_reconfigure service
84  ASSERT_TRUE(tc.loadService("test_reconfigure"));
85  ASSERT_TRUE(tc.provides()->hasService("test_reconfigure"));
86 
87  // properties should still have their original default value
88  EXPECT_EQ(0, tc.props.int_param);
89  EXPECT_EQ(0, tc.props.double_param);
90  EXPECT_EQ("", tc.props.str_param);
91  EXPECT_FALSE(tc.props.bool_param);
92 
93  // non-existent properties should have been created with the default value
94  ASSERT_TRUE(tc.properties()->getPropertyType<double>("non_existent"));
95  EXPECT_EQ(5.0, *(tc.properties()->getPropertyType<double>("non_existent")));
96 
97  // get a pointer to the reconfigure service
98  boost::shared_ptr<Server<TestConfig> > server = boost::dynamic_pointer_cast<Server<TestConfig> >(tc.provides("test_reconfigure"));
99  ASSERT_TRUE(server.get());
100 
101  // check ConfigDescription groups
102  dynamic_reconfigure::ConfigDescriptionPtr description = server->getDescriptionMessage();
103  EXPECT_TRUE(getParamDescription(getGroup(&(description->groups), "Default"), "int_param"));
104  EXPECT_TRUE(getParamDescription(getGroup(&(description->groups), "Default"), "double_param"));
105  EXPECT_TRUE(getParamDescription(getGroup(&(description->groups), "Default"), "str_param"));
106  EXPECT_TRUE(getParamDescription(getGroup(&(description->groups), "Default"), "bool_param"));
107  EXPECT_TRUE(getParamDescription(getGroup(&(description->groups), "Default"), "non_existent"));
108  //EXPECT_TRUE(getGroup(&(description->groups), "a_group"));
109  //EXPECT_TRUE(getParamDescription(getGroup(&(description->groups), "a_group"), "group_param"));
110 
111  // check ConfigDescription dflt/min/max values
112  struct {
113  int int_param;
114  double double_param;
115  std::string str_param;
116  bool bool_param;
117  std::string group_param;
118  } temp;
119  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "int_param", temp.int_param));
120  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "double_param", temp.double_param));
121  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "str_param", temp.str_param));
122  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "bool_param", temp.bool_param));
123  //EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "group_param", temp.group_param));
124  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "int_param", temp.int_param));
125  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "double_param", temp.double_param));
126  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "str_param", temp.str_param));
127  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "bool_param", temp.bool_param));
128  //EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "group_param", temp.group_param));
129  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "int_param", temp.int_param));
130  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "double_param", temp.double_param));
131  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "str_param", temp.str_param));
132  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "bool_param", temp.bool_param));
133  //EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "group_param", temp.group_param));
134 }
135 
137 {
138  // load test_reconfigure service
139  ASSERT_TRUE(tc.loadService("test_reconfigure"));
140  ASSERT_TRUE(tc.provides()->hasService("test_reconfigure"));
141 
142  // check minimum values
143  const RTT::PropertyBag &min = tc.provides("test_reconfigure")->properties()->getPropertyType<RTT::PropertyBag>("min")->rvalue();
144  EXPECT_EQ(0, *(min.getPropertyType<int>("int_param")));
145  EXPECT_EQ(0.0, *(min.getPropertyType<double>("double_param")));
146  EXPECT_EQ(0.0, *(min.getPropertyType<double>("non_existent")));
147 
148  // check maximum values
149  const RTT::PropertyBag &max = tc.provides("test_reconfigure")->properties()->getPropertyType<RTT::PropertyBag>("max")->rvalue();
150  EXPECT_EQ(100, *(max.getPropertyType<int>("int_param")));
151  EXPECT_EQ(1.0, *(max.getPropertyType<double>("double_param")));
152  EXPECT_EQ(10.0, *(max.getPropertyType<double>("non_existent")));
153 
154  // check default values
155  const RTT::PropertyBag &dflt = tc.provides("test_reconfigure")->properties()->getPropertyType<RTT::PropertyBag>("default")->rvalue();
156  EXPECT_EQ(50, *(dflt.getPropertyType<int>("int_param")));
157  EXPECT_EQ(.5, *(dflt.getPropertyType<double>("double_param")));
158  EXPECT_EQ("Hello World", dflt.getPropertyType<std::string>("str_param")->rvalue());
159  EXPECT_TRUE(*(dflt.getPropertyType<bool>("bool_param")));
160  EXPECT_EQ(5.0, *(dflt.getPropertyType<double>("non_existent")));
161 }
162 
163 TEST_F(DynamicReconfigureTest, DefaultUpdateCallback)
164 {
165  // load test_reconfigure service
166  ASSERT_TRUE(tc.loadService("reconfigure"));
167  ASSERT_TRUE(tc.provides()->hasService("reconfigure"));
168 
169  // check that no user callback has been called during service construction
170  EXPECT_FALSE(tc.updatePropertiesCalled);
171  EXPECT_FALSE(tc.updatePropertiesConstCalled);
172  EXPECT_FALSE(tc.notifyPropertiesUpdateCalled);
173 
174  // check actual callback
175  dynamic_reconfigure::Reconfigure reconfigure;
176  EXPECT_TRUE(tc.setConfigCallback("reconfigure", reconfigure.request, reconfigure.response));
177  EXPECT_FALSE(tc.updatePropertiesCalled);
178  EXPECT_FALSE(tc.updatePropertiesConstCalled);
179  EXPECT_FALSE(tc.notifyPropertiesUpdateCalled);
180 }
181 
182 TEST_F(DynamicReconfigureTest, UpdatePropertiesCallback)
183 {
184  // add updateProperties operation
185  tc.addOperation("updateProperties", &DynamicReconfigureTestComponent::updateProperties, &tc);
186 
187  // load test_reconfigure service
188  ASSERT_TRUE(tc.loadService("reconfigure"));
189  ASSERT_TRUE(tc.provides()->hasService("reconfigure"));
190 
191  // check that updateProperties callback has been called during service construction
192  EXPECT_TRUE(tc.updatePropertiesCalled);
193  EXPECT_FALSE(tc.updatePropertiesConstCalled);
194  EXPECT_FALSE(tc.notifyPropertiesUpdateCalled);
195  tc.updatePropertiesCalled = false;
196 
197  // check actual callback
198  dynamic_reconfigure::Reconfigure reconfigure;
199  EXPECT_TRUE(tc.setConfigCallback("reconfigure", reconfigure.request, reconfigure.response));
200  EXPECT_TRUE(tc.updatePropertiesCalled);
201  EXPECT_FALSE(tc.updatePropertiesConstCalled);
202  EXPECT_FALSE(tc.notifyPropertiesUpdateCalled);
203 }
204 
205 TEST_F(DynamicReconfigureTest, UpdatePropertiesConstCallback)
206 {
207  // add updateProperties operation
208  tc.addOperation("updateProperties", &DynamicReconfigureTestComponent::updatePropertiesConst, &tc);
209 
210  // load test_reconfigure service
211  ASSERT_TRUE(tc.loadService("reconfigure"));
212  ASSERT_TRUE(tc.provides()->hasService("reconfigure"));
213 
214  // check that updatePropertiesConst callback has been called during service construction
215  EXPECT_FALSE(tc.updatePropertiesCalled);
216  EXPECT_TRUE(tc.updatePropertiesConstCalled);
217  EXPECT_FALSE(tc.notifyPropertiesUpdateCalled);
218  tc.updatePropertiesConstCalled = false;
219 
220  // check actual callback
221  dynamic_reconfigure::Reconfigure reconfigure;
222  EXPECT_TRUE(tc.setConfigCallback("reconfigure", reconfigure.request, reconfigure.response));
223  EXPECT_FALSE(tc.updatePropertiesCalled);
224  EXPECT_TRUE(tc.updatePropertiesConstCalled);
225  EXPECT_FALSE(tc.notifyPropertiesUpdateCalled);
226 }
227 
228 TEST_F(DynamicReconfigureTest, NotifyPropertiesUpdateCallback)
229 {
230  // add updateProperties operation
231  tc.addOperation("notifyPropertiesUpdate", &DynamicReconfigureTestComponent::notifyPropertiesUpdate, &tc);
232 
233  // load test_reconfigure service
234  ASSERT_TRUE(tc.loadService("reconfigure"));
235  ASSERT_TRUE(tc.provides()->hasService("reconfigure"));
236 
237  // check that notifyPropertiesUpdate callback has been called during service construction
238  EXPECT_FALSE(tc.updatePropertiesCalled);
239  EXPECT_FALSE(tc.updatePropertiesConstCalled);
240  EXPECT_TRUE(tc.notifyPropertiesUpdateCalled);
241  tc.notifyPropertiesUpdateCalled = false;
242 
243  // check actual callback
244  dynamic_reconfigure::Reconfigure reconfigure;
245  EXPECT_TRUE(tc.setConfigCallback("reconfigure", reconfigure.request, reconfigure.response));
246  EXPECT_FALSE(tc.updatePropertiesCalled);
247  EXPECT_FALSE(tc.updatePropertiesConstCalled);
248  EXPECT_TRUE(tc.notifyPropertiesUpdateCalled);
249 }
250 
252 {
253  // load test_reconfigure service
254  ASSERT_TRUE(tc.loadService("reconfigure"));
255  ASSERT_TRUE(tc.provides()->hasService("reconfigure"));
256 
257  // get a pointer to the reconfigure service
258  boost::shared_ptr<Server<AutoConfig> > server = boost::dynamic_pointer_cast<Server<AutoConfig> >(tc.provides("reconfigure"));
259  ASSERT_TRUE(server.get());
260 
261  // min/max/default property bag should exist with the same number of properties
262  ASSERT_TRUE(tc.provides("reconfigure")->properties()->getPropertyType<RTT::PropertyBag>("min"));
263  ASSERT_TRUE(tc.provides("reconfigure")->properties()->getPropertyType<RTT::PropertyBag>("max"));
264  ASSERT_TRUE(tc.provides("reconfigure")->properties()->getPropertyType<RTT::PropertyBag>("default"));
265  ASSERT_EQ(tc.properties()->size(), tc.provides("reconfigure")->properties()->getPropertyType<RTT::PropertyBag>("min")->rvalue().size());
266  ASSERT_EQ(tc.properties()->size(), tc.provides("reconfigure")->properties()->getPropertyType<RTT::PropertyBag>("max")->rvalue().size());
267  ASSERT_EQ(tc.properties()->size(), tc.provides("reconfigure")->properties()->getPropertyType<RTT::PropertyBag>("default")->rvalue().size());
268 
269  // properties should still have their original default value
270  EXPECT_EQ(0, tc.props.int_param);
271  EXPECT_EQ(0.0, tc.props.double_param);
272  EXPECT_EQ("", tc.props.str_param);
273  EXPECT_FALSE(tc.props.bool_param);
274  EXPECT_EQ(0.0, tc.props.float_param);
275  EXPECT_EQ(0, tc.props.uint_param);
276  EXPECT_TRUE(tc.props.bag_param.size() == 1);
277  EXPECT_EQ("", tc.props.str_param_in_bag);
278  EXPECT_EQ(1.0, tc.props.vector3_param.x);
279  EXPECT_EQ(2.0, tc.props.vector3_param.y);
280  EXPECT_EQ(3.0, tc.props.vector3_param.z);
281 
282  // default value properties should exists with the initial value of the properties
283  const RTT::PropertyBag &dflt = tc.provides("reconfigure")->properties()->getPropertyType<RTT::PropertyBag>("default")->rvalue();
284  ASSERT_TRUE(dflt.getPropertyType<int>("int_param"));
285  EXPECT_EQ(tc.props.int_param, *(dflt.getPropertyType<int>("int_param")));
286  ASSERT_TRUE(dflt.getPropertyType<double>("double_param"));
287  EXPECT_EQ(tc.props.double_param, *(dflt.getPropertyType<double>("double_param")));
288  ASSERT_TRUE(dflt.getPropertyType<std::string>("str_param"));
289  EXPECT_EQ(tc.props.str_param, dflt.getPropertyType<std::string>("str_param")->rvalue());
290  ASSERT_TRUE(dflt.getPropertyType<bool>("bool_param"));
291  EXPECT_EQ(tc.props.bool_param, *(dflt.getPropertyType<bool>("bool_param")));
292  ASSERT_TRUE(dflt.getPropertyType<float>("float_param"));
293  EXPECT_EQ(tc.props.float_param, *(dflt.getPropertyType<float>("float_param")));
294  ASSERT_TRUE(dflt.getPropertyType<unsigned int>("uint_param"));
295  EXPECT_EQ(tc.props.uint_param, *(dflt.getPropertyType<unsigned int>("uint_param")));
296 
297  ASSERT_TRUE(dflt.getPropertyType<RTT::PropertyBag>("bag_param"));
298  const RTT::PropertyBag &dflt_bag = *(dflt.getPropertyType<RTT::PropertyBag>("bag_param"));
299  EXPECT_TRUE(dflt_bag.size() == 1);
300  ASSERT_TRUE(dflt_bag.getPropertyType<std::string>("str_param"));
301  EXPECT_EQ(tc.props.str_param_in_bag, dflt_bag.getPropertyType<std::string>("str_param")->rvalue());
302 
303  ASSERT_TRUE(dflt.getPropertyType<RTT::PropertyBag>("vector3_param"));
304  const RTT::PropertyBag &dflt_vector3_bag = *(dflt.getPropertyType<RTT::PropertyBag>("vector3_param"));
305  EXPECT_TRUE(dflt_vector3_bag.size() == 3);
306  ASSERT_TRUE(dflt_vector3_bag.getPropertyType<double>("x"));
307  ASSERT_TRUE(dflt_vector3_bag.getPropertyType<double>("y"));
308  ASSERT_TRUE(dflt_vector3_bag.getPropertyType<double>("z"));
309  EXPECT_EQ(tc.props.vector3_param.x, dflt_vector3_bag.getPropertyType<double>("x")->rvalue());
310  EXPECT_EQ(tc.props.vector3_param.y, dflt_vector3_bag.getPropertyType<double>("y")->rvalue());
311  EXPECT_EQ(tc.props.vector3_param.z, dflt_vector3_bag.getPropertyType<double>("z")->rvalue());
312 
313  // check ConfigDescription
314  dynamic_reconfigure::ConfigDescriptionPtr description = server->getDescriptionMessage();
315  ASSERT_TRUE(description->groups.size() == 3);
316  EXPECT_EQ("Default", description->groups[0].name);
317  EXPECT_EQ("", description->groups[0].type);
318  EXPECT_EQ(6, description->groups[0].parameters.size());
319  EXPECT_EQ(0, description->groups[0].parent);
320  EXPECT_EQ(0, description->groups[0].id);
321  EXPECT_EQ("bag_param", description->groups[1].name);
322  EXPECT_EQ("", description->groups[1].type);
323  EXPECT_EQ(1, description->groups[1].parameters.size());
324  EXPECT_EQ(0, description->groups[1].parent);
325  EXPECT_EQ(1, description->groups[1].id);
326  EXPECT_EQ("vector3_param", description->groups[2].name);
327  EXPECT_EQ("", description->groups[2].type);
328  EXPECT_EQ(3, description->groups[2].parameters.size());
329  EXPECT_EQ(0, description->groups[2].parent);
330  EXPECT_EQ(2, description->groups[2].id);
331 
332  // check default/minimum/maximum values in description message
333  struct {
334  int int_param;
335  double double_param;
336  std::string str_param;
337  bool bool_param;
338  double float_param;
339  int uint_param;
340  std::string str_param_in_bag;
341  geometry_msgs::Vector3 vector3_param;
342  } temp;
343  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "int_param", temp.int_param));
344  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "double_param", temp.double_param));
345  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "str_param", temp.str_param));
346  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "bool_param", temp.bool_param));
347  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "float_param", temp.float_param));
348  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "uint_param", temp.uint_param));
349  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "bag_param__str_param", temp.str_param_in_bag));
350  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "vector3_param__x", temp.vector3_param.x));
351  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "vector3_param__y", temp.vector3_param.y));
352  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "vector3_param__z", temp.vector3_param.z));
353  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "int_param", temp.int_param));
354  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "double_param", temp.double_param));
355  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "str_param", temp.str_param));
356  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "bool_param", temp.bool_param));
357  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "float_param", temp.float_param));
358  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "uint_param", temp.uint_param));
359  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "bag_param__str_param", temp.str_param_in_bag));
360  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "vector3_param__x", temp.vector3_param.x));
361  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "vector3_param__y", temp.vector3_param.y));
362  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "vector3_param__z", temp.vector3_param.z));
363  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "int_param", temp.int_param));
364  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "double_param", temp.double_param));
365  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "str_param", temp.str_param));
366  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "bool_param", temp.bool_param));
367  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "float_param", temp.float_param));
368  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "uint_param", temp.uint_param));
369  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "bag_param__str_param", temp.str_param_in_bag));
370  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "vector3_param__x", temp.vector3_param.x));
371  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "vector3_param__y", temp.vector3_param.y));
372  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "vector3_param__z", temp.vector3_param.z));
373 }
374 
375 TEST_F(DynamicReconfigureTest, AutoConfigAddPropertiesAndRefresh)
376 {
377  // load test_reconfigure service
378  ASSERT_TRUE(tc.loadService("reconfigure"));
379  ASSERT_TRUE(tc.provides()->hasService("reconfigure"));
380 
381  // get a pointer to the reconfigure service
382  boost::shared_ptr<Server<AutoConfig> > server = boost::dynamic_pointer_cast<Server<AutoConfig> >(tc.provides("reconfigure"));
383  ASSERT_TRUE(server.get());
384 
385  // add a property to the TaskContext after having loaded the reconfigure service
386  tc.properties()->ownProperty(new RTT::Property<std::string>("new_param"));
387 
388  // refresh dynamic reconfigure service
389  server->refresh();
390 
391  // check ConfigDescription
392  dynamic_reconfigure::ConfigDescriptionPtr description = server->getDescriptionMessage();
393  std::string str;
394  EXPECT_TRUE(getParamDescription(getGroup(&(description->groups), "Default"), "new_param"));
395  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->dflt, "new_param", str));
396  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->min, "new_param", str));
397  EXPECT_TRUE(dynamic_reconfigure::ConfigTools::getParameter(description->max, "new_param", str));
398 }
399 
400 int main(int argc, char **argv) {
401  ::testing::InitGoogleTest(&argc, argv);
402 
403  // Initialize Orocos
404  __os_init(argc, argv);
405 
406  RTT::Logger::log().setStdStream(std::cerr);
409 
410  RTT::ComponentLoader::Instance()->import("rtt_ros", std::string());
411  RTT::OperationCaller<bool(std::string)> import = RTT::internal::GlobalService::Instance()->provides("ros")->getOperation("import");
412  import("rtt_dynamic_reconfigure_tests");
413 
414  return RUN_ALL_TESTS();
415 }
int main(int argc, char **argv)
Property< T > * getPropertyType(const std::string &name) const
const T & min(const T &a, const T &b)
int __os_init(int argc, char **argv)
PropertyBag * properties()
static boost::shared_ptr< ComponentLoader > Instance()
const T & max(const T &a, const T &b)
bool ownProperty(base::PropertyBase *p)
void mayLogStdOut(bool tf)
DynamicReconfigureTestComponent tc
TEST_F(DynamicReconfigureTest, ConfigDescription)
bool updatePropertiesConst(const RTT::PropertyBag &bag, uint32_t)
static Logger & log()
bool updateProperties(RTT::PropertyBag &bag, uint32_t)
static const dynamic_reconfigure::ParamDescription * getParamDescription(const dynamic_reconfigure::Group *group, const std::string &name)
void setStdStream(std::ostream &stdos)
size_t size() const
static const dynamic_reconfigure::Group * getGroup(const dynamic_reconfigure::ConfigDescription::_groups_type *groups, const std::string &name)
dynamic_reconfigure::ConfigDescriptionPtr getDescriptionMessage()
static RTT_API Service::shared_ptr Instance()
void setLogLevel(LogLevel ll)


rtt_dynamic_reconfigure_tests
Author(s): Johannes Meyer
autogenerated on Mon May 10 2021 02:45:24