test_component.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Copyright (c) 2015, Intermodalics BVBA
4  * All rights reserved.
5  *
6  *********************************************************************/
7 
8 #ifndef RTT_DYNAMIC_RECONFIGURE_TESTS_TEST_COMPONENT_HPP
9 #define RTT_DYNAMIC_RECONFIGURE_TESTS_TEST_COMPONENT_HPP
10 
11 #include <rtt/TaskContext.hpp>
12 
13 #include <dynamic_reconfigure/Reconfigure.h>
14 #include <geometry_msgs/Vector3.h>
15 
18 
19 struct Properties {
21  : int_param()
22  , double_param()
23  , str_param()
24  , bool_param()
25  , float_param()
26  , uint_param()
27  , bag_param()
29  , vector3_param()
30  {}
31 
32  int int_param;
33  double double_param;
34  std::string str_param;
35  bool bool_param;
36 
37  // other property types
38  float float_param;
39  unsigned int uint_param;
40 
41  // PropertyBag properties
43  std::string str_param_in_bag;
44 
45  // composable properties
46  geometry_msgs::Vector3 vector3_param;
47 };
48 
49 namespace rtt_dynamic_reconfigure {
50 
52 {
53 public:
55  bool updatePropertiesCalled, updatePropertiesConstCalled, notifyPropertiesUpdateCalled;
56 
57  // types directly supported by dynamic_reconfigure
58  DynamicReconfigureTestComponent(const std::string &name = "component")
59  : RTT::TaskContext(name)
60  , updatePropertiesCalled(false)
61  , updatePropertiesConstCalled(false)
62  , notifyPropertiesUpdateCalled(false)
63  {
64  this->addProperty("int_param", props.int_param);
65  this->addProperty("double_param", props.double_param);
66  this->addProperty("str_param", props.str_param);
67  this->addProperty("bool_param", props.bool_param);
68 
69  this->addProperty("float_param", props.float_param);
70  this->addProperty("uint_param", props.uint_param);
71 
72  props.bag_param.addProperty("str_param", props.str_param_in_bag);
73  this->addProperty("bag_param", props.bag_param);
74 
75  props.vector3_param.x = 1.0;
76  props.vector3_param.y = 2.0;
77  props.vector3_param.z = 3.0;
78  this->addProperty("vector3_param", props.vector3_param);
79  }
80 
81  bool updateProperties(RTT::PropertyBag &bag, uint32_t) {
82  RTT::log(RTT::Info) << "updateProperties() callback called." << RTT::endlog();
83  updatePropertiesCalled = true;
84  return RTT::updateProperties(*properties(), bag);
85  }
86 
87  bool updatePropertiesConst(const RTT::PropertyBag &bag, uint32_t) {
88  RTT::log(RTT::Info) << "updatePropertiesConst() callback called." << RTT::endlog();
89  updatePropertiesConstCalled = true;
90  return RTT::updateProperties(*properties(), bag);
91  }
92 
93  void notifyPropertiesUpdate(uint32_t) {
94  RTT::log(RTT::Info) << "notifyPropertiesUpdate() callback called." << RTT::endlog();
95  notifyPropertiesUpdateCalled = true;
96  }
97 
98  bool setConfigCallback(const std::string &service_name,
99  dynamic_reconfigure::Reconfigure::Request &req,
100  dynamic_reconfigure::Reconfigure::Response &rsp) {
101  using namespace rtt_dynamic_reconfigure;
102  typename Server<AutoConfig>::shared_ptr service
103  = boost::dynamic_pointer_cast<Server<AutoConfig> >(provides()->getService(service_name));
104  if (!service) return false;
105  return service->setConfigCallback(req, rsp);
106  }
107 };
108 
109 } // namespace rtt_dynamic_reconfigure
110 
111 #endif // RTT_DYNAMIC_RECONFIGURE_TESTS_TEST_COMPONENT_HPP
bool updateProperties(PropertyBag &target, const PropertyBag &source)
RTT::PropertyBag bag_param
std::string str_param_in_bag
double double_param
unsigned int uint_param
std::string str_param
geometry_msgs::Vector3 vector3_param
bool setConfigCallback(const std::string &service_name, dynamic_reconfigure::Reconfigure::Request &req, dynamic_reconfigure::Reconfigure::Response &rsp)
Property< T > & addProperty(const std::string &name, T &attr)
DynamicReconfigureTestComponent(const std::string &name="component")
bool updatePropertiesConst(const RTT::PropertyBag &bag, uint32_t)
bool updateProperties(RTT::PropertyBag &bag, uint32_t)
static Logger & log()
static Logger::LogFunction endlog()


rtt_dynamic_reconfigure_tests
Author(s): Johannes Meyer
autogenerated on Sat Jun 8 2019 18:05:50