Ego Vehicle State

Ego State in SE(2)

class py123d.datatypes.vehicle_state.EgoStateSE2[source]

The EgoStateSE2 represents the state of the ego vehicle in SE2 (2D space). It includes the rear axle pose, vehicle parameters, optional dynamic state, and optional timepoint.

Public Data Attributes:

rear_axle_se2

The PoseSE2 of the rear axle in SE2.

vehicle_parameters

The VehicleParameters of the vehicle.

dynamic_state_se2

The DynamicStateSE2 of the vehicle.

timepoint

The TimePoint of the ego state, if available.

tire_steering_angle

The tire steering angle of the ego state, if available.

center_se2

The PoseSE2 of the center in SE2.

bounding_box_se2

The BoundingBoxSE2 of the ego vehicle.

box_detection_se2

The BoxDetectionSE2 projection of the ego vehicle.

Public Methods:

from_rear_axle(rear_axle_se2, ...[, ...])

Create an EgoStateSE2 from the rear axle pose.

from_center(center_se2, dynamic_state_se2, ...)

Create an EgoStateSE2 from the center pose.


classmethod from_rear_axle(rear_axle_se2, dynamic_state_se2, vehicle_parameters, timepoint, tire_steering_angle=0.0)[source]

Create an EgoStateSE2 from the rear axle pose.

Parameters:
  • rear_axle_se2 (PoseSE2) – The pose of the rear axle in SE2.

  • dynamic_state_se2 (DynamicStateSE2) – The dynamic state of the vehicle in SE2.

  • vehicle_parameters (VehicleParameters) – The parameters of the vehicle.

  • timepoint (TimePoint) – The timepoint of the state.

  • tire_steering_angle (float) – The tire steering angle, defaults to 0.0.

Return type:

EgoStateSE2

Returns:

An instance of EgoStateSE2.

classmethod from_center(center_se2, dynamic_state_se2, vehicle_parameters, timepoint, tire_steering_angle=0.0)[source]

Create an EgoStateSE2 from the center pose.

Parameters:
  • center_se2 (PoseSE2) – The pose of the center in SE2.

  • dynamic_state_se2 (DynamicStateSE2) – The dynamic state of the vehicle in SE2.

  • vehicle_parameters (VehicleParameters) – The parameters of the vehicle.

  • timepoint (TimePoint) – The timepoint of the state.

  • tire_steering_angle (float) – The tire steering angle, defaults to 0.0.

Return type:

EgoStateSE2

Returns:

An instance of EgoStateSE2.

property rear_axle_se2: PoseSE2

The PoseSE2 of the rear axle in SE2.

property vehicle_parameters: VehicleParameters

The VehicleParameters of the vehicle.

property dynamic_state_se2: DynamicStateSE2 | None

The DynamicStateSE2 of the vehicle.

property timepoint: TimePoint | None

The TimePoint of the ego state, if available.

property tire_steering_angle: float | None

The tire steering angle of the ego state, if available.

property center_se2: PoseSE2

The PoseSE2 of the center in SE2.

property bounding_box_se2: BoundingBoxSE2

The BoundingBoxSE2 of the ego vehicle.

property box_detection_se2: BoxDetectionSE2

The BoxDetectionSE2 projection of the ego vehicle.

Ego State in SE(3)

class py123d.datatypes.vehicle_state.EgoStateSE3[source]

The EgoStateSE3 represents the state of the ego vehicle in SE3 (3D space). It includes the rear axle pose, vehicle parameters, optional dynamic state, optional timepoint, and optional tire steering angle.

Public Data Attributes:

rear_axle_se3

The PoseSE3 of the rear axle in SE3.

rear_axle_se2

The PoseSE2 of the rear axle in SE2.

vehicle_parameters

The VehicleParameters of the vehicle.

dynamic_state_se3

The DynamicStateSE3 of the vehicle.

timepoint

The TimePoint of the ego state, if available.

tire_steering_angle

The tire steering angle of the ego state, if available.

center_se3

The PoseSE3 of the vehicle center in SE3.

center_se2

The PoseSE2 of the vehicle center in SE2.

bounding_box_se3

The BoundingBoxSE3 of the ego vehicle.

bounding_box_se2

The BoundingBoxSE2 of the ego vehicle.

box_detection_se3

The BoxDetectionSE3 projection of the ego vehicle.

box_detection_se2

The BoxDetectionSE2 projection of the ego vehicle.

ego_state_se2

The EgoStateSE2 projection of this SE3 ego state.

Public Methods:

from_center(center_se3, vehicle_parameters)

Create an EgoStateSE3 from the center pose.

from_rear_axle(rear_axle_se3, vehicle_parameters)

Create an EgoStateSE3 from the rear axle pose.


classmethod from_center(center_se3, vehicle_parameters, dynamic_state_se3=None, timepoint=None, tire_steering_angle=0.0)[source]

Create an EgoStateSE3 from the center pose.

Parameters:
  • center_se3 (PoseSE3) – The center pose in SE3.

  • vehicle_parameters (VehicleParameters) – The parameters of the vehicle.

  • dynamic_state_se3 (Optional[DynamicStateSE3]) – The dynamic state of the vehicle, defaults to None.

  • timepoint (Optional[TimePoint]) – The timepoint of the state, defaults to None.

  • tire_steering_angle (float) – The tire steering angle, defaults to 0.0.

Return type:

EgoStateSE3

Returns:

An EgoStateSE3 instance.

classmethod from_rear_axle(rear_axle_se3, vehicle_parameters, dynamic_state_se3=None, timepoint=None, tire_steering_angle=0.0)[source]

Create an EgoStateSE3 from the rear axle pose.

Parameters:
  • rear_axle_se3 (PoseSE3) – The pose of the rear axle in SE3.

  • vehicle_parameters (VehicleParameters) – The parameters of the vehicle.

  • dynamic_state_se3 (Optional[DynamicStateSE3]) – The dynamic state of the vehicle, defaults to None.

  • timepoint (Optional[TimePoint]) – The timepoint of the state, defaults to None.

  • tire_steering_angle (float) – The tire steering angle, defaults to 0.0.

Return type:

EgoStateSE3

Returns:

An EgoStateSE3 instance.

property rear_axle_se3: PoseSE3

The PoseSE3 of the rear axle in SE3.

property rear_axle_se2: PoseSE2

The PoseSE2 of the rear axle in SE2.

property vehicle_parameters: VehicleParameters

The VehicleParameters of the vehicle.

property dynamic_state_se3: DynamicStateSE3 | None

The DynamicStateSE3 of the vehicle.

property timepoint: TimePoint | None

The TimePoint of the ego state, if available.

property tire_steering_angle: float | None

The tire steering angle of the ego state, if available.

property center_se3: PoseSE3

The PoseSE3 of the vehicle center in SE3.

property center_se2: PoseSE2

The PoseSE2 of the vehicle center in SE2.

property bounding_box_se3: BoundingBoxSE3

The BoundingBoxSE3 of the ego vehicle.

property bounding_box_se2: BoundingBoxSE2

The BoundingBoxSE2 of the ego vehicle.

property box_detection_se3: BoxDetectionSE3

The BoxDetectionSE3 projection of the ego vehicle.

property box_detection_se2: BoxDetectionSE2

The BoxDetectionSE2 projection of the ego vehicle.

property ego_state_se2: EgoStateSE2

The EgoStateSE2 projection of this SE3 ego state.