TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
adapter_configurer.hpp
Go to the documentation of this file.
1 /**
2  * @file adapter_configurer.hpp
3  *
4  * @author Lucas Haug <lucas.haug@thuneratz.org>
5  *
6  * @brief Template configurer for an adapter
7  *
8  * @date 06/2021
9  *
10  * @copyright MIT License - Copyright (c) 2021 ThundeRatz
11  *
12  */
13 
14 #include <memory>
15 
16 #include <ros/ros.h>
17 #include <dynamic_reconfigure/server.h>
18 #include <boost/thread/recursive_mutex.hpp>
19 
20 #ifndef __ADAPTER_CONFIGURER_H__
21 #define __ADAPTER_CONFIGURER_H__
22 
23 /*****************************************
24  * Public Constants
25  *****************************************/
26 
27 #define BASE_CONFIGURER_NAMESPACE "travesim_adapters/"
28 
29 namespace travesim {
30 /*****************************************
31  * Class Definition
32  *****************************************/
33 
34 template <class AdapterConfigType>
36  public:
37  /**
38  * @brief Construct a new AdapterConfigurer object
39  *
40  * @note The base namespace is used
41  */
42  AdapterConfigurer(void);
43 
44  /**
45  * @brief Construct a new AdapterConfigurer object
46  *
47  * @param config_namespace Namespace of the adapter configurer
48  */
49  AdapterConfigurer(std::string config_namespace);
50 
51  /**
52  * @brief Get the reset config
53  *
54  * @return true if should reset, false otherwise
55  */
56  bool get_reset(void);
57 
58  protected:
59  bool reconfigured; /**< Whether the configs where changed or not */
60 
61  AdapterConfigType config; /**< Current config */
62 
63  boost::recursive_mutex mutex; /**< Dynamic Reconfigure Server Mutex for thread-safety */
64 
65  private:
66  std::unique_ptr<ros::NodeHandle> node_handle; /**< Pointer to ROS Node Handle */
67 
68  std::unique_ptr<dynamic_reconfigure::Server<AdapterConfigType>> server; /**< Dynamic Reconfigure Server */
69 
70  /**
71  * @brief Dynamic Reconfigure Server Callback
72  *
73  * @param config New config received
74  * @param level Result of doing an "OR" operation between all of
75  * level values of the parameters that have changed
76  */
77  void callback(AdapterConfigType& config, uint32_t level);
78 };
79 
80 /*****************************************
81  * Class Public Methods Implementation
82  *****************************************/
83 
84 template <class AdapterConfigType>
87 }
88 
89 template <class AdapterConfigType>
91  this->reconfigured = false;
92 
93  this->node_handle = std::unique_ptr<ros::NodeHandle>(new ros::NodeHandle(config_namespace));
94 
95  using server_t = dynamic_reconfigure::Server<AdapterConfigType>;
96  this->server = std::unique_ptr<server_t>(new server_t(this->mutex, *(this->node_handle)));
97 
98  typename server_t::CallbackType server_cb;
99  server_cb = boost::bind(&AdapterConfigurer::callback, this, _1, _2);
100  this->server->setCallback(server_cb);
101 
102  // Update the default config in the dynamic reconfigurer
103  boost::recursive_mutex::scoped_lock scoped_lock(this->mutex);
104  this->server->getConfigDefault(this->config);
105  this->server->updateConfig(this->config);
106 }
107 
108 template <class AdapterConfigType>
110  bool should_reset = this->config.reset || this->reconfigured;
111 
112  if (should_reset) {
113  boost::recursive_mutex::scoped_lock scoped_lock(this->mutex);
114 
115  this->reconfigured = false;
116 
117  this->config.reset = this->reconfigured;
118 
119  this->server->updateConfig(this->config);
120 
121  return true;
122  }
123 
124  return false;
125 }
126 
127 /*****************************************
128  * Class Private Methods Implementation
129  *****************************************/
130 
131 template <class AdapterConfigType>
132 void AdapterConfigurer<AdapterConfigType>::callback(AdapterConfigType& config, uint32_t level) {
133  this->config = config;
134  this->reconfigured = true;
135 }
136 } // namespace travesim
137 
138 #endif // __ADAPTER_CONFIGURER_H__
void callback(AdapterConfigType &config, uint32_t level)
Dynamic Reconfigure Server Callback.
AdapterConfigurer(void)
Construct a new AdapterConfigurer object.
bool get_reset(void)
Get the reset config.
std::unique_ptr< dynamic_reconfigure::Server< AdapterConfigType > > server
std::unique_ptr< ros::NodeHandle > node_handle
#define BASE_CONFIGURER_NAMESPACE
boost::recursive_mutex mutex