Note: This tutorials assumes that you have completed Setting up Dynamic Reconfigure for a Node(python) or (c++).
(!) 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.

Using the Dynamic Reconfigure Python Client

Description: This tutorial cover basic setup and usage of the dynamic_reconfigure client.

Tutorial Level:

The Code

Now that we have a node that we can reconfigure, we need to write a node to reconfigure it. Create a file called client.py in the nodes directory and add the following code to it:

   1 #!/usr/bin/env python
   2 
   3 import rospy
   4 
   5 import dynamic_reconfigure.client
   6 
   7 def callback(config):
   8     rospy.loginfo("Config set to {int_param}, {double_param}, {str_param}, {bool_param}, {size}".format(**config))
   9 
  10 if __name__ == "__main__":
  11     rospy.init_node("dynamic_client")
  12 
  13     client = dynamic_reconfigure.client.Client("dynamic_tutorials", timeout=30, config_callback=callback)
  14 
  15     r = rospy.Rate(0.1)
  16     x = 0
  17     b = False
  18     while not rospy.is_shutdown():
  19         x = x+1
  20         if x>10:
  21             x=0
  22         b = not b
  23         client.update_configuration({"int_param":x, "double_param":(1/(x+1)), "str_param":str(rospy.get_rostime()), "bool_param":b, "size":1})
  24         r.sleep()

The Breakdown

Writing a dynamic reconfigure client is very simple:

   1 #!/usr/bin/env python
   2 
   3 import rospy
   4 
   5 import dynamic_reconfigure.client

We first import rospy and dynamic_reconfigure.client.

   1 def callback(config):
   2     rospy.loginfo("Config set to {int_param}, {double_param}, {str_param}, {bool_param}, {size}".format(**config))

We then define a callback which will print the config returned by the server. There are two main differences between this callback and the servers, one it does not need to return an updated config object, two it does not have the "level" argument. This callback is optional.

   1 if __name__ == "__main__":
   2     rospy.init_node("dynamic_client")
   3 
   4     client = dynamic_reconfigure.client.Client("dynamic_tutorials", timeout=30, config_callback=callback)
   5 
   6     r = rospy.Rate(0.1)
   7     x = 0
   8     b = False
   9     while not rospy.is_shutdown():
  10         x = x+1
  11         if x>10:
  12             x=0
  13         b = not b
  14         client.update_configuration({"int_param":x, "double_param":(1/(x+1)), "str_param":str(rospy.get_rostime()), "bool_param":b, "size":1})
  15         r.sleep()

Lastly we initialize ROS and our Client. Our main loop runs once every ten seconds and simply calls update_configuration on the client every time. Note that you need not use a full configuration and could also pass in a dictionary with only one of the parameters as well.

Run It!

Once again make the node executable: chmod +x nodes/client.py Launch a core and your server node, and launch your new client node. If you've done everything correctly, both your client and server should begin to print out matching configurations every ten seconds.

Wiki: dynamic_reconfigure/Tutorials/UsingTheDynamicReconfigurePythonClient (last edited 2018-07-03 08:20:11 by reinzor)