f110_planning.reactive package

Submodules

f110_planning.reactive.bubble_planner module

Bubble planner for obstacle avoidance.

Logic: Local Repulsion. Mechanism: This planner identifies the single closest obstacle within a defined ‘safety_radius’ from the LiDAR scan. It then calculates a steering angle that points directly away from that obstacle (opposite direction).

class f110_planning.reactive.bubble_planner.BubblePlanner(safety_radius: float = 1.3, avoidance_speed: float = 2.0)

Bases: BasePlanner

A reactive planner that creates a ‘bubble’ around the car and avoids obstacles.

plan(obs: dict[str, Any], ego_idx: int = 0) Action

Plans by moving away from the closest obstacle within the safety radius.

f110_planning.reactive.bubble_planner.detect_obstacles_jit(lidar_data: ndarray, radius: float) ndarray

JIT-optimized obstacle detection.

f110_planning.reactive.disparity_extender_planner module

Disparity extender planner module.

Logic: Obstacle Inflation. Mechanism: 1. Searches for ‘disparities’—sudden jumps in distance between adjacent LiDAR beams. 2. ‘Blooms’ (extends) the nearer side of that disparity by the car’s width to mask out corners. 3. Picks the furthest remaining point in the masked scan to steer towards.

class f110_planning.reactive.disparity_extender_planner.DisparityExtenderPlanner

Bases: BasePlanner

Reactive 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.

plan(obs: dict[str, Any], ego_idx: int = 0) Action

Processes LIDAR data and returns a steering angle and velocity.

f110_planning.reactive.disparity_extender_planner.extend_disparities_jit(values: ndarray, disparities: ndarray, car_width: float, samples_per_radian: float) tuple[ndarray, ndarray]

JIT-optimized disparity extension.

f110_planning.reactive.disparity_extender_planner.find_disparities_jit(values: ndarray, threshold: float) ndarray

JIT-optimized disparity finding.

f110_planning.reactive.disparity_extender_planner.find_new_angle_jit(limited_values: ndarray, min_considered_angle: float, samples_per_radian: float) tuple[float, float]

JIT-optimized best angle finding.

f110_planning.reactive.dynamic_waypoint_planner module

Dynamic Waypoint Planner

This planner dynamically computes an imaginary waypoint at each step based on: - Left and right wall distances (for lateral centering) - Heading error angle (for angular alignment) The car follows this continuously updated waypoint to stay centered and aligned.

class f110_planning.reactive.dynamic_waypoint_planner.DynamicWaypointPlanner(waypoints: ndarray, lookahead_distance: float = 1.0, max_speed: float = 5.0, wheelbase: float = 0.33, lateral_gain: float = 1.0)

Bases: BasePlanner

Adaptive 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.

plan(obs: dict[str, Any], ego_idx: int = 0) Action

Plan action by computing dynamic waypoint from sensor data.

Parameters:
  • obs (dict) – Observation dictionary containing scans and poses

  • ego_idx (int) – Index of ego vehicle

Returns:

Steering angle and speed command

Return type:

Action

f110_planning.reactive.edge_cloud_planner module

Edge-Cloud hybrid DNN planner for F1TENTH.

Wraps two LidarDNNPlanner instances – a lightweight edge model called every time-step and a heavier cloud model whose result arrives with a configurable latency of N simulation steps. The two actions are blended with independent weights for steering and speed.

class f110_planning.reactive.edge_cloud_planner.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: BasePlanner

Hybrid 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 LidarDNNPlanner instances. edge_* prefixed arguments are forwarded to the edge planner and cloud_* prefixed arguments to the cloud planner. lookahead_distance, max_speed, and lateral_gain are 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 as track_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:

  1. Uses the scheduler to decide whether to issue a cloud request.

  2. Checks whether any in-flight cloud response has arrived.

  3. Runs the edge planner on the current observation.

  4. 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.

f110_planning.reactive.gap_follower_planner module

Gap Follower Planner (FGM) for F1TENTH.

Logic: Contiguous Free Space. Mechanism: 1. Finds the closest obstacle and sets a ‘bubble’ of nearby LiDAR beams to zero. 2. Identifies the largest contiguous sequence (the ‘gap’) of non-zero LiDAR beams. 3. Finds the ‘best point’ (midpoint or furthest point) within that gap and steers towards it.

class f110_planning.reactive.gap_follower_planner.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: BasePlanner

Reactive 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.

f110_planning.reactive.gap_follower_planner.find_best_point_jit(start_i: int, end_i: int, ranges: ndarray, best_point_conv_size: int) int

Finds the deepest point within a gap using a sliding window average.

Parameters:
  • start_i – Start index of the gap.

  • end_i – End index of the gap.

  • ranges – Original LiDAR ranges.

  • best_point_conv_size – Size of the smoothing window.

Returns:

The index of the chosen target point.

f110_planning.reactive.gap_follower_planner.find_max_gap_jit(free_space_ranges: ndarray) tuple[int, int]

Identifies the largest contiguous sequence of non-zero values in a scan.

Parameters:

free_space_ranges – Array of LiDAR ranges where obstacles have been masked.

Returns:

A tuple of (start_index, end_index) for the largest gap.

f110_planning.reactive.lidar_dnn_planner module

PyTorch-based DNN planner for F1TENTH. Uses trained models to predict wall distances and heading errors for navigation.

class f110_planning.reactive.lidar_dnn_planner.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: BasePlanner

Reactive 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:

Action

predict(model: Module | None, scan: ndarray) Any

Performs a forward pass through the provided model using normalized scan data.

Returns a scalar float, or None if model is None.

Module contents

Reactive planners for F1TENTH.

class f110_planning.reactive.BubblePlanner(safety_radius: float = 1.3, avoidance_speed: float = 2.0)

Bases: BasePlanner

A reactive planner that creates a ‘bubble’ around the car and avoids obstacles.

plan(obs: dict[str, Any], ego_idx: int = 0) Action

Plans by moving away from the closest obstacle within the safety radius.

class f110_planning.reactive.DisparityExtenderPlanner

Bases: BasePlanner

Reactive 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.

plan(obs: dict[str, Any], ego_idx: int = 0) Action

Processes LIDAR data and returns a steering angle and velocity.

class f110_planning.reactive.DynamicWaypointPlanner(waypoints: ndarray, lookahead_distance: float = 1.0, max_speed: float = 5.0, wheelbase: float = 0.33, lateral_gain: float = 1.0)

Bases: BasePlanner

Adaptive 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.

plan(obs: dict[str, Any], ego_idx: int = 0) Action

Plan action by computing dynamic waypoint from sensor data.

Parameters:
  • obs (dict) – Observation dictionary containing scans and poses

  • ego_idx (int) – Index of ego vehicle

Returns:

Steering angle and speed command

Return type:

Action

class f110_planning.reactive.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: BasePlanner

Hybrid 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 LidarDNNPlanner instances. edge_* prefixed arguments are forwarded to the edge planner and cloud_* prefixed arguments to the cloud planner. lookahead_distance, max_speed, and lateral_gain are 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 as track_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:

  1. Uses the scheduler to decide whether to issue a cloud request.

  2. Checks whether any in-flight cloud response has arrived.

  3. Runs the edge planner on the current observation.

  4. 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.reactive.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: BasePlanner

Reactive 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.reactive.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: BasePlanner

Reactive 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:

Action

predict(model: Module | None, scan: ndarray) Any

Performs a forward pass through the provided model using normalized scan data.

Returns a scalar float, or None if model is None.