ROS中使用ddynamicReconfigure
关于ddynamicReconfigure类
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.
The DDynamicReconfigure class is the main class responsible for keeping track of parameters basic properties, values, descriptions, etc.
It is also responsible of handling callbacks, config change requests, description setup and config setup, and the ROS publishers and services.
To operate a DDynamic instance, you must go through the following procedure:
- Construct a DDynamicReconfigure instance with proper handling.
- Add parameters to the instance as needed with any of the “add” methods.
- Start the ROS services with any of the “start” methods.
- If you need to change the callback after startup you may do so using “setCallback”.
- When you need to get any of the stored parameters, call either “get” or “at” on this instance, rather than through the callback.
常用函数原型&解析
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.
template<typename T>
void registerVariable(
const std::string &name,
T *variable,
const std::string &description = "",
T min = getMin<T>(),
T max = getMax<T>()
);
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 = ""
);
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.
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>()
);
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 = ""
);
publishServicesTopics starts the server once all the needed variables are registered.
void publishServicesTopics();
关于getMin()与getMax()
template <typename T>
inline T getMin()
{
return std::numeric_limits<T>::min();
}
template <>
inline bool getMin()
{
return false;
}
template <>
inline std::string getMin<std::string>()
{
return "";
}
template <typename T>
inline T getMax()
{
return std::numeric_limits<T>::min();
}
template <>
inline bool getMax()
{
return true;
}
template <>
inline std::string getMax()
{
return "";
}
简单示例
#include <ros/ros.h>
#include <ddynamic_reconfigure/ddynamic_reconfigure.h>
int global_int;
void paramCb(int new_value)
{
global_int = new_value;
ROS_INFO("Param modified: %d", global_int);
}
int main(int argc, char **argv) {
// ROS init stage
ros::init(argc, argv, "ddynamic_tutorials");
ros::NodeHandle nh;
ddynamic_reconfigure::DDynamicReconfigure ddr;
ddr.registerVariable<int>("int_param",124, boost::bind(paramCb, _1), "param description",-1000,2357);
ddr.publishServicesTopics();
// Now parameter can be modified from the dynamic_reconfigure GUI or other tools and the callback is called on each update
ros::spin();
return 0;
}