ddynamic_reconfigure.h
Go to the documentation of this file.
1 
31 #ifndef _DDYNAMIC_RECONFIGURE_
32 #define _DDYNAMIC_RECONFIGURE_
33 
34 #include <dynamic_reconfigure/server.h>
37 #include <ros/ros.h>
38 #include <ros/callback_queue.h>
39 #include <ros/spinner.h>
40 #include <atomic>
41 
43 {
52 {
53 public:
61  DDynamicReconfigure(const ros::NodeHandle &nh = ros::NodeHandle("~"), bool auto_update = true);
62 
63  virtual ~DDynamicReconfigure();
64 
72  template <typename T>
73  void registerVariable(const std::string &name, T *variable,
74  const std::string &description = "", T min = getMin<T>(),
75  T max = getMax<T>(), const std::string &group = "Default");
76 
77  template <typename T>
78  void registerEnumVariable(const std::string &name, T *variable,
79  const std::string &description = "",
80  std::map<std::string, T> enum_dict = {},
81  const std::string &enum_description = "",
82  const std::string &group = "Default");
88  template <typename T>
89  void registerVariable(const std::string &name, T *variable,
90  const boost::function<void(T value)> &callback,
91  const std::string &description = "", T min = getMin<T>(),
92  T max = getMax<T>(), const std::string &group = "Default");
93 
94  template <typename T>
95  void registerEnumVariable(const std::string &name, T *variable,
96  const boost::function<void(T)> &callback,
97  const std::string &description,
98  std::map<std::string, T> enum_dict = {},
99  const std::string &enum_description = "",
100  const std::string &group = "Default");
101 
109  template <typename T>
110  void registerVariable(const std::string &name, T current_value,
111  const boost::function<void(T value)> &callback,
112  const std::string &description = "", T min = getMin<T>(),
113  T max = getMax<T>(), const std::string &group = "Default");
114 
115  template <typename T>
116  void registerEnumVariable(const std::string &name, T current_value,
117  const boost::function<void(T)> &callback,
118  const std::string &description,
119  std::map<std::string, T> enum_dict = {},
120  const std::string &enum_description = "",
121  const std::string &group = "Default");
122 
127  virtual void publishServicesTopics();
128 
129  virtual void updatePublishedInformation();
130 
131  typedef boost::function<void()> UserCallbackType;
132 
137  virtual void setPreUpdateCallback(const UserCallbackType &callback);
138 
139  virtual void clearPreUpdateCallback();
140 
145  virtual void setPostUpdateCallback(const UserCallbackType &callback);
146 
147  virtual void clearPostUpdateCallback();
148 
158  virtual void setUserCallback(const UserCallbackType &callback);
159 
160  virtual void clearUserCallback();
161 
162  virtual void RegisterVariable(double *variable, std::string id, double min = -100,
163  double max = 100);
164 
165  virtual void RegisterVariable(int *variable, std::string id, int min = -100, int max = 100);
166 
167  virtual void RegisterVariable(bool *variable, std::string id);
168 
169  virtual void PublishServicesTopics();
170 
175  virtual void updateRegisteredVariablesData();
176 
177 protected:
178  template <typename T>
179  std::vector<std::unique_ptr<RegisteredParam<T>>> &getRegisteredVector();
180 
181  virtual dynamic_reconfigure::ConfigDescription generateConfigDescription() const;
182 
183  virtual dynamic_reconfigure::Config generateConfig();
184 
185  virtual bool setConfigCallback(dynamic_reconfigure::Reconfigure::Request &req,
186  dynamic_reconfigure::Reconfigure::Response &rsp);
187 
188  virtual void updateConfigData(const dynamic_reconfigure::Config &config);
189 
198 
201 
202  std::atomic_bool new_config_avail_;
203 
204  // Registered variables
205  std::vector<std::unique_ptr<RegisteredParam<int>>> registered_int_;
206  std::vector<std::unique_ptr<RegisteredParam<double>>> registered_double_;
207  std::vector<std::unique_ptr<RegisteredParam<bool>>> registered_bool_;
208  std::vector<std::unique_ptr<RegisteredParam<std::string>>> registered_string_;
209  std::vector<std::string> config_groups_;
210 
213 
215  dynamic_reconfigure::Config last_config_;
216  dynamic_reconfigure::Config updated_config_;
217 };
218 
220 }
221 
222 #endif
ddynamic_reconfigure::DDynamicReconfigure::generateConfigDescription
virtual dynamic_reconfigure::ConfigDescription generateConfigDescription() const
Definition: ddynamic_reconfigure.cpp:361
min
int min(int a, int b)
registered_param.h
ros::Publisher
ddynamic_reconfigure::DDynamicReconfigure::node_handle_
ros::NodeHandle node_handle_
setUserCallback Set a function to be called when parameters have changed
Definition: ddynamic_reconfigure.h:194
spinner.h
ddynamic_reconfigure::DDynamicReconfigure::getRegisteredVector
std::vector< std::unique_ptr< RegisteredParam< T > > > & getRegisteredVector()
boost::shared_ptr
ddynamic_reconfigure::DDynamicReconfigurePtr
boost::shared_ptr< DDynamicReconfigure > DDynamicReconfigurePtr
Definition: ddynamic_reconfigure.h:219
ddynamic_reconfigure::DDynamicReconfigure::new_config_avail_
std::atomic_bool new_config_avail_
Definition: ddynamic_reconfigure.h:202
ddynamic_reconfigure::DDynamicReconfigure::config_groups_
std::vector< std::string > config_groups_
Definition: ddynamic_reconfigure.h:209
ros.h
ddynamic_reconfigure::DDynamicReconfigure::post_update_callback_
UserCallbackType post_update_callback_
Definition: ddynamic_reconfigure.h:212
ddynamic_reconfigure::DDynamicReconfigure::setConfigCallback
virtual bool setConfigCallback(dynamic_reconfigure::Reconfigure::Request &req, dynamic_reconfigure::Reconfigure::Response &rsp)
Definition: ddynamic_reconfigure.cpp:188
ddynamic_reconfigure
Definition: ddynamic_reconfigure.h:42
ddynamic_reconfigure::DDynamicReconfigure::advertised_
bool advertised_
Definition: ddynamic_reconfigure.h:199
ddynamic_reconfigure::DDynamicReconfigure::set_service_
ros::ServiceServer set_service_
Definition: ddynamic_reconfigure.h:195
ddynamic_reconfigure::DDynamicReconfigure::clearUserCallback
virtual void clearUserCallback()
Definition: ddynamic_reconfigure.cpp:321
ddynamic_reconfigure::DDynamicReconfigure::updateConfigData
virtual void updateConfigData(const dynamic_reconfigure::Config &config)
Definition: ddynamic_reconfigure.cpp:284
ddynamic_reconfigure::DDynamicReconfigure::registerEnumVariable
void registerEnumVariable(const std::string &name, T *variable, const std::string &description="", std::map< std::string, T > enum_dict={}, const std::string &enum_description="", const std::string &group="Default")
Definition: ddynamic_reconfigure.cpp:82
ddynamic_reconfigure::DDynamicReconfigure::registered_double_
std::vector< std::unique_ptr< RegisteredParam< double > > > registered_double_
Definition: ddynamic_reconfigure.h:206
ddynamic_reconfigure::DDynamicReconfigure::last_config_
dynamic_reconfigure::Config last_config_
Definition: ddynamic_reconfigure.h:215
ddynamic_reconfigure::DDynamicReconfigure::registered_bool_
std::vector< std::unique_ptr< RegisteredParam< bool > > > registered_bool_
Definition: ddynamic_reconfigure.h:207
ros::ServiceServer
ddynamic_reconfigure::DDynamicReconfigure::PublishServicesTopics
virtual void PublishServicesTopics()
Definition: ddynamic_reconfigure.cpp:526
ddynamic_reconfigure::DDynamicReconfigure::registerVariable
void registerVariable(const std::string &name, T *variable, const std::string &description="", T min=getMin< T >(), T max=getMax< T >(), const std::string &group="Default")
registerVariable register a variable to be modified via the dynamic_reconfigure API....
Definition: ddynamic_reconfigure.cpp:74
ddynamic_reconfigure::DDynamicReconfigure::updateRegisteredVariablesData
virtual void updateRegisteredVariablesData()
updateRegisteredVariablesData - Method to be called to update the registered variable,...
Definition: ddynamic_reconfigure.cpp:531
ddynamic_reconfigure::DDynamicReconfigure::clearPostUpdateCallback
virtual void clearPostUpdateCallback()
Definition: ddynamic_reconfigure.cpp:341
ddynamic_reconfigure::DDynamicReconfigure::setUserCallback
virtual void setUserCallback(const UserCallbackType &callback)
setUserCallback An optional callback that will be called whenever a value is changed....
Definition: ddynamic_reconfigure.cpp:316
ddynamic_reconfigure::DDynamicReconfigure::pre_update_callback_
UserCallbackType pre_update_callback_
Definition: ddynamic_reconfigure.h:211
ddynamic_reconfigure::DDynamicReconfigure::~DDynamicReconfigure
virtual ~DDynamicReconfigure()
Definition: ddynamic_reconfigure.cpp:13
ddynamic_reconfigure::DDynamicReconfigure::clearPreUpdateCallback
virtual void clearPreUpdateCallback()
Definition: ddynamic_reconfigure.cpp:331
ddynamic_reconfigure_utils.h
ddynamic_reconfigure::DDynamicReconfigure::generateConfig
virtual dynamic_reconfigure::Config generateConfig()
Definition: ddynamic_reconfigure.cpp:476
callback_queue.h
ddynamic_reconfigure::DDynamicReconfigure::descr_pub_
ros::Publisher descr_pub_
Definition: ddynamic_reconfigure.h:197
ddynamic_reconfigure::DDynamicReconfigure::RegisterVariable
virtual void RegisterVariable(double *variable, std::string id, double min=-100, double max=100)
Definition: ddynamic_reconfigure.cpp:346
ddynamic_reconfigure::DDynamicReconfigure::UserCallbackType
boost::function< void()> UserCallbackType
Definition: ddynamic_reconfigure.h:131
ddynamic_reconfigure::DDynamicReconfigure
The DDynamicReconfigure class allows to use ROS dynamic reconfigure without the need to write a custo...
Definition: ddynamic_reconfigure.h:51
ddynamic_reconfigure::DDynamicReconfigure::pub_config_timer_
ros::Timer pub_config_timer_
Definition: ddynamic_reconfigure.h:214
ddynamic_reconfigure::DDynamicReconfigure::setPostUpdateCallback
virtual void setPostUpdateCallback(const UserCallbackType &callback)
setPostUpdateCallback An optional callback that will be called right after any value is changed.
Definition: ddynamic_reconfigure.cpp:336
ddynamic_reconfigure::DDynamicReconfigure::publishServicesTopics
virtual void publishServicesTopics()
publishServicesTopics starts the server once all the needed variables are registered
Definition: ddynamic_reconfigure.cpp:20
ddynamic_reconfigure::DDynamicReconfigure::setPreUpdateCallback
virtual void setPreUpdateCallback(const UserCallbackType &callback)
setPreUpdateCallback An optional callback that will be called right before any value is changed
Definition: ddynamic_reconfigure.cpp:326
ddynamic_reconfigure::DDynamicReconfigure::updated_config_
dynamic_reconfigure::Config updated_config_
Definition: ddynamic_reconfigure.h:216
ddynamic_reconfigure::DDynamicReconfigure::auto_update_
bool auto_update_
Definition: ddynamic_reconfigure.h:200
ddynamic_reconfigure::DDynamicReconfigure::DDynamicReconfigure
DDynamicReconfigure(const ros::NodeHandle &nh=ros::NodeHandle("~"), bool auto_update=true)
Definition: ddynamic_reconfigure.cpp:5
ddynamic_reconfigure::DDynamicReconfigure::registered_string_
std::vector< std::unique_ptr< RegisteredParam< std::string > > > registered_string_
Definition: ddynamic_reconfigure.h:208
ddynamic_reconfigure::DDynamicReconfigure::updatePublishedInformation
virtual void updatePublishedInformation()
Definition: ddynamic_reconfigure.cpp:158
ros::Timer
ddynamic_reconfigure::DDynamicReconfigure::registered_int_
std::vector< std::unique_ptr< RegisteredParam< int > > > registered_int_
Definition: ddynamic_reconfigure.h:205
ros::NodeHandle
ddynamic_reconfigure::DDynamicReconfigure::update_pub_
ros::Publisher update_pub_
Definition: ddynamic_reconfigure.h:196


ddynamic_reconfigure
Author(s): Hilario Tome
autogenerated on Tue Apr 22 2025 02:22:29