Ego Vehicle State¶
Ego State in SE(2)¶
- class py123d.datatypes.EgoStateSE2[source]¶
The EgoStateSE2 represents the state of the ego vehicle in SE2 (2D space).
The IMU pose is the primary internal representation. Rear axle and center poses are computed on demand via the ego metadata.
Public Data Attributes:
imu_se2The
PoseSE2of the IMU in SE2.rear_axle_se2The
PoseSE2of the rear axle in SE2.metadataThe
EgoStateSE3Metadataof the vehicle.timestampThe
Timestampof the ego statedynamic_state_se2The
DynamicStateSE2of the vehicle.tire_steering_angleThe tire steering angle of the ego state, if available.
center_se2The
PoseSE2of the center in SE2.bounding_box_se2The
BoundingBoxSE2of the ego vehicle.box_detection_se2The
BoxDetectionSE2projection of the ego vehicle.Public Methods:
from_imu(imu_se2, metadata, timestamp[, ...])Create an
EgoStateSE2from the IMU pose.from_rear_axle(rear_axle_se2, metadata, ...)Create an
EgoStateSE2from the rear axle pose.from_center(center_se2, metadata, timestamp)Create an
EgoStateSE2from the center pose.
- classmethod from_imu(imu_se2, metadata, timestamp, dynamic_state_se2=None, tire_steering_angle=0.0)[source]¶
Create an
EgoStateSE2from the IMU pose.This is the canonical factory method. The IMU pose is stored directly.
- Parameters:
imu_se2 (
PoseSE2) – The pose of the IMU in the global frame (SE2).metadata (
EgoStateSE3Metadata) – The ego metadata of the vehicle.timestamp (
Timestamp) – The timestamp of the state.dynamic_state_se2 (
Optional[DynamicStateSE2]) – The dynamic state of the vehicle in SE2, defaults to None.tire_steering_angle (
float) – The tire steering angle, defaults to 0.0.
- Return type:
- Returns:
An instance of
EgoStateSE2.
- classmethod from_rear_axle(rear_axle_se2, metadata, timestamp, dynamic_state_se2=None, tire_steering_angle=0.0)[source]¶
Create an
EgoStateSE2from the rear axle pose.Converts the rear axle pose to the IMU pose using the vehicle’s
rear_axle_to_imu_se3extrinsic calibration.- Parameters:
rear_axle_se2 (
PoseSE2) – The pose of the rear axle in SE2.metadata (
EgoStateSE3Metadata) – The ego metadata of the vehicle.timestamp (
Timestamp) – The timestamp of the state.dynamic_state_se2 (
Optional[DynamicStateSE2]) – The dynamic state of the vehicle in SE2, defaults to None.tire_steering_angle (
float) – The tire steering angle, defaults to 0.0.
- Return type:
- Returns:
An instance of
EgoStateSE2.
- classmethod from_center(center_se2, metadata, timestamp, dynamic_state_se2=None, tire_steering_angle=0.0)[source]¶
Create an
EgoStateSE2from the center pose.Converts the center pose to the IMU pose using the vehicle’s
center_to_imu_se3extrinsic calibration.- Parameters:
center_se2 (
PoseSE2) – The pose of the center in SE2.metadata (
EgoStateSE3Metadata) – The ego metadata of the vehicle.timestamp (
Timestamp) – The timestamp of the state.dynamic_state_se2 (
Optional[DynamicStateSE2]) – The dynamic state of the vehicle in SE2, defaults to None.tire_steering_angle (
float) – The tire steering angle, defaults to 0.0.
- Return type:
- Returns:
An instance of
EgoStateSE2.
- property metadata: EgoStateSE3Metadata¶
The
EgoStateSE3Metadataof the vehicle.
- property dynamic_state_se2: DynamicStateSE2 | None¶
The
DynamicStateSE2of the vehicle.
- property bounding_box_se2: BoundingBoxSE2¶
The
BoundingBoxSE2of the ego vehicle.
- property box_detection_se2: BoxDetectionSE2¶
The
BoxDetectionSE2projection of the ego vehicle.
Ego State in SE(3)¶
- class py123d.datatypes.EgoStateSE3[source]¶
The EgoStateSE3 represents the state of the ego vehicle in SE3 (3D space).
The IMU pose is the primary internal representation. Rear axle, center, and SE2 poses are computed on demand via the ego metadata.
Public Data Attributes:
imu_se3The
PoseSE3of the IMU in SE3.imu_se2The
PoseSE2of the IMU in SE2.rear_axle_se3The
PoseSE3of the rear axle in SE3.rear_axle_se2The
PoseSE2of the rear axle in SE2.metadataThe
EgoStateSE3Metadataof the vehicle.dynamic_state_se3The
DynamicStateSE3of the vehicle.timestampThe
Timestampof the ego state.tire_steering_angleThe tire steering angle of the ego state, if available.
center_se3The
PoseSE3of the vehicle center in SE3.center_se2The
PoseSE2of the vehicle center in SE2.bounding_box_se3The
BoundingBoxSE3of the ego vehicle.bounding_box_se2The
BoundingBoxSE2of the ego vehicle.box_detection_se3The
BoxDetectionSE3projection of the ego vehicle.box_detection_se2The
BoxDetectionSE2projection of the ego vehicle.ego_state_se2The
EgoStateSE2projection of this SE3 ego state.Inherited from
BaseModalitytimestampReturns the timestamp associated with this modality data, if available.
metadataReturns the metadata associated with this modality data.
modality_typeConvenience property to access the modality type directly from the modality data.
modality_idConvenience property to access the modality id directly from the modality data.
modality_keyConvenience property to access the modality key directly from the modality data.
Public Methods:
from_imu(imu_se3, metadata, timestamp[, ...])Create an
EgoStateSE3from the IMU pose.from_rear_axle(rear_axle_se3, metadata, ...)Create an
EgoStateSE3from the rear axle pose.from_center(center_se3, metadata, timestamp)Create an
EgoStateSE3from the center pose.
- classmethod from_imu(imu_se3, metadata, timestamp, dynamic_state_se3=None, tire_steering_angle=0.0)[source]¶
Create an
EgoStateSE3from the IMU pose.This is the canonical factory method. The IMU pose is stored directly.
- Parameters:
imu_se3 (
PoseSE3) – The pose of the IMU in the global frame.metadata (
EgoStateSE3Metadata) – The ego metadata of the vehicle.timestamp (
Timestamp) – The timestamp of the state.dynamic_state_se3 (
Optional[DynamicStateSE3]) – The dynamic state of the vehicle, defaults to None.tire_steering_angle (
float) – The tire steering angle, defaults to 0.0.
- Return type:
- Returns:
An
EgoStateSE3instance.
- classmethod from_rear_axle(rear_axle_se3, metadata, timestamp, dynamic_state_se3=None, tire_steering_angle=0.0)[source]¶
Create an
EgoStateSE3from the rear axle pose.Converts the rear axle pose to the IMU pose using the vehicle’s
rear_axle_to_imu_se3extrinsic calibration.- Parameters:
rear_axle_se3 (
PoseSE3) – The pose of the rear axle in SE3.metadata (
EgoStateSE3Metadata) – The ego metadata of the vehicle.timestamp (
Timestamp) – The timestamp of the statedynamic_state_se3 (
Optional[DynamicStateSE3]) – The dynamic state of the vehicle in ego frame, defaults to None.tire_steering_angle (
float) – The tire steering angle, defaults to 0.0.
- Return type:
- Returns:
An
EgoStateSE3instance.
- classmethod from_center(center_se3, metadata, timestamp, dynamic_state_se3=None, tire_steering_angle=0.0)[source]¶
Create an
EgoStateSE3from the center pose.Converts the center pose to the IMU pose using the vehicle’s
center_to_imu_se3extrinsic calibration.- Parameters:
center_se3 (
PoseSE3) – The center pose in SE3.metadata (
EgoStateSE3Metadata) – The ego metadata of the vehicle.timestamp (
Timestamp) – The timestamp of the state.dynamic_state_se3 (
Optional[DynamicStateSE3]) – The dynamic state of the vehicle in ego frame, defaults to None.tire_steering_angle (
float) – The tire steering angle, defaults to 0.0.
- Return type:
- Returns:
An
EgoStateSE3instance.
- property metadata: EgoStateSE3Metadata¶
The
EgoStateSE3Metadataof the vehicle.
- property dynamic_state_se3: DynamicStateSE3 | None¶
The
DynamicStateSE3of the vehicle.
- property bounding_box_se3: BoundingBoxSE3¶
The
BoundingBoxSE3of the ego vehicle.
- property bounding_box_se2: BoundingBoxSE2¶
The
BoundingBoxSE2of the ego vehicle.
- property box_detection_se3: BoxDetectionSE3¶
The
BoxDetectionSE3projection of the ego vehicle.
- property box_detection_se2: BoxDetectionSE2¶
The
BoxDetectionSE2projection of the ego vehicle.
- property ego_state_se2: EgoStateSE2¶
The
EgoStateSE2projection of this SE3 ego state.
- property modality_id: str | SerialIntEnum | None¶
Convenience property to access the modality id directly from the modality data.
- property modality_key: str¶
Convenience property to access the modality key directly from the modality data.
- property modality_type: ModalityType¶
Convenience property to access the modality type directly from the modality data.