Not working vs. Working nav2 params files

Created Diff never expires
42 removals
331 lines
103 additions
350 lines
amcl:
amcl:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False
alpha1: 0.2
alpha1: 0.2
alpha2: 0.2
alpha2: 0.2
alpha3: 0.2
alpha3: 0.2
alpha4: 0.2
alpha4: 0.2
alpha5: 0.2
alpha5: 0.2
base_frame_id: "base_footprint"
base_frame_id: "base_footprint"
beam_skip_distance: 0.5
beam_skip_distance: 0.5
beam_skip_error_threshold: 0.9
beam_skip_error_threshold: 0.9
beam_skip_threshold: 0.3
beam_skip_threshold: 0.3
do_beamskip: false
do_beamskip: false
global_frame_id: "map"
global_frame_id: "map"
lambda_short: 0.1
lambda_short: 0.1
laser_likelihood_max_dist: 2.0
laser_likelihood_max_dist: 2.0
laser_max_range: 100.0
laser_max_range: 100.0
laser_min_range: -1.0
laser_min_range: -1.0
laser_model_type: "likelihood_field"
laser_model_type: "likelihood_field"
max_beams: 60
max_beams: 60
max_particles: 2000
max_particles: 2000
min_particles: 500
min_particles: 500
odom_frame_id: "odom"
odom_frame_id: "odom"
pf_err: 0.05
pf_err: 0.05
pf_z: 0.99
pf_z: 0.99
recovery_alpha_fast: 0.0
recovery_alpha_fast: 0.0
recovery_alpha_slow: 0.0
recovery_alpha_slow: 0.0
resample_interval: 1
resample_interval: 1
robot_model_type: "nav2_amcl::DifferentialMotionModel"
robot_model_type: "differential"
save_pose_rate: 0.5
save_pose_rate: 0.5
sigma_hit: 0.2
sigma_hit: 0.2
tf_broadcast: true
tf_broadcast: true
transform_tolerance: 1.0
transform_tolerance: 1.0
update_min_a: 0.2
update_min_a: 0.2
update_min_d: 0.25
update_min_d: 0.25
z_hit: 0.5
z_hit: 0.5
z_max: 0.05
z_max: 0.05
z_rand: 0.5
z_rand: 0.5
z_short: 0.05
z_short: 0.05
scan_topic: scan
scan_topic: scan


amcl_map_client:
amcl_map_client:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False


amcl_rclcpp_node:
amcl_rclcpp_node:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False


bt_navigator:
bt_navigator:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False
global_frame: map
global_frame: map
robot_base_frame: base_link
robot_base_frame: base_link
odom_topic: /odom
odom_topic: /odom
bt_loop_duration: 10
bt_loop_duration: 10
default_server_timeout: 20
default_server_timeout: 20
default_bt_xml_filename: /opt/ros/BIRDSEYE_WS/auto/caretaker_nav/bt_configs/navigate_w_replanning_time.xml
default_bt_xml_filename: /home/raven/Birdseye/src/auto/caretaker_nav/bt_configs/navigate_w_replanning_time.xml
default_nav_to_pose_bt_xml: /opt/ros/BIRDSEYE_WS/auto/caretaker_nav/bt_configs/navigate_w_replanning_time.xml
default_nav_to_pose_bt_xml: /home/raven/Birdseye/src/auto/caretaker_nav/bt_configs/navigate_w_replanning_time.xml
default_nav_through_poses_bt_xml: /opt/ros/BIRDSEYE_WS/auto/caretaker_nav/bt_configs/navigate_w_replanning_time.xml
default_nav_through_poses_bt_xml: /home/raven/Birdseye/src/auto/caretaker_nav/bt_configs/navigate_w_replanning_time.xml
enable_groot_monitoring: True
enable_groot_monitoring: False
groot_zmq_publisher_port: 1666
groot_zmq_publisher_port: 1666
groot_zmq_server_port: 1667
groot_zmq_server_port: 1667
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
# '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_to_pose_w_replanning_and_recovery.xml
# nav2_bt_navigator/navigate_through_poses_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.
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
plugin_lib_names:
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_compute_path_to_pose_action_bt_node
# - nav2_compute_path_through_poses_action_bt_node
- nav2_compute_path_through_poses_action_bt_node
# - nav2_smooth_path_action_bt_node
# - nav2_smooth_path_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_follow_path_action_bt_node

