f110_planning package¶
Subpackages¶
- f110_planning.metrics package
- Submodules
- f110_planning.metrics.aggregator module
- f110_planning.metrics.base module
- f110_planning.metrics.cross_track_error module
- f110_planning.metrics.heading_error module
- f110_planning.metrics.lap_time module
- f110_planning.metrics.smoothness module
- f110_planning.metrics.speed module
- f110_planning.metrics.wall_proximity module
- Module contents
- f110_planning.misc package
- f110_planning.reactive package
- Submodules
- f110_planning.reactive.bubble_planner module
- f110_planning.reactive.disparity_extender_planner module
- f110_planning.reactive.dynamic_waypoint_planner module
- f110_planning.reactive.edge_cloud_planner module
- f110_planning.reactive.gap_follower_planner module
- f110_planning.reactive.lidar_dnn_planner module
- Module contents
- f110_planning.render_callbacks package
- f110_planning.schedulers package
- f110_planning.tracking package
- f110_planning.utils package
- Submodules
- f110_planning.utils.constants module
- f110_planning.utils.geometry_utils module
- f110_planning.utils.lidar_utils module
- f110_planning.utils.lqr_utils module
- f110_planning.utils.nn_models module
- f110_planning.utils.pure_pursuit_utils module
- f110_planning.utils.reactive_utils module
- f110_planning.utils.sim_utils module
- f110_planning.utils.tracking_utils module
- f110_planning.utils.waypoint_utils module
- Module contents
Module contents¶
F1TENTH Planning library.
- class f110_planning.Action(steer: float, speed: float)¶
Bases:
NamedTupleRepresents the control action for a vehicle.
- steer¶
Steering angle in radians.
- Type:
float
- speed¶
Requested longitudinal speed in meters per second.
- Type:
float
- speed: float¶
Alias for field number 1
- steer: float¶
Alias for field number 0
- class f110_planning.BasePlanner¶
Bases:
ABCAbstract base class for all vehicle planners.
- abstractmethod plan(obs: dict[str, Any], ego_idx: int = 0) Action¶
Computes the next control action based on the observation.
- Parameters:
obs – A dictionary containing simulation observations.
ego_idx – The index of the agent being controlled.
- Returns:
The computed steering and speed commands.
- Return type:
- class f110_planning.BubblePlanner(safety_radius: float = 1.3, avoidance_speed: float = 2.0)¶
Bases:
BasePlannerA reactive planner that creates a ‘bubble’ around the car and avoids obstacles.
- class f110_planning.CloudScheduler¶
Bases:
ABCDecides when to issue a cloud inference request.
Subclass this to implement arbitrary scheduling policies – fixed interval, adaptive, learned (RL), etc. The
EdgeCloudPlannercallsshould_call_cloud()once per simulation step.- abstractmethod should_call_cloud(step: int, obs: dict[str, Any], latest_cloud_action: Action | None) bool¶
Return
Trueto issue a cloud request on this step.- Parameters:
step – The current simulation step (0-based).
obs – The current observation dict.
latest_cloud_action – The most recent cloud action received (
Noneif no cloud result has arrived yet).
- Returns:
Whether to send a new cloud inference request.
- class f110_planning.DisparityExtenderPlanner¶
Bases:
BasePlannerReactive planner that uses the disparity extension algorithm to avoid obstacles.
- get_index(angle: float) int¶
Returns the index in the LIDAR samples corresponding to the given angle in radians.
- class f110_planning.DummyPlanner¶
Bases:
BasePlannerA dummy planner that always returns a constant action.
- class f110_planning.DynamicWaypointPlanner(waypoints: ndarray, lookahead_distance: float = 1.0, max_speed: float = 5.0, wheelbase: float = 0.33, lateral_gain: float = 1.0)¶
Bases:
BasePlannerAdaptive Dynamic waypoint following planner for F1TENTH
This planner creates an imaginary waypoint ahead of the car at each timestep, positioned to simultaneously: 1. Center the car between left and right walls (Reactive centering) 2. Align the car’s heading with the track direction (Heading alignment)
The lookahead distance and target speed are adjusted adaptively based on the car’s current velocity and the local track curvature. By continuously tracking this dynamically computed waypoint, the planner achieves behavior similar to Pure Pursuit on actual raceline waypoints without needing a pre-planned global path.
- Parameters:
waypoints (np.ndarray) – Reference waypoints for heading error computation
lookahead_distance (float, default=1.0) – Tuning gain for adaptive lookahead. Scaling this increases/decreases the speed-based lookahead window.
max_speed (float, default=5.0) – Maximum speed on straight sections. Planner will automatically decelerate for turns and centering maneuvers.
wheelbase (float, default=0.33) – Vehicle wheelbase for steering computation.
lateral_gain (float, default=1.0) – Multiplier for lateral centering aggressiveness.
- class f110_planning.EdgeCloudPlanner(cloud_latency: int = 10, alpha_steer: float = 0.7, alpha_speed: float = 0.7, scheduler: CloudScheduler | None = None, lookahead_distance: float = 1.0, max_speed: float = 5.0, lateral_gain: float = 1.0, edge_left_wall_model_path: str | None = None, edge_track_width_model_path: str | None = None, edge_heading_model_path: str | None = None, cloud_left_wall_model_path: str | None = None, cloud_track_width_model_path: str | None = None, cloud_heading_model_path: str | None = None)¶
Bases:
BasePlannerHybrid edge-cloud reactive planner.
- Parameters:
cloud_latency (int) – Round-trip latency in simulation steps for cloud inference. A cloud request issued at step t yields a result that becomes available at step t + cloud_latency.
scheduler (Optional[CloudScheduler]) – scheduler object that decides whether to issue a cloud request at each step. Defaults to
FixedIntervalScheduler(interval=1)(calls cloud every step).alpha_steer (float) – Blending weight for steering (0 = edge only, 1 = cloud only).
alpha_speed (float) – Blending weight for speed (0 = edge only, 1 = cloud only).
Note
The remaining keyword arguments configure the two underlying
LidarDNNPlannerinstances.edge_*prefixed arguments are forwarded to the edge planner andcloud_*prefixed arguments to the cloud planner.lookahead_distance,max_speed, andlateral_gainare shared by both unless overridden per-planner.Three separate single-output model files are required per planner:
*_left_wall_model_path(left wall distance),*_track_width_model_path(track width = left + right), and*_heading_model_path(heading error). Right wall distance is derived at inference time astrack_width - left_dist.- plan(obs: dict[str, Any], ego_idx: int = 0) Action¶
Compute the fused edge-cloud action for the current observation.
Call this once per simulation step. Internally it:
Uses the scheduler to decide whether to issue a cloud request.
Checks whether any in-flight cloud response has arrived.
Runs the edge planner on the current observation.
Returns either the pure edge action (if no cloud result yet) or the weighted blend of cloud and edge.
- reset() None¶
Reset internal step counter and in-flight cloud requests.
- class f110_planning.FixedIntervalScheduler(interval: int = 10)¶
Bases:
CloudSchedulerCalls the cloud every interval steps.
- Parameters:
interval (int) – Number of steps between successive cloud requests.
- should_call_cloud(step: int, obs: dict[str, Any], latest_cloud_action: Action | None) bool¶
Return
Trueto issue a cloud request on this step.- Parameters:
step – The current simulation step (0-based).
obs – The current observation dict.
latest_cloud_action – The most recent cloud action received (
Noneif no cloud result has arrived yet).
- Returns:
Whether to send a new cloud inference request.
- class f110_planning.FlippyPlanner(flip_every: int = 1, steer: float = 2, speed: float = 1)¶
Bases:
BasePlannerPlanner designed to exploit integration methods and dynamics. For testing only. To observe this error, use single track dynamics for all velocities >0.1
- class f110_planning.GapFollowerPlanner(bubble_radius: int = 160, corners_speed: float = 4.0, straights_speed: float = 6.0, straights_steering_angle: float = 0.17453292519943295, preprocess_conv_size: int = 3, best_point_conv_size: int = 80, max_lidar_dist: float = 10.0)¶
Bases:
BasePlannerReactive planner that steers toward the largest contiguous gap in LiDAR scans.
The “Follow the Gap” (FGM) algorithm works by: 1. Preprocessing the scan to ignore the area behind the vehicle. 2. Placing a “virtual bubble” around the closest obstacle to avoid collisions. 3. Identifying the largest sequence of obstacle-free beams (the gap). 4. Navigating toward the deepest point within that gap.
- plan(obs: dict[str, Any], ego_idx: int = 0) Action¶
Computes the next steering and speed action based on the ‘Follow the Gap’ logic.
- preprocess_lidar(ranges: ndarray) tuple[ndarray, int, int]¶
Slices the LiDAR scan to the front hemisphere and applies smoothing.
- class f110_planning.HybridPlanner(manual_planner: ManualPlanner, auto_planner: BasePlanner)¶
Bases:
BasePlannerArbitrator that delegates control based on human input.
The Hybrid Planner monitors the keyboard state. If any movement keys (‘W’, ‘A’, ‘S’, ‘D’) are active, it hands over control to the human operator. Otherwise, it defaults to the provided autonomous planner.
- class f110_planning.LQRPlanner(wheelbase: float = 0.33, waypoints: ndarray | None = None, max_speed: float = 5.0, timestep: float = 0.01, matrix_q_1: float = 0.999, matrix_q_2: float = 0.0, matrix_q_3: float = 0.0066, matrix_q_4: float = 0.0, matrix_r: float = 0.75, iterations: int = 50, eps: float = 0.001)¶
Bases:
BasePlannerLateral Controller using Linear Quadratic Regulator (LQR).
This planner linearizes the vehicle dynamics around a reference path and solves for an optimal gain matrix K that minimizes a cost function representing both tracking error and control effort.
- calc_control_points(vehicle_state: ndarray, waypoints: ndarray) tuple[float, float, float, float, float]¶
Calculates the current state errors and reference curvature.
- controller(vehicle_state: ndarray) tuple[float, float]¶
Optimal lateral control calculation.
This discrete-time LQR implementation computes steering based on a 4-state error vector: [crosstrack, lateral_velocity, heading, heading_rate].
- class f110_planning.LidarDNNPlanner(left_model_path: str | None = None, track_width_model_path: str | None = None, heading_model_path: str | None = None, lookahead_distance: float = 1.0, max_speed: float = 5.0, lateral_gain: float = 1.0)¶
Bases:
BasePlannerReactive planner that uses PyTorch models to predict control features from LiDAR.
This planner mimics the behavior of the DynamicWaypointPlanner, but instead of using geometric calculations on the map/scan, it uses neural networks to predict wall distances and orientation errors directly from raw sensor data.
- plan(obs: dict[str, Any], ego_idx: int = 0) Action¶
Computes the next control action based on the observation.
- Parameters:
obs – A dictionary containing simulation observations.
ego_idx – The index of the agent being controlled.
- Returns:
The computed steering and speed commands.
- Return type:
- predict(model: Module | None, scan: ndarray) Any¶
Performs a forward pass through the provided model using normalized scan data.
Returns a scalar float, or
Noneif model isNone.
- class f110_planning.ManualPlanner(s_min: float = -0.4189, s_max: float = 0.4189, v_min: float = -5.0, v_max: float = 20.0, accel: float = 8.0, decel: float = 15.0, steer_rate: float = 1.5, dt: float = 0.01)¶
Bases:
BasePlannerKeyboard-based control interface with simplified vehicle dynamics.
This planner allows a human operator to control the vehicle using ‘WASD’ or Arrow keys. It simulates realistic steering and acceleration rates by integrating inputs over the simulation timestep.
- class f110_planning.PurePursuitPlanner(wheelbase: float = 0.33, lookahead_distance: float = 0.8, max_speed: float = 5.0, waypoints: ndarray | None = None)¶
Bases:
BasePlannerGeometrically-inspired waypoint tracking controller.
Pure Pursuit calculates the curvature required to move the vehicle from its current position to a point on the reference path that is one ‘lookahead’ distance away.
Reference: Coulter, R. Craig. “Implementation of the Pure Pursuit Path Tracking Algorithm.” Carnegie Mellon University, 1992.
- class f110_planning.RandomPlanner(s_min: float = -0.4189, s_max: float = 0.4189, v_min: float = 0.5, v_max: float = 5.0)¶
Bases:
BasePlannerExperimental planner that yields stochastic control actions.
Used primarily for environment stress-testing and data diversity generation.
- class f110_planning.StanleyPlanner(wheelbase: float = 0.33, waypoints: ndarray | None = None, max_speed: float = 5.0, k_path: float = 5.0)¶
Bases:
BasePlannerFront Wheel Feedback Controller (Stanley) for path tracking.
The Stanley controller combines heading alignment and cross-track error compensation (from the perspective of the front axle) into a single steering law.
Reference: Thrun et al, “Stanley: The Robot that Won the DARPA Grand Challenge”, 2005.
- calc_theta_and_ef(vehicle_state: ndarray, waypoints: ndarray) tuple[float, float, int, float]¶
Computes the current tracking errors relative to the front axle hub.
- controller(vehicle_state: ndarray, waypoints: ndarray, k_path: float) tuple[float, float]¶
Computes steering and speed using the Stanley control law.
The steering angle delta is defined as: delta(t) = theta_e(t) + arctan((k * e(t)) / v(t))