Box Detections¶
- class py123d.datatypes.detections.BoxDetectionWrapper[source]¶
The BoxDetectionWrapper is a container for multiple box detections. It provides methods to access individual detections as well as to retrieve a detection by track token. The wrapper is used to read and write box detections from/to logs.
Public Data Attributes:
box_detectionsList of individual
BoxDetectionSE2orBoxDetectionSE3.Public Methods:
get_detection_by_track_token(track_token)Retrieve a box detection by its track token.
occupancy_map_2dThe
OccupancyMap2Drepresenting the 2D occupancy of all box detections.
- property box_detections: List[BoxDetectionSE2 | BoxDetectionSE3]¶
List of individual
BoxDetectionSE2orBoxDetectionSE3.
- get_detection_by_track_token(track_token)[source]¶
Retrieve a box detection by its track token.
- Parameters:
track_token (
str) – The track token of the box detection.- Return type:
Union[BoxDetectionSE2,BoxDetectionSE3,None]- Returns:
The box detection with the given track token, or None if not found.
- property occupancy_map_2d: OccupancyMap2D¶
The
OccupancyMap2Drepresenting the 2D occupancy of all box detections.
- class py123d.datatypes.detections.BoxDetectionMetadata[source]¶
Stores data about the box detection, including its label, track token, number of LiDAR points, and timepoint.
Public Data Attributes:
labelThe
BoxDetectionLabel, from the original dataset's label set.track_tokenThe unique track token of the detection, consistent across frames.
num_lidar_pointsOptionally, the number of LiDAR points associated with the detection.
timepointOptionally, the
TimePointof the detection.default_labelThe unified
DefaultBoxDetectionLabelcorresponding to the detection's label.
- property label: BoxDetectionLabel¶
The
BoxDetectionLabel, from the original dataset’s label set.
- property num_lidar_points: int | None¶
Optionally, the number of LiDAR points associated with the detection.
- property default_label: DefaultBoxDetectionLabel¶
The unified
DefaultBoxDetectionLabelcorresponding to the detection’s label.
- class py123d.datatypes.detections.BoxDetectionSE2[source]¶
Detected, tracked, and oriented bounding box 2D space.
Public Data Attributes:
metadataThe
BoxDetectionMetadataof the detection.bounding_box_se2The
BoundingBoxSE2of the detection.velocity_2dThe
Vector2Drepresenting the velocity.center_se2The
PoseSE2representing the center of the bounding box.shapely_polygonThe shapely polygon of the bounding box in 2D space.
box_detection_se2Returns self to maintain interface consistency.
- property metadata: BoxDetectionMetadata¶
The
BoxDetectionMetadataof the detection.
- property bounding_box_se2: BoundingBoxSE2¶
The
BoundingBoxSE2of the detection.
- property shapely_polygon: Polygon¶
The shapely polygon of the bounding box in 2D space.
- property box_detection_se2: BoxDetectionSE2¶
Returns self to maintain interface consistency.
- class py123d.datatypes.detections.BoxDetectionSE3[source]¶
Detected, tracked, and oriented bounding box 3D space.
Public Data Attributes:
metadataThe
BoxDetectionMetadataof the detection.bounding_box_se3The
BoundingBoxSE3of the detection.bounding_box_se2The SE2 projection
BoundingBoxSE2of the SE3 bounding box.velocity_3dThe
Vector3Drepresenting the velocity.velocity_2dThe 2D projection
Vector2Dof the 3D velocity.center_se3The
PoseSE3representing the center of the bounding box.center_se2The
PoseSE2representing the center of the SE2 bounding box.box_detection_se2The
BoxDetectionSE2projection of this SE3 box detection.shapely_polygonThe shapely polygon of the bounding box in 2D space.
- property metadata: BoxDetectionMetadata¶
The
BoxDetectionMetadataof the detection.
- property bounding_box_se3: BoundingBoxSE3¶
The
BoundingBoxSE3of the detection.
- property bounding_box_se2: BoundingBoxSE2¶
The SE2 projection
BoundingBoxSE2of the SE3 bounding box.
- property box_detection_se2: BoxDetectionSE2¶
The
BoxDetectionSE2projection of this SE3 box detection.
- property shapely_polygon: Polygon¶
The shapely polygon of the bounding box in 2D space.