smarts.core.observations module

class smarts.core.observations.CustomRenderData(metadata: GridMapMetadata, data: np.ndarray)[source]

Describes information about a custom render.

data: ndarray

The image data from the render.

metadata: GridMapMetadata

Render metadata.

class smarts.core.observations.DrivableAreaGridMap(metadata: GridMapMetadata, data: np.ndarray)[source]

Drivable area map.

data: ndarray

A grid map that shows the static drivable area around the ego vehicle.

metadata: GridMapMetadata

Map metadata.

class smarts.core.observations.EgoVehicleObservation(id: str, position: Tuple[float, float, float], bounding_box: Dimensions, heading: Heading, speed: float, steering: float, yaw_rate: float, road_id: str, lane_id: str, lane_index: int, mission: plan.NavigationMission, linear_velocity: Tuple[float, float, float], angular_velocity: Tuple[float, float, float], linear_acceleration: Tuple[float, float, float] | None, angular_acceleration: Tuple[float, float, float] | None, linear_jerk: Tuple[float, float, float] | None, angular_jerk: Tuple[float, float, float] | None, lane_position: RefLinePoint | None = None)[source]

Perceived ego vehicle information.

angular_acceleration: Tuple[float, float, float] | None

Acceleration of vehicle-heading rotation about the z-axis. Units=rad/s^2. Requires accelerometer sensor.

angular_jerk: Tuple[float, float, float] | None

Jerk of vehicle-heading rotation about the z-axis. Units=rad/s^3. Requires accelerometer sensor.

angular_velocity: Tuple[float, float, float]

Velocity of vehicle-heading rotation about the z-axis. Equivalent vector representation of yaw_rate. Units=rad/s.

bounding_box: Dimensions

Bounding box describing the length, width, and height, of the vehicle.

heading: Heading

Facing direction of the vehicle. Units=rad.

id: str

Vehicle identifier.

lane_id: str

Identifier for the lane nearest to this vehicle.

lane_index: int

Index of the nearest lane on the road nearest to this vehicle. Right most lane has index 0 and index increments to the left.

lane_position: RefLinePoint | None

(s,t,h) coordinates within the lane, where s is the longitudinal offset along the lane, t is the lateral displacement from the lane center, and h (not yet supported) is the vertical displacement from the lane surface. See the Reference Line coordinate system in OpenDRIVE here: https://www.asam.net/index.php?eID=dumpFile&t=f&f=4089&token=deea5d707e2d0edeeb4fccd544a973de4bc46a09#_coordinate_systems

linear_acceleration: Tuple[float, float, float] | None

Acceleration of vehicle along the global coordinate axes. Units=m/s^2. Requires accelerometer sensor.

linear_jerk: Tuple[float, float, float] | None

Jerk of vehicle along the global coordinate axes. Units=m/s^3. Requires accelerometer sensor.

linear_velocity: Tuple[float, float, float]

Velocity of vehicle along the global coordinate axes. Units=m/s.

mission: plan.NavigationMission

Vehicle’s desired destination.

position: Tuple[float, float, float]

Center coordinate of the vehicle bounding box’s bottom plane.

road_id: str

Identifier for the road nearest to this vehicle.

speed: float

Travel speed in the direction of the vehicle. Units=m/s.

steering: float

Angle of front wheels in radians between [-pi, pi].

yaw_rate: float

Speed of vehicle-heading rotation about the z-axis. Equivalent scalar representation of angular_velocity. Units=rad/s.

class smarts.core.observations.GridMapMetadata(resolution: float, width: int, height: int, camera_position: Tuple[float, float, float], camera_heading: float)[source]

Map grid metadata.

camera_heading: float

Camera rotation angle along z-axis when projected onto the map.

camera_position: Tuple[float, float, float]

Camera position when projected onto the map.

height: int

Map height in # of cells.

resolution: float

Map resolution in world-space-distance/cell.

width: int

Map width in # of cells.

class smarts.core.observations.Observation(dt: float, step_count: int, steps_completed: int, elapsed_sim_time: float, events: Events, ego_vehicle_state: EgoVehicleObservation, under_this_agent_control: bool, neighborhood_vehicle_states: Tuple[VehicleObservation] | None, waypoint_paths: List[List[Waypoint]] | None, distance_travelled: float, road_waypoints: RoadWaypoints | None, via_data: Vias, lidar_point_cloud: Tuple[List[np.ndarray], List[bool], List[Tuple[np.ndarray, np.ndarray]]] | None = None, drivable_area_grid_map: DrivableAreaGridMap | None = None, occupancy_grid_map: OccupancyGridMap | None = None, top_down_rgb: TopDownRGB | None = None, signals: Tuple[SignalObservation] | None = None, occlusion_map: OcclusionRender | None = None, custom_renders: Tuple[CustomRenderData, ...] = ())[source]

The simulation observation.

custom_renders: Tuple[CustomRenderData, ...]

Custom renders.

distance_travelled: float

Road distance driven by the vehicle.

drivable_area_grid_map: DrivableAreaGridMap | None

Drivable area map.

dt: float

Amount of simulation time the last step took.

ego_vehicle_state: EgoVehicleObservation

