f110_gym.envs package

Submodules

f110_gym.envs.cloud_scheduler_env module

Gymnasium environment for learning cloud scheduling policies.

This wrapper creates an underlying f110_gym:f110-v0 environment along with an EdgeCloudPlanner whose RLScheduler is controlled by the RL agent. The action space is simply Discrete(2) (0=no cloud, 1=call cloud) and the observation dictionary mirrors the underlying F110 observation with two extra entries describing the planner state.

A customizable reward function may be passed; by default the environment returns the negative squared cross-track error for the ego vehicle (as that is closely related to the RMSE objective). Users can override the reward to any other signal that depends on the observation and chosen scheduling action.

class f110_gym.envs.cloud_scheduler_env.CloudSchedulerEnv(*, map: str, waypoints: ndarray, cloud_latency: int = 10, alpha_steer: float = 0.7, alpha_speed: float = 0.7, 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, reward_fn: Callable[[dict[str, Any], int], float] | None = None, cloud_cost: float = 0.1, cloud_cost_window: int = 100, **env_kwargs: Any)

Bases: Env

Gym environment that exposes cloud scheduling as the action.

The environment forwards low-level control decisions to an internal EdgeCloudPlanner and returns the usual simulator observations. The agent is responsible for toggling the scheduler on each step.

close() None

After the user has finished using the environment, close contains the code necessary to “clean up” the environment.

This is critical for closing rendering windows, database or HTTP connections. Calling close on an already closed environment has no effect and won’t raise an error.

metadata = {'render_fps': 200, 'render_modes': ['human', 'human_fast']}
render() None

Compute the render frames as specified by render_mode during the initialization of the environment.

The environment’s metadata render modes (env.metadata[“render_modes”]) should contain the possible ways to implement the render modes. In addition, list versions for most render modes is achieved through gymnasium.make which automatically applies a wrapper to collect rendered frames.

Note

As the render_mode is known during __init__, the objects used to render the environment state should be initialised in __init__.

By convention, if the render_mode is:

  • None (default): no render is computed.

  • “human”: The environment is continuously rendered in the current display or terminal, usually for human consumption. This rendering should occur during step() and render() doesn’t need to be called. Returns None.

  • “rgb_array”: Return a single frame representing the current state of the environment. A frame is a np.ndarray with shape (x, y, 3) representing RGB values for an x-by-y pixel image.

  • “ansi”: Return a strings (str) or StringIO.StringIO containing a terminal-style text representation for each time step. The text can include newlines and ANSI escape sequences (e.g. for colors).

  • “rgb_array_list” and “ansi_list”: List based version of render modes are possible (except Human) through the wrapper, gymnasium.wrappers.RenderCollection that is automatically applied during gymnasium.make(..., render_mode="rgb_array_list"). The frames collected are popped after render() is called or reset().

Note

Make sure that your class’s metadata "render_modes" key includes the list of supported modes.

Changed in version 0.25.0: The render function was changed to no longer accept parameters, rather these parameters should be specified in the environment initialised, i.e., gymnasium.make("CartPole-v1", render_mode="human")

reset(*, seed: int | None = None, options: dict | None = None)

Resets the environment to an initial internal state, returning an initial observation and info.

This method generates a new starting state often with some randomness to ensure that the agent explores the state space and learns a generalised policy about the environment. This randomness can be controlled with the seed parameter otherwise if the environment already has a random number generator and reset() is called with seed=None, the RNG is not reset.

Therefore, reset() should (in the typical use case) be called with a seed right after initialization and then never again.

For Custom environments, the first line of reset() should be super().reset(seed=seed) which implements the seeding correctly.

Changed in version v0.25: The return_info parameter was removed and now info is expected to be returned.

Parameters:
  • seed (optional int) – The seed that is used to initialize the environment’s PRNG (np_random) and the read-only attribute np_random_seed. If the environment does not already have a PRNG and seed=None (the default option) is passed, a seed will be chosen from some source of entropy (e.g. timestamp or /dev/urandom). However, if the environment already has a PRNG and seed=None is passed, the PRNG will not be reset and the env’s np_random_seed will not be altered. If you pass an integer, the PRNG will be reset even if it already exists. Usually, you want to pass an integer right after the environment has been initialized and then never again. Please refer to the minimal example above to see this paradigm in action.

  • options (optional dict) – Additional information to specify how the environment is reset (optional, depending on the specific environment)

Returns:

Observation of the initial state. This will be an element of observation_space

(typically a numpy array) and is analogous to the observation returned by step().

info (dictionary): This dictionary contains auxiliary information complementing observation. It should be analogous to

the info returned by step().

Return type:

observation (ObsType)

step(action: int)

Apply a scheduling action and advance the environment by one step.

Parameters:

action (int) – scheduling decision; 1 triggers a cloud call on this step, 0 uses the cached cloud result.

Returns:

(obs, reward, terminated, truncated, info) following the

Gymnasium convention. obs is the augmented observation dict (including latest_cloud_action, cloud_request_pending, and crosstrack_dist). info contains the keys forwarded from the underlying f110-v0 environment plus latest_cloud_action, cloud_request_pending, and step.

Return type:

tuple

f110_gym.envs.collision_models module

Prototype of Utility functions and GJK algorithm for Collision checks between vehicles Originally from https://github.com/kroitor/gjk.c Author: Hongrui Zheng

f110_gym.envs.collision_models.collision(vertices1: ndarray, vertices2: ndarray) bool

GJK test to see whether two bodies overlap