- nav2_spin_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_wait_action_bt_node
- nav2_back_up_action_bt_node
- nav2_back_up_action_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_goal_updated_condition_bt_node
# - nav2_globally_updated_goal_condition_bt_node
# - nav2_globally_updated_goal_condition_bt_node
# - nav2_is_path_valid_condition_bt_node
# - nav2_is_path_valid_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_truncate_path_action_bt_node
- nav2_truncate_path_action_bt_node
- nav2_goal_updater_node_bt_node
- nav2_goal_updater_node_bt_node
- nav2_recovery_node_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_time_expired_condition_bt_node
# - nav2_path_expiring_timer_condition
# - nav2_path_expiring_timer_condition
- nav2_distance_traveled_condition_bt_node
- nav2_distance_traveled_condition_bt_node
# - nav2_single_trigger_bt_node
# - nav2_single_trigger_bt_node
- nav2_is_battery_low_condition_bt_node
- nav2_is_battery_low_condition_bt_node
# - nav2_navigate_through_poses_action_bt_node
# - nav2_navigate_through_poses_action_bt_node
- nav2_navigate_to_pose_action_bt_node
- nav2_navigate_to_pose_action_bt_node
- nav2_remove_passed_goals_action_bt_node
- nav2_remove_passed_goals_action_bt_node
# - nav2_planner_selector_bt_node
# - nav2_planner_selector_bt_node
# - nav2_controller_selector_bt_node
# - nav2_controller_selector_bt_node
# - nav2_goal_checker_selector_bt_node
# - nav2_goal_checker_selector_bt_node
# - nav2_controller_cancel_bt_node
# - nav2_controller_cancel_bt_node
# - nav2_path_longer_on_approach_bt_node
# - nav2_path_longer_on_approach_bt_node
# - nav2_wait_cancel_bt_node
# - nav2_wait_cancel_bt_node
# - nav2_spin_cancel_bt_node
# - nav2_spin_cancel_bt_node
# - nav2_back_up_cancel_bt_node
# - nav2_back_up_cancel_bt_node


bt_navigator_rclcpp_node:
bt_navigator_rclcpp_node:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False


controller_server:
controller_server:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False
controller_frequency: 20.0
controller_frequency: 20.0
min_x_velocity_threshold: 0.001
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
min_theta_velocity_threshold: 0.001
failure_tolerance: 0.3
failure_tolerance: 0.3
odom_topic: "odom"
odom_topic: "odom"
progress_checker_plugin: "progress_checker"
progress_checker_plugin: "progress_checker"
goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
controller_plugins: ["FollowPath"]
controller_plugins: ["FollowPath"]


