ROS 导航过程中修改move_base参数

/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;
}
  • 0
    点赞
  • 10
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值