17 #include <dynamic_reconfigure/server.h> 18 #include <boost/thread/recursive_mutex.hpp> 20 #ifndef __ADAPTER_CONFIGURER_H__ 21 #define __ADAPTER_CONFIGURER_H__ 27 #define BASE_CONFIGURER_NAMESPACE "travesim_adapters/" 34 template <
class AdapterConfigType>
68 std::unique_ptr<dynamic_reconfigure::Server<AdapterConfigType>>
server;
84 template <
class AdapterConfigType>
89 template <
class AdapterConfigType>
91 this->reconfigured =
false;
93 this->node_handle = std::unique_ptr<ros::NodeHandle>(
new ros::NodeHandle(config_namespace));
95 using server_t = dynamic_reconfigure::Server<AdapterConfigType>;
96 this->server = std::unique_ptr<server_t>(
new server_t(this->mutex, *(this->node_handle)));
98 typename server_t::CallbackType server_cb;
99 server_cb = boost::bind(&AdapterConfigurer::callback,
this, _1, _2);
100 this->server->setCallback(server_cb);
103 boost::recursive_mutex::scoped_lock scoped_lock(this->mutex);
104 this->server->getConfigDefault(this->config);
105 this->server->updateConfig(this->config);
108 template <
class AdapterConfigType>
110 bool should_reset = this->config.reset || this->reconfigured;
113 boost::recursive_mutex::scoped_lock scoped_lock(this->mutex);
115 this->reconfigured =
false;
117 this->config.reset = this->reconfigured;
119 this->server->updateConfig(this->config);
131 template <
class AdapterConfigType>
133 this->config = config;
134 this->reconfigured =
true;
138 #endif // __ADAPTER_CONFIGURER_H__