# Progress checker parameters
# Progress checker parameters
progress_checker:
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
required_movement_radius: 0.5
movement_time_allowance: 10.0
movement_time_allowance: 10.0
# Goal checker parameters
# Goal checker parameters
#precise_goal_checker:
#precise_goal_checker:
# plugin: "nav2_controller::SimpleGoalChecker"
# plugin: "nav2_controller::SimpleGoalChecker"
# xy_goal_tolerance: 0.25
# xy_goal_tolerance: 0.25
# yaw_goal_tolerance: 0.25
# yaw_goal_tolerance: 0.25
# stateful: True
# stateful: True
general_goal_checker:
general_goal_checker:
stateful: True
stateful: True
plugin: "nav2_controller::SimpleGoalChecker"
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25
xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
# DWB parameters
# DWB parameters
FollowPath:
FollowPath:
plugin: "dwb_core::DWBLocalPlanner"
plugin: "dwb_core::DWBLocalPlanner"
debug_trajectory_details: True
debug_trajectory_details: True
min_vel_x: 0.0
min_vel_x: 0.0
min_vel_y: 0.0
min_vel_y: 0.0
max_vel_x: 0.26
max_vel_x: 0.26
max_vel_y: 0.0
max_vel_y: 0.0
max_vel_theta: 1.0
max_vel_theta: 0.3
min_speed_xy: 0.0
min_speed_xy: 0.0
max_speed_xy: 0.26
max_speed_xy: 0.26
min_speed_theta: 0.0
min_speed_theta: 0.0
# Add high threshold velocity for turtlebot 3 issue.
# Add high threshold velocity for turtlebot 3 issue.
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
acc_lim_x: 2.5
acc_lim_x: 2.5
acc_lim_y: 0.0
acc_lim_y: 0.0
acc_lim_theta: 3.2
acc_lim_theta: 3.2
decel_lim_x: -2.5
decel_lim_x: -2.5
decel_lim_y: 0.0
decel_lim_y: 0.0
decel_lim_theta: -3.2
decel_lim_theta: -3.2
vx_samples: 20
vx_samples: 20
vy_samples: 5
vy_samples: 5
vtheta_samples: 20
vtheta_samples: 20
sim_time: 1.7
sim_time: 1.7
linear_granularity: 0.05
linear_granularity: 0.05
angular_granularity: 0.025
angular_granularity: 0.025
transform_tolerance: 0.2
transform_tolerance: 0.2
xy_goal_tolerance: 0.25
xy_goal_tolerance: 0.25
trans_stopped_velocity: 0.25
trans_stopped_velocity: 0.25
short_circuit_trajectory_evaluation: True
short_circuit_trajectory_evaluation: True
stateful: True
stateful: True
critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
critics:
[
"RotateToGoal",
"Oscillation",
"BaseObstacle",
"GoalAlign",
"PathAlign",
"PathDist",
"GoalDist",
]
BaseObstacle.scale: 0.02
BaseObstacle.scale: 0.02
PathAlign.scale: 32.0
PathAlign.scale: 32.0
PathAlign.forward_point_distance: 0.1
PathAlign.forward_point_distance: 0.1
GoalAlign.scale: 24.0
GoalAlign.scale: 24.0
GoalAlign.forward_point_distance: 0.1
GoalAlign.forward_point_distance: 0.1
PathDist.scale: 32.0
PathDist.scale: 32.0
GoalDist.scale: 24.0
GoalDist.scale: 24.0
RotateToGoal.scale: 32.0
RotateToGoal.scale: 32.0
RotateToGoal.slowing_factor: 5.0
RotateToGoal.slowing_factor: 5.0
RotateToGoal.lookahead_time: -1.0
RotateToGoal.lookahead_time: -1.0


controller_server_rclcpp_node:
controller_server_rclcpp_node:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False


local_costmap:
local_costmap:
local_costmap:
local_costmap:
ros__parameters:
ros__parameters:
update_frequency: 5.0
update_frequency: 5.0
publish_frequency: 2.0
publish_frequency: 2.0
global_frame: odom
global_frame: odom
robot_base_frame: base_link
robot_base_frame: base_link
use_sim_time: False
use_sim_time: False
rolling_window: true
rolling_window: true
width: 3
width: 3
height: 3
height: 3
resolution: 0.05
resolution: 0.05
robot_radius: 0.22
robot_radius: 0.22
plugins: ["voxel_layer", "inflation_layer"]
plugins: ["inflation_layer"]
inflation_layer:
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
cost_scaling_factor: 3.0
inflation_radius: 0.55
inflation_radius: 0.55
voxel_layer:
# voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
# plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
# enabled: False
publish_voxel_map: True
# publish_voxel_map: True
origin_z: 0.0
# origin_z: 0.0
z_resolution: 0.05
# z_resolution: 0.05
z_voxels: 16
# z_voxels: 16
max_obstacle_height: 2.0
# max_obstacle_height: 2.0
mark_threshold: 0
# mark_threshold: 0
observation_sources: scan
# observation_sources: scan
scan:
# scan:
topic: /scan
# topic: /scan
max_obstacle_height: 2.0
# max_obstacle_height: 2.0
clearing: True
# clearing: True
marking: True
# marking: True
data_type: "LaserScan"
# data_type: "LaserScan"
raytrace_max_range: 3.0
# raytrace_max_range: 3.0
raytrace_min_range: 0.0
# raytrace_min_range: 0.0
obstacle_max_range: 2.5
# obstacle_max_range: 2.5
obstacle_min_range: 0.0
# obstacle_min_range: 0.0
static_layer:
static_layer:
map_subscribe_transient_local: True
map_subscribe_transient_local: True
always_send_full_costmap: True
always_send_full_costmap: True
local_costmap_client:
local_costmap_client:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False
local_costmap_rclcpp_node:
local_costmap_rclcpp_node:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False


