基本参数下载:
链接:https://pan.baidu.com/s/1HFTGSQY07DEpKNyaD5iMLQ 
提取码:sqp1 
--来自百度网盘超级会员V3的分享在move_base.launch中增加:
 <!-- move_base use Tinymal planner-->
  <group if="$(eval planner == 'tinymal')">
	<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
	<param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
	<rosparam file="$(find robot_vslam)/param/Tinymal/costmap_common_params.yaml" command="load" ns="global_costmap" />
	<rosparam file="$(find robot_vslam)/param/Tinymal/costmap_common_params.yaml" command="load" ns="local_costmap" />
	<rosparam file="$(find robot_vslam)/param/Tinymal/local_costmap_params.yaml" command="load" />
	<rosparam file="$(find robot_vslam)/param/Tinymal/global_costmap_params.yaml" command="load" />
	<rosparam file="$(find robot_vslam)/param/Tinymal/move_base_params.yaml" command="load" />
	<remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
	<remap from="odom" to="$(arg odom_topic)"/>
        <rosparam file="$(find robot_vslam)/param/Tinymal/teb_local_planner_params.yaml" command="load" />
	<param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
	</node>
  </group>2023年3月5日
参数配置如下:
(1)TEB参数
TebLocalPlannerROS:
 odom_topic: odom
    
 # Trajectory
  
 teb_autosize: True
 dt_ref: 0.45
 dt_hysteresis: 0.1
 max_samples: 500
 global_plan_overwrite_orientation: True
 allow_init_with_backwards_motion: True
 max_global_plan_lookahead_dist: 0.0
 global_plan_viapoint_sep: 0.35
 global_plan_prune_distance: 1
 exact_arc_length: False
 feasibility_check_no_poses: 5
 publish_feedback: False
    
 # Robot
         
 max_vel_x: 0.25
 max_vel_x_backwards: 0.15
 max_vel_y: 0.2
 max_vel_theta: 0.45 # the angular velocity is also bounded by min_turning_radius in case of a carlike robot (r = v / omega)
 acc_lim_x: 0.2
 acc_lim_y: 0.15
 acc_lim_theta: 0.2
 # ********************** Carlike robot parameters ********************
 min_turning_radius: 0.15        # Min turning radius of the carlike robot (compute value using a model or adjust with rqt_reconfigure manually)
 wheelbase: 0.1                 # 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.14, 0.0] # for type "line"
   line_end: [0.14, 0.0] # for type "line"
 # GoalTolerance
    
 xy_goal_tolerance: 0.15
 yaw_goal_tolerance: 0.57
 free_goal_vel: False
 complete_global_plan: True
    
 # Obstacles
    
 min_obstacle_dist: 0.2 # 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.0
 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_y: 1
 weight_max_vel_theta: 1
 weight_acc_lim_x: 1
 weight_acc_lim_y: 1
 weight_acc_lim_theta: 1
 weight_kinematics_nh: 1000
 weight_kinematics_forward_drive: 1
 weight_kinematics_turning_radius: 0.1
 weight_optimaltime: 2 # must be > 0
 weight_shortest_path: 1
 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: True
 oscillation_v_eps: 0.1
 oscillation_omega_eps: 0.1
 oscillation_recovery_min_duration: 10
 oscillation_filter_duration: 10(2)move base
controller_frequency: 5.0
controller_patience: 3.0
planner_frequency: 2
planner_patience: 5.0
conservative_reset_dist: 3.0
oscillation_timeout: 1000.0
oscillation_distance: 0.35
clearing_rotation_allowed: false (3)local cost
local_costmap:
  global_frame: map
  robot_base_frame: base_footprint
  update_frequency: 15.0
  publish_frequency: 10.0
  rolling_window: true
  width: 2.5
  height: 2.5
  resolution: 0.05
  transform_tolerance: 0.5
  
  plugins:
   - {name: static_layer,        type: "costmap_2d::StaticLayer"}
   - {name: obstacle_layer,      type: "costmap_2d::ObstacleLayer"}(4)global planner
