[PYTHON] Use Dynamic Reconfigure to dynamically change move_base parameters during execution

Introduction

Nice to meet you, this is porizou. I usually work on developing autonomous mobile robots using ROS.

I was wondering whether to post an article on ROS and Navigation, but I thought that many people were still using it, so I decided to write an article. Since I was using ROS NavigationStack and had to dynamically change the move_base parameters while the node was running, I've summarized the methods for using rqt_reconfigure and changing from other nodes.

About Dynamic Reconfigure

Dynamic Reconfigure is a ROS feature that allows you to dynamically change the value of rosparam while a node is running. As for the explanation of Dynamic Reconfigure itself, the following ROS course article is easy to understand, so details are omitted in this article.

ROS Lecture 28 Using Dynamic Reconfigure

The move_base parameters are implemented using the Dynamic Reconfigure Server, with some exceptions, so they can be changed dynamically while the node is running.

testing environment

We have confirmed the operation in the following environment. I'm using Noetic, but Melodic can do the same.

item value
CPU Ryzen5
OS Ubuntu20.04LTS
ROS Noetic

I used the familiar Turtlebot3 Gazebo simulation to check the operation of move_base. https://github.com/ROBOTIS-GIT/turtlebot3_simulations

Modifiable parameters

Below are the move_base related parameters that can be changed with Dynamic Reconfigure when dwa_local_planner is used for Local Planner. Parameters of Global Planner and move_base itself (such as controller_frequency) cannot be changed dynamically.

name Explanation
/move_base/DWAPlannerROS dwa_local_planner parameters
/move_base/global_costmap/inflation_layer Global Costmap Inflation Layer Parameters
/move_base/global_costmap/obstacle_layer Global Costmap Obstacle Layer Parameters
/move_base/local_costmap/inflation_layer Local Costmap Inflation Layer Parameters
/move_base/local_costmap/obstacle_layer Local Costmap Obstacle Layer Parameters

Addendum: When base_local_planner is used for LocalPlanner, it is defined as/move_base/TrajectryPlannerROS.

How to change from rqt_reconfigure

Parameters can be changed dynamically from the GUI screen by using rqt_reconfigure. Execute with the following command while move_base is running.

rqt_Run reconfigure


$ rosrun rqt_reconfigure rqt_reconfigure 

A screen like this will appear.

Screenshot from 2020-12-30 14-07-18.png You can change the parameters by moving the bar of each parameter.

By using rqt_reconfigure, you can adjust the parameters of move_base while moving the robot without having to rewrite the configuration file and restart the node.

How to change dynamically from another node (Python)

Below is a sample program that dynamically changes parameters from a Python node.

I created a program that switches the inflation_radius value of inflation_layer of LocalCostmap every second so that it can be easily confirmed from rviz. The second line imports dynamic_reconfigure.client and the sixth line creates Clent. Specify the parameter name and value you want to change in the argument of client.update_configureation.

When you run the script below, the value of inflation_radius will switch between 0.5 and 1.0 every second.

sample.py


import rospy
import dynamic_reconfigure.client

if __name__ == '__main__':
    rospy.init_node("dynamic_reconfigure_client")
    client = dynamic_reconfigure.client.Client("/move_base/local_costmap/inflation_layer/")
    while not rospy.is_shutdown():
        client.update_configuration({"inflation_radius": 0.5})
        rospy.sleep(1)
        client.update_configuration({"inflation_radius": 1.0})
        rospy.sleep(1)
        
    rospy.spin()

How to change dynamically from another node (C ++)

Below is a sample program that dynamically changes parameters from a C ++ node. In the case of C ++, it was necessary to include each Config file.

#include <ros/ros.h>
#include <dynamic_reconfigure/client.h>
#include "costmap_2d/InflationPluginConfig.h"

int main(int argc, char **argv){
  ros::init(argc, argv, "dynamic_reconfigure_client");
  dynamic_reconfigure::Client<costmap_2d::InflationPluginConfig> client("/move_base/local_costmap/inflation_layer/");
  costmap_2d::InflationPluginConfig config;

  while(ros::ok())
  {
    config.inflation_radius = 0.5;
    client.setConfiguration(config);
    ros::Duration(1).sleep();

    config.inflation_radius = 1.0;
    client.setConfiguration(config);
    ros::Duration(1).sleep();
  }
  return 0;
}

Execution result

Launch Turtlebot 3 Navigation below

move_Run base


$ roslaunch turtlebot3_navigation turtlebot3_navigation.launch 

Run the above sample program (Python version) in another terminal

Run sample


$ python3 sample.py

Below is the rviz screen (Global Costmap etc. are hidden)

inflation_radius : 0.5rviz_screenshot_2020_12_30-16_21_52.png

inflation_radius : 1.0rviz_screenshot_2020_12_30-16_21_36.png

I think these screens alternate every second.

Finally

This time I introduced an example of changing the parameters of move_base, but it is also possible to change the parameters of amcl dynamically as well. Also, I wrote a sample to change parameters from the program in python, but I will add a C ++ version at a later date.

Addendum: A C ++ version of the sample program has been added. (2021/1/13)

reference

dynamic_reconfigure tutorial http://wiki.ros.org/dynamic_reconfigure/Tutorials/UsingTheDynamicReconfigurePythonClient

How to dynamically reconfigure the hokuyo_node from the command line or code. http://wiki.ros.org/hokuyo_node/Tutorials/UsingDynparamToChangeHokuyoLaserParameters

Dynamic Reconfigure allows you to change ROS node parameters while the node is running http://urusulambda.com/2018/04/19/ros%E3%81%AE%E3%83%8E%E3%83%BC%E3%83%89%E3%81%AE%E3%83%91%E3%83%A9%E3%83%A1%E3%83%BC%E3%82%BF%E3%82%92%E3%83%8E%E3%83%BC%E3%83%89%E5%AE%9F%E8%A1%8C%E4%B8%AD%E3%81%AB%E5%A4%89%E6%9B%B4%E3%81%A7/

https://blog.csdn.net/u014610460/article/details/79531616

Recommended Posts

Use Dynamic Reconfigure to dynamically change move_base parameters during execution