30 #ifndef RTT_DYNAMIC_RECONFIGURE_TESTS_TEST_COMPONENT_HPP 31 #define RTT_DYNAMIC_RECONFIGURE_TESTS_TEST_COMPONENT_HPP 35 #include <dynamic_reconfigure/Reconfigure.h> 36 #include <geometry_msgs/Vector3.h> 81 :
RTT::TaskContext(name)
82 , updatePropertiesCalled(false)
83 , updatePropertiesConstCalled(false)
84 , notifyPropertiesUpdateCalled(false)
86 this->addProperty(
"int_param", props.
int_param);
88 this->addProperty(
"str_param", props.
str_param);
89 this->addProperty(
"bool_param", props.
bool_param);
91 this->addProperty(
"float_param", props.
float_param);
92 this->addProperty(
"uint_param", props.
uint_param);
95 this->addProperty(
"bag_param", props.
bag_param);
105 updatePropertiesCalled =
true;
111 updatePropertiesConstCalled =
true;
117 notifyPropertiesUpdateCalled =
true;
121 dynamic_reconfigure::Reconfigure::Request &req,
122 dynamic_reconfigure::Reconfigure::Response &rsp) {
125 = boost::dynamic_pointer_cast<
Server<AutoConfig> >(provides()->getService(service_name));
126 if (!service)
return false;
127 return service->setConfigCallback(req, rsp);
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
geometry_msgs::Vector3 vector3_param
Property< T > & addProperty(const std::string &name, T &attr)
static Logger::LogFunction endlog()