f110_planning.metrics package¶
Submodules¶
f110_planning.metrics.aggregator module¶
Aggregator that orchestrates multiple metric callbacks and prints a summary.
- class f110_planning.metrics.aggregator.MetricAggregator(callbacks: list[BaseMetric])¶
Bases:
objectManages a collection of
BaseMetricinstances, delegating lifecycle calls and producing a unified summary report.Example usage:
metrics = MetricAggregator.create_default(waypoints=wpts) metrics.on_reset(obs, waypoints=wpts) while not done: action = planner.plan(obs) obs, reward, term, trunc, _ = env.step(...) metrics.on_step(obs, action, reward) metrics.report() # prints table and returns merged dict
- classmethod create_default(waypoints: ndarray | None = None) MetricAggregator¶
Build an aggregator with all available metrics.
Waypoint-dependent metrics (cross-track error, heading error) are included only when waypoints is provided and non-empty.
- Parameters:
waypoints – Reference path
(N, 2+), orNone.- Returns:
A fully-configured
MetricAggregator.
- property metric_count: int¶
Return the number of registered metric callbacks.
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Forward
on_resetto every registered metric.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Forward
on_stepto every registered metric.
- report() dict[str, float]¶
Collect statistics from all metrics, print a formatted summary table, and return the merged dictionary.
f110_planning.metrics.base module¶
Base class for evaluation metric callbacks.
- class f110_planning.metrics.base.BaseMetric¶
Bases:
ABCAbstract base class for simulation evaluation metrics.
- Metric callbacks follow a lifecycle:
on_reset()— called once at the start of each episode.on_step()— called after everyenv.step().report()— called at episode end to compute summary statistics.
Subclasses must implement all three methods plus the
nameproperty.- abstract property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- abstractmethod on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- abstractmethod on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- abstractmethod report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
f110_planning.metrics.cross_track_error module¶
Cross-track (lateral deviation) error metric.
- class f110_planning.metrics.cross_track_error.CrossTrackErrorMetric¶
Bases:
BaseMetricMeasures how far the vehicle deviates from a reference path.
Uses
nearest_point()to compute the perpendicular distance from the car position to the closest segment of the waypoint trajectory at every simulation step.Requires
waypointsto be passed viaon_reset().- property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- f110_planning.metrics.cross_track_error.crosstrack_error(pos: ndarray, waypoints: ndarray) float¶
Return the perpendicular distance from pos to the nearest segment of waypoints.
- Parameters:
pos –
(2,)array[x, y]of the vehicle position.waypoints –
(N, 2+)array of reference waypoints. Only the first two columns (x, y) are used.
- Returns:
Non-negative lateral distance in metres.
f110_planning.metrics.heading_error module¶
Heading (orientation) error metric.
- class f110_planning.metrics.heading_error.HeadingErrorMetric¶
Bases:
BaseMetricMeasures the angular deviation between the car’s heading and the local path tangent.
Uses
get_heading_error()fromf110_planning.utilswhich returns a signed heading error in radians. Summary statistics are reported in degrees for readability.Requires
waypointspassed viaon_reset().- property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- f110_planning.metrics.heading_error.heading_error_rad(pos: ndarray, theta: float, waypoints: ndarray) float¶
Return the signed heading error (vehicle vs. local path tangent) in radians.
- Parameters:
pos –
(2,)array[x, y]of the vehicle position.theta – Vehicle heading in radians (from simulator
poses_theta).waypoints –
(N, 2+)reference waypoints.
- Returns:
Signed heading error in radians. Use
abs()for magnitude.
f110_planning.metrics.lap_time module¶
Lap time and completion metric.
- class f110_planning.metrics.lap_time.LapTimeMetric¶
Bases:
BaseMetricTracks simulated lap time, collision status, and lap completion.
Lap time is accumulated from the per-step reward (which equals
env.timestep, typically 0.01 s).- property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- f110_planning.metrics.lap_time.has_collision(obs: dict[str, Any], ego_idx: int = 0) bool¶
Return
Trueif the ego vehicle has collided according to the observation.- Parameters:
obs – Observation dictionary from
F110Env.step().ego_idx – Index of the ego vehicle.
- Returns:
Truewhenobs["collisions"][ego_idx] > 0.
f110_planning.metrics.smoothness module¶
Steering smoothness metric.
- class f110_planning.metrics.smoothness.SmoothnessMetric¶
Bases:
BaseMetricEvaluates control smoothness by analysing steering rate of change.
The steering rate is
|Δsteer / Δt|between consecutive steps. High values indicate jerky, oscillatory control which is undesirable both for passenger comfort and tyre wear.- property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- f110_planning.metrics.smoothness.steering_rate(prev_steer: float, curr_steer: float, dt: float) float¶
Return the absolute steering rate
|Δsteer / dt|in rad/s.Returns
0.0when dt ≤ 0 (degenerate / first step) or when prev_steer isNone.- Parameters:
prev_steer – Steering angle (rad) applied at the previous step.
curr_steer – Steering angle (rad) applied at the current step.
dt – Elapsed time between steps in seconds (== simulator timestep, typically 0.01 s).
- Returns:
Absolute steering rate in rad/s.
f110_planning.metrics.speed module¶
Speed profile metric.
- class f110_planning.metrics.speed.SpeedMetric¶
Bases:
BaseMetricRecords the vehicle’s actual longitudinal speed throughout an episode.
Uses
obs["linear_vels_x"](measured speed, not commanded) so that the statistics reflect real vehicle dynamics including slip and acceleration limits.- property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- f110_planning.metrics.speed.current_speed(obs: dict[str, Any], ego_idx: int = 0) float¶
Return the longitudinal speed of the ego vehicle from an observation.
- Parameters:
obs – Observation dictionary produced by
F110Env.step()/F110Env.reset().ego_idx – Index of the ego vehicle in multi-agent observations.
- Returns:
Longitudinal speed in m/s (
obs["linear_vels_x"][ego_idx]).
f110_planning.metrics.wall_proximity module¶
Wall proximity (safety) metric.
- class f110_planning.metrics.wall_proximity.WallProximityMetric¶
Bases:
BaseMetricTracks how close the vehicle comes to walls during an episode.
At every step the minimum of left and right wall distances (from LiDAR) is recorded. The global minimum over the episode answers “how close did we get to crashing?” while the mean captures overall centering quality.
- property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- f110_planning.metrics.wall_proximity.min_wall_dist(scan: ndarray) float¶
Return the minimum of the left and right wall distances from a LiDAR scan.
- Parameters:
scan –
(num_beams,)LiDAR range scan for a single agent.- Returns:
Minimum side-clearance in metres.
Module contents¶
Evaluation metrics for the F1TENTH simulation.
This package exposes both the stateful BaseMetric callback classes
(which accumulate per-step statistics) and the pure, stateless computation
functions they delegate to.
- class f110_planning.metrics.BaseMetric¶
Bases:
ABCAbstract base class for simulation evaluation metrics.
- Metric callbacks follow a lifecycle:
on_reset()— called once at the start of each episode.on_step()— called after everyenv.step().report()— called at episode end to compute summary statistics.
Subclasses must implement all three methods plus the
nameproperty.- abstract property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- abstractmethod on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- abstractmethod on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- abstractmethod report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- class f110_planning.metrics.CrossTrackErrorMetric¶
Bases:
BaseMetricMeasures how far the vehicle deviates from a reference path.
Uses
nearest_point()to compute the perpendicular distance from the car position to the closest segment of the waypoint trajectory at every simulation step.Requires
waypointsto be passed viaon_reset().- property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- class f110_planning.metrics.HeadingErrorMetric¶
Bases:
BaseMetricMeasures the angular deviation between the car’s heading and the local path tangent.
Uses
get_heading_error()fromf110_planning.utilswhich returns a signed heading error in radians. Summary statistics are reported in degrees for readability.Requires
waypointspassed viaon_reset().- property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- class f110_planning.metrics.LapTimeMetric¶
Bases:
BaseMetricTracks simulated lap time, collision status, and lap completion.
Lap time is accumulated from the per-step reward (which equals
env.timestep, typically 0.01 s).- property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- class f110_planning.metrics.MetricAggregator(callbacks: list[BaseMetric])¶
Bases:
objectManages a collection of
BaseMetricinstances, delegating lifecycle calls and producing a unified summary report.Example usage:
metrics = MetricAggregator.create_default(waypoints=wpts) metrics.on_reset(obs, waypoints=wpts) while not done: action = planner.plan(obs) obs, reward, term, trunc, _ = env.step(...) metrics.on_step(obs, action, reward) metrics.report() # prints table and returns merged dict
- classmethod create_default(waypoints: ndarray | None = None) MetricAggregator¶
Build an aggregator with all available metrics.
Waypoint-dependent metrics (cross-track error, heading error) are included only when waypoints is provided and non-empty.
- Parameters:
waypoints – Reference path
(N, 2+), orNone.- Returns:
A fully-configured
MetricAggregator.
- property metric_count: int¶
Return the number of registered metric callbacks.
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Forward
on_resetto every registered metric.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Forward
on_stepto every registered metric.
- report() dict[str, float]¶
Collect statistics from all metrics, print a formatted summary table, and return the merged dictionary.
- class f110_planning.metrics.SmoothnessMetric¶
Bases:
BaseMetricEvaluates control smoothness by analysing steering rate of change.
The steering rate is
|Δsteer / Δt|between consecutive steps. High values indicate jerky, oscillatory control which is undesirable both for passenger comfort and tyre wear.- property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- class f110_planning.metrics.SpeedMetric¶
Bases:
BaseMetricRecords the vehicle’s actual longitudinal speed throughout an episode.
Uses
obs["linear_vels_x"](measured speed, not commanded) so that the statistics reflect real vehicle dynamics including slip and acceleration limits.- property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- class f110_planning.metrics.WallProximityMetric¶
Bases:
BaseMetricTracks how close the vehicle comes to walls during an episode.
At every step the minimum of left and right wall distances (from LiDAR) is recorded. The global minimum over the episode answers “how close did we get to crashing?” while the mean captures overall centering quality.
- property name: str¶
Human-readable identifier for the metric (e.g. ‘Lap Time’).
- on_reset(obs: dict[str, Any], waypoints: ndarray | None = None) None¶
Initialise / clear internal state at the start of an episode.
- Parameters:
obs – Initial observation dictionary from
env.reset().waypoints – Reference path
(N, 2+)if available, elseNone.
- on_step(obs: dict[str, Any], action: Action, reward: float, ego_idx: int = 0) None¶
Accumulate data from a single simulation step.
- Parameters:
obs – Observation dictionary returned by
env.step().action – The
Actionapplied during this step.reward – Scalar reward (equal to
env.timestep, typically 0.01 s).ego_idx – Index of the ego vehicle in multi-agent observations.
- report() dict[str, float]¶
Compute and return summary statistics for the episode.
- Returns:
A dictionary mapping human-readable stat names to float values.
- f110_planning.metrics.crosstrack_error(pos: ndarray, waypoints: ndarray) float¶
Return the perpendicular distance from pos to the nearest segment of waypoints.
- Parameters:
pos –
(2,)array[x, y]of the vehicle position.waypoints –
(N, 2+)array of reference waypoints. Only the first two columns (x, y) are used.
- Returns:
Non-negative lateral distance in metres.
- f110_planning.metrics.current_speed(obs: dict[str, Any], ego_idx: int = 0) float¶
Return the longitudinal speed of the ego vehicle from an observation.
- Parameters:
obs – Observation dictionary produced by
F110Env.step()/F110Env.reset().ego_idx – Index of the ego vehicle in multi-agent observations.
- Returns:
Longitudinal speed in m/s (
obs["linear_vels_x"][ego_idx]).
- f110_planning.metrics.has_collision(obs: dict[str, Any], ego_idx: int = 0) bool¶
Return
Trueif the ego vehicle has collided according to the observation.- Parameters:
obs – Observation dictionary from
F110Env.step().ego_idx – Index of the ego vehicle.
- Returns:
Truewhenobs["collisions"][ego_idx] > 0.
- f110_planning.metrics.heading_error_rad(pos: ndarray, theta: float, waypoints: ndarray) float¶
Return the signed heading error (vehicle vs. local path tangent) in radians.
- Parameters:
pos –
(2,)array[x, y]of the vehicle position.theta – Vehicle heading in radians (from simulator
poses_theta).waypoints –
(N, 2+)reference waypoints.
- Returns:
Signed heading error in radians. Use
abs()for magnitude.
- f110_planning.metrics.min_wall_dist(scan: ndarray) float¶
Return the minimum of the left and right wall distances from a LiDAR scan.
- Parameters:
scan –
(num_beams,)LiDAR range scan for a single agent.- Returns:
Minimum side-clearance in metres.
- f110_planning.metrics.steering_rate(prev_steer: float, curr_steer: float, dt: float) float¶
Return the absolute steering rate
|Δsteer / dt|in rad/s.Returns
0.0when dt ≤ 0 (degenerate / first step) or when prev_steer isNone.- Parameters:
prev_steer – Steering angle (rad) applied at the previous step.
curr_steer – Steering angle (rad) applied at the current step.
dt – Elapsed time between steps in seconds (== simulator timestep, typically 0.01 s).
- Returns:
Absolute steering rate in rad/s.