ROS1 go2 vlp16 小范围局部避障

接上一文《宇树go2 gazebo仿真》。go1 的深度相机进行避障,以及gp2 的move_base 使用(不能实时避障)。

本文讲述给go2添加vlp雷达,实现实时避障。
使用环境:ubuntu 2004 ros neotic (docker 环境)

  1. 下载编译velodyne_simulator
#在上一篇go2 仿真的工作空间下,就是src下clone了unitree guide等包的工作路径
cd ~/catkin_ws/src
git clone https://github.com/ros-drivers/velodyne_simulator.git

cd .. && catkin_make
  1. 创建有雷达的go2模型
cd ~/catkin_ws/src
cp unitree_ros/robots/go2_description/xacro/robot.xacro unitree_ros/robots/go2_description/xacro/vlp_robot.xacro
vi unitree_ros/robots/go2_description/xacro/vlp_robot.xacro # 也可以gedit打开

在倒数第二行</robot>之前插入如下内容:

    <xacro:include filename="$(find velodyne_description)/urdf/VLP-16.urdf.xacro"/>
    <xacro:VLP-16 parent="trunk" name="velodyne" topic="/velodyne_points" hz="10" samples="440">
      <origin xyz="0.23 0 0.15" rpy="0 0 0" />
    </xacro:VLP-16>

</robot>
  1. 编写launch文件
    unitree_guide/unitree_move_base/launch/my_go_navigation.launch
<launch>
  <node pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan_node" name="face_pointcloud_to_laserscan" 
      respawn="false" output="screen">
      <remap from="cloud_in" to="/velodyne_points"/>
      <remap from="/scan" to="/headLaserScan"/>
      <rosparam>
          target_frame: velodyne
          transform_tolerance: 0.1 
          min_height: -0.3
          max_height: 0.3 

          angle_min: -3.14159
          angle_max: 3.14159
          angle_increment: 0.0175
          scan_time: 0.1 
          range_min: 0.5 
          range_max: 15.0
          use_inf: false

          # Concurrency level, affects number of pointclouds queued for processing and number of threads used
          # 0 : Detect number of cores
          # 1 : Single threaded
          # 2->inf : Parallelism level
          concurrency_level: 1
      </rosparam>
  </node>


  <!-- MoveBase --> 
  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    <rosparam file="$(find unitree_move_base)/config/vlp_costmap_common_params.yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find unitree_move_base)/config/vlp_costmap_common_params.yaml" command="load" ns="local_costmap" />
    <rosparam file="$(find unitree_move_base)/config/global_costmap_params.yaml" command="load" />
    <rosparam file="$(find unitree_move_base)/config/local_costmap_params.yaml" command="load" />
    <rosparam file="$(find unitree_move_base)/config/teb_local_planner_params.yaml" command="load" />
    <!-- (TEB) --> 
    <!--param name="base_global_planner" value="global_planner/GlobalPlanner"/-->
    <param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS"/>
  </node>

  <!-- AMCL --> 
  <!-- <include file="$(find unitree_move_base)/launch/amcl.launch" /> --> 

    <!-- rviz --> 
    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find unitree_move_base)/config/my_move_base.rviz"/>
</launch>         
  1. costmap 配置文件
    unitree_guide/unitree_move_base/config/vlp_costmap_common_params.yaml内容如下:
lobstacle_range: 1.0 
raytrace_range: 1.5 
footprint: [[0.3, 0.15], [0.3, -0.15], [-0.35, -0.15], [-0.35, 0.15]]
# robot_radius: 0.3
inflation_radius: 0.03
max_obstacle_height: 1.0 
min_obstacle_height: 0.0 
# observation_sources: scan
# scan: {data_type: LaserScan, topic: /merged_laserscan, marking: true, clearing: true, expected_update_rate: 3.3}
observation_sources: headLaserScan
headLaserScan: {data_type: LaserScan, topic: /headLaserScan, marking: true, clearing: true, expected_update_rate: 10} 
  1. 启动避障步骤
roslaunch unitree_guide vlp_go2.launch
./devel/lib/unitree_guide/junior_ctrl # 按2 站立,后按5 move_base
roslaunch unitree_move_base my_go_navigation.launch

在这里插入图片描述

ROS1 go2 vlp16 大范围局部避障

