Track System
The track system handles loading racing circuits, managing centerline and raceline data, and coordinate conversions.
Source: gymkhana/envs/track/
Track loading
Tracks are loaded from map files following the ROS map convention:
A
.yamlmetadata file withresolution(m/pixel) andoriginfieldsA single-channel black-and-white image (black = obstacles, white = free space)
Both files must share the same base name and directory.
Map management
Maps are managed through a two-tier system:
Local
maps/directory: git submodule from https://github.com/TeoIlie/F1TENTH_Racetracks — used for developmentUser cache
~/.gymkhana/maps/: auto-downloaded from GitHub releases for pip-installed users
The download URL is configured in gymkhana/envs/track/track_utils.py::MAPS_URL.
Frenet coordinates
The track system supports conversion between Cartesian and Frenet (arc-length based) coordinate frames.
frenet_to_cartesian()Convert Frenet coordinates to Cartesian. Available in
gymkhana/envs/track/track.py.
This is useful for initializing vehicles at specific positions along the track using env.reset(options={"poses": ...}).
Centerline and raceline
Each track includes:
Centerline: the geometric center of the track, used for Frenet projection and progress measurement
Raceline: an optimized racing line (when available), rendered in red when
render_track_linesis enabled
Both use cubic spline interpolation for smooth trajectories.
API reference
- class gymkhana.envs.track.track.TrackSpec(name: 'Optional[str]', image: 'Optional[str]', resolution: 'float', origin: 'Tuple[float, float, float]', negate: 'int', occupied_thresh: 'float', free_thresh: 'float')
- name: str | None
- image: str | None
- resolution: float
- origin: Tuple[float, float, float]
- negate: int
- occupied_thresh: float
- free_thresh: float
- class gymkhana.envs.track.track.Track(spec: 'TrackSpec', occupancy_map: 'np.ndarray', filepath: 'Optional[str]' = None, ext: 'Optional[str]' = None, centerline: 'Optional[Raceline]' = None, raceline: 'Optional[Raceline]' = None)
-
- filepath: str | None
- ext: str | None
- occupancy_map: ndarray
- set_direction(reversed: bool) None
Set track direction by swapping active centerline/raceline references.
- Args:
reversed: If True, use reversed versions. If False, use regular versions.
- static load_spec(track: str, filespec: str) TrackSpec
Load track specification from yaml file.
Parameters
- trackstr
name of the track
- filespecstr
path to the yaml file
Returns
- TrackSpec
track specification
- static from_track_name(track: str, track_scale: float = 1.0) Track
Load track from track name.
Parameters
- trackstr
name of the track
- track_scalefloat, optional
scale of the track, by default 1.0
Returns
- Track
track object
Raises
- FileNotFoundError
if the track cannot be loaded
- static from_track_path(path: Path, track_scale: float = 1.0) Track
Load track from track path.
Parameters
- pathpathlib.Path
path to the track yaml file
Returns
- Track
track object
Raises
- FileNotFoundError
if the track cannot be loaded
- static from_refline(x: ndarray, y: ndarray, velx: ndarray)
Create an empty track reference line.
Parameters
- xnp.ndarray
x-coordinates of the waypoints
- ynp.ndarray
y-coordinates of the waypoints
- velxnp.ndarray
velocities at the waypoints
Returns
- track: Track
track object
- frenet_to_cartesian(s, ey, ephi, use_raceline=False)
Convert Frenet coordinates to Cartesian coordinates.
s: distance along the raceline ey: lateral deviation ephi: heading deviation
- returns:
x: x-coordinate y: y-coordinate psi: yaw angle
- cartesian_to_frenet(x, y, phi, use_raceline=False, s_guess=0, precise=False, debug=False)
WARNING: Only use “precise=True” if you pass an excellent s_guess. More work required to validate this even works.
Convert Cartesian coordinates to Frenet coordinates.
x: x-coordinate (Cartesian coord from std_state[“x”]) y: y-coordinate (Cartesian coord from std_state[“y”]) phi: yaw angle (from std_state[“yaw”]) use_raceline: Calculate with respect to raceline or centerline s_guess: Initial guess for arc length calculation debug: Enable debug logging and validation
- returns:
s: arc length distance along the centerline/raceline ey: lateral deviation from centerline/raceline ephi: heading deviation (angle between vehicle and track heading) in radians
- render_centerline(e: EnvRenderer) None
Render the track centerline.
The centerline represents the geometric center of the track and is rendered in green.
Parameters
- eEnvRenderer
Environment renderer object.
- render_raceline(e: EnvRenderer) None
Render the track raceline.
The raceline represents the optimal racing line through the track and is rendered in red.
Parameters
- eEnvRenderer
Environment renderer object.
- render_both_lines(e: EnvRenderer) None
Render both the centerline and raceline.
This is a convenience method that renders both the centerline (green) and raceline (red).
Parameters
- eEnvRenderer
Environment renderer object.
- render_arc_length_annotations(e: EnvRenderer, interval: float = 5.0, point_color: tuple[int, int, int] = (255, 165, 0), text_color: tuple[int, int, int] = (255, 165, 0), point_size: int = 6, font_size: int = 10) None
Render arc length annotations along the centerline at specified intervals.
Shows arc length values (s in Frenet coordinates) at regular intervals to help identify positions along the track.
Parameters
- eEnvRenderer
Environment renderer object.
- intervalfloat, optional
Distance interval between annotations in meters, by default 5.0
- point_colortuple[int, int, int], optional
RGB color for annotation points, by default orange (255, 165, 0)
- text_colortuple[int, int, int], optional
RGB color for text labels, by default orange (255, 165, 0)
- point_sizeint, optional
Size of annotation points in pixels, by default 6
- font_sizeint, optional
Font size for text labels, by default 10
- render_frenet_projection(e: EnvRenderer, vehicle_color: tuple[int, int, int] = (255, 0, 255), projected_color: tuple[int, int, int] = (0, 255, 255), line_color: tuple[int, int, int] = (255, 128, 0), size: int = 8) None
Render debug visualization of Frenet coordinate projection.
Shows: - Vehicle position (magenta) - Projected point on centerline (cyan) - Line connecting them (orange)
This helps diagnose if cartesian_to_frenet is finding the correct closest point.
Parameters
- eEnvRenderer
Environment renderer object
- vehicle_colortuple[int, int, int]
RGB color for vehicle position marker
- projected_colortuple[int, int, int]
RGB color for projected point marker
- line_colortuple[int, int, int]
RGB color for connection line
- sizeint
Size of rendered points in pixels
- render_lookahead_curvatures(e: EnvRenderer, vehicle_s: float, n_points: int, ds: float, color: tuple[int, int, int] = (0, 0, 255), size: int = 6) None
Render lookahead curvature sampling points ahead of vehicle.
Visualizes the points where curvature is sampled for drift control, matching the behavior of sample_lookahead_curvatures() in observation.py.
Parameters
- eEnvRenderer
Environment renderer object
- vehicle_sfloat
Current arc length position of vehicle on centerline (meters)
- n_pointsint, optional
Number of lookahead points to render (default 10)
- dsfloat, optional
Spacing between points in meters (default 0.3m = 30cm)
- colortuple[int, int, int], optional
RGB color tuple for points (default yellow: (255, 255, 0))
- sizeint, optional
Size of rendered points in pixels (default 4)
Notes
Points are sampled starting at (vehicle_s + ds), not at current position
For closed tracks, sampling wraps around using modulo arithmetic
Requires centerline with valid spline to be initialized
- class gymkhana.envs.track.raceline.Raceline(xs: ndarray, ys: ndarray, velxs: ndarray, ss: ndarray | None = None, psis: ndarray | None = None, kappas: ndarray | None = None, accxs: ndarray | None = None, spline: CubicSpline2D | None = None, w_lefts: ndarray | None = None, w_rights: ndarray | None = None)
Raceline object.
Attributes
- nint
number of waypoints
- ssnp.ndarray
arclength along the raceline
- xsnp.ndarray
x-coordinates of the waypoints
- ysnp.ndarray
y-coordinates of the waypoints
- yawsnp.ndarray
yaw angles of the waypoints
- ksnp.ndarray
curvature of the waypoints
- vxsnp.ndarray
velocity along the raceline
- axsnp.ndarray
acceleration along the raceline
- w_leftsnp.ndarray
left track width at each waypoint
- w_rightsnp.ndarray
right track width at each waypoint
- lengthfloat
length of the raceline
- splineCubicSpline2D
spline object through the waypoints
- static from_centerline_file(filepath: Path, delimiter: str | None = ',', fixed_speed: float | None = 1.0, track_scale: float | None = 1.0)
Load raceline from a centerline file.
Parameters
- filepathpathlib.Path
path to the centerline file
- delimiterstr, optional
delimiter used in the file, by default “,”
- fixed_speedfloat, optional
fixed speed along the raceline, by default 1.0
- track_scalefloat, optional
scaling factor for the track, by default 1.0
Returns
- Raceline
raceline object
- static from_raceline_file(filepath: Path, delimiter: str = ';', track_scale: float | None = 1.0) Raceline
Load raceline from a raceline file.
Parameters
- filepathpathlib.Path
path to the raceline file
- delimiterstr, optional
delimiter used in the file, by default “;”
- track_scalefloat, optional
scaling factor for the track, by default 1.0
Returns
- Raceline
raceline object