test_component.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  *  Copyright (c) 2015, Intermodalics BVBA
00004  *  All rights reserved.
00005  *
00006  *********************************************************************/
00007 
00008 #ifndef RTT_DYNAMIC_RECONFIGURE_TESTS_TEST_COMPONENT_HPP
00009 #define RTT_DYNAMIC_RECONFIGURE_TESTS_TEST_COMPONENT_HPP
00010 
00011 #include <rtt/TaskContext.hpp>
00012 
00013 #include <dynamic_reconfigure/Reconfigure.h>
00014 #include <geometry_msgs/Vector3.h>
00015 
00016 #include <rtt_dynamic_reconfigure/server.h>
00017 #include <rtt_dynamic_reconfigure/auto_config.h>
00018 
00019 struct Properties {
00020     Properties()
00021     : int_param()
00022     , double_param()
00023     , str_param()
00024     , bool_param()
00025     , float_param()
00026     , uint_param()
00027     , bag_param()
00028     , str_param_in_bag()
00029     , vector3_param()
00030     {}
00031 
00032     int int_param;
00033     double double_param;
00034     std::string str_param;
00035     bool bool_param;
00036 
00037     // other property types
00038     float float_param;
00039     unsigned int uint_param;
00040 
00041     // PropertyBag properties
00042     RTT::PropertyBag bag_param;
00043     std::string str_param_in_bag;
00044 
00045     // composable properties
00046     geometry_msgs::Vector3 vector3_param;
00047 };
00048 
00049 namespace rtt_dynamic_reconfigure {
00050 
00051 class DynamicReconfigureTestComponent : public RTT::TaskContext
00052 {
00053 public:
00054     Properties props;
00055     bool updatePropertiesCalled, updatePropertiesConstCalled, notifyPropertiesUpdateCalled;
00056 
00057     // types directly supported by dynamic_reconfigure
00058     DynamicReconfigureTestComponent(const std::string &name = "component")
00059         : RTT::TaskContext(name)
00060         , updatePropertiesCalled(false)
00061         , updatePropertiesConstCalled(false)
00062         , notifyPropertiesUpdateCalled(false)
00063     {
00064         this->addProperty("int_param", props.int_param);
00065         this->addProperty("double_param", props.double_param);
00066         this->addProperty("str_param", props.str_param);
00067         this->addProperty("bool_param", props.bool_param);
00068 
00069         this->addProperty("float_param", props.float_param);
00070         this->addProperty("uint_param", props.uint_param);
00071 
00072         props.bag_param.addProperty("str_param", props.str_param_in_bag);
00073         this->addProperty("bag_param", props.bag_param);
00074 
00075         props.vector3_param.x = 1.0;
00076         props.vector3_param.y = 2.0;
00077         props.vector3_param.z = 3.0;
00078         this->addProperty("vector3_param", props.vector3_param);
00079     }
00080 
00081     bool updateProperties(RTT::PropertyBag &bag, uint32_t) {
00082         RTT::log(RTT::Info) << "updateProperties() callback called." << RTT::endlog();
00083         updatePropertiesCalled = true;
00084         return RTT::updateProperties(*properties(), bag);
00085     }
00086 
00087     bool updatePropertiesConst(const RTT::PropertyBag &bag, uint32_t) {
00088         RTT::log(RTT::Info) << "updatePropertiesConst() callback called." << RTT::endlog();
00089         updatePropertiesConstCalled = true;
00090         return RTT::updateProperties(*properties(), bag);
00091     }
00092 
00093     void notifyPropertiesUpdate(uint32_t) {
00094         RTT::log(RTT::Info) << "notifyPropertiesUpdate() callback called." << RTT::endlog();
00095         notifyPropertiesUpdateCalled = true;
00096     }
00097 
00098     bool setConfigCallback(const std::string &service_name,
00099                            dynamic_reconfigure::Reconfigure::Request &req,
00100                            dynamic_reconfigure::Reconfigure::Response &rsp) {
00101         using namespace rtt_dynamic_reconfigure;
00102         typename Server<AutoConfig>::shared_ptr service
00103             = boost::dynamic_pointer_cast<Server<AutoConfig> >(provides()->getService(service_name));
00104         if (!service) return false;
00105         return service->setConfigCallback(req, rsp);
00106     }
00107 };
00108 
00109 } // namespace rtt_dynamic_reconfigure
00110 
00111 #endif // RTT_DYNAMIC_RECONFIGURE_TESTS_TEST_COMPONENT_HPP


rtt_dynamic_reconfigure_tests
Author(s): Johannes Meyer
autogenerated on Thu Jun 6 2019 18:06:30