test_component.hpp
Go to the documentation of this file.
1 /*
2  * (C) 2015, 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 #ifndef RTT_DYNAMIC_RECONFIGURE_TESTS_TEST_COMPONENT_HPP
31 #define RTT_DYNAMIC_RECONFIGURE_TESTS_TEST_COMPONENT_HPP
32 
33 #include <rtt/TaskContext.hpp>
34 
35 #include <dynamic_reconfigure/Reconfigure.h>
36 #include <geometry_msgs/Vector3.h>
37 
40 
41 struct Properties {
43  : int_param()
44  , double_param()
45  , str_param()
46  , bool_param()
47  , float_param()
48  , uint_param()
49  , bag_param()
51  , vector3_param()
52  {}
53 
54  int int_param;
55  double double_param;
56  std::string str_param;
57  bool bool_param;
58 
59  // other property types
60  float float_param;
61  unsigned int uint_param;
62 
63  // PropertyBag properties
65  std::string str_param_in_bag;
66 
67  // composable properties
68  geometry_msgs::Vector3 vector3_param;
69 };
70 
71 namespace rtt_dynamic_reconfigure {
72 
74 {
75 public:
77  bool updatePropertiesCalled, updatePropertiesConstCalled, notifyPropertiesUpdateCalled;
78 
79  // types directly supported by dynamic_reconfigure
80  DynamicReconfigureTestComponent(const std::string &name = "component")
81  : RTT::TaskContext(name)
82  , updatePropertiesCalled(false)
83  , updatePropertiesConstCalled(false)
84  , notifyPropertiesUpdateCalled(false)
85  {
86  this->addProperty("int_param", props.int_param);
87  this->addProperty("double_param", props.double_param);
88  this->addProperty("str_param", props.str_param);
89  this->addProperty("bool_param", props.bool_param);
90 
91  this->addProperty("float_param", props.float_param);
92  this->addProperty("uint_param", props.uint_param);
93 
94  props.bag_param.addProperty("str_param", props.str_param_in_bag);
95  this->addProperty("bag_param", props.bag_param);
96 
97  props.vector3_param.x = 1.0;
98  props.vector3_param.y = 2.0;
99  props.vector3_param.z = 3.0;
100  this->addProperty("vector3_param", props.vector3_param);
101  }
102 
103  bool updateProperties(RTT::PropertyBag &bag, uint32_t) {
104  RTT::log(RTT::Info) << "updateProperties() callback called." << RTT::endlog();
105  updatePropertiesCalled = true;
106  return RTT::updateProperties(*properties(), bag);
107  }
108 
109  bool updatePropertiesConst(const RTT::PropertyBag &bag, uint32_t) {
110  RTT::log(RTT::Info) << "updatePropertiesConst() callback called." << RTT::endlog();
111  updatePropertiesConstCalled = true;
112  return RTT::updateProperties(*properties(), bag);
113  }
114 
115  void notifyPropertiesUpdate(uint32_t) {
116  RTT::log(RTT::Info) << "notifyPropertiesUpdate() callback called." << RTT::endlog();
117  notifyPropertiesUpdateCalled = true;
118  }
119 
120  bool setConfigCallback(const std::string &service_name,
121  dynamic_reconfigure::Reconfigure::Request &req,
122  dynamic_reconfigure::Reconfigure::Response &rsp) {
123  using namespace rtt_dynamic_reconfigure;
124  typename Server<AutoConfig>::shared_ptr service
125  = boost::dynamic_pointer_cast<Server<AutoConfig> >(provides()->getService(service_name));
126  if (!service) return false;
127  return service->setConfigCallback(req, rsp);
128  }
129 };
130 
131 } // namespace rtt_dynamic_reconfigure
132 
133 #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 Mon May 10 2021 02:45:24