|
@@ -68,11 +68,11 @@ controller_server:
|
|
|
goal_checker:
|
|
|
plugin: "nav2_controller::SimpleGoalChecker"
|
|
|
xy_goal_tolerance: 1.0
|
|
|
- yaw_goal_tolerance: 0.1
|
|
|
+ yaw_goal_tolerance: 0.2
|
|
|
stateful: True
|
|
|
FollowPath:
|
|
|
plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
|
|
|
- desired_linear_vel: 0.7
|
|
|
+ desired_linear_vel: 0.8
|
|
|
lookahead_dist: 1.0
|
|
|
min_lookahead_dist: 0.3
|
|
|
max_lookahead_dist: 2.0
|
|
@@ -80,17 +80,17 @@ controller_server:
|
|
|
rotate_to_heading_angular_vel: 0.2
|
|
|
transform_tolerance: 0.01
|
|
|
use_velocity_scaled_lookahead_dist: false
|
|
|
- min_approach_linear_velocity: 0.05
|
|
|
+ min_approach_linear_velocity: 0.2
|
|
|
use_approach_linear_velocity_scaling: true
|
|
|
approach_velocity_scaling_dist: 3.5
|
|
|
max_allowed_time_to_collision_up_to_carrot: 1.0
|
|
|
use_regulated_linear_velocity_scaling: true
|
|
|
use_cost_regulated_linear_velocity_scaling: true
|
|
|
- regulated_linear_scaling_min_radius: 5.6
|
|
|
- regulated_linear_scaling_min_speed: 0.20
|
|
|
+ regulated_linear_scaling_min_radius: 4.2
|
|
|
+ regulated_linear_scaling_min_speed: 0.50
|
|
|
use_rotate_to_heading: false
|
|
|
rotate_to_heading_min_angle: 0.785
|
|
|
- max_angular_accel: 3.2
|
|
|
+ max_angular_accel: 1.2
|
|
|
max_robot_pose_search_dist: 10.0
|
|
|
use_interpolation: false
|
|
|
cost_scaling_dist: 0.3
|
|
@@ -212,7 +212,7 @@ planner_server:
|
|
|
angle_quantization_bins: 64 # For Hybrid nodes: Number of angle bins for search, must be 1 for 2D node (no angle search)
|
|
|
analytic_expansion_ratio: 3.5 # For Hybrid/Lattice nodes: 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 (in meters). This should be scaled with minimum turning radius and be no less than 4-5x the minimum radius
|
|
|
- minimum_turning_radius: 4.3 # For Hybrid/Lattice nodes: minimum turning radius in m of path / vehicle
|
|
|
+ minimum_turning_radius: 3.6 # For Hybrid/Lattice nodes: minimum turning radius in m of path / vehicle
|
|
|
reverse_penalty: 2.1 # For Reeds-Shepp model: penalty to apply if motion is reversing, must be => 1
|
|
|
change_penalty: 0.0 # For Hybrid nodes: penalty to apply if motion is changing directions, must be >= 0
|
|
|
non_straight_penalty: 2.30 # For Hybrid nodes: penalty to apply if motion is non-straight, must be => 1
|
|
@@ -277,3 +277,17 @@ waypoint_follower:
|
|
|
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
|
|
|
enabled: True
|
|
|
waypoint_pause_duration: 200
|
|
|
+
|
|
|
+velocity_smoother:
|
|
|
+ ros__parameters:
|
|
|
+ smoothing_frequency: 20.0
|
|
|
+ scale_velocities: false
|
|
|
+ feedback: "OPEN_LOOP"
|
|
|
+ max_velocity: [1.0, 0.0, 2.5]
|
|
|
+ min_velocity: [-0.5, 0.0, -2.5]
|
|
|
+ deadband_velocity: [0.0, 0.0, 0.0]
|
|
|
+ velocity_timeout: 1.0
|
|
|
+ max_accel: [2.5, 0.0, 3.2]
|
|
|
+ max_decel: [-2.5, 0.0, -3.2]
|
|
|
+ odom_topic: "odom"
|
|
|
+ odom_duration: 0.1
|