global_costmap:
global_costmap:
global_costmap:
global_costmap:
ros__parameters:
ros__parameters:
update_frequency: 1.0
update_frequency: 1.0
publish_frequency: 1.0
publish_frequency: 1.0
global_frame: map
global_frame: map
robot_base_frame: base_link
robot_base_frame: base_link
use_sim_time: False
use_sim_time: False
robot_radius: 0.22
robot_radius: 0.22
resolution: 0.05
resolution: 0.05
track_unknown_space: true
track_unknown_space: true
plugins: ["static_layer", "inflation_layer"]
plugins: ["static_layer", "inflation_layer"]
# obstacle_layer:
# obstacle_layer:
# plugin: "nav2_costmap_2d::ObstacleLayer"
# plugin: "nav2_costmap_2d::ObstacleLayer"
# enabled: False
# enabled: False
# observation_sources: scan
# observation_sources: scan
# scan:
# scan:
# topic: /scan
# topic: /scan
# max_obstacle_height: 2.0
# max_obstacle_height: 2.0
# clearing: True
# clearing: True
# marking: True
# marking: True
# data_type: "LaserScan"
# data_type: "LaserScan"
# raytrace_max_range: 3.0
# raytrace_max_range: 3.0
# raytrace_min_range: 0.0
# raytrace_min_range: 0.0
# obstacle_max_range: 2.5
# obstacle_max_range: 2.5
# obstacle_min_range: 0.0
# obstacle_min_range: 0.0
static_layer:
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
map_subscribe_transient_local: True
inflation_layer:
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
cost_scaling_factor: 3.0
inflation_radius: 0.55
inflation_radius: 0.55
always_send_full_costmap: True
always_send_full_costmap: True
global_costmap_client:
global_costmap_client:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False
global_costmap_rclcpp_node:
global_costmap_rclcpp_node:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False


map_server:
map_server:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False
yaml_filename: "turtlebot3_world.yaml"
yaml_filename: "turtlebot3_world.yaml"


map_saver:
map_saver:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False
save_map_timeout: 5.0
save_map_timeout: 5.0
free_thresh_default: 0.25
free_thresh_default: 0.25
occupied_thresh_default: 0.65
occupied_thresh_default: 0.65
map_subscribe_transient_local: True
map_subscribe_transient_local: True


planner_server:
planner_server:
ros__parameters:
ros__parameters:
expected_planner_frequency: 20.0
expected_planner_frequency: 20.0
use_sim_time: False
use_sim_time: False
planner_plugins: ["GridBased"]
planner_plugins: ["GridBased"]
GridBased:
GridBased:
plugin: "nav2_navfn_planner/NavfnPlanner"
plugin: "nav2_navfn_planner/NavfnPlanner"
tolerance: 0.5
tolerance: 0.5
use_astar: false
use_astar: false
allow_unknown: true
allow_unknown: true


planner_server_rclcpp_node:
planner_server_rclcpp_node:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False


smoother_server:
recoveries_server:
ros__parameters:
ros__parameters:
costmap_topic: local_costmap/costmap_raw
footprint_topic: local_costmap/published_footprint
cycle_frequency: 10.0
recovery_plugins: ["spin", "backup", "wait"]
spin:
plugin: "nav2_recoveries/Spin"
backup:
plugin: "nav2_recoveries/BackUp"
wait:
plugin: "nav2_recoveries/Wait"
global_frame: odom
robot_base_frame: base_link
transform_timeout: 0.1
use_sim_time: False
use_sim_time: False
smoother_plugins: ["simple_smoother"]
simulate_ahead_time: 2.0
simple_smoother:
max_rotational_vel: 1.0
plugin: "nav2_smoother::SimpleSmoother"
min_rotational_vel: 0.4
tolerance: 1.0e-10
rotational_acc_lim: 3.2
max_its: 1000
do_refinement: True


robot_state_publisher:
robot_state_publisher:
ros__parameters:
ros__parameters:
use_sim_time: False
use_sim_time: False


waypoint_follower:
waypoint_follower:
ros__parameters:
ros__parameters:
loop_rate: 20
loop_rate: 20
stop_on_failure: false
stop_on_failure: false
waypoint_task_executor_plugin: "wait_at_waypoint"
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
enabled: True
enabled: True
waypoint_pause_duration: 200
waypoint_pause_duration: 200