Ego vehicle status.

elapsed_sim_time: float

Amount of simulation time elapsed for the current scenario.

events: Events

Classified observations that can trigger agent done status.

lidar_point_cloud: Tuple[List[np.ndarray], List[bool], List[Tuple[np.ndarray, np.ndarray]]] | None

Lidar point cloud consisting of [points, hits, (ray_origin, ray_vector)]. Points missed (i.e., not hit) have inf value.

neighborhood_vehicle_states: Tuple[VehicleObservation] | None

List of neighborhood vehicle states.

occlusion_map: OcclusionRender | None

Observable area map.

occupancy_grid_map: OccupancyGridMap | None

Occupancy map.

road_waypoints: RoadWaypoints | None

Per-road waypoints information.

signals: Tuple[SignalObservation] | None

List of nearby traffic signal (light) states on this time-step.

step_count: int

Number of steps taken by SMARTS thus far in the current scenario.

steps_completed: int

Number of steps this agent has taken within SMARTS.

top_down_rgb: TopDownRGB | None

RGB camera observation.

under_this_agent_control: bool

Whether this agent currently has control of the vehicle.

via_data: Vias

Listing of nearby collectible ViaPoints and ViaPoints collected in the last step.

waypoint_paths: List[List[Waypoint]] | None

Dynamic evenly-spaced points on the road ahead of the vehicle, showing potential routes ahead.

class smarts.core.observations.OcclusionRender(metadata: GridMapMetadata, data: np.ndarray)[source]

Occlusion map.

data: ndarray

A map showing what is visible from the ego vehicle

metadata: GridMapMetadata

Map metadata.

class smarts.core.observations.OccupancyGridMap(metadata: GridMapMetadata, data: np.ndarray)[source]

Occupancy map.

data: ndarray

An occupancy grid map around the ego vehicle.

See https://en.wikipedia.org/wiki/Occupancy_grid_mapping.

metadata: GridMapMetadata

Map metadata.

class smarts.core.observations.RoadWaypoints(lanes: Dict[str, List[List[Waypoint]]])[source]

Per-road waypoint information.

lanes: Dict[str, List[List[Waypoint]]]

Mapping of road ids to their lane waypoints.

class smarts.core.observations.SignalObservation(state: signals.SignalLightState, stop_point: Point, controlled_lanes: Tuple[str], last_changed: float | None)[source]

Describes an observation of a traffic signal (light) on this time-step.

controlled_lanes: Tuple[str]

If known, the lane_ids of all lanes controlled-by this signal. May be empty if this is not easy to determine.

last_changed: float | None

If known, the simulation time this signal last changed its state.

state: signals.SignalLightState

The state of the traffic signal.

stop_point: Point

The stopping point for traffic controlled by the signal, i.e., the point where actors should stop when the signal is in a stop state.

class smarts.core.observations.TopDownRGB(metadata: GridMapMetadata, data: np.ndarray)[source]

RGB camera observation.

data: ndarray

A RGB image with the ego vehicle at the center.

metadata: GridMapMetadata

Map metadata.

class smarts.core.observations.VehicleObservation(id: str, position: Tuple[float, float, float], bounding_box: Dimensions, heading: Heading, speed: float, road_id: str, lane_id: str, lane_index: int, lane_position: RefLinePoint | None = None, interest: bool = False)[source]

Perceived vehicle information.

bounding_box: Dimensions

A bounding box describing the extents of the vehicle.

heading: Heading

The facing direction of the vehicle.

id: str

The vehicle identifier.

interest: bool

If this vehicle is of interest in the current scenario.

lane_id: str

The identifier for the lane nearest to this vehicle.

lane_index: int

The index of the nearest lane on the road nearest to this vehicle.

lane_position: RefLinePoint | None

(s,t,h) coordinates within the lane, where s is the longitudinal offset along the lane, t is the lateral displacement from the lane center, and h (not yet supported) is the vertical displacement from the lane surface. See the Reference Line coordinate system in OpenDRIVE here: https://www.asam.net/index.php?eID=dumpFile&t=f&f=4089&token=deea5d707e2d0edeeb4fccd544a973de4bc46a09#_coordinate_systems

position: Tuple[float, float, float]

The position of the vehicle within the simulation.

road_id: str

The identifier for the road nearest to this vehicle.

speed: float

The travel m/s in the direction of the vehicle.

class smarts.core.observations.ViaPoint(position: Tuple[float, float], lane_index: float, road_id: str, required_speed: float, hit: bool)[source]

‘Collectibles’ that can be placed within the simulation.

hit: bool

If this via point was hit in the last step.

lane_index: float

Lane index on the road this collectible is associated with.

position: Tuple[float, float]

Location (x,y) of this collectible.

required_speed: float

Approximate speed required to collect this collectible.

road_id: str

Road id this collectible is associated with.

class smarts.core.observations.Vias(near_via_points: Tuple[ViaPoint])[source]

Listing of nearby collectible ViaPoints and ViaPoints collected in the last step.

property hit_via_points: Tuple[ViaPoint]

List of points that were hit in the previous step.

near_via_points: Tuple[ViaPoint]

Ordered list of nearby points that have not been hit.