Parameters:
  • vertices1 (np.ndarray, (n, 2)) – vertices of the first body

  • vertices2 (np.ndarray, (n, 2)) – vertices of the second body

Returns:

True if two bodies collide

Return type:

overlap (boolean)

f110_gym.envs.collision_models.collision_multiple(vertices) tuple[ndarray, ndarray]

Check pair-wise collisions for all provided vertices

Parameters:

vertices (np.ndarray (num_bodies, 4, 2)) – all vertices for checking pair-wise collision

Returns:

whether each body is in collision collision_idx (np.ndarray (num_vertices, )): index of the colliding body, -1 if none

Return type:

collisions (np.ndarray (num_vertices, ))

f110_gym.envs.collision_models.get_all_vertices(poses: ndarray, length: float, width: float) ndarray

Utility function to return vertices of all cars given poses and size

Parameters:
  • poses (np.ndarray, (num_agents, 3)) – current world coordinate poses of the vehicles

  • length (float) – car length

  • width (float) – car width

Returns:

corner vertices of all vehicle bodies

Return type:

all_vertices (np.ndarray, (num_agents, 4, 2))

f110_gym.envs.collision_models.get_trmtx(pose: ndarray) ndarray

Get transformation matrix of vehicle frame -> global frame

Parameters:

pose (np.ndarray (3, )) – current pose of the vehicle

Returns:

transformation matrix

Return type:

H (np.ndarray (4, 4))

f110_gym.envs.collision_models.get_vertices(pose: ndarray, length: float, width: float) ndarray

Utility function to return vertices of the car body given pose and size

Parameters:
  • pose (np.ndarray, (3, )) – current world coordinate pose of the vehicle

  • length (float) – car length

  • width (float) – car width

Returns:

corner vertices of the vehicle body

Return type:

vertices (np.ndarray, (4, 2))

f110_gym.envs.collision_models.idx_furthest_pt(vertices, d) int

Return the index of the vertex furthest away along a direction in the list of vertices

Parameters:

vertices (np.ndarray, (n, 2)) – the vertices we want to find avg on

Returns:

index of the furthest point

Return type:

idx (int)

f110_gym.envs.collision_models.perpendicular(pt: ndarray) ndarray

Return a 2-vector’s perpendicular vector

Parameters:

pt (np.ndarray, (2,)) – input vector

Returns:

perpendicular vector

Return type:

pt (np.ndarray, (2,))

f110_gym.envs.collision_models.support(vertices1: ndarray, vertices2: ndarray, d: ndarray) ndarray

Minkowski sum support function for GJK

Parameters:
  • vertices1 (np.ndarray, (n, 2)) – vertices of the first body

  • vertices2 (np.ndarray, (n, 2)) – vertices of the second body

  • d (np.ndarray, (2, )) – direction to find the support along

Returns:

Minkowski sum

Return type:

support (np.ndarray, (n, 2))

f110_gym.envs.collision_models.triple_product(a: ndarray, b: ndarray, c: ndarray) ndarray

Return triple product of three vectors

Parameters:
  • a (np.ndarray, (2,)) – input vectors

  • b (np.ndarray, (2,)) – input vectors

  • c (np.ndarray, (2,)) – input vectors

Returns:

triple product

Return type:

(np.ndarray, (2,))

f110_gym.envs.defaults module

Global physical constants and default configuration for the F1TENTH vehicle.

This file is the single auditable source of truth for: - Physical constants used in dynamic-model calculations (e.g. gravity). - Default vehicle parameter values for the F1TENTH 1:10 scale race car. - Vehicle geometry used across the gym (dynamics, collision, rendering).

References for the F1TENTH car parameters:

https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/ https://f1tenth.org/build.html

f110_gym.envs.defaults.CAR_LENGTH: float = 0.58

Overall vehicle length [m].

f110_gym.envs.defaults.CAR_WIDTH: float = 0.31

Overall vehicle width [m].

f110_gym.envs.defaults.DEFAULT_VEHICLE_PARAMS: dict = {'C_Sf': 4.718, 'C_Sr': 5.4562, 'I': 0.04712, 'a_max': 9.51, 'h': 0.074, 'length': 0.58, 'lf': 0.15875, 'lr': 0.17145, 'm': 3.74, 'mu': 1.0489, 's_max': 0.4189, 's_min': -0.4189, 'sv_max': 3.2, 'sv_min': -3.2, 'v_max': 20.0, 'v_min': -5.0, 'v_switch': 7.319, 'width': 0.31}

10 scale car.

Type:

Default dynamics parameter set for the F1TENTH 1

f110_gym.envs.defaults.GRAVITY: float = 9.81

Gravitational acceleration [m/s²].

f110_gym.envs.dynamic_models module

Prototype of vehicle dynamics functions and classes for simulating 2D Single Track dynamic model Following the implementation of commanroad’s Single Track Dynamics model Original implementation: https://gitlab.lrz.de/tum-cps/commonroad-vehicle-models/ Author: Hongrui Zheng

f110_gym.envs.dynamic_models.accl_constraints(vel: float, accl: float, params: VehicleParams) float

Acceleration constraints, adjusts the acceleration based on constraints

Args:

vel (float): current velocity of the vehicle accl (float): unconstraint desired acceleration params (VehicleParams): vehicle parameters

Returns:

accl (float): adjusted acceleration

f110_gym.envs.dynamic_models.pid(speed: float, steer: float, current_speed: float, current_steer: float, params: VehicleParams) tuple[float, float]

Basic controller for speed/steer -> accl./steer vel.

Args:

speed (float): desired input speed steer (float): desired input steering angle

Returns:

accl (float): desired input acceleration sv (float): desired input steering velocity

f110_gym.envs.dynamic_models.steering_constraint(steering_angle: float, steering_velocity: float, params: VehicleParams) float

Steering constraints, adjusts the steering velocity based on constraints

Args:

steering_angle (float): current steering_angle of the vehicle steering_velocity (float): unconstraint desired steering_velocity params (VehicleParams): vehicle parameters

Returns:

steering_velocity (float): adjusted steering velocity

f110_gym.envs.dynamic_models.vehicle_dynamics_ks(x: ndarray, u_init: ndarray, params: VehicleParams) ndarray

Single Track Kinematic Vehicle Dynamics.

Args:
x (numpy.ndarray (3, )): vehicle state vector (x1, x2, x3, x4, x5)

x1: x position in global coordinates x2: y position in global coordinates x3: steering angle of front wheels x4: velocity in x direction x5: yaw angle

u (numpy.ndarray (2, )): control input vector (u1, u2)

u1: steering angle velocity of front wheels u2: longitudinal acceleration

Returns:

f (numpy.ndarray): right hand side of differential equations

f110_gym.envs.dynamic_models.vehicle_dynamics_st(x: ndarray, u_init: ndarray, params: VehicleParams) ndarray

Single Track Dynamic Vehicle Dynamics.

Args:
x (numpy.ndarray (3, )): vehicle state vector (x1, x2, x3, x4, x5, x6, x7)

x1: x position in global coordinates x2: y position in global coordinates x3: steering angle of front wheels x4: velocity in x direction x5: yaw angle x6: yaw rate x7: slip angle at vehicle center

u (numpy.ndarray (2, )): control input vector (u1, u2)

u1: steering angle velocity of front wheels u2: longitudinal acceleration

Returns:

f (numpy.ndarray): right hand side of differential equations

f110_gym.envs.f110_env module

Author: Hongrui Zheng

class f110_gym.envs.f110_env.F110Env(**kwargs: Any)

Bases: Env

F1TENTH Gym Environment.

This environment simulates the dynamics of high-speed 1/10th scale racing cars. It provides a Gymnasium-compatible interface for training and evaluating navigation and control algorithms.

State includes: - LIDAR scans (2D point clouds) - Ego poses (x, y, theta) - Linear and angular velocities - Steering angles (at current step) - Lap counters and times - Collision status

Initialization (kwargs):

seed (int): Random seed. map (str): Path to map yaml. params (dict): Vehicle physics parameters (mu, masses, etc.). num_agents (int): Number of racing agents. timestep (float): Simulation physics interval. ego_idx (int): Global index of the ego agent.

add_render_callback(callback_func: Any) None

Add extra drawing function to call during rendering.

Parameters:

callback_func (function (EnvRenderer) -> None) – custom function to call during render()

metadata = {'render_fps': 200, 'render_modes': ['human', 'human_fast']}
render() None

Renders the environment with pyglet. Use mouse scroll in the window to zoom in/out, use mouse click drag to pan. Shows the agents, the map, current fps (bottom left corner), and the race information near as text.

Parameters:

mode (str, default='human') – rendering mode, currently supports 'human' (real-time) or 'human_fast' (as fast as possible)

Returns:

None

render_callbacks: list[Any] = []
renderer: EnvRenderer | None = None
reset(*, seed: int | None = None, options: dict[str, Any] | None = None) tuple[dict[str, Any], dict[str, Any]]

Reset the gym environment by given poses

Parameters:
  • seed – random seed for the environment

  • options – dictionary of options, including ‘poses’

Returns:

observation of the current step info (dict): auxillary information dictionary

Return type:

obs (dict)

step(action: ndarray) tuple[dict[str, Any], float, bool, bool, dict[str, Any]]

Step function for the gym env

Parameters:

action (np.ndarray(num_agents, 2))

Returns:

observation of the current step reward (float, default=self.timestep): step reward, currently is physics timestep terminated (bool): if the simulation is terminated truncated (bool): if the simulation is truncated info (dict): auxillary information dictionary

Return type:

obs (dict)

update_map(map_path: str, map_ext: str) None

Updates the map used by simulation

Parameters:
  • map_path (str) – absolute path to the map yaml file

  • map_ext (str) – extension of the map image file

Returns:

None

update_params(params: dict[str, Any], index: int = -1) None

Updates the parameters used by simulation for vehicles

Parameters:
  • params (dict) – dictionary of parameters

  • index (int, default=-1) – if >= 0 then only update a specific agent’s params

Returns:

None

f110_gym.envs.f110_env.update_lap_counts(poses_x: ndarray, poses_y: ndarray, start_xs: ndarray, start_ys: ndarray, start_rot: ndarray, num_agents: int, current_time: float, near_starts: ndarray, toggle_list: ndarray, lap_counts: ndarray, lap_times: ndarray) None

Update lap counts and times based on vehicle positions relative to start line.

f110_gym.envs.integrator module

Integrator types for vehicle dynamics simulation.

class f110_gym.envs.integrator.Integrator(*values)

Bases: Enum

Integrator Enum for selecting integration method

EULER = 2
RK4 = 1

f110_gym.envs.laser_models module

Prototype of Utility functions and classes for simulating 2D LIDAR scans Author: Hongrui Zheng

class f110_gym.envs.laser_models.ScanSimulator2D(num_beams: int, fov: float, **kwargs)

Bases: object

2D LIDAR scan simulator class

num_beams

number of beams in the scan

Type:

int

fov

field of view of the laser scan

Type:

float

eps

ray tracing iteration termination condition

Type:

float, default=0.0001

theta_dis

number of steps to discretize the angles between 0 and 2pi for look up

Type:

int, default=2000

max_range

maximum range of the laser

Type:

float, default=30.0

get_increment() float

Get the increment of the scan angles

Parameters:

None

Returns:

angle increment

Return type:

increment (float)

scan(pose, rng: Generator | None, std_dev: float = 0.01)

Perform simulated 2D scan by pose on the given map

Parameters:
  • pose (numpy.ndarray (3, )) – pose of the scan frame (x, y, theta)

  • rng (numpy.random.Generator) – random number generator to use for whitenoise in scan, or None

  • std_dev (float, default=0.01) – standard deviation of the generated whitenoise in the scan

Returns:

data array of the laserscan, n=num_beams

Return type:

scan (numpy.ndarray (n, ))

Raises:

ValueError – when scan is called before a map is set

set_map(map_path: str, map_ext: str) None

Set the bitmap of the scan simulator by path

Args:

map_path (str): path to the map yaml file map_ext (str): extension (image type) of the map image

Returns:

flag (bool): if image reading and loading is successful

f110_gym.envs.laser_models.are_collinear(pt_a: ndarray, pt_b: ndarray, pt_c: ndarray) bool

Checks if three points are collinear in 2D

Parameters:
  • pt_a (np.ndarray(2, )) – points to check in 2D

  • pt_b (np.ndarray(2, )) – points to check in 2D

  • pt_c (np.ndarray(2, )) – points to check in 2D

Returns:

whether three points are collinear

Return type:

col (bool)

f110_gym.envs.laser_models.check_ttc_jit(scan: ndarray, vel: float, cosines: ndarray, side_distances: ndarray, ttc_thresh: float) bool

Checks the iTTC of each beam in a scan for collision with environment

Parameters:
  • scan (np.ndarray(num_beams, )) – current scan to check

  • vel (float) – current velocity

  • cosines (np.ndarray(num_beams, )) – precomped cosines of the scan angles

  • side_distances (np.ndarray(num_beams, )) – precomped distances at each beam from the laser to the sides of the car

  • ttc_thresh (float) – threshold for iTTC for collision

Returns:

whether vehicle is in collision with environment

Return type:

in_collision (bool)

f110_gym.envs.laser_models.cross(v1: ndarray, v2: ndarray) float

Cross product of two 2-vectors

Parameters:
  • v1 (np.ndarray(2, )) – input vectors

  • v2 (np.ndarray(2, )) – input vectors

Returns:

cross product

Return type:

crossproduct (float)

f110_gym.envs.laser_models.distance_transform(x: float, y: float, map_params: tuple) float

Look up corresponding distance in the distance matrix

Parameters:
  • x (float) – x coordinate of the lookup point

  • y (float) – y coordinate of the lookup point

  • map_params (tuple) – (orig_x, orig_y, orig_c, orig_s, height, width, resolution, dt)

Returns:

corresponding shortest distance to obstacle in meters

Return type:

distance (float)

f110_gym.envs.laser_models.get_blocked_view_indices(pose, vertices, scan_angles) tuple[int, int]

Get the indices of the start and end of blocked fov in scans by another vehicle

Parameters:
  • pose (np.ndarray(3, )) – pose of the scanning vehicle

  • vertices (np.ndarray(4, 2)) – four vertices of a vehicle pose

  • scan_angles (np.ndarray(num_beams, )) – corresponding beam angles

Returns:

index of the start of the blocked view max_ind (int): index of the end of the blocked view

Return type:

min_ind (int)

f110_gym.envs.laser_models.get_dt(bitmap: ndarray, resolution: float) ndarray

Distance transformation, returns the distance matrix from the input bitmap. Uses scipy.ndimage, cannot be JITted.

Parameters:
  • bitmap (numpy.ndarray, (n, m)) – input binary bitmap of the environment, where 0 is obstacles, and 255 (or anything > 0) is freespace

  • resolution (float) – resolution of the input bitmap (m/cell)

Returns:

output distance matrix, where each cell has the

corresponding distance (in meters) to the closest obstacle

Return type:

dt (numpy.ndarray, (n, m))

f110_gym.envs.laser_models.get_range(pose, beam_theta: float, va, vb)

Get the distance at a beam angle to the vector formed by two of the four vertices of a vehicle

Parameters:
  • pose (np.ndarray(3, )) – pose of the scanning vehicle

  • beam_theta (float) – angle of the current beam (world frame)

  • va (np.ndarray(2, )) – the two vertices forming an edge

  • vb (np.ndarray(2, )) – the two vertices forming an edge

Returns:

smallest distance at beam theta from scanning pose to edge

Return type:

distance (float)

f110_gym.envs.laser_models.get_scan(pose: ndarray, scan_params: tuple, map_params: tuple) ndarray

Perform the scan for each discretized angle of each beam of the laser, loop heavy, should be JITted

Parameters:
  • pose (numpy.ndarray(3, )) – current pose of the scan frame in the map

  • scan_params (tuple) – (theta_dis, fov, num_beams, theta_index_increment, sines, cosines, eps, max_range)

  • map_params (tuple) – (orig_x, orig_y, orig_c, orig_s, height, width, resolution, dt)

Returns:

resulting laser scan at the pose, n=num_beams

Return type:

scan (numpy.ndarray(n, ))

f110_gym.envs.laser_models.ray_cast(pose: ndarray, scan: ndarray, scan_angles: ndarray, vertices: ndarray) ndarray

Modify a scan by ray casting onto another agent’s four vertices

Parameters:
  • pose (np.ndarray(3, )) – pose of the vehicle performing scan

  • scan (np.ndarray(num_beams, )) – original scan to modify

  • scan_angles (np.ndarray(num_beams, )) – corresponding beam angles

  • vertices (np.ndarray(4, 2)) – four vertices of a vehicle pose

Returns:

modified scan

Return type:

new_scan (np.ndarray(num_beams, ))

f110_gym.envs.laser_models.ray_cast_multiple(pose: ndarray, scan: ndarray, scan_angles: ndarray, opp_vertices: ndarray) ndarray

Modify a scan by ray casting onto multiple other agents

Parameters:
  • pose (np.ndarray(3, )) – pose of the vehicle performing scan

  • scan (np.ndarray(num_beams, )) – original scan to modify

  • scan_angles (np.ndarray(num_beams, )) – corresponding beam angles

  • opp_vertices (np.ndarray(num_opps, 4, 2)) – vertices of all other agents

Returns:

modified scan

Return type:

new_scan (np.ndarray(num_beams, ))

f110_gym.envs.laser_models.trace_ray(x: float, y: float, theta_index: float, scan_params: tuple, map_params: tuple) float

Find the length of a specific ray at a specific scan angle theta Purely math calculation and loops, should be JITted.

Parameters:
  • x (float) – current x coordinate of the ego (scan) frame

  • y (float) – current y coordinate of the ego (scan) frame

  • theta_index (int) – current index of the scan beam in the scan range

  • sines (numpy.ndarray (n, )) – pre-calculated sines of the angle array

  • cosines (numpy.ndarray (n, )) – pre-calculated cosines …

Returns:

the distance to first obstacle on the current scan beam

Return type:

total_distance (float)

f110_gym.envs.laser_models.xy_2_rc(x: float, y: float, map_params: tuple) tuple[int, int]

Translate (x, y) coordinate into (r, c) in the matrix

Parameters:
  • x (float) – coordinate in x (m)

  • y (float) – coordinate in y (m)

  • map_params (tuple) – (orig_x, orig_y, orig_c, orig_s, height, width, resolution, dt)

Returns:

row number in the transform matrix of the given point c (int): column number in the transform matrix of the given point

Return type:

r (int)

f110_gym.envs.race_car module

RaceCar class implementation for the F1TENTH gym environment. Handles vehicle dynamics, LIDAR simulation, and collision checking.

class f110_gym.envs.race_car.LidarConfig(num_beams: int, fov: float, lidar_dist: float, ttc_thresh: float)

Bases: object

LIDAR sensor configuration parameters.

fov: float
lidar_dist: float
num_beams: int
ttc_thresh: float
class f110_gym.envs.race_car.RaceCar(params: dict[str, Any], seed: int, **kwargs: Any)

Bases: object

Base level race car class, handles the physics and laser scan of a single vehicle

v_params

physical vehicle parameters

Type:

RaceCarVehicleParams

config

simulation configuration

Type:

RaceCarConfig

state

state vector [x, y, steer_angle, vel, yaw_angle, yaw_rate, slip_angle], shape (7,)

Type:

np.ndarray

opp_poses

current poses of other agents

Type:

np.ndarray | None

control

control inputs and steering buffer

Type:

RaceCarControlState

in_collision

collision indicator

Type:

bool

scan_rng

random number generator for scan noise

Type:

np.random.Generator

check_ttc(current_scan: ndarray) bool

Check iTTC against the environment, sets vehicle states accordingly if collision occurs. Note that this does NOT check collision with other agents.

state is [x, y, steer_angle, vel, yaw_angle, yaw_rate, slip_angle]

Parameters:

current_scan (np.ndarray) – current laser scan

Returns:

None

cosines = None
ray_cast_agents(scan: ndarray) ndarray

Ray cast onto other agents in the env, modify original scan

Parameters:

scan (np.ndarray, (n, )) – original scan range array

Returns:

modified scan

Return type:

new_scan (np.ndarray, (n, ))

reset(pose: ndarray) None

Resets the vehicle to a pose

Parameters:

pose (np.ndarray (3, )) – pose to reset the vehicle to

Returns:

None

scan_angles = None
scan_simulator = None
set_map(map_path: str, map_ext: str) None

Sets the map for scan simulator

Parameters:
  • map_path (str) – absolute path to the map yaml file

  • map_ext (str) – extension of the map image file

side_distances = None
update_opp_poses(opp_poses: ndarray) None

Updates the vehicle’s information on other vehicles

Parameters:

opp_poses (np.ndarray(num_other_agents, 3)) – updated poses of other agents

Returns:

None

update_params(params: dict[str, Any]) None

Updates the physical parameters of the vehicle Note that does not need to be called at initialization of class anymore

Parameters:

params (dict) – new parameters for the vehicle

Returns:

None

update_pose(raw_steer: float, vel: float) ndarray

Steps the vehicle’s physical simulation

Parameters:
  • steer (float) – desired steering angle

  • vel (float) – desired longitudinal velocity

Returns:

current_scan

update_scan(agent_scans: list[ndarray], agent_index: int) None

Steps the vehicle’s laser scan simulation Separated from update_pose because needs to update scan based on NEW poses of agents in the environment

Parameters:
  • list (agent scans)

  • index (agent)

Returns:

None

class f110_gym.envs.race_car.RaceCarConfig(seed: int, is_ego: bool, time_step: float, integrator: Integrator, lidar: LidarConfig)

Bases: object

Configuration parameters for the race car simulation.

integrator: Integrator
is_ego: bool
lidar: LidarConfig
seed: int
time_step: float
class f110_gym.envs.race_car.RaceCarControlState(accel: float, steer_angle_vel: float, steer_buffer: ndarray, steer_buffer_size: int)

Bases: object

Control inputs and buffers for steering and acceleration.

accel: float
steer_angle_vel: float
steer_buffer: ndarray
steer_buffer_size: int
class f110_gym.envs.race_car.RaceCarVehicleParams(params: dict[str, Any], params_tuple: VehicleParams)

Bases: object

Physical parameters of the vehicle.

params: dict[str, Any]
params_tuple: VehicleParams

f110_gym.envs.rendering module

Rendering engine for f1tenth gym env based on pyglet and OpenGL Author: Hongrui Zheng Updated for pyglet 2.x compatibility

class f110_gym.envs.rendering.CameraViewport(left: float, right: float, bottom: float, top: float)

Bases: object

Ortho bounds for the camera.

bottom: float
left: float
right: float
top: float
class f110_gym.envs.rendering.CarShape(vertices: list[float], color: tuple[int, int, int], batch: pyglet.graphics.Batch)

Bases: object

Custom shape class for rendering cars as quads using pyglet 2.x shapes API.

delete() None

Clean up and delete all sub-shapes associated with this car.

property vertices: list[float]

Get the current vertices of the car shape.

class f110_gym.envs.rendering.EnvRenderer(*args: Any, **kwargs: Any)

Bases: Window

F1TENTH Environment Renderer.

A window class inheriting from pyglet.window.Window that handles the camera, coordinate projections, and object rendering for the simulation.

Features: - Support for Pyglet 2.x graphics API. - Ego-centric camera following with rotation capability. - Automatic coordinate scaling (50.0 pixels per meter). - Map and LIDAR scan visualization.

property bottom: float

Backwards compatibility for viewport bottom bound.

property cars: list[CarShape]

Backwards compatibility for cars list.

property left: float

Backwards compatibility for viewport left bound.

on_close() None

Callback function when the ‘x’ is clicked on the window, overrides inherited method. Also throws exception to end the python program when in a loop.

Parameters:

None

Returns:

None

Raises:

RuntimeError – with a message that indicates the rendering window was closed

on_draw() None

Function when the pyglet is drawing. The function draws the batch created that includes the map points, the agent polygons, the information text, and the fps display.

Parameters:

None

Returns:

None

on_mouse_drag(x: int, y: int, dx: int, dy: int, buttons: int, modifiers: int) None

Callback function on mouse drag, overrides inherited method.

Parameters:
  • x (int) – Distance in pixels from the left edge of the window.

  • y (int) – Distance in pixels from the bottom edge of the window.

  • dx (int) – Relative X position from the previous mouse position.

  • dy (int) – Relative Y position from the previous mouse position.

  • buttons (int) – Bitwise combination of the mouse buttons currently pressed.

  • modifiers (int) – Bitwise combination of any keyboard modifiers currently active.

Returns:

None

on_mouse_scroll(x: int, y: int, scroll_x: float, scroll_y: float) None

Callback function on mouse scroll, overrides inherited method.

Parameters:
  • x (int) – Distance in pixels from the left edge of the window.

  • y (int) – Distance in pixels from the bottom edge of the window.

  • dx (float) – Amount of movement on the horizontal axis.

  • dy (float) – Amount of movement on the vertical axis.

Returns:

None

on_resize(width: int, height: int) None

Callback function on window resize, overrides inherited method, and updates camera values on top of the inherited on_resize() method.

Potential improvements on current behavior: zoom/pan resets on window resize.

Parameters:
  • width (int) – new width of window

  • height (int) – new height of window

Returns:

None

property poses: ndarray | None

Backwards compatibility for poses.

property right: float

Backwards compatibility for viewport right bound.

property scans: list[ndarray] | None

Backwards compatibility for scans list.

property top: float

Backwards compatibility for viewport top bound.

update_map(map_path: str, map_ext: str) None

Update the map being drawn by the renderer. Converts image to a list of 3D points representing each obstacle pixel in the map.

Parameters:
  • map_path (str) – absolute path to the map without extensions

  • map_ext (str) – extension for the map image file

Returns:

None

update_obs(obs: dict[str, Any]) None

Updates the renderer with the latest observation from the gym environment, including the agent poses, and the information text.

Parameters:

obs (dict) – observation dict from the gym env

Returns:

None

window_block() _ProjectionContext

Context manager for setting window projection

class f110_gym.envs.rendering.RendererCamera(viewport: CameraViewport, zoom_level: float, zoomed_width: int, zoomed_height: int, x: float, y: float, rotation: float = 0.0)

Bases: object

Camera and view state for the renderer.

rotation: float = 0.0
viewport: CameraViewport
x: float
y: float
zoom_level: float
zoomed_height: int
zoomed_width: int
class f110_gym.envs.rendering.RendererMap(points: ndarray | None, shapes: list[pyglet.shapes.Circle])

Bases: object

Map-related data and shapes.

points: ndarray | None
shapes: list[pyglet.shapes.Circle]
class f110_gym.envs.rendering.RendererSim(poses: ndarray | None, ego_idx: int, cars: list[CarShape], scans: list[ndarray] | None)

Bases: object

Simulation-related data (agent poses, scans, etc.).

cars: list[CarShape]
ego_idx: int
poses: ndarray | None
scans: list[ndarray] | None
class f110_gym.envs.rendering.RendererUI(score_label: pyglet.text.Label, fps_display: pyglet.window.FPSDisplay)

Bases: object

UI elements displayed over the simulation.

fps_display: pyglet.window.FPSDisplay
score_label: pyglet.text.Label

f110_gym.envs.simulator module

Simulator class for the F1TENTH Gym environment.

class f110_gym.envs.simulator.Simulator(params: SimulatorParams)

Bases: object

Simulation engine for F1TENTH.

Handles the temporal update of all vehicles, collision detection, and sensor (LIDAR) data generation.

num_agents

Number of simulated cars.

Type:

int

time_step

Physics integration interval (dt).

Type:

float

agent_poses

Array of [x, y, theta] for all agents.

Type:

np.ndarray

steering_angles

Current steering angle for all agents.

Type:

np.ndarray

agents

List of individual RaceCar instances.

Type:

list[RaceCar]

collisions

Boolean mask indicating if an agent has crashed.

Type:

np.ndarray

check_collision() None

Checks for collision between agents using GJK and agents’ body vertices

Parameters:

None

Returns:

None

reset(poses: ndarray) None

Resets the simulation environment by given poses

Parameters:

poses (np.ndarray (num_agents, 3)) – poses to reset agents to

Returns:

None

set_map(map_path: str, map_ext: str) None

Sets the map of the environment and sets the map for scan simulator of each agent

Parameters:
  • map_path (str) – path to the map yaml file

  • map_ext (str) – extension for the map image file

Returns:

None

step(control_inputs: ndarray) dict[str, Any]

Steps the simulation environment

Parameters:

control_inputs (np.ndarray (num_agents, 2)) – control inputs of all agents, first column is desired steering angle, second column is desired velocity

Returns:

dictionary for observations: poses of agents,

current laser scan of each agent, collision indicators, etc.

Return type:

observations (dict)

update_params(params: dict[str, Any], agent_idx: int = -1) None

Updates the params of agents, if an index of an agent is given, update only that agent’s params

Parameters:
  • params (dict) – dictionary of params, see details in docstring of __init__

  • agent_idx (int, default=-1) – index for agent that needs param update, if negative, update all agents

Returns:

None

f110_gym.envs.simulator_params module

Configuration parameters for the F1TENTH Simulator.

class f110_gym.envs.simulator_params.SimulatorParams(vehicle_params: dict[str, Any], num_agents: int, seed: int, time_step: float = 0.01, ego_idx: int = 0, integrator: Integrator = Integrator.RK4, lidar_dist: float = 0.0)

Bases: object

Configuration parameters for the Simulator.

ego_idx: int = 0
integrator: Integrator = 1
lidar_dist: float = 0.0
num_agents: int
seed: int
time_step: float = 0.01
vehicle_params: dict[str, Any]

f110_gym.envs.vehicle_params module

Vehicle parameter definitions for the F1TENTH Gym environment.

class f110_gym.envs.vehicle_params.VehicleParams(mu: float, C_Sf: float, C_Sr: float, lf: float, lr: float, h: float, m: float, MoI: float, s_min: float, s_max: float, sv_min: float, sv_max: float, v_switch: float, a_max: float, v_min: float, v_max: float)

Bases: NamedTuple

Physical parameters of a vehicle.

C_Sf: float

Cornering stiffness coefficient, front

C_Sr: float

Cornering stiffness coefficient, rear

MoI: float

Moment of inertia of the entire vehicle about the z axis

a_max: float

Maximum longitudinal acceleration

h: float

Height of center of gravity

lf: float

Distance from center of gravity to front axle

lr: float

Distance from center of gravity to rear axle

m: float

Total mass of the vehicle

mu: float

Surface friction coefficient

s_max: float

Maximum steering angle constraint

s_min: float

Minimum steering angle constraint

sv_max: float

Maximum steering velocity constraint

sv_min: float

Minimum steering velocity constraint

v_max: float

Maximum longitudinal velocity

v_min: float

Minimum longitudinal velocity

v_switch: float

Switching velocity (velocity at which the acceleration is no longer able to create wheel spin)

Module contents

F1TENTH Gym environment modules.

class f110_gym.envs.CloudSchedulerEnv(*, map: str, waypoints: ndarray, cloud_latency: int = 10, alpha_steer: float = 0.7, alpha_speed: float = 0.7, 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, reward_fn: Callable[[dict[str, Any], int], float] | None = None, cloud_cost: float = 0.1, cloud_cost_window: int = 100, **env_kwargs: Any)

Bases: Env

Gym environment that exposes cloud scheduling as the action.

The environment forwards low-level control decisions to an internal EdgeCloudPlanner and returns the usual simulator observations. The agent is responsible for toggling the scheduler on each step.

close() None

After the user has finished using the environment, close contains the code necessary to “clean up” the environment.

This is critical for closing rendering windows, database or HTTP connections. Calling close on an already closed environment has no effect and won’t raise an error.

metadata = {'render_fps': 200, 'render_modes': ['human', 'human_fast']}
render() None

Compute the render frames as specified by render_mode during the initialization of the environment.

The environment’s metadata render modes (env.metadata[“render_modes”]) should contain the possible ways to implement the render modes. In addition, list versions for most render modes is achieved through gymnasium.make which automatically applies a wrapper to collect rendered frames.

Note

As the render_mode is known during __init__, the objects used to render the environment state should be initialised in __init__.