本节调节参数,扩大局部costmap的范围,进行大范围局部避障。
在这里插入图片描述

配置文件介绍
  1. 性能优化:降低分辨率、减小地图尺寸可显著提高性能
  2. 安全优先:合理设置膨胀半径和最小障碍物距离
  3. 实时性:局部地图需要更高更新频率
  4. 传感器配置:确保话题名称和坐标系正确
  5. 逐步调参:每次只修改少量参数,观察效果
配置文件 主要作用 核心组件
costmap_common_params.yaml 定义全局/局部代价地图共用参数 机器人模型、传感器配置、障碍物处理
global_costmap_params.yaml 配置全局路径规划使用的地图 静态地图层、全局障碍物检测
local_costmap_params.yaml 配置局部避障和轨迹规划使用的地图 实时障碍物检测、滚动窗口
teb_local_planner_params.yaml 配置TEB局部规划器的行为 轨迹优化、速度控制、避障参数
1. costmap_common_params

costmap_common_params.yaml - 代价地图共用参数

此文件包含全局和局部代价地图共享的参数配置。

  • 机器人足迹配置
参数 类型 默认值 说明
robot_radius float - 圆形机器人的半径(与footprint二选一)
footprint list of points - 多边形机器人的顶点坐标,如[[x1,y1],[x2,y2],...]
  • 障碍物层参数 (ObstacleLayer)
参数 类型 默认值 说明
max_obstacle_height float 2.0 最大障碍物高度(米)
min_obstacle_height float 0.0 最小障碍物高度,用于过滤地面点
obstacle_range float 2.5 能够检测障碍物的最远距离(米)
raytrace_range float 3.0 能够清理自由空间的最远距离(米)
origin_z float 0.0 3D代价地图的Z轴原点
z_resolution float 0.2 Z轴分辨率(米)
z_voxels int 10 Z轴体素数量
  • 膨胀层参数 (InflationLayer)
参数 类型 默认值 说明
inflation_radius float 0.55 膨胀半径,决定障碍物影响范围
cost_scaling_factor float 10.0 成本衰减因子,值越小衰减越快
  • 传感器配置
参数 类型 默认值 说明
observation_sources string - 传感器源列表,如scan rgbd
[source_name].topic string - 传感器话题名称
[source_name].data_type string - 数据类型:LaserScanPointCloud2
[source_name].marking bool true 是否用于标记障碍物
[source_name].clearing bool true 是否用于清理自由空间
[source_name].sensor_frame string - 传感器坐标系名称
2. global_costmap

global_costmap_params.yaml - 全局代价地图参数

配置用于全局路径规划的地图。

  • 基础参数
参数 类型 默认值 说明
global_frame string map 全局坐标系,通常为map
robot_base_frame string base_link 机器人基座坐标系
update_frequency float 1.0 地图更新频率(Hz)
publish_frequency float 0.0 地图发布频率,0表示不发布
static_map bool true 是否使用静态地图
rolling_window bool false 是否使用滚动窗口(与static_map互斥)
width float 10.0 地图宽度(米)
height float 10.0 地图高度(米)
resolution float 0.05 地图分辨率(米/像素)
transform_tolerance float 0.5 坐标变换容差时间(秒)
  • 插件配置
参数 类型 说明
plugins list 插件列表,顺序决定处理优先级

典型插件顺序:

  1. static_layer - 静态地图层
  2. obstacle_layer - 障碍物层(处理动态障碍)
  3. inflation_layer - 膨胀层
3. local_costmap

local_costmap_params.yaml - 局部代价地图参数

配置用于局部避障的实时地图。

  • 基础参数
参数 类型 默认值 说明
global_frame string odom 通常使用odom坐标系
robot_base_frame string base_link 机器人基座坐标系
update_frequency float 5.0 需要更高更新频率(Hz)
publish_frequency float 2.0 发布频率通常高于全局地图
static_map bool false 不使用静态地图
rolling_window bool true 使用滚动窗口跟随机器人
width float 6.0 滚动窗口宽度(米)
height float 6.0 滚动窗口高度(米)
resolution float 0.05 分辨率(米/像素)
transform_tolerance float 0.5 坐标变换容差(秒)
origin_x float -3.0 窗口原点X偏移(确保机器人在中心)
origin_y float -3.0 窗口原点Y偏移
  • 典型插件配置
    • obstacle_layer - 实时障碍物检测
    • inflation_layer - 膨胀层