GlobalPlanner:
  allow_unknown: true
  default_tolerance: 0.2
  use_grid_path: false
  use_quadratic: true
  old_navfn_behavior: false
  lethal_cost: 253
  neutral_cost: 50
  cost_factor: 3
  publish_potential: true
  orientation_mode: 2
  orientation_window_size: 1
  outline_map: true
  visualize_potential: false(5)costmap common 
#---standard pioneer footprint---
#---(in meters)---
footprint: [ [-0.15,-0.13], [0.15,-0.13], [0.15,0.13], [-0.15,0.13] ]
transform_tolerance: 0.2
always_send_full_costmap: true
obstacle_layer:
 enabled: true
 obstacle_range: 3.0
 raytrace_range: 4.0
 inflation_radius: 0.2
 track_unknown_space: true
 combination_method: 1
 observation_sources: laser_scan_sensor
 laser_scan_sensor: {data_type: LaserScan, topic: scan, marking: true, clearing: true}
inflation_layer:
  enabled:              true
  cost_scaling_factor:  10.0  # exponential rate at which the obstacle cost drops off (default: 10)
  inflation_radius:     0.5  # max. distance from an obstacle at which costs are incurred for planning paths.
static_layer:
  enabled:              true
  map_topic:            "/map"(6)global cost
global_costmap:
  global_frame: map
  robot_base_frame: base_footprint
  update_frequency: 2.0
  publish_frequency: 1.0
 
  transform_tolerance: 0.5
  plugins:
    - {name: static_layer,            type: "costmap_2d::StaticLayer"}
    - {name: obstacle_layer,          type: "costmap_2d::VoxelLayer"}
    - {name: inflation_layer,         type: "costmap_2d::InflationLayer"}
https://blog.csdn.net/allenhsu6/article/details/113523546
2023年3月7日
相比之前版本优化参数,之前在走直线中会互相超调晃动导致机器人移动效率低,这个版本参数优化了该问题,但是会导致机器人在终点处倒车
TebLocalPlannerROS:
 odom_topic: odom
    
 # Trajectory
  
 teb_autosize: True
 dt_ref: 0.45
 dt_hysteresis: 0.045
 max_samples: 500
 global_plan_overwrite_orientation: True
 allow_init_with_backwards_motion: True
 max_global_plan_lookahead_dist: 0.0
 global_plan_viapoint_sep: 0.16
 global_plan_prune_distance: 1
 exact_arc_length: False
 feasibility_check_no_poses: 5
 publish_feedback: False
    
 # Robot
         
 max_vel_x: 0.3
 max_vel_x_backwards: 0.25
 max_vel_y: 0.2
 max_vel_theta: 0.45 # the angular velocity is also bounded by min_turning_radius in case of a carlike robot (r = v / omega)
 acc_lim_x: 0.2
 acc_lim_y: 0.15
 acc_lim_theta: 0.35
 # ********************** Carlike robot parameters ********************
 min_turning_radius: 0.15        # Min turning radius of the carlike robot (compute value using a model or adjust with rqt_reconfigure manually)
 wheelbase: 0.01                 # 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.14, 0.0] # for type "line"
   line_end: [0.14, 0.0] # for type "line"
 # GoalTolerance
    
 xy_goal_tolerance: 0.15
 yaw_goal_tolerance: 1.57
 free_goal_vel: False
 complete_global_plan: True
    
 # Obstacles
    
 min_obstacle_dist: 0.2 # 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.0
 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_y: 1
 weight_max_vel_theta: 1
 weight_acc_lim_x: 1
 weight_acc_lim_y: 1
 weight_acc_lim_theta: 1
 weight_kinematics_nh: 1000
 weight_kinematics_forward_drive: 1
 weight_kinematics_turning_radius: 1
 weight_optimaltime: 2 # must be > 0
 weight_shortest_path: 1
 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: True
 oscillation_v_eps: 0.1
 oscillation_omega_eps: 0.1
 oscillation_recovery_min_duration: 10
 oscillation_filter_duration: 10 
                
              