SeReST Controller Fine-Tuningο
This guide explains how to tune the SeReST (Safe Reparameterized Time) controller to track discrete paths (e.g., A* polylines) precisely, slow down smoothly near goals, and behave safely around dynamic obstacles.
It includes grouped parameters, recommended defaults, and practical βif you see X, change Yβ advice.
Overviewο
The SeReST controller is a real-time trajectory follower used in EasyNav. It blends path tracking, safety constraints, and curvature-aware motion limits into a single reactive control loop.
You will typically find it configured in:
controller_node:
ros__parameters:
controller_types: [serest]
serest:
plugin: easynav_serest_controller/SerestController
rt_freq: 30.0
β
Quick-Start Defaultsο
Start with these default parameters (adjust namespace as needed):
serest_controller:
ros__parameters:
# motion policy
v_ref: 0.6
max_linear_speed: 0.6
max_angular_speed: 1.5
max_linear_acc: 0.8
max_angular_acc: 2.0
allow_reverse: false
# tracking gains
k_theta: 2.0
k_y: 1.2
k_s: 0.8
ell: 0.3
# safety governor
a_brake: 1.2
a_lat_max: 1.5
d0_margin: 0.20
tau_latency: 0.10
d_hard: 0.15
t_emerg: 0.25
# local heading smoothing
blend_base: 0.6
blend_k_per_v: 0.6
kappa_max: 2.5
# progress robustness
v_progress_min: 0.05
k_s_share_max: 0.5
# goal behavior
goal_pos_tol: 0.07
goal_yaw_tol_deg: 6.0
slow_radius: 0.60
slow_min_speed: 0.03
final_align_k: 2.0
final_align_wmax: 0.6
# corner guard (tight turns)
corner_guard_enable: true
a_lat_soft: 1.1
corner_gain_ey: 1.5
corner_gain_eth: 0.7
corner_gain_kappa: 0.4
corner_min_alpha: 0.35
corner_boost_omega: 0.8
apex_ey_des: 0.05
β
Core Conceptsο
Tracking controller: keeps the robot close to the reference path using heading and lateral-error feedback (
k_theta,k_y,ell) plus a small longitudinal βsuctionβ term (k_s).Safety governor: dynamically re-parameterizes time, reducing forward progress when approaching obstacles or when curvature demands lower speeds.
Local heading smoothing: blends headings around corners to remove discontinuities while preserving the geometric path.
Goal behavior: decelerates within a configurable radius, aligning to the final yaw precisely.
Corner guard: limits lateral acceleration and boosts yaw authority to prevent drifting wide on tight turns.
β
Parameter-by-Parameter Guidanceο
Tracking Gainsο
``k_theta`` (1.5β3.0; default 2.0) Heading stiffness. β if turns feel sluggish; β if oscillating.
``k_y`` (0.8β2.0; default 1.2) Lateral correction authority. β if robot cuts corners; β if wobbly.
``ell`` (0.25β0.5 m; default 0.3) Lateral lookahead. β to reduce twitchiness; β for faster convergence.
``k_s`` (0.4β1.2; default 0.8) Longitudinal suction. β if drifting along the segment; β if resisting motion.
Motion Limits & Referenceο
``v_ref`` (0.4β0.8 m/s) β Desired cruise speed.
``max_linear_speed`` / ``max_angular_speed`` β Respect hardware limits.
``max_linear_acc`` / ``max_angular_acc`` β β if sluggish; β if slipping.
Progress Robustnessο
``v_progress_min`` (0.03β0.10) β Minimum forward motion; prevents stalls.
``k_s_share_max`` (0.3β0.7) β Caps suction influence; β if stalling, β if overshooting laterally.
Safety Governorο
``a_brake`` (1.0β2.0) β Deceleration limit for safe stopping.
``a_lat_max`` (1.2β2.5) β Max lateral acceleration for curvature limits.
``d0_margin`` (0.15β0.30) β Safety margin; β for larger robots or noisy sensors.
``tau_latency`` (0.08β0.15 s) β Compensates sensor/control delay.
``d_hard`` / ``t_emerg`` β Emergency stop thresholds; β/β to adjust conservatism.
Local Heading Smoothingο
``blend_base`` (0.4β0.9) β Base length for corner blending.
``blend_k_per_v`` (0.4β0.9) β Extra smoothing proportional to velocity.
``kappa_max`` (2.0β3.5) β Curvature cap for feed-forward yawing.
Goal Behaviorο
``slow_radius`` (0.5β1.0 m) β Begin slowing within this range.
``goal_pos_tol`` (0.05β0.10 m) β Position tolerance for success.
``goal_yaw_tol_deg`` (4β10Β°) β Final yaw tolerance.
``slow_min_speed`` (0.02β0.05) β Maintains slow progress.
``final_align_k`` / ``final_align_wmax`` β Tune final rotation precision.
Corner Guardο
``corner_guard_enable`` (bool) β Enables corner control logic.
``a_lat_soft`` (0.9β1.4) β Corner-specific accel cap; β if drifting, β if braking too much.
``corner_gain_ey`` (1.0β2.0) β Penalizes outside drift.
``corner_gain_eth`` (0.5β1.0) β Penalizes heading error in turns.
``corner_gain_kappa`` (0.3β0.7) β Penalizes curvature magnitude.
``corner_min_alpha`` (0.3β0.5) β Minimum speed scaling in corners.
``corner_boost_omega`` (0.6β1.0) β Yaw boost when outside curve.
``apex_ey_des`` (0.03β0.08) β Small inward bias to stay centered at apex.
β
Troubleshooting by Symptomο
Robot βmoonwalksβ (tries to go backward)ο
Set allow_reverse: false (default).
If it still pulls backward, reduce k_s and increase v_progress_min.
Stalls near corners or from standstillο
Increase v_progress_min and/or k_s_share_max.
Increase blend_base for smoother heading transitions.
Oscillates near goalο
Increase slow_radius or goal_pos_tol.
Lower slow_min_speed; reduce final_align_k or final_align_wmax if overshooting.
Cuts corners or rides outsideο
Enable corner guard. Decrease a_lat_soft.
Increase corner_gain_ey and/or corner_boost_omega.
If still wide, raise blend_base or reduce v_ref.
Overreacts laterally (βnervousβ)ο
Increase ell; reduce k_y.
If only in corners, lower corner_boost_omega.
Feels sluggish to turnο
Increase k_theta.
Verify max_angular_speed and max_angular_acc are not too low.
Reduce corner_gain_eth or corner_gain_kappa if over-limiting.
Emergency stops too oftenο
Reduce conservatism: increase t_emerg, reduce d_hard or d0_margin.
Only do this if sensing latency is well-characterized.
Obstacle distance seems too pessimisticο
Lower lethal_cost_threshold (if available) or reduce dist_search_radius.
Consider publishing measured closest_obstacle_distance in NavState.
β
Recommended Tuning Orderο
Set kinematics: choose safe
max_*andv_refvalues.Tune tracking: adjust
k_theta,k_y,ellfor stable path following.Verify safety: confirm emergency stop triggers correctly.
Optimize corners: tune
blend_*,a_lat_soft, and corner gains.Smooth goal arrival: adjust
slow_radiusandfinal_align_*.Ensure progress: tweak
v_progress_minandk_s_share_maxif stalling occurs.
β
FAQο
Q: Can I enable reverse motion?
A: Yes. Set allow_reverse: true. Tune goal and slow behavior carefully to prevent unwanted reversals.
Q: My path is jaggedβwhat should I do?
A: Increase blend_base and/or blend_k_per_v. Reduce kappa_max and v_ref slightly.
Q: How aggressive should ``a_lat_soft`` be? A: For indoor robots with good traction, 1.0β1.4 m/sΒ² works well. On slippery or uneven surfaces, use 0.8β1.0 m/sΒ² for safety.