update 2/2

This commit is contained in:
2026-02-02 14:02:25 +07:00
parent 1fa6af01fd
commit 15f842d703
13 changed files with 788 additions and 520 deletions

View File

@@ -1,12 +1,12 @@
### replanning
controller_frequency: 20.0 # run controller at 15.0 Hz
controller_frequency: 30.0 # run controller at 15.0 Hz
controller_patience: 0.0 # if the controller failed, clear obstacles and retry; after 15.0 s, abort and replan
planner_frequency: 0.0 # don't continually replan (only when controller failed)
planner_patience: 5.0 # if the first planning attempt failed, abort planning retries after 5.0 s...
planner_patience: 2.0 # if the first planning attempt failed, abort planning retries after 5.0 s...
max_planning_retries: 5 # ... or after 10 attempts (whichever happens first)
oscillation_timeout: -1 # abort controller and trigger recovery behaviors after 30.0 s
oscillation_distance: 0.4
oscillation_distance: 0.5
### recovery behaviors
recovery_behavior_enabled: true
recovery_behaviors: [

View File

@@ -1,6 +1,6 @@
yaw_goal_tolerance: 0.017
xy_goal_tolerance: 0.03
min_approach_linear_velocity: 0.06
xy_goal_tolerance: 0.02
min_approach_linear_velocity: 0.05
LocalPlannerAdapter:
library_path: liblocal_planner_adapter
@@ -48,14 +48,14 @@ LimitedAccelGenerator:
min_vel_y: 0.0 # diff drive robot
max_speed_xy: 2.0 # max_trans_vel: 0.8 # choose slightly less than the base's capability
min_speed_xy: 0.1 # min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity
min_speed_xy: 0.25 # min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity
max_vel_theta: 0.9 # max_rot_vel: 1.0 # choose slightly less than the base's capability
min_vel_theta: 0.04 # min_rot_vel: 0.1 default: 0.4 # this is the min angular velocity when there is negligible translational velocity
max_vel_theta: 0.7 # max_rot_vel: 1.0 # choose slightly less than the base's capability
min_vel_theta: 0.07 # min_rot_vel: 0.1 default: 0.4 # this is the min angular velocity when there is negligible translational velocity
acc_lim_x: 1.0
acc_lim_y: 0.0 # diff drive robot
acc_lim_theta: 0.9
acc_lim_theta: 1.5
decel_lim_x: -1.0
decel_lim_y: -0.0
decel_lim_theta: -1.5
@@ -75,8 +75,8 @@ LimitedAccelGenerator:
MKTAlgorithmDiffPredictiveTrajectory:
library_path: libmkt_algorithm_diff
avoid_obstacles: false
xy_local_goal_tolerance: 0.01
angle_threshold: 0.6
xy_local_goal_tolerance: 0.02
angle_threshold: 0.47
index_samples: 60
follow_step_path: true
@@ -85,12 +85,12 @@ MKTAlgorithmDiffPredictiveTrajectory:
# 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: 0.5 # The minimum lookahead distance (m) threshold. (default: 0.3)
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.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)
min_journey_squared: 0.2 # 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)
max_lateral_accel: 0.9 # 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)
@@ -100,7 +100,7 @@ MKTAlgorithmDiffPredictiveTrajectory:
# stoped
rot_stopped_velocity: 0.05
trans_stopped_velocity: 0.03
trans_stopped_velocity: 0.06
# Regulated linear velocity scaling
use_regulated_linear_velocity_scaling: false # Whether to use the regulated features for path curvature (e.g. slow on high curvature paths). (default: true)
@@ -114,20 +114,6 @@ MKTAlgorithmDiffPredictiveTrajectory:
cost_scaling_dist: 0.2 # (default: 0.6)
cost_scaling_gain: 2.0 # (default: 1.0)
use_mpc: true
mpc_horizon: 10
mpc_dt: 0.1
mpc_w_pos: 6.0
mpc_w_theta: 2.0
mpc_w_v: 0.2
mpc_w_w: 0.2
mpc_w_dv: 0.4
mpc_w_dw: 0.4
mpc_iterations: 3
mpc_step: 0.15
mpc_eps: 0.001
MKTAlgorithmDiffGoStraight:
library_path: libmkt_algorithm_diff
avoid_obstacles: false