8 #ifndef RTT_DYNAMIC_RECONFIGURE_TESTS_TEST_COMPONENT_HPP 9 #define RTT_DYNAMIC_RECONFIGURE_TESTS_TEST_COMPONENT_HPP 13 #include <dynamic_reconfigure/Reconfigure.h> 14 #include <geometry_msgs/Vector3.h> 59 :
RTT::TaskContext(name)
60 , updatePropertiesCalled(false)
61 , updatePropertiesConstCalled(false)
62 , notifyPropertiesUpdateCalled(false)
64 this->addProperty(
"int_param", props.
int_param);
66 this->addProperty(
"str_param", props.
str_param);
67 this->addProperty(
"bool_param", props.
bool_param);
69 this->addProperty(
"float_param", props.
float_param);
70 this->addProperty(
"uint_param", props.
uint_param);
73 this->addProperty(
"bag_param", props.
bag_param);
83 updatePropertiesCalled =
true;
89 updatePropertiesConstCalled =
true;
95 notifyPropertiesUpdateCalled =
true;
99 dynamic_reconfigure::Reconfigure::Request &req,
100 dynamic_reconfigure::Reconfigure::Response &rsp) {
103 = boost::dynamic_pointer_cast<
Server<AutoConfig> >(provides()->getService(service_name));
104 if (!service)
return false;
105 return service->setConfigCallback(req, rsp);
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
geometry_msgs::Vector3 vector3_param
Property< T > & addProperty(const std::string &name, T &attr)
static Logger::LogFunction endlog()