The DDynamicReconfigure class allows to use ROS dynamic reconfigure without the need to write a custom cpf file, variables are registered and exposed at run time. Modification of the variables is done through a variable pointer or through a callback function. More...
#include <ddynamic_reconfigure.h>
Public Types | |
typedef boost::function< void()> | UserCallbackType |
Public Member Functions | |
virtual void | clearUserCallback () |
DDynamicReconfigure (const ros::NodeHandle &nh=ros::NodeHandle("~"), bool auto_update=true) | |
template<> | |
std::vector< std::unique_ptr< RegisteredParam< int > > > & | getRegisteredVector () |
virtual void | publishServicesTopics () |
publishServicesTopics starts the server once all the needed variables are registered More... | |
virtual void | PublishServicesTopics () |
template<typename T > | |
void | registerEnumVariable (const std::string &name, T *variable, const boost::function< void(T value)> &callback, const std::string &description, std::map< std::string, T > enum_dict, const std::string &enum_description, const std::string &group) |
template<typename T > | |
void | registerEnumVariable (const std::string &name, T *variable, const boost::function< void(T)> &callback, const std::string &description, std::map< std::string, T > enum_dict={}, const std::string &enum_description="", const std::string &group="Default") |
template<typename T > | |
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") |
template<typename T > | |
void | registerEnumVariable (const std::string &name, T current_value, const boost::function< void(T)> &callback, const std::string &description, std::map< std::string, T > enum_dict={}, const std::string &enum_description="", const std::string &group="Default") |
virtual void | RegisterVariable (bool *variable, std::string id) |
template<typename T > | |
void | registerVariable (const std::string &name, T *variable, const boost::function< void(T value)> &callback, const std::string &description="", T min=getMin< T >(), T max=getMax< T >(), const std::string &group="Default") |
registerVariable like the functions above, but with a callback to be called when the variable is changed from the dynamic_reconfigure API. More... | |
template<typename T > | |
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. When a change is made, it will be reflected in the variable directly More... | |
template<typename T > | |
void | registerVariable (const std::string &name, T current_value, const boost::function< void(T value)> &callback, 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. When a change is made, the callback will be called with the new value. The variable itself is not modified when registered using this method. This method is useful for "dynamic reconfigure variables" that don't have a direct equivalent in the C++ code, such as vector.size(). More... | |
virtual void | RegisterVariable (double *variable, std::string id, double min=-100, double max=100) |
virtual void | RegisterVariable (int *variable, std::string id, int min=-100, int max=100) |
virtual void | setUserCallback (const UserCallbackType &callback) |
setUserCallback An optional callback that will be called whenever a value is changed More... | |
virtual void | updatePublishedInformation () |
virtual void | updateRegisteredVariablesData () |
updateRegisteredVariablesData - Method to be called to update the registered variable, incase the auto_update is not choosen More... | |
virtual | ~DDynamicReconfigure () |
Protected Member Functions | |
virtual dynamic_reconfigure::Config | generateConfig () |
virtual dynamic_reconfigure::ConfigDescription | generateConfigDescription () const |
template<typename T > | |
std::vector< std::unique_ptr< RegisteredParam< T > > > & | getRegisteredVector () |
virtual bool | setConfigCallback (dynamic_reconfigure::Reconfigure::Request &req, dynamic_reconfigure::Reconfigure::Response &rsp) |
virtual void | updateConfigData (const dynamic_reconfigure::Config &config) |
Protected Attributes | |
bool | advertised_ |
bool | auto_update_ |
std::vector< std::string > | config_groups_ |
ros::Publisher | descr_pub_ |
dynamic_reconfigure::Config | last_config_ |
std::atomic_bool | new_config_avail_ |
ros::NodeHandle | node_handle_ |
setUserCallback Set a function to be called when parameters have changed More... | |
ros::Timer | pub_config_timer_ |
std::vector< std::unique_ptr< RegisteredParam< bool > > > | registered_bool_ |
std::vector< std::unique_ptr< RegisteredParam< double > > > | registered_double_ |
std::vector< std::unique_ptr< RegisteredParam< int > > > | registered_int_ |
std::vector< std::unique_ptr< RegisteredParam< std::string > > > | registered_string_ |
ros::ServiceServer | set_service_ |
ros::Publisher | update_pub_ |
dynamic_reconfigure::Config | updated_config_ |
UserCallbackType | user_callback_ |
The DDynamicReconfigure class allows to use ROS dynamic reconfigure without the need to write a custom cpf file, variables are registered and exposed at run time. Modification of the variables is done through a variable pointer or through a callback function.
Definition at line 51 of file ddynamic_reconfigure.h.
typedef boost::function<void()> ddynamic_reconfigure::DDynamicReconfigure::UserCallbackType |
Definition at line 131 of file ddynamic_reconfigure.h.
ddynamic_reconfigure::DDynamicReconfigure::DDynamicReconfigure | ( | const ros::NodeHandle & | nh = ros::NodeHandle("~") , |
bool | auto_update = true |
||
) |
nh | the queue associated to this nh should spined() somewhere else |
auto_update | - Update the variable values immediately on change by service call. When it is true, it is not Thread Safe. In case it is set to False, updateRegisteredVariablesData method needs to be called to update the registered variables |
Definition at line 5 of file ddynamic_reconfigure.cpp.
|
virtual |
Definition at line 13 of file ddynamic_reconfigure.cpp.
|
virtual |
Definition at line 301 of file ddynamic_reconfigure.cpp.
|
protectedvirtual |
Definition at line 436 of file ddynamic_reconfigure.cpp.
|
protectedvirtual |
Definition at line 321 of file ddynamic_reconfigure.cpp.
std::vector< std::unique_ptr< RegisteredParam< std::string > > > & ddynamic_reconfigure::DDynamicReconfigure::getRegisteredVector | ( | ) |
Definition at line 45 of file ddynamic_reconfigure.cpp.
|
protected |
|
virtual |
publishServicesTopics starts the server once all the needed variables are registered
Definition at line 20 of file ddynamic_reconfigure.cpp.
|
virtual |
Definition at line 486 of file ddynamic_reconfigure.cpp.
void ddynamic_reconfigure::DDynamicReconfigure::registerEnumVariable | ( | const std::string & | name, |
T * | variable, | ||
const boost::function< void(T value)> & | callback, | ||
const std::string & | description, | ||
std::map< std::string, T > | enum_dict, | ||
const std::string & | enum_description, | ||
const std::string & | group | ||
) |
Definition at line 99 of file ddynamic_reconfigure.cpp.
void ddynamic_reconfigure::DDynamicReconfigure::registerEnumVariable | ( | const std::string & | name, |
T * | variable, | ||
const boost::function< void(T)> & | callback, | ||
const std::string & | description, | ||
std::map< std::string, T > | enum_dict = {} , |
||
const std::string & | enum_description = "" , |
||
const std::string & | group = "Default" |
||
) |
void ddynamic_reconfigure::DDynamicReconfigure::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 at line 78 of file ddynamic_reconfigure.cpp.
void ddynamic_reconfigure::DDynamicReconfigure::registerEnumVariable | ( | const std::string & | name, |
T | current_value, | ||
const boost::function< void(T)> & | callback, | ||
const std::string & | description, | ||
std::map< std::string, T > | enum_dict = {} , |
||
const std::string & | enum_description = "" , |
||
const std::string & | group = "Default" |
||
) |
Definition at line 126 of file ddynamic_reconfigure.cpp.
|
virtual |
Definition at line 316 of file ddynamic_reconfigure.cpp.
void ddynamic_reconfigure::DDynamicReconfigure::registerVariable | ( | const std::string & | name, |
T * | variable, | ||
const boost::function< void(T value)> & | callback, | ||
const std::string & | description = "" , |
||
T | min = getMin<T>() , |
||
T | max = getMax<T>() , |
||
const std::string & | group = "Default" |
||
) |
registerVariable like the functions above, but with a callback to be called when the variable is changed from the dynamic_reconfigure API.
Definition at line 88 of file ddynamic_reconfigure.cpp.
void ddynamic_reconfigure::DDynamicReconfigure::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. When a change is made, it will be reflected in the variable directly
Definition at line 70 of file ddynamic_reconfigure.cpp.
void ddynamic_reconfigure::DDynamicReconfigure::registerVariable | ( | const std::string & | name, |
T | current_value, | ||
const boost::function< void(T value)> & | callback, | ||
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. When a change is made, the callback will be called with the new value. The variable itself is not modified when registered using this method. This method is useful for "dynamic reconfigure variables" that don't have a direct equivalent in the C++ code, such as vector.size().
Definition at line 114 of file ddynamic_reconfigure.cpp.
|
virtual |
Deprecated functions. For backwards compatibility, cannot be a template for legacy reasons
Definition at line 306 of file ddynamic_reconfigure.cpp.
|
virtual |
Definition at line 311 of file ddynamic_reconfigure.cpp.
|
protectedvirtual |
Definition at line 184 of file ddynamic_reconfigure.cpp.
|
virtual |
setUserCallback An optional callback that will be called whenever a value is changed
Definition at line 296 of file ddynamic_reconfigure.cpp.
|
protectedvirtual |
Definition at line 264 of file ddynamic_reconfigure.cpp.
|
virtual |
Definition at line 154 of file ddynamic_reconfigure.cpp.
|
virtual |
updateRegisteredVariablesData - Method to be called to update the registered variable, incase the auto_update is not choosen
Definition at line 491 of file ddynamic_reconfigure.cpp.
|
protected |
Definition at line 183 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 184 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 193 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 181 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 198 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 186 of file ddynamic_reconfigure.h.
|
protected |
setUserCallback Set a function to be called when parameters have changed
Definition at line 178 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 197 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 191 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 190 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 189 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 192 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 179 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 180 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 199 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 195 of file ddynamic_reconfigure.h.