From 96a262a5f51f0f7db60a6cd40158a94d18c06cea Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Fri, 6 Oct 2023 07:35:14 +0200 Subject: [PATCH] update --- config/nav2_params.yaml | 153 ++++++++++++++++++++++++++-------------- 1 file changed, 100 insertions(+), 53 deletions(-) diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index 2dff178..27789c2 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -108,6 +108,76 @@ bt_navigator_navigate_to_pose_rclcpp_node: ros__parameters: use_sim_time: True +# 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 +# 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" +# debug_trajectory_details: True +# min_vel_x: -0.1 +# 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 +# # Add high threshold velocity for turtlebot 3 issue. +# # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75 +# 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", "ObstacleFootprint", "PreferForward"] +# 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 controller_server: ros__parameters: use_sim_time: True @@ -115,69 +185,46 @@ controller_server: min_x_velocity_threshold: 0.001 min_y_velocity_threshold: 0.5 min_theta_velocity_threshold: 0.001 - failure_tolerance: 0.3 - progress_checker_plugin: "progress_checker" - goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker" + progress_checker_plugins: ["progress_checker"] # progress_checker_plugin: "progress_checker" For Humble and older + goal_checker_plugins: ["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 + goal_checker: plugin: "nav2_controller::SimpleGoalChecker" xy_goal_tolerance: 0.25 yaw_goal_tolerance: 0.25 - # DWB parameters - FollowPath: - plugin: "dwb_core::DWBLocalPlanner" - debug_trajectory_details: True - min_vel_x: -0.1 - 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 - # Add high threshold velocity for turtlebot 3 issue. - # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75 - 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", "ObstacleFootprint", "PreferForward"] - 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 + 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 + use_interpolation: false + local_costmap: local_costmap: