通用的代价地图配置参数:
max_obstacle_height: 2.0 #传感器读数的最大有效高度,单位为 meters;
#通常设置为略高于机器人的实际高度,高度是指包含机械臂打直情况下的最大高度。
# robot_radius: 0.4 # 如果机器人圆形的,注释下面的一行,开启这个
footprint: [[-0.133, -0.125], [-0.133, 0.125],[0.133,0.125],[0.133, -0.125]] # [[x0, y0], [x1, y1], ... [xn, yn]]
# 当机器人非圆形时,先找机器人的旋转中心,即两个轮的中心点设置成(0,0),
# 然后确定机器人摆放方向,x,y为每个robot几何型的每条边的每个顶点。
# 将所有顶点都列到其中。就完成了robot的footprint。
#map_type: voxel # 地图类型,这里为voxel(体素地图)。
# 另一种地图类型为costmap(代价地图)。
# 这两者之间的区别是前者是世界的3D表示,后者为世界的2D表示。
obstacle_layer: # 障碍物层参数
enabled: true #使能障碍层
max_obstacle_height: 2.0 #传感器读数的最大有效高度(单位:m)。 通常设置为略高于机器人的高度。 此参数设置为大于全局max_obstacle_height参数的值将会失效。
#设置为小于全局max_obstacle_height的值将过滤掉传感器上大于该高度以的点。
min_obstacle_height: 0.0
#origin_z: 0.0 # z原点,单位为米,仅对voxel地图
#z_resolution: 0.2 #z分辨率,单位meters/cell
#z_voxels: 2 #每个垂直列中的体素数目,ROS Nav功能包的默认值为10。请参考https://github.com/teddyluo/ROSNavGuide-Chinese
#unknown_threshold: 15 #当整列的voxel是“已知”(``known’’)的时候,含有的未知单元(“unknown”)的最大数量
#mark_threshold: 0 # 整列voxel是“自由”(“free”)的时候,含有的已标记的cell(“marked”)的最大数目。
combination_method: 1 #只能设置为0或1,用来更新地图上的代价值,一般设置为1;
track_unknown_space: true #如果设置为false,那么地图上代价值就只分为致命碰撞和自由区域两种,如果设置为true,那么就分为致命碰撞,自由区域和未知区域三种。
#意思是说假如该参数设置为false的话,就意味着地图上的未知区域也会被认为是可以自由移动的区域,这样在进行全局路径规划时,
#可以把一些未探索的未知区域也来参与到路径规划,如果你需要这样的话就将该参数设置为false。不过一般情况未探索的区域不应该当作可以自由移动的区域,
#因此一般将该参数设置为true;
obstacle_range: 2.5 #这些参数设置了代价地图中的障碍物信息的阈值。 "obstacle_range" 参数确定最大范围传感器读数
#这将导致障碍物被放入代价地图中。在这里,我们把它设置在2.5米,这意味着机器人只会更新其地图包含距离移动基座2.5米以内的障碍物的信息。
raytrace_range: 3.0 #“raytrace_range”参数确定了用于清除指定范围外的空间。
#将其设置为3.0米,这意味着机器人将尝试清除3米外的空间,在代价地图中清除3米外的障碍物。
#origin_z: 0.0 #z原点,单位为米,仅对voxel地图
#z_resolution: 0.2
#z_voxels: 2
publish_voxel_map: false #是否发布底层的体素栅格地图,其主要用于可视化。
observation_sources: scan # 设置导航中所使用的传感器,这里可以用逗号形式来区分开很多个传感器,例如激光雷达,碰撞传感器,超声波传感器等,我们这里只设置了激光雷达;
scan: #观察源之一:激光数据。定义了:观察源的数据类型,发布话题,标记和添加障碍物
data_type: LaserScan #观察源的数据类型:激光扫描
topic: "/scan" #发布话题为scan
marking: true #启用标记障碍物功能
clearing: true #启用清除障碍物功能
#关于Marking and Clearing:
# marking和clearing参数用来表示是否需要使用传感器的实时信息来添加或清除代价地图中的障碍物信息)
# 代价地图自动订阅传感器主题并自动更新。
# 每个传感器用于标记操作(将障碍物信息插入到代价地图中),清除操作(从代价地图中删除障碍物信息)或两者操作都执行。
# 如果使用的是体素层,每一列上的障碍信息需要先进行投影转化成二维之后才能放入代价地图中。
expected_update_rate: 0
#min_obstacle_height: 0.25 #传感器最低有效读数,以米为单位。
#通常设置为地面高度,但可以根据传感器的噪声模型设置为更高或更低。
#max_obstacle_height: 0.35 #传感器读数的最大有效高度,以米为单位。
#通常设置为略大于机器人的最大高度。设置为大于全局的max_obstacle_height的值会失效。
#设置为小于全局max_obstacle_height将从传感器上过滤掉该高度以上的点。
inflation_layer: #膨胀层参数
enabled: true #使能膨胀层
cost_scaling_factor: 5.0 #在膨胀期间应用于代价值的尺度因子。
#默认值:10。对在内接半径之外的cells、以及在内接半径之内的cells这两种不同的cells, 代价函数的计算公式为:
#exp(-1.0 * cost_scaling_factor * (distance_from_obstacle - inscribed_radius)) * (costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1)
inflation_radius: 0.2 #机器人膨胀半径,比如设置为0.3,意味着规划的路径距离0.3米以上,这个参数理论上越大越安全
#但是会导致无法穿过狭窄的地方
static_layer: #静态地图层
enabled: true #启用静态地图
map_topic: "/map"
footprint 参数补充说明:
global_costmap:
global_frame: map #全局代价地图需要在哪个坐标系下运行;
robot_base_frame: base_footprint #在全局代价地图中机器人本体的基坐标系,就是机器人上的根坐标系。通过global_frame和robot_base_frame就可以计算两个坐标系之间的变换,得知机器人在全局坐标系中的坐标了。
update_frequency: 1.5 #参数决定了代价地图更新的频率(以Hz为单位)。根据传感器数据,全局地图更新的频率,这个数值越大,你的计算机的CPU负担会越重,特别对于全局地图,通常设定一个相对较小、在1.0到5.0之间的值。
publish_frequency: 1.0 #参数决定代价地图发布可视化信息的速率(以Hz为单位)。
#static_map: true #参数确定是否由map_server提供的地图服务来进行代价地图的初始化。如果您没有使用现有的地图或地图服务器,请将static_map参数设置为false。当本地地图需要根据传感器数据动态更新的时候,我们通常会把这个参数设为false。
transform_tolerance: 1 #坐标系间的转换可以忍受的最大延时
plugins: #在global_costmap中使用下面三个插件来融合三个不同图层,分别是static_layer、obstacle_layer和inflation_layer,合成一个master_layer来进行全局路径规划。
- {name: static_layer, type: "costmap_2d::StaticLayer"}
- {name: obstacle_layer, type: "costmap_2d::VoxelLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
local_costmap:
global_frame: odom #里程计坐标系
robot_base_frame: base_footprint #机器人坐标系
update_frequency: 10.0 #代价地图更新频率
publish_frequency: 10.0 #代价地图的发布频率
transform_tolerance: 0.5 #等待坐标变换发布信息的超时时间
static_map: false #不需要静态地图,可以提升导航效果
rolling_window: true #是否使用动态窗口,默认为false,在静态的全局地图中,地图不会变化
width: 3 # 局部地图宽度 单位是 m
height: 3 # 局部地图高度 单位是 m
resolution: 0.05 # 局部地图分辨率 单位是 m,一般与静态地图分辨率保持一致
注意:
参数配置技巧
以上配置在实操中,可能会出现机器人在本地路径规划时与全局路径规划不符而进入膨胀区域出现假死的情况,如何尽量避免这种情形呢?
全局路径规划与本地路径规划虽然设置的参数是一样的,但是二者路径规划和避障的职能不同,可以采用不同的参数设置策略:
- 全局代价地图可以将膨胀半径和障碍物系数设置的偏大一些;
- 本地代价地图可以将膨胀半径和障碍物系数设置的偏小一些。
这样,在全局路径规划时,规划的路径会尽量远离障碍物,而本地路径规划时,机器人即便偏离全局路径也会和障碍物之间保留更大的自由空间,从而避免了陷入“假死”的情形
将costmap_common_params.yaml里面的膨胀半径剪切出来分别添加到global/local_costmap_params.yaml里面进行修改;(costmap_common_params.yaml最终也是要和global/local_costmap_params.yaml自己融合的。方便起见将共有的部分写进costmap_common_params.yaml里面)
shutdown_costmaps: false #当move_base在不活动状态时,是否关掉costmap.
controller_frequency: 10.0 #向底盘控制移动话题cmd_vel发送命令的频率.
controller_patience: 3.0 #在空间清理操作执行前,控制器花多长时间等有效控制下发
planner_frequency: 1.0 #全局规划操作的执行频率.如果设置为0.0,则全局规划器仅
#在接收到新的目标点或者局部规划器报告路径堵塞时才会重新执行规划操作.
planner_patience: 3.0 #在空间清理操作执行前,留给规划器多长时间来找出一条有效规划.
oscillation_timeout: 10.0 #执行修复机制前,允许振荡的时长.
oscillation_distance: 0.02 #来回运动在多大距离以上不会被认为是振荡.
#全局路径规划器
base_global_planner: "global_planner/GlobalPlanner" #指定用于move_base的全局规划器插件名称.
#base_global_planner: "navfn/NavfnROS" #指定用于move_base的局部规划器插件名称.
#base_global_planner: "global_planner/GlobalPlanner"
#base_global_planner: "carrot_planner/CarrotPlanner"
#局部路径规划器的调用在文件【teb_local_planner.launch】、【dwa_local_planner.launch】对应文件内自动调用,该部分可以忽略
base_local_planner: "teb_local_planner/TebLocalPlannerROS" #指定用于move_base的局部规划器插件名称.
#base_local_planner: "dwa_local_planner/DWAPlannerROS" #指定用于move_base的全局规划器插件名称.
max_planning_retries: 1 #最大规划路径的重复次数,-1表示无限次
recovery_behavior_enabled: false #是否启动恢复机制
clearing_rotation_allowed: false #是否启动旋转的恢复,必须是recovery_behavior_enabled在使能的基础上才能生效
recovery_behaviors: # 自恢复行为
- name: 'conservative_reset'
type: 'clear_costmap_recovery/ClearCostmapRecovery'
#- name: 'aggressive_reset'
# type: 'clear_costmap_recovery/ClearCostmapRecovery'
#- name: 'super_reset'
# type: 'clear_costmap_recovery/ClearCostmapRecovery'
- name: 'clearing_rotation'
type: 'rotate_recovery/RotateRecovery'
#- name: 'move_slow_and_clear'
#type: 'move_slow_and_clear/MoveSlowAndClear'
#保守清除,用户指定区域之外的障碍物将从机器人地图中清除
conservative_reset:
reset_distance: 1.0
#layer_names: [static_layer, obstacle_layer, inflation_layer]
layer_names: [obstacle_layer]
#保守清除后,如果周围障碍物允许,机器人将进行原地旋转以清理空间
#保守清除失败,积极清除,清除指定区域之外的所有障碍物,然后进行旋转
aggressive_reset:
reset_distance: 3.0
#layer_names: [static_layer, obstacle_layer, inflation_layer]
layer_names: [obstacle_layer]
#积极清除也失败后,放弃规划路径
#可能是更进一步的清除,wiki未找到相关资料
super_reset:
reset_distance: 5.0
#layer_names: [static_layer, obstacle_layer, inflation_layer]
layer_names: [obstacle_layer]
#另一种恢复行为,需要注意该行为只能与具有动态设置速度限制功能的局部路径规划器适配,例如dwa
move_slow_and_clear:
clearing_distance: 0.5 #与小车距离0.5内的障碍物会被清除
limited_trans_speed: 0.1
limited_rot_speed: 0.4
limited_distance: 0.3
GlobalPlanner:
old_navfn_behavior: false #是否使用旧版本导航功能,默认false
use_quadratic: true #是否使用二次逼近的趋势,默认为true,否则使用简单的线性方法 二次近似函数,false使用更简单的计算方式节省硬件资源(否的话会扩展周边4个点,是扩展周边八个)
use_dijkstra: true #是否使用D*全局规划算法,默认为true,如果为false,则使用A*算法
use_grid_path: false #是否沿着网格规划路径,默认为false,false时使用最速下降法计算路径
allow_unknown: true #是否允许规划路径穿越未知区域
planner_window_x: 0.0 # default 0.0 指定可选窗口的x,y大小以限定规划器的工作空间(程序中未用到)
planner_window_y: 0.0 # default 0.0
default_tolerance: 0.0 # default 0.0 允许目标点的误差范围
局部路径规划有多种的规划方案:如:DWA、TEB、PMC等;
TrajectoryPlannerROS:
# Robot Configuration Parameters
max_vel_x: 0.5 # X 方向最大速度
min_vel_x: 0.1 # X 方向最小速速
max_vel_theta: 1.0 #
min_vel_theta: -1.0
min_in_place_vel_theta: 1.0
acc_lim_x: 1.0 # X 加速限制
acc_lim_y: 0.0 # Y 加速限制
acc_lim_theta: 0.6 # 角速度加速限制
# Goal Tolerance Parameters,目标公差
xy_goal_tolerance: 0.10
yaw_goal_tolerance: 0.05
# Differential-drive robot configuration
# 是否是全向移动机器人
holonomic_robot: false
# Forward Simulation Parameters,前进模拟参数--目的为调整局部路径尽可能的贴近全部路径规划
sim_time: 0.8
vx_samples: 18
vtheta_samples: 20
sim_granularity: 0.05
DWA
DWAPlannerROS:
# Robot Configuration Parameters - Kobuki
max_vel_x: 0.25 # 0.55
min_vel_x: 0.0
max_vel_y: 0.0 # diff drive robot
min_vel_y: 0.0 # diff drive robot
max_trans_vel: 0.5 # choose slightly less than the base's capability
min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity
trans_stopped_vel: 0.1
# Warning!
# do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities
# are non-negligible and small in place rotational velocities will be created.
max_rot_vel: 0.7 # choose slightly less than the base's capability
min_rot_vel: 0.3 # this is the min angular velocity when there is negligible translational velocity
rot_stopped_vel: 0.4
acc_lim_x: 0.8 # maximum is theoretically 2.0, but we
acc_lim_theta: 3.5
acc_lim_y: 0.0 # diff drive robot
# Goal Tolerance Parameters
yaw_goal_tolerance: 0.1 # 0.05
xy_goal_tolerance: 0.1 # 0.10
# latch_xy_goal_tolerance: false
# Forward Simulation Parameters#前进模拟参数--目的为调整局部路径尽可能的贴近全部路径规划
sim_time: 1.8 # 1.7
vx_samples: 6 # 3
vy_samples: 1 # diff drive robot, there is only one sample
vtheta_samples: 20 # 20
# Trajectory Scoring Parameters
path_distance_bias: 64.0 # 32.0 - weighting for how much it should stick to the global path plan
goal_distance_bias: 24.0 # 24.0 - wighting for how much it should attempt to reach its goal
occdist_scale: 0.5 # 0.01 - weighting for how much the controller should avoid obstacles
forward_point_distance: 0.325 # 0.325 - how far along to place an additional scoring point
stop_time_buffer: 0.2 # 0.2 - amount of time a robot must stop in before colliding for a valid traj.
scaling_speed: 0.25 # 0.25 - absolute velocity at which to start scaling the robot's footprint
max_scaling_factor: 0.2 # 0.2 - how much to scale the robot's footprint when at speed.
# Oscillation Prevention Parameters
oscillation_reset_dist: 0.05 # 0.05 - how far to travel before resetting oscillation flags
# Debugging
publish_traj_pc : true
publish_cost_grid_pc: true
global_frame_id: odom_combined
# Differential-drive robot configuration - necessary?
# holonomic_robot: false
TEB
TebLocalPlannerROS:
odom_topic: odom
# 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: True
max_global_plan_lookahead_dist: 3.0
global_plan_viapoint_sep: -1
global_plan_prune_distance: 1
exact_arc_length: False
feasibility_check_no_poses: 2
publish_feedback: False
# Robot
max_vel_x: 0.25
max_vel_x_backwards: 0.25
max_vel_y: 0.0
max_vel_theta: 0.63 # the angular velocity is also bounded by min_turning_radius in case of a carlike robot (r = v / omega)
acc_lim_x: 0.5
acc_lim_theta: 0.7
# ********************** Carlike robot parameters ********************
min_turning_radius: 0.35 # Min turning radius of the carlike robot (compute value using a model or adjust with rqt_reconfigure manually)
wheelbase: 0.163 # Wheelbase of our robot
cmd_angle_instead_rotvel: False # stage simulator takes the angle instead of the rotvel as input (twist message)
# ********************************************************************
footprint_model: # types: "point", "circular", "two_circles", "line", "polygon"
type: "line"
line_start: [0.05, 0.0] # for type "line"
line_end: [0.10, 0.0] # for type "line"
# GoalTolerance
xy_goal_tolerance: 0.2
yaw_goal_tolerance: 0.1
free_goal_vel: False
complete_global_plan: True
# Obstacles
min_obstacle_dist: 0.12 # This value must also include our robot's expansion, since footprint_model is set to "line".
inflation_dist: 0.6
include_costmap_obstacles: True
costmap_obstacles_behind_robot_dist: 1.5
obstacle_poses_affected: 15
dynamic_obstacle_inflation_dist: 0.6
include_dynamic_obstacles: True
costmap_converter_plugin: ""
costmap_converter_spin_thread: True
costmap_converter_rate: 5
# Optimization
no_inner_iterations: 5
no_outer_iterations: 4
optimization_activate: True
optimization_verbose: False
penalty_epsilon: 0.1
obstacle_cost_exponent: 4
weight_max_vel_x: 2
weight_max_vel_theta: 1
weight_acc_lim_x: 1
weight_acc_lim_theta: 1
weight_kinematics_nh: 1000
weight_kinematics_forward_drive: 1
weight_kinematics_turning_radius: 1
weight_optimaltime: 1 # must be > 0
weight_shortest_path: 0
weight_obstacle: 100
weight_inflation: 0.2
weight_dynamic_obstacle: 10 # not in use yet
weight_dynamic_obstacle_inflation: 0.2
weight_viapoint: 1
weight_adapt_factor: 2
# Homotopy Class Planner
enable_homotopy_class_planning: False
enable_multithreading: True
max_number_classes: 4
selection_cost_hysteresis: 1.0
selection_prefer_initial_plan: 0.95
selection_obst_cost_scale: 1.0
selection_alternative_time_cost: False
roadmap_graph_no_samples: 15
roadmap_graph_area_width: 5
roadmap_graph_area_length_scale: 1.0
h_signature_prescaler: 0.5
h_signature_threshold: 0.1
obstacle_heading_threshold: 0.45
switching_blocking_period: 0.0
viapoints_all_candidates: True
delete_detours_backwards: True
max_ratio_detours_duration_best_duration: 3.0
visualize_hc_graph: False
visualize_with_time_as_z_axis_scale: False
# Recovery
shrink_horizon_backup: True
shrink_horizon_min_duration: 10
oscillation_recovery: False
oscillation_v_eps: 0.1
oscillation_omega_eps: 0.1
oscillation_recovery_min_duration: 10
oscillation_filter_duration: 10