## For instruction on writing tutorials ## http://www.ros.org/wiki/WritingTutorials #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0= ## descriptive title for the tutorial ## title = Setting Up Dynamic Reconfigure for a Node ## multi-line description to be displayed in search ## description = Setting Up Dynamic Reconfigure for a Node ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link= ## next.1.link= ## what level user is this tutorial for ## level=IntermediateCategory ## keywords =dynamic_reconfigure configure cpp #################################### <> <> 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 [[http://www.ros.org/doc/api/driver_base/html/msg/SensorLevels.html|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. 1. Make your package depend on [[dynamic_reconfigure]] by adding this line to your `manifest.xml`, {{{ }}} . or if your ROS distribution is Groovy or higher use this: {{{ dynamic_reconfigure dynamic_reconfigure }}} The example below will also need . {{{ }}} . or if your ROS distribution is Groovy or higher use this: {{{ driver_base driver_base }}} * Create a configuration file, saved it as ''your_package''`/cfg/MyStuff.cfg`: {{{ #!/usr/bin/python # 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`: {{{#!cplusplus #include #include void callback(your_package::MyStuffConfig &config, uint32_t level) { ROS_INFO("Reconfigure request : %f %f %i %i %i %s %i %s %f %i", config.groups.angles.min_ang, config.groups.angles.max_ang, (int)config.intensity, config.cluster, config.skip, config.port.c_str(), (int)config.calibrate_time, config.frame_id.c_str(), config.time_offset, (int)config.allow_unsafe_settings); // do nothing for now } int main(int argc, char **argv) { ros::init(argc, argv, "dynamic_reconfigure_node"); dynamic_reconfigure::Server srv; dynamic_reconfigure::Server::CallbackType f; f = boost::bind(&callback, _1, _2); srv.setCallback(f); ROS_INFO("Starting to spin..."); ros::spin(); return 0; } }}} * 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 }}} ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## DynamicReconfigureCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE