Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Setting Up Dynamic Reconfigure for a Node
Description: Setting Up Dynamic Reconfigure for a NodeKeywords: dynamic_reconfigure configure cpp
Tutorial Level: INTERMEDIATE
A simple example of a dynamically reconfigurable node can be found under dynamic_reconfigure/test
Setting Up Dynamic Reconfigure for a Node
This example shows how to setup a dynamic reconfigure node to reconfigure variables in the ROS message driver_base/SensorLevels.h. Suppose you are adding the dynamic reconfigure server node to your package which we'll refer to as your_package from now on.
Make your package depend on dynamic_reconfigure by adding this line to your manifest.xml,
<depend package="dynamic_reconfigure" />
- or if your ROS distribution is Groovy or higher use this:
<build_depend>dynamic_reconfigure</build_depend> <run_depend>dynamic_reconfigure</run_depend>
The example below will also need
<depend package="driver_base" />
- or if your ROS distribution is Groovy or higher use this:
<build_depend>driver_base</build_depend> <run_depend>driver_base</run_depend>
Create a configuration file, saved it as your_package/cfg/MyStuff.cfg:
# Forearm camera configuration PACKAGE='your_package' import roslib; roslib.load_manifest(PACKAGE) from math import pi from driver_base.msg import SensorLevels from dynamic_reconfigure.parameter_generator import * gen = ParameterGenerator() angles = gen.add_group("Angles") # Name Type Reconfiguration level # Description # Default Min Max angles.add("min_ang", double_t, SensorLevels.RECONFIGURE_STOP, "The angle of the first range measurement. The unit depends on ~ang_radians.", -pi/2,-pi, pi) angles.add("max_ang", double_t, SensorLevels.RECONFIGURE_STOP, "The angle of the first range measurement. The unit depends on ~ang_radians.", pi/2, -pi, pi) gen.add("intensity", bool_t, SensorLevels.RECONFIGURE_STOP, "Whether or not the hokuyo returns intensity values.", False) gen.add("cluster", int_t, SensorLevels.RECONFIGURE_STOP, "The number of adjacent range measurements to cluster into a single reading", 1, 0, 99) gen.add("skip", int_t, SensorLevels.RECONFIGURE_STOP, "The number of scans to skip between each measured scan", 0, 0, 9) gen.add("port", str_t, SensorLevels.RECONFIGURE_CLOSE, "The serial port where the hokuyo device can be found", "/dev/ttyACM0") gen.add("calibrate_time", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Whether the node should calibrate the hokuyo's time offset", True) gen.add("frame_id", str_t, SensorLevels.RECONFIGURE_RUNNING, "The frame in which laser scans will be returned", "laser") gen.add("time_offset", double_t, SensorLevels.RECONFIGURE_RUNNING, "An offet to add to the timestamp before publication of a scan", 0, -0.25, 0.25) gen.add("allow_unsafe_settings",bool_t, SensorLevels.RECONFIGURE_CLOSE, "Turn this on if you wish to use the UTM-30LX with an unsafe angular range. Turning this option on may cause occasional crashes or bad data. This option is a tempory workaround that will hopefully be removed in an upcoming driver version.", False) exit(gen.generate(PACKAGE, "dynamic_reconfigure_node", "MyStuff"))
Make the .cfg file executable
chmod a+x your_package/cfg/MyStuff.cfg
Create a ROS node that processes callbacks, for example, save the following file as your_package/src/dynamic_reconfigure_node.cpp:
1 #include <dynamic_reconfigure/server.h> 2 #include <your_package/MyStuffConfig.h> 3 4 void callback(your_package::MyStuffConfig &config, uint32_t level) 5 { 6 ROS_INFO("Reconfigure request : %f %f %i %i %i %s %i %s %f %i", 7 config.groups.angles.min_ang, 8 config.groups.angles.max_ang, 9 (int)config.intensity, 10 config.cluster, 11 config.skip, 12 config.port.c_str(), 13 (int)config.calibrate_time, 14 config.frame_id.c_str(), 15 config.time_offset, 16 (int)config.allow_unsafe_settings); 17 18 // do nothing for now 19 } 20 21 int main(int argc, char **argv) 22 { 23 ros::init(argc, argv, "dynamic_reconfigure_node"); 24 dynamic_reconfigure::Server<your_package::MyStuffConfig> srv; 25 dynamic_reconfigure::Server<your_package::MyStuffConfig>::CallbackType f; 26 f = boost::bind(&callback, _1, _2); 27 srv.setCallback(f); 28 ROS_INFO("Starting to spin..."); 29 ros::spin(); 30 return 0; 31 }
Update your CMakeLists.txt to compile above by adding these lines
# add dynamic reconfigure api rosbuild_find_ros_package(dynamic_reconfigure) include(${dynamic_reconfigure_PACKAGE_PATH}/cmake/cfgbuild.cmake) gencfg() rosbuild_add_executable(dynamic_reconfigure_node src/dynamic_reconfigure_node.cpp)
- or if your ROS distribution is Groovy or higher use this:
. find_package(catkin REQUIRED COMPONENTS dynamic_reconfigure ) . generate_dynamic_reconfigure_options( cfg/MyStuff.cfg) . include_directories(${dynamic_reconfigure_PACKAGE_PATH}/cmake/cfgbuild.cmake) . add_executable(dynamic_reconfigure_node src/dynamic_reconfigure_node.cpp) . add_dependencies(dynamic_reconfigure_node ${PROJECT_NAME}_gencfg) . target_link_libraries(dynamic_reconfigure_node ${catkin_LIBRARIES})
- rosmake your package and launch the node.
rosrun your_package dynamic_reconfigure_node
taken directly from forearm camera configuration. (1)