Note: This tutorial assumes that you have completed the previous tutorials: How to use Hokuyo laser scanners with the hokuyo_node, How to dynamically reconfigure the hokuyo_node using reconfigure_gui.
(!) 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.

How to dynamically reconfigure the hokuyo_node from the command line or code.

Description: After completing this tutorial, you will be able to reconfigure the parameters of the hokuyo_node from the command line or python code.

Keywords: reconfigure, Hokuyo, parameters, laser driver, laser, laser scanner, laser scan

Tutorial Level: INTERMEDIATE

Compiling

Start by getting the dependencies and compiling dynamic_reconfigure.

$ rosdep install dynamic_reconfigure 
$ rosmake dynamic_reconfigure 

Using dynamic_reconfigure from the command line

You can reconfigure the hokuyo_node parameters by calling dynamic_reconfigure from the command line with the following invocation:

rosrun dynamic_reconfigure dynparam set /<node_name> <param> <value>

For example, if the node is named hokuyo_node and the parameter is min_ang, the call would look like:

rosrun dynamic_reconfigure dynparam set /hokuyo_node min_ang -1.0

Try it with any of the hokuyo_node parameters.

You can see the result of setting the parameters by visualizing the laser scan in rviz.

Using dynparam from a launch file

You can use dynparam with the set_from_parameter command to set parameters of an already running node from a launch file.

For example to set the hokuyo scanning range, you could use the following launch file (using set_from_parameters. Other verb can be used):

<launch>
  <node name="$(anon dynparam)" pkg="dynamic_reconfigure" type="dynparam" args="set_from_parameters hokuyo_node">
    <param name="min_ang" type="double" value="-1.0" />
    <param name="max_ang" type="double" value="1.0" />
  </node>
</launch>

Using dynamic_reconfigure from Python code

You can change hokuyo_node parameters from Python scripts by importing:

import dynamic_reconfigure.client

creating a node

rospy.init_node('myconfig_py', anonymous=True)

creating a client instance (node_to_reconfigure is the name of the node to reconfigure, for example 'hokuyo_node')

client = dynamic_reconfigure.client.Client(<node_to_reconfigure>)

and calling update_configuration with a dictionary of changes to make:

params = { 'my_string_parameter' : 'value', 'my_int_parameter' : 5 }
config = client.update_configuration(params)

config now contains the full configuration of the node after the parameter update.

Using dynparam from C++ code

Not yet implemented. Use the system command as a temporary workaround. For example, the following invocation tells the narrow stereo camera to produce textured images:

   system("rosrun dynamic_reconfigure dynparam set_from_parameters camera_synchronizer_node narrow_stereo_trig_mode 3");

Wiki: hokuyo_node/Tutorials/UsingDynparamToChangeHokuyoLaserParameters (last edited 2020-06-18 08:11:54 by IsaacSaito)