By convention, if the render_mode is:

  • None (default): no render is computed.

  • “human”: The environment is continuously rendered in the current display or terminal, usually for human consumption. This rendering should occur during step() and render() doesn’t need to be called. Returns None.

  • “rgb_array”: Return a single frame representing the current state of the environment. A frame is a np.ndarray with shape (x, y, 3) representing RGB values for an x-by-y pixel image.

  • “ansi”: Return a strings (str) or StringIO.StringIO containing a terminal-style text representation for each time step. The text can include newlines and ANSI escape sequences (e.g. for colors).

  • “rgb_array_list” and “ansi_list”: List based version of render modes are possible (except Human) through the wrapper, gymnasium.wrappers.RenderCollection that is automatically applied during gymnasium.make(..., render_mode="rgb_array_list"). The frames collected are popped after render() is called or reset().

Note

Make sure that your class’s metadata "render_modes" key includes the list of supported modes.

Changed in version 0.25.0: The render function was changed to no longer accept parameters, rather these parameters should be specified in the environment initialised, i.e., gymnasium.make("CartPole-v1", render_mode="human")

reset(*, seed: int | None = None, options: dict | None = None)

Resets the environment to an initial internal state, returning an initial observation and info.

This method generates a new starting state often with some randomness to ensure that the agent explores the state space and learns a generalised policy about the environment. This randomness can be controlled with the seed parameter otherwise if the environment already has a random number generator and reset() is called with seed=None, the RNG is not reset.

Therefore, reset() should (in the typical use case) be called with a seed right after initialization and then never again.

For Custom environments, the first line of reset() should be super().reset(seed=seed) which implements the seeding correctly.

Changed in version v0.25: The return_info parameter was removed and now info is expected to be returned.

Parameters:
  • seed (optional int) – The seed that is used to initialize the environment’s PRNG (np_random) and the read-only attribute np_random_seed. If the environment does not already have a PRNG and seed=None (the default option) is passed, a seed will be chosen from some source of entropy (e.g. timestamp or /dev/urandom). However, if the environment already has a PRNG and seed=None is passed, the PRNG will not be reset and the env’s np_random_seed will not be altered. If you pass an integer, the PRNG will be reset even if it already exists. Usually, you want to pass an integer right after the environment has been initialized and then never again. Please refer to the minimal example above to see this paradigm in action.

  • options (optional dict) – Additional information to specify how the environment is reset (optional, depending on the specific environment)

Returns:

Observation of the initial state. This will be an element of observation_space

(typically a numpy array) and is analogous to the observation returned by step().

info (dictionary): This dictionary contains auxiliary information complementing observation. It should be analogous to

the info returned by step().

Return type:

observation (ObsType)

step(action: int)

Apply a scheduling action and advance the environment by one step.

Parameters:

action (int) – scheduling decision; 1 triggers a cloud call on this step, 0 uses the cached cloud result.

Returns:

(obs, reward, terminated, truncated, info) following the

Gymnasium convention. obs is the augmented observation dict (including latest_cloud_action, cloud_request_pending, and crosstrack_dist). info contains the keys forwarded from the underlying f110-v0 environment plus latest_cloud_action, cloud_request_pending, and step.

Return type:

tuple

class f110_gym.envs.F110Env(**kwargs: Any)

Bases: Env

F1TENTH Gym Environment.

This environment simulates the dynamics of high-speed 1/10th scale racing cars. It provides a Gymnasium-compatible interface for training and evaluating navigation and control algorithms.

State includes: - LIDAR scans (2D point clouds) - Ego poses (x, y, theta) - Linear and angular velocities - Steering angles (at current step) - Lap counters and times - Collision status

Initialization (kwargs):

seed (int): Random seed. map (str): Path to map yaml. params (dict): Vehicle physics parameters (mu, masses, etc.). num_agents (int): Number of racing agents. timestep (float): Simulation physics interval. ego_idx (int): Global index of the ego agent.

add_render_callback(callback_func: Any) None

Add extra drawing function to call during rendering.

Parameters:

callback_func (function (EnvRenderer) -> None) – custom function to call during render()

metadata = {'render_fps': 200, 'render_modes': ['human', 'human_fast']}
render() None

Renders the environment with pyglet. Use mouse scroll in the window to zoom in/out, use mouse click drag to pan. Shows the agents, the map, current fps (bottom left corner), and the race information near as text.

Parameters:

mode (str, default='human') – rendering mode, currently supports 'human' (real-time) or 'human_fast' (as fast as possible)

Returns:

None

render_callbacks: list[Any] = []
renderer: EnvRenderer | None = None
reset(*, seed: int | None = None, options: dict[str, Any] | None = None) tuple[dict[str, Any], dict[str, Any]]

Reset the gym environment by given poses

Parameters:
  • seed – random seed for the environment

  • options – dictionary of options, including ‘poses’

Returns:

observation of the current step info (dict): auxillary information dictionary

Return type:

obs (dict)

step(action: ndarray) tuple[dict[str, Any], float, bool, bool, dict[str, Any]]

Step function for the gym env

Parameters:

action (np.ndarray(num_agents, 2))

Returns:

observation of the current step reward (float, default=self.timestep): step reward, currently is physics timestep terminated (bool): if the simulation is terminated truncated (bool): if the simulation is truncated info (dict): auxillary information dictionary

Return type:

obs (dict)

update_map(map_path: str, map_ext: str) None

Updates the map used by simulation

Parameters:
  • map_path (str) – absolute path to the map yaml file

  • map_ext (str) – extension of the map image file

Returns:

None

update_params(params: dict[str, Any], index: int = -1) None

Updates the parameters used by simulation for vehicles

Parameters:
  • params (dict) – dictionary of parameters

  • index (int, default=-1) – if >= 0 then only update a specific agent’s params

Returns:

None