mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2024-11-23 15:45:08 +00:00
633 lines
22 KiB
YAML
633 lines
22 KiB
YAML
amcl:
|
|
ros__parameters:
|
|
use_sim_time: False
|
|
alpha1: 0.2
|
|
alpha2: 0.2
|
|
alpha3: 0.2
|
|
alpha4: 0.2
|
|
alpha5: 0.2
|
|
base_frame_id: "base_footprint"
|
|
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: -1.0 # was 100 before: setting now to laser reported range (8m)
|
|
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
|
|
|
|
bt_navigator:
|
|
ros__parameters:
|
|
use_sim_time: False
|
|
global_frame: map
|
|
robot_base_frame: base_link
|
|
odom_topic: /odometry
|
|
bt_loop_duration: 10
|
|
default_server_timeout: 20
|
|
# '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:
|
|
- nav2_compute_path_to_pose_action_bt_node
|
|
- nav2_compute_path_through_poses_action_bt_node
|
|
- nav2_smooth_path_action_bt_node
|
|
- nav2_follow_path_action_bt_node
|
|
#- nav2_spin_action_bt_node
|
|
- nav2_wait_action_bt_node
|
|
- nav2_assisted_teleop_action_bt_node
|
|
- nav2_back_up_action_bt_node
|
|
- nav2_drive_on_heading_bt_node
|
|
- nav2_clear_costmap_service_bt_node
|
|
- nav2_is_stuck_condition_bt_node
|
|
- nav2_goal_reached_condition_bt_node
|
|
- nav2_goal_updated_condition_bt_node
|
|
- nav2_globally_updated_goal_condition_bt_node
|
|
- nav2_is_path_valid_condition_bt_node
|
|
- nav2_initial_pose_received_condition_bt_node
|
|
- nav2_reinitialize_global_localization_service_bt_node
|
|
- nav2_rate_controller_bt_node
|
|
- nav2_distance_controller_bt_node
|
|
- nav2_speed_controller_bt_node
|
|
- nav2_truncate_path_action_bt_node
|
|
- nav2_truncate_path_local_action_bt_node
|
|
- nav2_goal_updater_node_bt_node
|
|
- nav2_recovery_node_bt_node
|
|
- nav2_pipeline_sequence_bt_node
|
|
- nav2_round_robin_node_bt_node
|
|
- nav2_transform_available_condition_bt_node
|
|
- nav2_time_expired_condition_bt_node
|
|
- nav2_path_expiring_timer_condition
|
|
- nav2_distance_traveled_condition_bt_node
|
|
- nav2_single_trigger_bt_node
|
|
- nav2_goal_updated_controller_bt_node
|
|
- nav2_is_battery_low_condition_bt_node
|
|
- nav2_navigate_through_poses_action_bt_node
|
|
- nav2_navigate_to_pose_action_bt_node
|
|
- nav2_remove_passed_goals_action_bt_node
|
|
- nav2_planner_selector_bt_node
|
|
- nav2_controller_selector_bt_node
|
|
- nav2_goal_checker_selector_bt_node
|
|
- nav2_controller_cancel_bt_node
|
|
- nav2_path_longer_on_approach_bt_node
|
|
- nav2_wait_cancel_bt_node
|
|
- nav2_spin_cancel_bt_node
|
|
- nav2_back_up_cancel_bt_node
|
|
- nav2_assisted_teleop_cancel_bt_node
|
|
- nav2_drive_on_heading_cancel_bt_node
|
|
- nav2_is_battery_charging_condition_bt_node
|
|
|
|
bt_navigator_navigate_through_poses_rclcpp_node:
|
|
ros__parameters:
|
|
use_sim_time: False
|
|
|
|
bt_navigator_navigate_to_pose_rclcpp_node:
|
|
ros__parameters:
|
|
use_sim_time: False
|
|
|
|
# controller_server:
|
|
# ros__parameters:
|
|
# use_sim_time: False
|
|
# controller_frequency: 30.0
|
|
# min_x_velocity_threshold: 0.001
|
|
# min_y_velocity_threshold: 0.001
|
|
# min_theta_velocity_threshold: 0.001
|
|
# failure_tolerance: 0.3
|
|
# progress_checker_plugin: "progress_checker"
|
|
# goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
|
|
# controller_plugins: ["FollowPath"]
|
|
|
|
# # 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
|
|
# # DWB parameters
|
|
# FollowPath:
|
|
# # plugin: "dwb_core::DWBLocalPlanner"
|
|
|
|
# # trying roation_shim_controller
|
|
# #plugin: "nav2_rotation_shim_controller::RotationShimController"
|
|
# #plugin: "dwb_core::DWBLocalPlanner"
|
|
# #primary_controller: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
|
|
# #primary_controller: "dwb_core::DWBLocalPlanner"
|
|
# # angular_dist_threshold: 0.785
|
|
# # forward_sampling_distance: 0.5
|
|
# # rotate_to_heading_angular_vel: 0.3
|
|
# # max_angular_accel: 0.2
|
|
# # simulate_ahead_time: 1.0
|
|
|
|
# # # primary controller params (dwb)
|
|
# # debug_trajectory_details: True
|
|
# # min_vel_x: 0.0
|
|
# # min_vel_y: 0.0
|
|
# # max_vel_x: 0.26
|
|
# # max_vel_y: 0.26
|
|
# # max_vel_theta: 1.0
|
|
# # min_speed_xy: 0.001
|
|
# # max_speed_xy: 0.26
|
|
# # min_speed_theta: 0.0
|
|
# # # Add high threshold velocity for turtlebot 3 issue.
|
|
# # # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
|
|
# # acc_lim_x: 0.02 # was 2.5
|
|
# # acc_lim_y: 0.02
|
|
# # acc_lim_theta: 1.0 # was 3.2
|
|
# # decel_lim_x: -0.02 # was -2.5
|
|
# # decel_lim_y: -0.02
|
|
# # decel_lim_theta: -0.1 # was -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
|
|
# # PathAlign.forward_point_distance: 0.1
|
|
# # GoalAlign.scale: 24.0
|
|
# # 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
|
|
|
|
# # trying mppi_controller
|
|
# 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: false
|
|
# reset_period: 1.0 # (only in Humble)
|
|
# TrajectoryVisualizer:
|
|
# trajectory_step: 5
|
|
# time_step: 3
|
|
# AckermannConstrains:
|
|
# min_turning_r: 0.2
|
|
# critics: ["ConstraintCritic", "ObstaclesCritic", "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
|
|
# ObstaclesCritic:
|
|
# enabled: true
|
|
# cost_power: 1
|
|
# repulsion_weight: 1.5
|
|
# critical_weight: 20.0
|
|
# consider_footprint: false
|
|
# collision_cost: 10000.0
|
|
# collision_margin_distance: 0.1
|
|
# near_goal_distance: 0.5
|
|
# inflation_radius: 0.55 # (only in Humble)
|
|
# cost_scaling_factor: 10.0 # (only in Humble)
|
|
# PathAlignCritic:
|
|
# enabled: true
|
|
# cost_power: 1
|
|
# cost_weight: 14.0
|
|
# max_path_occupancy_ratio: 0.05
|
|
# trajectory_point_step: 3
|
|
# 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
|
|
# # TwirlingCritic:
|
|
# # enabled: true
|
|
# # twirling_cost_power: 1
|
|
# # twirling_cost_weight: 10.0
|
|
|
|
# #try mppi controller --> leads to crash on startup!
|
|
# controller_server:
|
|
# ros__parameters:
|
|
# controller_frequency: 30.0
|
|
# FollowPath:
|
|
# 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: false
|
|
# reset_period: 1.0 # (only in Humble)
|
|
# TrajectoryVisualizer:
|
|
# trajectory_step: 5
|
|
# time_step: 3
|
|
# AckermannConstrains:
|
|
# min_turning_r: 0.2
|
|
# critics: ["ConstraintCritic", "ObstaclesCritic", "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
|
|
# ObstaclesCritic:
|
|
# enabled: true
|
|
# cost_power: 1
|
|
# repulsion_weight: 1.5
|
|
# critical_weight: 20.0
|
|
# consider_footprint: false
|
|
# collision_cost: 10000.0
|
|
# collision_margin_distance: 0.1
|
|
# near_goal_distance: 0.5
|
|
# inflation_radius: 0.55 # (only in Humble)
|
|
# cost_scaling_factor: 10.0 # (only in Humble)
|
|
# PathAlignCritic:
|
|
# enabled: true
|
|
# cost_power: 1
|
|
# cost_weight: 14.0
|
|
# max_path_occupancy_ratio: 0.05
|
|
# trajectory_point_step: 3
|
|
# 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
|
|
# # TwirlingCritic:
|
|
# # enabled: true
|
|
# # twirling_cost_power: 1
|
|
# # twirling_cost_weight: 10.0
|
|
|
|
# try rpp controller
|
|
controller_server:
|
|
ros__parameters:
|
|
use_sim_time: True
|
|
controller_frequency: 20.0
|
|
min_x_velocity_threshold: 0.001
|
|
min_y_velocity_threshold: 0.5
|
|
min_theta_velocity_threshold: 0.001
|
|
progress_checker_plugins: ["progress_checker"] # progress_checker_plugin: "progress_checker" For Humble and older
|
|
goal_checker_plugins: ["goal_checker"]
|
|
controller_plugins: ["FollowPath"]
|
|
|
|
progress_checker:
|
|
plugin: "nav2_controller::SimpleProgressChecker"
|
|
required_movement_radius: 0.5
|
|
movement_time_allowance: 10.0
|
|
goal_checker:
|
|
plugin: "nav2_controller::SimpleGoalChecker"
|
|
xy_goal_tolerance: 0.25
|
|
yaw_goal_tolerance: 0.25
|
|
stateful: True
|
|
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: 0.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: true
|
|
rotate_to_heading_min_angle: 0.785
|
|
max_angular_accel: 3.2
|
|
max_robot_pose_search_dist: 10.0
|
|
use_interpolation: true
|
|
|
|
local_costmap:
|
|
local_costmap:
|
|
ros__parameters:
|
|
update_frequency: 20.0 # was 5.0
|
|
publish_frequency: 5.0 # was 2.0
|
|
global_frame: odom
|
|
robot_base_frame: base_link
|
|
use_sim_time: False
|
|
rolling_window: true
|
|
width: 3
|
|
height: 3
|
|
resolution: 0.05
|
|
#robot_radius: 0.50
|
|
footprint: "[ [0.18, 0.255], [0.18, -0.255], [-0.54, -0.165], [-0.54, 0.165] ]" # gave another points for the polygon
|
|
plugins: ["voxel_layer", "inflation_layer", "denoise_layer"]
|
|
denoise_layer:
|
|
plugin: "nav2_costmap_2d::DenoiseLayer"
|
|
enabled: True
|
|
inflation_layer:
|
|
plugin: "nav2_costmap_2d::InflationLayer"
|
|
cost_scaling_factor: 8.0 # was 3.0
|
|
inflation_radius: 0.44
|
|
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: 8.0 # was 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
|
|
use_sim_time: False
|
|
#robot_radius: 0.50
|
|
footprint: "[ [0.18, 0.255], [0.18, -0.255], [-0.54, -0.165], [-0.54, 0.165] ]" # gave another points for the polygon
|
|
resolution: 0.05
|
|
track_unknown_space: true
|
|
plugins: ["static_layer", "obstacle_layer", "inflation_layer", "denoise_layer"]
|
|
denoise_layer:
|
|
plugin: "nav2_costmap_2d::DenoiseLayer"
|
|
enabled: True
|
|
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: 8.0 # was 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: 8.0 # was 3.0
|
|
inflation_radius: 0.44
|
|
always_send_full_costmap: True
|
|
|
|
map_server:
|
|
ros__parameters:
|
|
use_sim_time: False
|
|
# Overridden in launch by the "map" launch configuration or provided default value.
|
|
# To use in yaml, remove the default "map" value in the tb3_simulation_launch.py file & provide full path to map below.
|
|
yaml_filename: "/repo/map_floor_save.yaml"
|
|
|
|
map_saver:
|
|
ros__parameters:
|
|
use_sim_time: False
|
|
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
|
|
# use_sim_time: False
|
|
# planner_plugins: ["GridBased"]
|
|
# GridBased:
|
|
# plugin: "nav2_navfn_planner/NavfnPlanner"
|
|
# #plugin: "nav2_smac_planner/SmacPlanner2D"
|
|
# tolerance: 0.5
|
|
# #use_astar: false
|
|
# allow_unknown: true
|
|
|
|
# trying smac hybrid planner
|
|
planner_server:
|
|
ros__parameters:
|
|
planner_plugins: ["GridBased"]
|
|
use_sim_time: True
|
|
|
|
GridBased:
|
|
plugin: "nav2_smac_planner/SmacPlannerHybrid"
|
|
downsample_costmap: false # whether or not to downsample the map
|
|
downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm)
|
|
tolerance: 0.25 # dist-to-goal heuristic cost (distance) for valid tolerance endpoints if exact goal cannot be found.
|
|
allow_unknown: true # allow traveling in unknown space
|
|
max_iterations: 1000000 # maximum total iterations to search for before failing (in case unreachable), set to -1 to disable
|
|
max_on_approach_iterations: 1000 # Maximum number of iterations after within tolerances to continue to try to find exact solution
|
|
max_planning_time: 5.0 # max time in s for planner to plan, smooth
|
|
motion_model_for_search: "DUBIN" #was DUBIN # Hybrid-A* Dubin, Redds-Shepp
|
|
angle_quantization_bins: 72 # Number of angle bins for search
|
|
analytic_expansion_ratio: 3.5 # The ratio to attempt analytic expansions during search for final approach.
|
|
analytic_expansion_max_length: 3.0 # For Hybrid/Lattice nodes: The maximum length of the analytic expansion to be considered valid to prevent unsafe shortcutting
|
|
minimum_turning_radius: 0.15 # was 0.40 # minimum turning radius in m of path / vehicle
|
|
reverse_penalty: 2.0 # Penalty to apply if motion is reversing, must be => 1
|
|
change_penalty: 0.5 # was 0.0 # Penalty to apply if motion is changing directions (L to R), must be >= 0
|
|
non_straight_penalty: 1.2 # Penalty to apply if motion is non-straight, must be => 1
|
|
cost_penalty: 2.0 # Penalty to apply to higher cost areas when adding into the obstacle map dynamic programming distance expansion heuristic. This drives the robot more towards the center of passages. A value between 1.3 - 3.5 is reasonable.
|
|
retrospective_penalty: 0.015
|
|
lookup_table_size: 20.0 # Size of the dubin/reeds-sheep distance window to cache, in meters.
|
|
cache_obstacle_heuristic: true #was fasle # Cache the obstacle map dynamic programming distance expansion heuristic between subsiquent replannings of the same goal location. Dramatically speeds up replanning performance (40x) if costmap is largely static.
|
|
debug_visualizations: false # For Hybrid nodes: Whether to publish expansions on the /expansions topic as an array of poses (the orientation has no meaning) and the path's footprints on the /planned_footprints topic. WARNING: heavy to compute and to display, for debug only as it degrades the performance.
|
|
use_quadratic_cost_penalty: False
|
|
downsample_obstacle_heuristic: True
|
|
allow_primitive_interpolation: False
|
|
smooth_path: True # If true, does a simple and quick smoothing post-processing to the path
|
|
|
|
smoother:
|
|
max_iterations: 1000
|
|
w_smooth: 0.3
|
|
w_data: 0.2
|
|
tolerance: 1.0e-10
|
|
do_refinement: true
|
|
refinement_num: 2
|
|
|
|
smoother_server:
|
|
ros__parameters:
|
|
use_sim_time: False
|
|
smoother_plugins: ["simple_smoother"]
|
|
simple_smoother:
|
|
plugin: "nav2_smoother::SimpleSmoother"
|
|
tolerance: 1.0e-10
|
|
max_its: 1000
|
|
do_refinement: True
|
|
|
|
behavior_server:
|
|
ros__parameters:
|
|
costmap_topic: local_costmap/costmap_raw
|
|
footprint_topic: local_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"
|
|
global_frame: odom
|
|
robot_base_frame: base_link
|
|
transform_tolerance: 0.1
|
|
use_sim_time: False
|
|
simulate_ahead_time: 2.0
|
|
max_rotational_vel: 1.0
|
|
min_rotational_vel: 0.4
|
|
rotational_acc_lim: 3.2
|
|
|
|
robot_state_publisher:
|
|
ros__parameters:
|
|
use_sim_time: False
|
|
|
|
waypoint_follower:
|
|
ros__parameters:
|
|
use_sim_time: False
|
|
loop_rate: 20
|
|
stop_on_failure: false
|
|
waypoint_task_executor_plugin: "wait_at_waypoint"
|
|
wait_at_waypoint:
|
|
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
|
|
enabled: True
|
|
waypoint_pause_duration: 200
|
|
|
|
velocity_smoother:
|
|
ros__parameters:
|
|
use_sim_time: False
|
|
smoothing_frequency: 20.0
|
|
scale_velocities: False
|
|
#feedback: "OPEN_LOOP"
|
|
feedback: "CLOSED_LOOP"
|
|
max_velocity: [0.26, 0.0, 1.0]
|
|
min_velocity: [-0.26, 0.0, -1.0]
|
|
max_accel: [2.5, 0.0, 3.2]
|
|
max_decel: [-2.5, 0.0, -3.2]
|
|
odom_topic: "odometry"
|
|
odom_duration: 0.1
|
|
deadband_velocity: [0.0, 0.0, 0.0]
|
|
velocity_timeout: 1.0 |