ROS navigation导航包使用

  • 机器人配置图:

 

  • 导航包launch文件:
<launch>
  <master auto="start"/>

  <!-- Run the map server -->
  <node name="map_server" pkg="map_server" type="map_server" args="$(find my_map_package)/my_map.pgm my_map_resolution"/>

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

  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    <rosparam file="$(find my_navigation)/costmap_common_params.yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find my_navigation)/costmap_common_params.yaml" command="load" ns="local_costmap" />
    <rosparam file="$(find my_navigation)/local_costmap_params.yaml" command="load" />
    <rosparam file="$(find my_navigation)/global_costmap_params.yaml" command="load" />
    <!--- 使用teb_local_planner -->
    <!--rosparam file="$(find my_navigation)/base_local_planner_params.yaml" command="load" /-->
    <rosparam file="$(find my_navigation)/teb_local_planner_params.yaml" command="load" />
  </node>
</launch>

参数配置:(待优化)

costmap_common_params.yaml

obstacle_range: 2.5
raytrace_range: 3.0

footprint: [[0.17, 0.22], [0.17, -0.22], [-0.42, -0.22], [-0.42, 0.22]]
#robot_radius: 0.105

inflation_radius: 0.35 #0.5
cost_scaling_factor: 3.0

map_type: costmap
  observation_sources: scan
  scan: {sensor_frame: velodyne, 
  data_type: LaserScan, 
  topic: laser_scan, 
  marking: true, 
  clearing: true,
}

local_costmap_params.yaml

local_costmap:
  global_frame: map
  robot_base_frame: base_footprint

  update_frequency: 10.0
  publish_frequency: 10.0
  transform_tolerance: 0.5

  static_map: false 
  rolling_window: true
  width: 3
  height: 3
  resolution: 0.05

  #add 
  #inscribed_radius: 0.45
  #circumscribed_radius: 0.5 
  #clearing_rotation_allowed: false

global_costmap_params.yaml

global_costmap:
  global_frame: map
  robot_base_frame: base_footprint

  update_frequency: 10.0
  publish_frequency: 10.0
  transform_tolerance: 0.5

  static_map: true

teb_local_planner_params.yaml

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: False
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: 5
publish_feedback: False

# Robot

max_vel_x: 0.4
max_vel_x_backwards: 0.2
max_vel_y: 0.0
max_vel_theta: 0.3
acc_lim_x: 0.5
acc_lim_theta: 0.5
min_turning_radius: 0.0 # diff-drive robot (can turn on place!)

footprint_model:
type: "point"

# GoalTolerance

xy_goal_tolerance: 0.2
yaw_goal_tolerance: 0.1
free_goal_vel: False
complete_global_plan: True

# Obstacles

min_obstacle_dist: 0.45 # This value must also include our robot radius, since footprint_model is set to "point".
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
weight_dynamic_obstacle_inflation: 0.2
weight_viapoint: 1
weight_adapt_factor: 2

# Homotopy Class Planner

enable_homotopy_class_planning: True
enable_multithreading: True
max_number_classes: 4
selection_cost_hysteresis: 1.0
selection_prefer_initial_plan: 0.9
selection_obst_cost_scale: 100.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: True
oscillation_v_eps: 0.1
oscillation_omega_eps: 0.1
oscillation_recovery_min_duration: 10
oscillation_filter_duration: 10