4. base/teb_local_planner

teb_local_planner_params.yaml - TEB规划器参数

配置Time Elastic Band局部规划器。

  • 轨迹参数
参数 类型 默认值 说明
teb_autosize bool true 自动调整轨迹点数量
dt_ref float 0.3 参考时间步长(秒)
dt_hysteresis float 0.1 滞后时间(秒)
max_samples int 500 最大轨迹样本数
global_plan_overwrite_orientation bool true 全局路径覆盖方向
  • 机器人动力学参数
参数 类型 默认值 说明
max_vel_x float 0.5 最大前进速度(m/s)
max_vel_x_backwards float 0.2 最大后退速度(m/s)
max_vel_theta float 0.4 最大旋转速度(rad/s)
acc_lim_x float 0.5 线加速度限制(m/s²)
acc_lim_theta float 0.5 角加速度限制(rad/s²)
min_turning_radius float 0.0 最小转弯半径(全向机器人为0)
  • 目标容差参数
参数 类型 默认值 说明
xy_goal_tolerance float 0.1 XY位置容差(米)
yaw_goal_tolerance float 0.2 角度容差(弧度)
free_goal_vel bool false 是否忽略目标点速度
  • 优化权重参数
参数 类型 默认值 说明
weight_obstacle float 50 障碍物代价权重
weight_inflation float 0.2 膨胀代价权重
weight_optimaltime float 1 时间最优权重
weight_kinematics_forward_drive float 1 前向驱动权重
weight_kinematics_turning_radius float 1 转弯半径权重
  • **障碍物避障参数
参数 类型 默认值 说明
min_obstacle_dist float 0.4 与障碍物最小距离(米)
inflation_dist float 0.6 膨胀距离(米)
include_dynamic_obstacles bool true 是否包含动态障碍物
5. base_local_planner_params.yaml - 基础局部规划器参数

如果使用DWA等传统规划器时的配置。

  • 核心参数
参数 类型 默认值 说明
max_vel_x float 0.5 最大线速度
min_vel_x float 0.1 最小线速度
max_vel_theta float 1.0 最大角速度
min_vel_theta float -1.0 最小角速度
acc_lim_x float 2.5 线加速度限制
acc_lim_theta float 3.2 角加速度限制
goal_distance_bias float 0.8 目标距离权重
path_distance_bias float 0.6 路径跟踪权重
occdist_scale float 0.1 障碍物距离权重
配置文件内容

unitree_guide/unitree_move_base/launch/my_go_navigation.launch

<launch>
  <node pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan_node" name="pointcloud_to_laserscan" 
      respawn="false" output="screen">
      <remap from="cloud_in" to="/velodyne_points"/>
      <remap from="/scan" to="/headLaserScan"/>
      <rosparam>
          target_frame: velodyne
          transform_tolerance: 0.1 
          min_height: 0.0 
          max_height: 1.0 

          angle_min: -3.14159
          angle_max: 3.14159
          angle_increment: 0.0175
          scan_time: 0.1 
          range_min: 0.5 
          range_max: 25.0
          use_inf: false

          # Concurrency level, affects number of pointclouds queued for processing and number of threads used
          # 0 : Detect number of cores
          # 1 : Single threaded
          # 2->inf : Parallelism level
          concurrency_level: 1
      </rosparam>
  </node>


  <!-- MoveBase --> 
  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    <rosparam file="$(find unitree_move_base)/config/vlp_costmap_common_params.yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find unitree_move_base)/config/vlp_costmap_common_params.yaml" command="load" ns="local_costmap" />
    <rosparam file="$(find unitree_move_base)/config/vlp_global_costmap_params.yaml" command="load" />
    <rosparam file="$(find unitree_move_base)/config/vlp_local_costmap_params.yaml" command="load" />
    <rosparam file="$(find unitree_move_base)/config/teb_local_planner_params.yaml" command="load" />
    <!-- (TEB) --> 
    <!--param name="base_global_planner" value="global_planner/GlobalPlanner"/-->
    <param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS"/>
  </node>

  <!-- AMCL --> 
  <!-- <include file="$(find unitree_move_base)/launch/amcl.launch" /> --> 

    <!-- rviz --> 
    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find unitree_move_base)/config/my_move_base.rviz"/>
</launch>

