/move_base/DWAPlannerROS
/move_base/global_costmap/inflation_layer
/move_base/global_costmap/obstacle_layer
/move_base/local_costmap/inflation_layer
/move_base/local_costmap/obstacle_layer
python
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()
C++
#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;
}