446 lines
13 KiB
YAML
446 lines
13 KiB
YAML
amcl:
|
|
ros__parameters:
|
|
alpha1: 0.2
|
|
alpha2: 0.2
|
|
alpha3: 0.2
|
|
alpha4: 0.2
|
|
alpha5: 0.2
|
|
base_frame_id: "base_link"
|
|
beam_skip_distance: 0.5
|
|
beam_skip_error_threshold: 0.9
|
|
beam_skip_threshold: 0.3
|
|
do_beamskip: false
|
|
global_frame_id: "map"
|
|
lambda_short: 0.1
|
|
laser_likelihood_max_dist: 2.0
|
|
laser_max_range: 100.0
|
|
laser_min_range: -1.0
|
|
laser_model_type: "likelihood_field"
|
|
max_beams: 60
|
|
max_particles: 2000
|
|
min_particles: 500
|
|
odom_frame_id: "odom"
|
|
pf_err: 0.05
|
|
pf_z: 0.99
|
|
recovery_alpha_fast: 0.0
|
|
recovery_alpha_slow: 0.0
|
|
resample_interval: 1
|
|
robot_model_type: "nav2_amcl::DifferentialMotionModel"
|
|
save_pose_rate: 0.5
|
|
sigma_hit: 0.2
|
|
tf_broadcast: true
|
|
transform_tolerance: 1.0
|
|
update_min_a: 0.2
|
|
update_min_d: 0.25
|
|
z_hit: 0.5
|
|
z_max: 0.05
|
|
z_rand: 0.5
|
|
z_short: 0.05
|
|
scan_topic: scan
|
|
enable_stamped_cmd_vel: true
|
|
|
|
bt_navigator:
|
|
ros__parameters:
|
|
global_frame: map
|
|
robot_base_frame: base_link
|
|
odom_topic: /odom
|
|
bt_loop_duration: 10
|
|
default_server_timeout: 20
|
|
wait_for_service_timeout: 1000
|
|
action_server_result_timeout: 900.0
|
|
navigators: ["navigate_to_pose", "navigate_through_poses"]
|
|
navigate_to_pose:
|
|
plugin: "nav2_bt_navigator::NavigateToPoseNavigator"
|
|
navigate_through_poses:
|
|
plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator"
|
|
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
|
|
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
|
|
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
|
|
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
|
|
|
|
# plugin_lib_names is used to add custom BT plugins to the executor (vector of strings).
|
|
# Built-in plugins are added automatically
|
|
# plugin_lib_names: []
|
|
enable_stamped_cmd_vel: true
|
|
|
|
error_code_names:
|
|
- compute_path_error_code
|
|
- follow_path_error_code
|
|
|
|
controller_server:
|
|
ros__parameters:
|
|
controller_frequency: 20.0
|
|
min_x_velocity_threshold: 0.001
|
|
min_y_velocity_threshold: 0.5
|
|
min_theta_velocity_threshold: 0.001
|
|
failure_tolerance: 0.3
|
|
progress_checker_plugins: ["progress_checker"]
|
|
goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
|
|
controller_plugins: ["FollowPath"]
|
|
use_realtime_priority: false
|
|
enable_stamped_cmd_vel: true
|
|
|
|
# Progress checker parameters
|
|
progress_checker:
|
|
plugin: "nav2_controller::SimpleProgressChecker"
|
|
required_movement_radius: 0.5
|
|
movement_time_allowance: 10.0
|
|
# Goal checker parameters
|
|
#precise_goal_checker:
|
|
# plugin: "nav2_controller::SimpleGoalChecker"
|
|
# xy_goal_tolerance: 0.25
|
|
# yaw_goal_tolerance: 0.25
|
|
# stateful: True
|
|
general_goal_checker:
|
|
stateful: True
|
|
plugin: "nav2_controller::SimpleGoalChecker"
|
|
xy_goal_tolerance: 0.25
|
|
yaw_goal_tolerance: 0.25
|
|
FollowPath:
|
|
plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
|
|
desired_linear_vel: 0.5
|
|
lookahead_dist: 0.6
|
|
min_lookahead_dist: 0.3
|
|
max_lookahead_dist: 0.9
|
|
lookahead_time: 1.5
|
|
rotate_to_heading_angular_vel: 1.8
|
|
transform_tolerance: 0.1
|
|
use_velocity_scaled_lookahead_dist: false
|
|
min_approach_linear_velocity: 0.05
|
|
approach_velocity_scaling_dist: 0.6
|
|
use_collision_detection: true
|
|
max_allowed_time_to_collision_up_to_carrot: 1.0
|
|
use_regulated_linear_velocity_scaling: true
|
|
use_fixed_curvature_lookahead: false
|
|
curvature_lookahead_dist: 0.25
|
|
use_cost_regulated_linear_velocity_scaling: false
|
|
regulated_linear_scaling_min_radius: 0.9
|
|
regulated_linear_scaling_min_speed: 0.25
|
|
use_rotate_to_heading: true
|
|
allow_reversing: false
|
|
rotate_to_heading_min_angle: 0.785
|
|
max_angular_accel: 3.2
|
|
max_robot_pose_search_dist: 10.0
|
|
|
|
# plugin: "nav2_mppi_controller::MPPIController"
|
|
# time_steps: 56
|
|
# model_dt: 0.05
|
|
# batch_size: 2000
|
|
# vx_std: 0.2
|
|
# vy_std: 0.2
|
|
# wz_std: 0.4
|
|
# vx_max: 0.5
|
|
# vx_min: -0.35
|
|
# vy_max: 0.5
|
|
# wz_max: 1.9
|
|
# iteration_count: 1
|
|
# prune_distance: 1.7
|
|
# transform_tolerance: 0.1
|
|
# temperature: 0.3
|
|
# gamma: 0.015
|
|
# motion_model: "DiffDrive"
|
|
# visualize: true
|
|
# regenerate_noises: true
|
|
# TrajectoryVisualizer:
|
|
# trajectory_step: 5
|
|
# time_step: 3
|
|
# AckermannConstraints:
|
|
# min_turning_r: 0.2
|
|
# critics: [
|
|
# "ConstraintCritic", "CostCritic", "GoalCritic",
|
|
# "GoalAngleCritic", "PathAlignCritic", "PathFollowCritic",
|
|
# "PathAngleCritic", "PreferForwardCritic"]
|
|
# ConstraintCritic:
|
|
# enabled: true
|
|
# cost_power: 1
|
|
# cost_weight: 4.0
|
|
# GoalCritic:
|
|
# enabled: true
|
|
# cost_power: 1
|
|
# cost_weight: 5.0
|
|
# threshold_to_consider: 1.4
|
|
# GoalAngleCritic:
|
|
# enabled: true
|
|
# cost_power: 1
|
|
# cost_weight: 3.0
|
|
# threshold_to_consider: 0.5
|
|
# PreferForwardCritic:
|
|
# enabled: true
|
|
# cost_power: 1
|
|
# cost_weight: 5.0
|
|
# threshold_to_consider: 0.5
|
|
# CostCritic:
|
|
# enabled: true
|
|
# cost_power: 1
|
|
# cost_weight: 3.81
|
|
# critical_cost: 300.0
|
|
# consider_footprint: true
|
|
# collision_cost: 1000000.0
|
|
# near_goal_distance: 1.0
|
|
# trajectory_point_step: 2
|
|
# PathAlignCritic:
|
|
# enabled: true
|
|
# cost_power: 1
|
|
# cost_weight: 14.0
|
|
# max_path_occupancy_ratio: 0.05
|
|
# trajectory_point_step: 4
|
|
# threshold_to_consider: 0.5
|
|
# offset_from_furthest: 20
|
|
# use_path_orientations: false
|
|
# PathFollowCritic:
|
|
# enabled: true
|
|
# cost_power: 1
|
|
# cost_weight: 5.0
|
|
# offset_from_furthest: 5
|
|
# threshold_to_consider: 1.4
|
|
# PathAngleCritic:
|
|
# enabled: true
|
|
# cost_power: 1
|
|
# cost_weight: 2.0
|
|
# offset_from_furthest: 4
|
|
# threshold_to_consider: 0.5
|
|
# max_angle_to_furthest: 1.0
|
|
# mode: 0
|
|
|
|
# plugin: "dwb_core::DWBLocalPlanner"
|
|
# debug_trajectory_details: True
|
|
# min_vel_x: 0.0
|
|
# min_vel_y: 0.0
|
|
# max_vel_x: 0.26
|
|
# max_vel_y: 0.0
|
|
# max_vel_theta: 1.0
|
|
# min_speed_xy: 0.0
|
|
# max_speed_xy: 0.26
|
|
# min_speed_theta: 0.0
|
|
# acc_lim_x: 2.5
|
|
# acc_lim_y: 0.0
|
|
# acc_lim_theta: 3.2
|
|
# decel_lim_x: -2.5
|
|
# decel_lim_y: 0.0
|
|
# decel_lim_theta: -3.2
|
|
# vx_samples: 20
|
|
# vy_samples: 5
|
|
# vtheta_samples: 20
|
|
# sim_time: 1.7
|
|
# linear_granularity: 0.05
|
|
# angular_granularity: 0.025
|
|
# transform_tolerance: 0.2
|
|
# xy_goal_tolerance: 0.25
|
|
# trans_stopped_velocity: 0.25
|
|
# short_circuit_trajectory_evaluation: True
|
|
# stateful: True
|
|
# critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
|
|
# BaseObstacle.scale: 0.02
|
|
# PathAlign.scale: 32.0
|
|
# GoalAlign.scale: 24.0
|
|
# PathAlign.forward_point_distance: 0.1
|
|
# GoalAlign.forward_point_distance: 0.1
|
|
# PathDist.scale: 32.0
|
|
# GoalDist.scale: 24.0
|
|
# RotateToGoal.scale: 32.0
|
|
# RotateToGoal.slowing_factor: 5.0
|
|
# RotateToGoal.lookahead_time: -1.0
|
|
# TwirlingCritic:
|
|
# enabled: true
|
|
# twirling_cost_power: 1
|
|
# twirling_cost_weight: 10.0
|
|
|
|
local_costmap:
|
|
local_costmap:
|
|
ros__parameters:
|
|
update_frequency: 5.0
|
|
publish_frequency: 2.0
|
|
global_frame: odom
|
|
robot_base_frame: base_link
|
|
rolling_window: true
|
|
width: 3
|
|
height: 3
|
|
resolution: 0.05
|
|
robot_radius: 0.22
|
|
plugins: ["voxel_layer", "inflation_layer"]
|
|
inflation_layer:
|
|
plugin: "nav2_costmap_2d::InflationLayer"
|
|
cost_scaling_factor: 3.0
|
|
inflation_radius: 0.70
|
|
voxel_layer:
|
|
plugin: "nav2_costmap_2d::VoxelLayer"
|
|
enabled: True
|
|
publish_voxel_map: True
|
|
origin_z: 0.0
|
|
z_resolution: 0.05
|
|
z_voxels: 16
|
|
max_obstacle_height: 2.0
|
|
mark_threshold: 0
|
|
observation_sources: scan
|
|
scan:
|
|
topic: /scan
|
|
max_obstacle_height: 2.0
|
|
clearing: True
|
|
marking: True
|
|
data_type: "LaserScan"
|
|
raytrace_max_range: 3.0
|
|
raytrace_min_range: 0.0
|
|
obstacle_max_range: 2.5
|
|
obstacle_min_range: 0.0
|
|
static_layer:
|
|
plugin: "nav2_costmap_2d::StaticLayer"
|
|
map_subscribe_transient_local: True
|
|
always_send_full_costmap: True
|
|
|
|
global_costmap:
|
|
global_costmap:
|
|
ros__parameters:
|
|
update_frequency: 1.0
|
|
publish_frequency: 1.0
|
|
global_frame: map
|
|
robot_base_frame: base_link
|
|
robot_radius: 0.22
|
|
resolution: 0.05
|
|
track_unknown_space: true
|
|
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
|
|
obstacle_layer:
|
|
plugin: "nav2_costmap_2d::ObstacleLayer"
|
|
enabled: True
|
|
observation_sources: scan
|
|
scan:
|
|
topic: /scan
|
|
max_obstacle_height: 2.0
|
|
clearing: True
|
|
marking: True
|
|
data_type: "LaserScan"
|
|
raytrace_max_range: 3.0
|
|
raytrace_min_range: 0.0
|
|
obstacle_max_range: 2.5
|
|
obstacle_min_range: 0.0
|
|
static_layer:
|
|
plugin: "nav2_costmap_2d::StaticLayer"
|
|
map_subscribe_transient_local: True
|
|
inflation_layer:
|
|
plugin: "nav2_costmap_2d::InflationLayer"
|
|
cost_scaling_factor: 3.0
|
|
inflation_radius: 0.7
|
|
always_send_full_costmap: True
|
|
enable_stamped_cmd_vel: true
|
|
|
|
# The yaml_filename does not need to be specified since it going to be set by defaults in launch.
|
|
# If you'd rather set it in the yaml, remove the default "map" value in the tb3_simulation_launch.py
|
|
# file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used.
|
|
# map_server:
|
|
# ros__parameters:
|
|
# yaml_filename: ""
|
|
|
|
map_saver:
|
|
ros__parameters:
|
|
save_map_timeout: 5.0
|
|
free_thresh_default: 0.25
|
|
occupied_thresh_default: 0.65
|
|
map_subscribe_transient_local: True
|
|
|
|
planner_server:
|
|
ros__parameters:
|
|
expected_planner_frequency: 20.0
|
|
planner_plugins: ["GridBased"]
|
|
GridBased:
|
|
plugin: "nav2_navfn_planner::NavfnPlanner"
|
|
tolerance: 0.5
|
|
use_astar: false
|
|
allow_unknown: true
|
|
|
|
smoother_server:
|
|
ros__parameters:
|
|
smoother_plugins: ["simple_smoother"]
|
|
simple_smoother:
|
|
plugin: "nav2_smoother::SimpleSmoother"
|
|
tolerance: 1.0e-10
|
|
max_its: 1000
|
|
do_refinement: True
|
|
enable_stamped_cmd_vel: true
|
|
enable_stamped_cmd_vel: true
|
|
|
|
behavior_server:
|
|
ros__parameters:
|
|
local_costmap_topic: local_costmap/costmap_raw
|
|
global_costmap_topic: global_costmap/costmap_raw
|
|
local_footprint_topic: local_costmap/published_footprint
|
|
global_footprint_topic: global_costmap/published_footprint
|
|
cycle_frequency: 10.0
|
|
behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
|
|
spin:
|
|
plugin: "nav2_behaviors::Spin"
|
|
backup:
|
|
plugin: "nav2_behaviors::BackUp"
|
|
drive_on_heading:
|
|
plugin: "nav2_behaviors::DriveOnHeading"
|
|
wait:
|
|
plugin: "nav2_behaviors::Wait"
|
|
assisted_teleop:
|
|
plugin: "nav2_behaviors::AssistedTeleop"
|
|
local_frame: odom
|
|
global_frame: map
|
|
robot_base_frame: base_link
|
|
transform_tolerance: 0.1
|
|
simulate_ahead_time: 2.0
|
|
max_rotational_vel: 1.0
|
|
min_rotational_vel: 0.4
|
|
rotational_acc_lim: 3.2
|
|
enable_stamped_cmd_vel: true
|
|
|
|
waypoint_follower:
|
|
ros__parameters:
|
|
loop_rate: 20
|
|
stop_on_failure: false
|
|
action_server_result_timeout: 900.0
|
|
waypoint_task_executor_plugin: "wait_at_waypoint"
|
|
wait_at_waypoint:
|
|
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
|
|
enabled: True
|
|
waypoint_pause_duration: 200
|
|
enable_stamped_cmd_vel: true
|
|
|
|
velocity_smoother:
|
|
ros__parameters:
|
|
smoothing_frequency: 20.0
|
|
scale_velocities: False
|
|
feedback: "OPEN_LOOP"
|
|
max_velocity: [0.5, 0.0, 2.0]
|
|
min_velocity: [-0.5, 0.0, -2.0]
|
|
max_accel: [2.5, 0.0, 3.2]
|
|
max_decel: [-2.5, 0.0, -3.2]
|
|
odom_topic: "odom"
|
|
odom_duration: 0.1
|
|
deadband_velocity: [0.0, 0.0, 0.0]
|
|
velocity_timeout: 1.0
|
|
enable_stamped_cmd_vel: true
|
|
|
|
collision_monitor:
|
|
ros__parameters:
|
|
base_frame_id: "base_link"
|
|
odom_frame_id: "odom"
|
|
cmd_vel_in_topic: "cmd_vel_smoothed"
|
|
cmd_vel_out_topic: "cmd_vel"
|
|
state_topic: "collision_monitor_state"
|
|
transform_tolerance: 0.2
|
|
source_timeout: 1.0
|
|
base_shift_correction: True
|
|
stop_pub_timeout: 2.0
|
|
enable_stamped_cmd_vel: true
|
|
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
|
|
# and robot footprint for "approach" action type.
|
|
polygons: ["FootprintApproach"]
|
|
FootprintApproach:
|
|
type: "polygon"
|
|
action_type: "approach"
|
|
footprint_topic: "/local_costmap/published_footprint"
|
|
time_before_collision: 1.2
|
|
simulation_time_step: 0.1
|
|
min_points: 6
|
|
visualize: False
|
|
enabled: True
|
|
observation_sources: ["scan"]
|
|
scan:
|
|
type: "scan"
|
|
topic: "scan"
|
|
min_height: 0.15
|
|
max_height: 2.0
|
|
enabled: True
|