unitree_guide/unitree_move_base/config/vlp_costmap_common_params.yaml

obstacle_range: 20 
raytrace_range: 25
footprint: [[0.3, 0.15], [0.3, -0.15], [-0.35, -0.15], [-0.35, 0.15]]
# robot_radius: 0.3
inflation_radius: 0.03
max_obstacle_height: 5.0 
min_obstacle_height: 0.0 
origin_z: 0.0 
# observation_sources: scan
# scan: {data_type: LaserScan, topic: /merged_laserscan, marking: true, clearing: true, expected_update_rate: 3.3}
observation_sources: headLaserScan  # 这里topic 对应 <remap from="/scan" to="/headLaserScan"/>
headLaserScan: {data_type: LaserScan, topic: /headLaserScan, marking: true, clearing: true, expected_update_rate: 10} 
#observation_sources: scan # observation_sources 和 下边的起始标签要一致
#scan: {data_type: LaserScan, topic: scan, marking: true, clearing: true, expected_update_rate: 10}

unitree_guide/unitree_move_base/config/vlp_global_costmap_params.yaml

global_costmap:
   global_frame: odom
   robot_base_frame: base
   update_frequency: 1.0 
   publish_frequency: 1.0 
   rolling_window: true
   width: 20.0
   height: 20.0
   resolution: 0.05
   transform_tolerance: 1.0 
plugins:
  - {name: static_layer, type: "costmap_2d::StaticLayer"}
  - {name: obstacles, type: "costmap_2d::ObstacleLayer"}
  - {name: inflation, type: "costmap_2d::InflationLayer"}

unitree_guide/unitree_move_base/config/vlp_local_costmap_params.yaml

local_costmap:
   global_frame: odom
   robot_base_frame: base
   update_frequency: 2.0 
   publish_frequency: 1.0 
   rolling_window: true
   width: 10.0
   height: 10.0
   resolution: 0.05
   transform_tolerance: 1.0 
plugins:
   - {name: obstacles, type: "costmap_2d::ObstacleLayer"}
   - {name: inflation, type: "costmap_2d::InflationLayer"}

unitree_guide/unitree_move_base/config/vlp_teb_local_planner_params.yaml

TebLocalPlannerROS:
  trajectory:
    teb_autosize: true
    dt_ref: 0.3 
    dt_hysteresis: 0.1 
    max_samples: 500 
    global_plan_overwrite_orientation: true
    allow_init_with_backwards_motion: false
    max_global_plan_lookahead_dist: 5.0 
    feasibility_check_no_poses: 5
  
  robot:
    max_vel_x: 1.5 
    max_vel_x_backwards: 0.5    
    max_vel_theta: 2.0 
    acc_lim_x: 1.0 
    acc_lim_theta: 1.5 
    footprint_model:
      type: "polygon"
    
  goal_tolerance:
    xy_goal_tolerance: 0.10
    yaw_goal_tolerance: 0.15
    free_goal_vel: false
  
  optimization:
    no_inner_iterations: 5
    no_outer_iterations: 4
    penalty_epsilon: 0.1 
    weight_obstacle: 50
    weight_inflation: 0.2 
    weight_kinematics_forward_drive: 1
    weight_kinematics_turning_radius: 1
    weight_optimaltime: 1

  
  obstacles:
    min_obstacle_dist: 0.3    
    inflation_dist: 0.5    
    include_dynamic_obstacles: true
    costmap_obstacles_behind_robot_dist: 1.5 

  recovery:
    oscillation_recovery: true
    oscillation_v_eps: 0.1 
    oscillation_omega_eps: 0.1 

遇到问题

由于costmap太大,引起的算力不足的问题。那就需要恢复小costmap局部避障了。
比如,将local_costmapglobal_costmap中的 width&height
costmap_common 里的obstacle_rangeraytrace_range
以及launch文件中pointcloud_to_laserscanrange_min和range_max参数。参考第一节《小范围局部避障的值》。

Logo

火山引擎开发者社区是火山引擎打造的AI技术生态平台,聚焦Agent与大模型开发,提供豆包系列模型(图像/视频/视觉)、智能分析与会话工具,并配套评测集、动手实验室及行业案例库。社区通过技术沙龙、挑战赛等活动促进开发者成长,新用户可领50万Tokens权益,助力构建智能应用。

更多推荐