This commit is contained in:
Björn Ellensohn 2023-09-08 10:36:05 +02:00
parent a06bdbc18c
commit 5b1f07ecec

View File

@ -364,9 +364,58 @@ bt_navigator_navigate_to_pose_rclcpp_node:
# # twirling_cost_power: 1 # # twirling_cost_power: 1
# # twirling_cost_weight: 10.0 # # twirling_cost_weight: 10.0
# try rpp controller # # try rpp controller
# controller_server:
# ros__parameters:
# use_sim_time: False
# 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.8 # was 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.4 # was 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: false # set to false because can't be set together with allow_reversing
# allow_reversing: true
# rotate_to_heading_min_angle: 0.785
# max_angular_accel: 1.2
# max_robot_pose_search_dist: 10.0
# use_interpolation: true
# try DWB controller
controller_server: controller_server:
ros__parameters: ros__parameters:
# controller server parameters (see Controller Server for more info)
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
@ -375,7 +424,6 @@ controller_server:
progress_checker_plugins: ["progress_checker"] # progress_checker_plugin: "progress_checker" For Humble and older progress_checker_plugins: ["progress_checker"] # progress_checker_plugin: "progress_checker" For Humble and older
goal_checker_plugins: ["goal_checker"] goal_checker_plugins: ["goal_checker"]
controller_plugins: ["FollowPath"] controller_plugins: ["FollowPath"]
progress_checker: progress_checker:
plugin: "nav2_controller::SimpleProgressChecker" plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5 required_movement_radius: 0.5
@ -385,32 +433,46 @@ controller_server:
xy_goal_tolerance: 0.25 xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25 yaw_goal_tolerance: 0.25
stateful: True stateful: True
# DWB controller parameters
FollowPath: FollowPath:
plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController" plugin: "dwb_core::DWBLocalPlanner"
desired_linear_vel: 0.8 # was 0.5 debug_trajectory_details: True
lookahead_dist: 0.6 min_vel_x: 0.0
min_lookahead_dist: 0.3 min_vel_y: 0.0
max_lookahead_dist: 0.9 max_vel_x: 0.26
lookahead_time: 1.5 max_vel_y: 0.0
rotate_to_heading_angular_vel: 0.4 # was 0.8 max_vel_theta: 1.0
transform_tolerance: 0.1 min_speed_xy: 0.0
use_velocity_scaled_lookahead_dist: false max_speed_xy: 0.26
min_approach_linear_velocity: 0.05 min_speed_theta: 0.0
approach_velocity_scaling_dist: 0.6 acc_lim_x: 2.5
use_collision_detection: true acc_lim_y: 0.0
max_allowed_time_to_collision_up_to_carrot: 1.0 acc_lim_theta: 3.2
use_regulated_linear_velocity_scaling: true decel_lim_x: -2.5
use_fixed_curvature_lookahead: false decel_lim_y: 0.0
curvature_lookahead_dist: 0.25 decel_lim_theta: -3.2
use_cost_regulated_linear_velocity_scaling: false vx_samples: 20
regulated_linear_scaling_min_radius: 0.9 vy_samples: 5
regulated_linear_scaling_min_speed: 0.25 vtheta_samples: 20
use_rotate_to_heading: false # set to false because can't be set together with allow_reversing sim_time: 1.7
allow_reversing: true linear_granularity: 0.05
rotate_to_heading_min_angle: 0.785 angular_granularity: 0.025
max_angular_accel: 1.2 transform_tolerance: 0.2
max_robot_pose_search_dist: 10.0 xy_goal_tolerance: 0.25
use_interpolation: true 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
local_costmap: local_costmap:
local_costmap: local_costmap: