Base Classes

The base classes handle physical simulation and interaction between vehicles.

Source: gymkhana/envs/base_classes.py

RaceCar

Handles the simulation of a single vehicle’s dynamics model and laser scan generation.

Each RaceCar instance:

  • Maintains the vehicle’s state (position, velocity, orientation, etc.)

  • Steps the selected dynamics model forward in time

  • Generates simulated LiDAR scans via the laser model

Simulator

Orchestrates the multi-agent simulation, including:

  • Managing multiple RaceCar instances

  • Collision checking between agents and with track boundaries

  • Stepping all agents simultaneously for deterministic simulation

The step method (line 503) is the core simulation loop. All agents’ physics are stepped simultaneously, and all randomness is seeded for reproducibility. The explicit stepping enables faster-than-real-time execution.

API reference

Prototype of base classes Replacement of the old RaceCar, Simulator classes in C++ Author: Hongrui Zheng, Teodor Ilie

class gymkhana.envs.base_classes.RaceCar(params, seed, wall_deflection, action_type: CarAction, integrator=<gymkhana.envs.integrator.EulerIntegrator object>, model=DynamicModel.ST, is_ego=False, time_step=0.01, num_beams=1080, fov=4.7)

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

Data Members:

params (dict): vehicle parameters dictionary is_ego (bool): ego identifier time_step (float): physics timestep num_beams (int): number of beams in laser fov (float): field of view of laser state (np.ndarray (7, )): state vector [x, y, theta, vel, steer_angle, ang_vel, slip_angle] odom (np.ndarray(13, )): odometry vector [x, y, z, qx, qy, qz, qw, linear_x, linear_y, linear_z, angular_x, angular_y, angular_z] accel (float): current acceleration input steer_angle_vel (float): current steering velocity input in_collision (bool): collision indicator

scan_simulator = None
cosines = None
scan_angles = None
side_distances = None
update_params(params)

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

Args:

params (dict): new parameters for the vehicle

Returns:

None

set_map(map: str | Track, map_scale: float = 1.0)

Sets the map for scan simulator

Args:

map (str | Track): name of the map, or Track object map_scale (float, default=1.0): scale of the map, larger scale means larger map

reset(pose, state=None)

Resets the vehicle to a pose or full state.

Args:

pose (np.ndarray (3, )): pose to reset the vehicle to state (np.ndarray (7, ), optional): full state for STD model

[x, y, delta, v, yaw, yaw_rate, slip_angle] If provided, pose is ignored and state is used instead.

Returns:

None

ray_cast_agents(scan)

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

Args:

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

Returns:

new_scan (np.ndarray, (n, )): modified scan

check_ttc(current_scan)

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]

Args:

current_scan

Returns:

None

update_pose(raw_steer, raw_throttle, skip_integration=False)

Steps the vehicle’s physical simulation by one time step

Args:

raw_steer (float): desired steering angle, or desired steering velocity raw_throttle (float): desired longitudinal velocity, or desired longitudinal acceleration skip_integration (bool): if True, skip dynamics integration (used in reset to generate obs)

Returns:

current_scan

update_opp_poses(opp_poses)

Updates the vehicle’s information on other vehicles

Args:

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

Returns:

None

update_scan(agent_scans, agent_index)

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

Args:

agent scans list (modified in-place), agent index (int)

Returns:

None

property standard_state: dict

Returns the state of the vehicle as an observation

Returns:

np.ndarray (7, ): state of the vehicle

class gymkhana.envs.base_classes.Simulator(params, num_agents, seed, num_beams, wall_deflection, action_type: CarAction, integrator=<class 'gymkhana.envs.integrator.Integrator'>, model=DynamicModel.ST, time_step=0.01, ego_idx=0)

Simulator class, handles the interaction and update of all vehicles in the environment

TODO check description

Data Members:

num_agents (int): number of agents in the environment time_step (float): physics time step agent_poses (np.ndarray(num_agents, 3)): all poses of all agents agents (list[RaceCar]): container for RaceCar objects collisions (np.ndarray(num_agents, )): array of collision indicator for each agent collision_idx (np.ndarray(num_agents, )): which agent is each agent in collision with integrator (Integrator): integrator to use for vehicle dynamics model (Model): model to use for vehicle dynamics action_type (Action): action type to use for vehicle dynamics

agents: list[RaceCar]
set_map(map: str | Track, map_scale: float = 1.0)

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

Args:

map (str | Track): name of the map, or Track object map_scale (float, default=1.0): scale of the map, larger scale means larger map

Returns:

None

update_params(params, agent_idx=-1)

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

Args:

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

check_collision()

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

Args:

None

Returns:

None

step(control_inputs, skip_integration=False)

Steps the simulation environment

Args:

control_inputs (np.ndarray (num_agents, 2)): control inputs of all agents, first column is desired steering angle, second column is desired velocity skip_integration (bool): if True, skip dynamics integration (used in reset to generate obs)

Returns:

observations (dict): dictionary for observations: poses of agents, current laser scan of each agent, collision indicators, etc.

reset(poses, states=None)

Resets the simulation environment by given poses or full states.

Args:

poses (np.ndarray (num_agents, 3)): poses to reset agents to states (np.ndarray (num_agents, 7), optional): full states for STD model

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

Returns:

None