Configuration
All local path planner parameters are configured in the all_settings
package. This page explains available settings and tuning guidance.
Settings Structure
The local planner uses LocalOptSettings
from all_settings/all_settings/all_settings.py
:
class LocalOptSettings(metaclass=Settings):
"""Settings for local path planning"""
N: int = 10
solver: str = 'ipopt'
solver_opts: Dict = {...}
car_params: dict = {'l_r': 1.58/2, 'l_f': 1.58/2, 'm': 1.}
bbox: dict = {'l': 2.7, 'w': 1.6}
DF_MAX: float = 0.5
ACC_MIN: float = -4.5
ACC_MAX_FN: Union[float, Function] = 2.5
DF_DOT_MAX: float = 1.0
V_MIN: float = 0.0
V_MAX: float = 10.0
FRIC_MAX: Union[float, Function] = 7.0
write_to_file: bool = False
save_to_gif: bool = False
use_history: bool = False
filtering_method: int = 0
distance_cone_order: bool = True
Optimization Parameters
N (Number of Waypoints)
Type: int
Default: 10
Description: Number of waypoints in the optimized trajectory.
Impact:
Larger N: Longer lookahead distance, smoother paths, but slower solve times
Smaller N: Shorter horizon, faster computation, but more myopic planning
Tuning guidance:
N=10 provides ~10-20m lookahead (depends on track spacing)
Increase if paths are too aggressive or jerky
Decrease if solver times exceed 200ms consistently
Typical range: 8-15 waypoints
solver
Type: str
Default: 'ipopt'
Options: 'ipopt'
, 'worhp'
, 'snopt'
Description: Which NLP solver to use.
Note: IPOPT is the standard choice. Other solvers require additional licenses/installations.
solver_opts
Type: Dict
Default:
{
'ipopt.linear_solver': 'ma57',
'expand': True,
'ipopt.print_level': 0,
'ipopt.sb': 'yes',
'ipopt.ma57_automatic_scaling': 'no',
'print_time': 0,
}
Description: Options passed to the IPOPT solver.
Key options:
ipopt.linear_solver
: Which linear solver to use (ma27, ma57, ma86, ma97, mumps)expand
: Expand MX to SX expressions (typically faster)ipopt.print_level
: Verbosity (0 = silent, 5 = debug)acceptable_tol
: Convergence tolerance (default 1e-2)acceptable_obj_change_tol
: Stop when objective changes < this (default 1e-3)
Vehicle Parameters
car_params
Type: dict
Default: {'l_r': 0.79, 'l_f': 0.79, 'm': 1.0}
Description: Vehicle parameters for bicycle dynamics model.
l_r
: Distance from CG to rear axle (meters)l_f
: Distance from CG to front axle (meters)m
: Vehicle mass (kg, currently unused but reserved for future dynamics)
Tuning guidance: Measure from physical vehicle. Total wheelbase = l_r + l_f = 1.58m for 2025 car.
bbox
Type: dict
Default: {'l': 2.7, 'w': 1.6}
Description: Bounding box of the vehicle (length × width in meters).
Note: Currently not actively used in collision avoidance (cone constraints are disabled), but reserved for future use.
Constraint Limits
DF_MAX
Type: float
Default: 0.5
radians (±28.6°)
Description: Maximum steering angle.
Tuning guidance: Set based on physical steering limits. Include safety margin to prevent mechanical damage.
ACC_MIN
Type: float
Default: -4.5
m/s²
Description: Maximum braking acceleration (negative value).
Tuning guidance:
Depends on tire grip and brake performance
Conservative: -3.0 m/s²
Aggressive: -5.0 to -7.0 m/s² (requires good tires and braking system)
ACC_MAX_FN
Type: float
or Function
Default: 2.5
m/s²
Description: Maximum forward acceleration. Can be a constant or a function of velocity to model motor torque curves.
As constant:
ACC_MAX_FN = 2.5 # Constant acceleration limit
As function:
v = SX.sym('v')
ACC_MAX_FN = Function('acc_max', [v], [
if_else(v < 5.0, 4.0, 2.5 - 0.1*(v-5)) # Decreases with speed
])
DF_DOT_MAX
Type: float
Default: 1.0
rad/s
Description: Maximum steering rate (how fast steering angle can change).
Tuning guidance:
Limited by steering actuator speed
Slower rates = smoother steering but slower response
Faster rates = quicker response but potential instability
Test empirically: increase until oscillations appear, then reduce 20-30%
V_MIN and V_MAX
Type: float
Default: V_MIN = 0.0
, V_MAX = 10.0
m/s
Description: Velocity bounds.
Tuning guidance:
V_MIN = 0 prevents reverse driving
V_MAX sets top speed for safety
Can reduce V_MAX during testing or on tight tracks
FRIC_MAX
Type: float
or Function
Default: 7.0
m/s² (~0.7g)
Description: Maximum combined acceleration (friction circle radius).
As constant:
FRIC_MAX = 7.0 # Constant friction limit
As function (velocity-dependent for aero/downforce):
v = SX.sym('v')
FRIC_MAX = Function('fric_max', [v], [
7.0 + 0.05*v**2 # Increases with speed due to downforce
])
Tuning guidance:
Depends on tire compound, track surface, and downforce
Conservative: 6.0 m/s² (~0.6g)
Moderate: 7-8 m/s² (~0.7-0.8g)
Aggressive: 9-12 m/s² (~0.9-1.2g, requires excellent tires/aero)
Cone Ordering Configuration
distance_cone_order
Type: bool
Default: True
Description: Use distance-based greedy nearest-neighbor cone ordering algorithm.
Options:
True
: Use distance-based ordering (recommended for 2025 competition)False
: Use alternative ordering algorithm (funny_cone_ordering
, not fully validated)
Tuning guidance: Keep as True
unless specifically testing the alternative algorithm.
Debugging and Visualization
write_to_file
Type: bool
Default: False
Description: Write path planning results to file for offline analysis.
Note: Not actively used in current implementation.
save_to_gif
Type: bool
Default: False
Description: Save cone ordering visualization frames to GIF for debugging.
Usage:
save_to_gif: bool = True
Generates local_cone_ordering.gif
showing cone ordering evolution.
Warning: Significantly slows down the planner. Use only for debugging.
use_history
Type: bool
Default: False
Description: Use cone history tracking for improved ordering consistency.
Note: Experimental feature, not thoroughly tested.
filtering_method
Type: int
Default: 0
Description: Which cone filtering method to use (if any).
Note: Currently not actively used. Reserved for future filtering strategies.
ROS Topics
Subscribed Topics:
Topic |
Type |
Description |
---|---|---|
|
feb_msgs/Map |
Local cone observations from SLAM |
|
feb_msgs/Map |
Global map (triggers planner shutdown) |
|
feb_msgs/State |
Current vehicle state |
|
std_msgs/Bool |
Signal from other nodes that path is complete |
Published Topics:
Topic |
Type |
Description |
---|---|---|
|
feb_msgs/FebPath |
Optimized local trajectory |
|
sensor_msgs/PointCloud |
Path visualization (waypoints as points) |
|
nav_msgs/Path |
Path visualization (full poses) |
|
visualization_msgs/Marker |
Cone pairing visualization (red lines) |
Example Configurations
Conservative (Testing)
N = 8 # Shorter horizon
V_MAX = 5.0 # Reduced speed
ACC_MAX_FN = 1.5 # Gentle acceleration
FRIC_MAX = 5.0 # Conservative cornering
DF_DOT_MAX = 0.5 # Slow steering
Balanced (Typical Racing)
N = 10 # Standard horizon
V_MAX = 10.0 # Moderate speed
ACC_MAX_FN = 2.5 # Balanced acceleration
FRIC_MAX = 7.0 # Good tire grip
DF_DOT_MAX = 1.0 # Quick steering response
Aggressive (Competition)
N = 12 # Longer lookahead
V_MAX = 12.0 # High speed
ACC_MAX_FN = 3.0 # Strong acceleration
FRIC_MAX = 9.0 # High grip tires
DF_DOT_MAX = 1.5 # Fast steering
Tight/Technical Track
N = 10 # Standard horizon
V_MAX = 8.0 # Lower speed for corners
ACC_MAX_FN = 2.0 # Moderate power
FRIC_MAX = 8.0 # Need good cornering
DF_DOT_MAX = 1.2 # Quick direction changes