Gym Environment

GKEnv is the main Gymnasium environment class, implementing the F1/10th vehicle simulation with realistic dynamics.

Source: gymkhana/envs/gymkhana_env.py

Creating an environment

import gymnasium as gym
from gymkhana.envs.gymkhana_env import GKEnv

env = gym.make('gymkhana:gymkhana-v0', config={
    'map': 'Spielberg',
    'num_agents': 1,
    'model': 'std',
    'control_input': ['accl', 'steering_angle'],
    'params': GKEnv.f1tenth_std_vehicle_params(),
    'render_mode': 'human',
})

See Configuration for the full list of config options.

Vehicle parameter methods

GKEnv.f1tenth_std_vehicle_params()

Returns the default parameter dictionary for the 1/10 scale F1TENTH car with the STD (single-track drift) model. Includes PAC2002 tire parameters adjusted from a full-scale car.

GKEnv.f1tenth_std_drift_bias_params()

Returns drift-biased parameters for more aggressive drifting behavior.

Step and reset

env.step(action)

Steps the simulation. Returns (obs, reward, terminated, truncated, info).

  • action: ndarray of shape (num_agents, 2) — see Action System for control input types

env.reset(options=None)

Resets the environment. Returns (obs, info).

  • options: optional dict with "poses" or "states" keys (see Configuration)

env.update_params(params_dict, index=None)

Update vehicle parameters. If index is specified, updates only that vehicle; otherwise updates all vehicles.

API reference

class gymkhana.envs.gymkhana_env.GKEnv(config: dict = None, render_mode=None, **kwargs)

Gymnasium environment for Gym-Khana. For API specs, see https://gymnasium.farama.org/api/env/#

Args:
kwargs:

seed (int, default=12345): seed for random state and reproducibility map (str, default=’vegas’): name of the map used for the environment.

params (dict, default={‘mu’: 1.0489, ‘C_Sf’:, ‘C_Sr’:, ‘lf’: 0.15875, ‘lr’: 0.17145, ‘h’: 0.074, ‘m’: 3.74, ‘I’: 0.04712, ‘s_min’: -0.4189, ‘s_max’: 0.4189, ‘sv_min’: -3.2, ‘sv_max’: 3.2, ‘v_switch’:7.319, ‘a_max’: 9.51, ‘v_min’:-5.0, ‘v_max’: 20.0, ‘width’: 0.31, ‘length’: 0.58}): dictionary of vehicle parameters. mu: surface friction coefficient C_Sf: Cornering stiffness coefficient, front C_Sr: Cornering stiffness coefficient, rear lf: Distance from center of gravity to front axle lr: Distance from center of gravity to rear axle h: Height of center of gravity m: Total mass of the vehicle I: Moment of inertial of the entire vehicle about the z axis s_min: Minimum steering angle constraint s_max: Maximum steering angle constraint sv_min: Minimum steering velocity constraint sv_max: Maximum steering velocity constraint v_switch: Switching velocity (velocity at which the acceleration is no longer able to create wheel spin) a_max: Maximum longitudinal acceleration v_min: Minimum longitudinal velocity v_max: Maximum longitudinal velocity width: width of the vehicle in meters length: length of the vehicle in meters

num_agents (int, default=2): number of agents in the environment

timestep (float, default=0.01): physics timestep

ego_idx (int, default=0): ego’s index in list of agents

metadata = {'render_fps': 100, 'render_modes': ['human', 'human_fast', 'rgb_array']}
classmethod fullscale_vehicle_params() dict

This is copied as-is from commonroad-vehicle-models/PYTHON/vehiclemodels/parameters/parameters_vehicle1.yaml

classmethod f1fifth_vehicle_params() dict
classmethod f1tenth_vehicle_params() dict

Default parameters.

classmethod f1tenth_std_drift_bias_params() dict

Returns params for Single Track Drift (STD) model with drift bias.

Returns:

dict: Parameter dictionary with drift bias for STD model

classmethod f1tenth_std_vehicle_params() dict

Returns default parameters for Single Track Drift (STD) model. Extends standard F1TENTH parameters with wheel dynamics and Pacejka tire model.

Returns:

dict: Complete parameter dictionary for STD model

classmethod default_config() dict

Default environment configuration.

Can be overloaded in environment implementations, or by calling configure().

Args:

None

Returns:

a configuration dict

configure(config: dict) None
set_recovery_ranges(v_range, beta_range, r_range, yaw_range)

Set recovery initial state sampling ranges (used by curriculum learning).

step(action, skip_integration=False)

Step function for the gym env

Args:

action (np.ndarray(num_agents, 2)) skip_integration (bool): if True, skip dynamics integration (used in reset to generate obs)

Returns:

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

reset(seed=None, options=None)

Reset the gym environment by given poses or full states.

Args:

seed: random seed for the reset options: dictionary of options for the reset:

  • “poses”: np.ndarray (num_agents, 3) - [x, y, yaw] per agent

  • “states”: np.ndarray (num_agents, 7) - full state per agent (STD model only)

    [x, y, delta, v, yaw, yaw_rate, slip_angle]

Note: Cannot specify both “poses” and “states”.

Returns:

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

update_map(map_name: str)

Updates the map used by simulation

Args:

map_name (str): name of the map

Returns:

None

update_params(params, index=-1)

Updates the parameters used by simulation for vehicles

Args:

params (dict): dictionary of parameters index (int, default=-1): if >= 0 then only update a specific agent’s params

Returns:

None

add_render_callback(callback_func)

Add extra drawing function to call during rendering.

Args:

callback_func (function (EnvRenderer) -> None): custom function to called during render()

render(mode='human')

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.

Args:
mode (str, default=’human’): rendering mode, currently supports:

‘human’: slowed down rendering such that the env is rendered in a way that sim time elapsed is close to real time elapsed ‘human_fast’: render as fast as possible

Returns:

None

close()

Ensure renderer is closed upon deletion