update 28/2
This commit is contained in:
@@ -1,4 +1,3 @@
|
||||
|
||||
LocalPlannerAdapter:
|
||||
library_path: liblocal_planner_adapter
|
||||
yaw_goal_tolerance: 0.017
|
||||
@@ -77,7 +76,7 @@ MKTAlgorithmDiffPredictiveTrajectory:
|
||||
library_path: libmkt_algorithm_diff
|
||||
avoid_obstacles: false
|
||||
xy_local_goal_tolerance: 0.01
|
||||
angle_threshold: 0.6
|
||||
angle_threshold: 0.4
|
||||
index_samples: 60
|
||||
follow_step_path: true
|
||||
|
||||
@@ -88,9 +87,10 @@ MKTAlgorithmDiffPredictiveTrajectory:
|
||||
# only when true:
|
||||
min_lookahead_dist: 0.6 # The minimum lookahead distance (m) threshold. (default: 0.3)
|
||||
max_lookahead_dist: 2.0 # The maximum lookahead distance (m) threshold. (default: 0.9)
|
||||
lookahead_time: 1.6 # The time (s) to project the velocity by, a.k.a. lookahead gain. (default: 1.5)
|
||||
lookahead_time: 1.9 # The time (s) to project the velocity by, a.k.a. lookahead gain. (default: 1.5)
|
||||
min_journey_squared: 0.3 # Minimum squared journey to consider for goal (default: 0.2)
|
||||
max_journey_squared: 0.8 # Maximum squared journey to consider for goal (default: 0.2)
|
||||
max_lateral_accel: 2.0 # Max lateral accel for speed reduction on curves (m/s^2)
|
||||
|
||||
# Rotate to heading param - onle one of use_rotate_to_heading and allow_reversing can be set to true
|
||||
use_rotate_to_heading: true # Whether to enable rotating to rough heading and goal orientation when using holonomic planners. Recommended on for all robot types that can rotate in place. (default: true)
|
||||
@@ -141,9 +141,9 @@ MKTAlgorithmDiffGoStraight:
|
||||
# only when false:
|
||||
lookahead_dist: 0.5 # The lookahead distance (m) to use to find the lookahead point. (default: 0.6)
|
||||
# only when true:
|
||||
min_lookahead_dist: 1.0 # The minimum lookahead distance (m) threshold. (default: 0.3)
|
||||
min_lookahead_dist: 0.325 # The minimum lookahead distance (m) threshold. (default: 0.3)
|
||||
max_lookahead_dist: 1.5 # The maximum lookahead distance (m) threshold. (default: 0.9)
|
||||
lookahead_time: 2.5 # The time (s) to project the velocity by, a.k.a. lookahead gain. (default: 1.5)
|
||||
lookahead_time: 1.9 # The time (s) to project the velocity by, a.k.a. lookahead gain. (default: 1.5)
|
||||
min_journey_squared: 0.3 # Minimum squared journey to consider for goal (default: 0.2)
|
||||
max_journey_squared: 0.6 # Minimum squared journey to consider for goal (default: 0.2)
|
||||
|
||||
|
||||
Reference in New Issue
Block a user