Module Prediction

The CommonRoad XML-specification provides three possibilities to describe the movement of dynamic obstacles over time: known behavior, unknown behavior bounded by sets, and unknown behavior described by probability distributions. Known behaviour and unknown behavior bounded by sets are described by the class TrajectoryPrediction and SetBasedPrediction. Unknown behavior described by probability distributions is not supported in version 2024.1 and will be added in a future release.

Inheritance diagram of SetBasedPrediction, TrajectoryPrediction

Prediction class

class commonroad.prediction.prediction.Prediction[source]

Base class for a prediction module.

abstract property final_time_step: int | Interval

Final time step of the prediction.

abstract property initial_time_step: int

Initial time step of the prediction.

occupancy_at_time_step(time_step)[source]

Occupancy at a specific time step.

Parameters:

time_step (int) – discrete time step

Return type:

Optional[Occupancy]

Returns:

occupancy at time_step if time_step is within the time interval of the prediction; otherwise, None

abstract property occupancy_set: List[Occupancy]

List of occupancies over time.

TrajectoryPrediction class

class commonroad.prediction.prediction.TrajectoryPrediction(trajectory, shape, center_lanelet_assignment=None, shape_lanelet_assignment=None, **kwargs)[source]

Class to represent the predicted movement of an obstacle using a trajectory. A trajectory is modeled as a state sequence over time. The occupancy of an obstacle along a trajectory is uniquely defined given its shape.

property center_lanelet_assignment: None | Dict[int, Set[int]]

Predicted lanelet assignment of obstacle center.

property final_time_step: int | Interval

Final time step of the prediction.

property initial_time_step: int

Initial time step of the prediction.

occupancy_at_time_step(time_step)

Occupancy at a specific time step.

Parameters:

time_step (int) – discrete time step

Return type:

Optional[Occupancy]

Returns:

occupancy at time_step if time_step is within the time interval of the prediction; otherwise, None

property occupancy_set: List[Occupancy]

List of occupancies over time.

property shape: Shape

Shape of the predicted object.

property shape_lanelet_assignment: None | Dict[int, Set[int]]

Predicted lanelet assignment of obstacle shape.

property trajectory: Trajectory

Predicted trajectory of the object.

translate_rotate(translation, angle)[source]

Translates and rotates all states of the trajectory and re-computes the translated and rotated occupancy set.

Parameters:
  • translation (ndarray) – translation vector [x_off, y_off] in x- and y-direction

  • angle (float) – rotation angle in radian (counter-clockwise)

property wheelbase_lengths: List[float] | None

List of wheelbase lengths corresponding to the shape.

SetBasedPrediction class

class commonroad.prediction.prediction.SetBasedPrediction(initial_time_step, occupancy_set)[source]

Class to represent the future behavior of obstacles by bounded occupancy sets.

property final_time_step: int | Interval

Final time step of the prediction.

property initial_time_step: int

Initial time step of the prediction.

occupancy_at_time_step(time_step)

Occupancy at a specific time step.

Parameters:

time_step (int) – discrete time step

Return type:

Optional[Occupancy]

Returns:

occupancy at time_step if time_step is within the time interval of the prediction; otherwise, None

property occupancy_set: List[Occupancy]

List of occupancies over time.

translate_rotate(translation, angle)[source]

Translates and rotates the occupancy set.

Parameters:
  • translation (ndarray) – translation vector [x_off, y_off] in x- and y-direction

  • angle (float) – rotation angle in radian (counter-clockwise)

Occupancy class

class commonroad.prediction.prediction.Occupancy(time_step, shape)[source]

Class describing an occupied area in the position domain. The occupied area can be defined for a certain time step or a time interval.

draw(renderer, draw_params=None)[source]

Draw the object

Parameters:
  • renderer (IRenderer) – Renderer to use for drawing

  • draw_params (Optional[OccupancyParams]) – optional parameters for plotting, overriding the parameters of the renderer

Returns:

None

property shape: Shape | Rectangle | Circle | Polygon | ShapeGroup

Shape representing an occupied area in the position domain.

property time_step: int | Interval

The occupied area is either defined for a certain time step or a time interval.

translate_rotate(translation, angle)[source]

Translates and rotates the occupied area.

Parameters:
  • translation (ndarray) – translation vector [x_off, y_off] in x- and y-direction

  • angle (float) – rotation angle in radian (counter-clockwise)

Predictor Interface

PredictorInterface class

class commonroad.prediction.prediction_interface.PredictorInterface[source]

Base class for prediction.

predict(sc, initial_time_step=0)[source]

Abstract method for performing predictions.

Parameters:
  • sc (Scenario) – Scenario containing no predictions for obstacles.

  • initial_time_step (int) – Time step to start prediction.

Return type:

Scenario

Returns:

CommonRoad scenario containing predictions.