Skip to content

Latest commit

 

History

History
137 lines (99 loc) · 3.91 KB

README.md

File metadata and controls

137 lines (99 loc) · 3.91 KB

ddynamic_reconfigure

The ddynamic_reconfigure package is a C++ extension of dynamic_reconfigure that allows modifying parameters of a ROS node using the dynamic_reconfigure framework without having to write cfg files.

Usage

This package requires at least C++11. If you have cmake version at least 3.1 the easiest way to do it is: set (CMAKE_CXX_STANDARD 11)

Modifying in place a variable:

#include <ros/ros.h>
#include <ddynamic_reconfigure/ddynamic_reconfigure.h>

int main(int argc, char **argv) {
    // ROS init stage
    ros::init(argc, argv, "ddynamic_tutorials");
    ros::NodeHandle nh;
    ddynamic_reconfigure::DDynamicReconfigure ddr;
    int int_param = 0;
    ddr.registerVariable<int>("int_param", &int_param, "param description");
    ddr.publishServicesTopics();
    // Now parameter can be modified from the dynamic_reconfigure GUI or other tools and the variable int_param is updated automatically
    
    int_param = 10; //This will also update the dynamic_reconfigure tools with the new value 10
    ros::spin();
    return 0;
 }

Modifying a variable via a callback:

#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");
}

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", 10 /* initial value */, boost::bind(paramCb, _1), "param description");
    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;
 }

Registering an enum:

#include <ros/ros.h>
#include <ddynamic_reconfigure/ddynamic_reconfigure.h>

int main(int argc, char **argv) {
    // ROS init stage
    ros::init(argc, argv, "ddynamic_tutorials");
    ros::NodeHandle nh;
    ddynamic_reconfigure::DDynamicReconfigure ddr;
    
    std::map<std::string, std::string> enum_map = {{"Key 1", "Value 1"}, {"Key 2", "Value 2"}};
    std::string enum_value = enum_map["Key 1"];
    ddr.registerEnumVariable<std::string>("string_enum", &enum_value,"param description", enum_map);
    ddr.publishServicesTopics();
    ros::spin();
    return 0;
 }

Registering variables in a private namespace "ddynamic_tutorials/other_namespace/int_param":

#include <ros/ros.h>
#include <ddynamic_reconfigure/ddynamic_reconfigure.h>

int main(int argc, char **argv) {
    // ROS init stage
    ros::init(argc, argv, "ddynamic_tutorials");
    ros::NodeHandle nh("~/other_namespace");
    ddynamic_reconfigure::DDynamicReconfigure ddr(nh);

    int int_param = 0;
    ddr.registerVariable<int>("int_param", &int_param, "param description");
    ddr.publishServicesTopics();
    
    ros::spin();
    return 0;
}

Same scenario, but with the NodeHandle created after the ddr instantiation:

#include <ros/ros.h>
#include <ddynamic_reconfigure/ddynamic_reconfigure.h>

std::unique_ptr<ddynamic_reconfigure::DDynamicReconfigure> ddr;
int main(int argc, char **argv) {
    // ROS init stage
    ros::init(argc, argv, "ddynamic_tutorials");
    ros::NodeHandle nh("~/other_namespace");

    ddr.reset(new ddynamic_reconfigure::DDynamicReconfigure(nh));
    int int_param = 0;
    ddr->registerVariable<int>("int_param", &int_param, "param description");
    ddr->publishServicesTopics();
    
    ros::spin();
    return 0;
}

Issues

Undefined reference to registerVariable or registerEnumVariable

These methods are templated, but the implementation is hidden, and there are explicit template instantiations for int, bool, double and std::string. If you are getting an undefined reference to one of these methods, make sure that you are passing parameters of this type.