Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions tools/auto_labeling_3d/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,9 @@ RUN git clone -b ${perception_dataset_version} ${perception_dataset_url} \
WORKDIR /workspace
COPY projects projects

## Setup Auto Labeling 3D
RUN pip install polars

## Setup CenterPoint
ENV CUBLAS_WORKSPACE_CONFIG=:4096:8

Expand Down
26 changes: 16 additions & 10 deletions tools/auto_labeling_3d/attach_tracking_id/mot.py
Original file line number Diff line number Diff line change
Expand Up @@ -166,6 +166,7 @@ def _transform_pred_instance_to_global_t4box(
# [vx, vy, vz]
velocity: Tuple[float] = (*velocity, np.float64(0.0))

# T4Box3D validates unix_time as int; the tracker keeps the precise float timestamp separately.
box = T4Box3D(
unix_time=int(timestamp),
frame_id="base_link",
Expand Down Expand Up @@ -231,7 +232,7 @@ class KalmanBoxTracker:

count: int = 0

def __init__(self, t4box3d: T4Box3D, class_params=CLASS_PARAMS):
def __init__(self, t4box3d: T4Box3D, timestamp: float, class_params=CLASS_PARAMS):
"""
Initialize Kalman filter with class-specific parameters.

Expand All @@ -246,8 +247,8 @@ def __init__(self, t4box3d: T4Box3D, class_params=CLASS_PARAMS):
"""
self.kf = KalmanFilter(dim_x=4, dim_z=4)

self.prev_timestamp: float = t4box3d.unix_time
self.latest_timestamp: float = t4box3d.unix_time
self.prev_timestamp: float = float(timestamp)
self.latest_timestamp: float = float(timestamp)
self.id: str = t4box3d.uuid

# Measurement matrix (identity matrix for direct state observation). States are x,y,vx,vy
Expand Down Expand Up @@ -298,7 +299,7 @@ def predict(self, timestamp: float) -> TrackedBox2D:
tracked_box = TrackedBox2D(position_xy=self.kf.x[:2].reshape((2,)), class_name=self.class_name)
return tracked_box

def update(self, t4box3d: T4Box3D):
def update(self, t4box3d: T4Box3D, timestamp: float):
"""
Update state with new measurement.

Expand All @@ -313,7 +314,7 @@ def update(self, t4box3d: T4Box3D):
# Update Kalman filter with new measurement
self.kf.update(np.concatenate([t4box3d.position[:2], t4box3d.velocity[:2]]).reshape((4, 1)))

self.prev_timestamp = t4box3d.unix_time
self.prev_timestamp = float(timestamp)

def end_of_life(self):
"""Check if tracker should be terminated.
Expand Down Expand Up @@ -483,7 +484,12 @@ def _convert_pred_instance_to_global_t4boxes(

return instance_ids, bbox_list

def _add_new_tracker(self, bbox_list: List[T4Box3D], det_ids: Optional[Iterable[int]] = None):
def _add_new_tracker(
self,
bbox_list: List[T4Box3D],
timestamp: float,
det_ids: Optional[Iterable[int]] = None,
):
"""
Add new trackers for specified detections.

Expand All @@ -495,7 +501,7 @@ def _add_new_tracker(self, bbox_list: List[T4Box3D], det_ids: Optional[Iterable[
if det_ids is None:
det_ids = range(len(bbox_list))
for i in det_ids:
self.trackers.append(KalmanBoxTracker(bbox_list[i]))
self.trackers.append(KalmanBoxTracker(bbox_list[i], timestamp=timestamp))

def _remove_old_tracker(self):
"""Remove trackers that have exceeded their maximum age.
Expand Down Expand Up @@ -528,7 +534,7 @@ def frame_mot(self, pred_instances_3d: List[Dict[str, Any]], ego2global: NDArray

# Initialize new trackers for all detections if no existing trackers
if not len(self.trackers):
self._add_new_tracker(bbox_list)
self._add_new_tracker(bbox_list, timestamp=timestamp)
return instance_ids

# Get tracked_box_list from active trackers
Expand All @@ -538,13 +544,13 @@ def frame_mot(self, pred_instances_3d: List[Dict[str, Any]], ego2global: NDArray
valid_matches, unmatched_dets = associate_detections_to_tracks(bbox_list, tracked_box_list)

# For unmatched detections, add new trackes
self._add_new_tracker(bbox_list, unmatched_dets)
self._add_new_tracker(bbox_list, timestamp=timestamp, det_ids=unmatched_dets)

# Update matched trackers and instance IDs
for det_idx, trk_idx in valid_matches:
# Update matched tracker
trk = self.trackers[trk_idx]
trk.update(bbox_list[det_idx])
trk.update(bbox_list[det_idx], timestamp=timestamp)

# Update instance id
instance_ids[det_idx] = trk.id
Expand Down
22 changes: 11 additions & 11 deletions tools/auto_labeling_3d/entrypoint/configs/example.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -27,25 +27,25 @@ create_info:
# model_zoo_url: https://url/to/download/checkpoint.pth
- name: streampetr
model_config:
config_path: /workspace/projects/StreamPETR/configs/t4dataset/t4_base_vov_flash_480x640_baseline.py
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/streampetr/streampetr-vov99/t4base/v2.5/t4_base_vov_flash_480x640_baseline.py
config_path: /workspace/work_dirs/checkpoints/streampetr_2.5.0_config.py
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/streampetr/streampetr-vov99/t4base/v2.5/streampetr_2.5.0_auto_labeling_3d_config.py
checkpoint:
checkpoint_path: /workspace/work_dirs/checkpoints/streampetr_2.5.0_model.pth
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/streampetr/streampetr-vov99/t4base/v2.5/best_NuScenesmetric_T4Metric_mAP_epoch_34.pth
checkpoint_path: /workspace/work_dirs/checkpoints/example_model_streampetr.pth
- name: centerpoint
model_config:
config_path: /workspace/projects/CenterPoint/configs/t4dataset/Centerpoint/second_secfpn_4xb16_121m_j6gen2_base_amp_t4metric_v2.py
model_zoo_url:
config_path: /workspace/work_dirs/checkpoints/centerpoint_2.5.1_config.py
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/centerpoint/centerpoint/j6gen2/v2.5.1/centerpoint_2.5.1_auto_labeling_3d_config.py
checkpoint:
checkpoint_path: /workspace/work_dirs/checkpoints/example_model.pth
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/centerpoint/centerpoint/j6gen2/v2.3.1/best_NuScenes_metric_T4Metric_mAP_epoch_29.pth
checkpoint_path: /workspace/work_dirs/checkpoints/centerpoint_2.5.1_model.pth
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/centerpoint/centerpoint/j6gen2/v2.5.1/best_NuScenes%20metric_T4Metric_mAP_epoch_28.pth
- name: bevfusion
model_config:
config_path: /workspace/projects/BEVFusion/configs/t4dataset/BEVFusion-CL/bevfusion_camera_lidar_voxel_second_secfpn_4xb8_gen2_base.py
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/bevfusion/bevfusion-cl/t4base/v2.0.0/bevfusion_camera_lidar_voxel_second_secfpn_4xb8_base.py
config_path: /workspace/work_dirs/checkpoints/bevfusion_L_2.5.1_config.py
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/bevfusion/bevfusion-l/j6gen2/2.5.1/bevfusion_L_2.5.1_auto_labeling_3d_config.py
checkpoint:
checkpoint_path: /workspace/work_dirs/checkpoints/example_model_bevfusion.pth
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/bevfusion/bevfusion-cl/t4base/v2.0.0/best_NuScenes_metric_T4Metric_mAP_epoch_48.pth
checkpoint_path: /workspace/work_dirs/checkpoints/bevfusion_L_2.5.1_model.pth
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/bevfusion/bevfusion-l/j6gen2/2.5.1/best_NuScenes%20metric_T4Metric_mAP_epoch_30.pth

# ensemble_infos configuration
# Please update the config file for ensemble_infos when changing the latest model_config in create_info
Expand Down
23 changes: 17 additions & 6 deletions tools/auto_labeling_3d/entrypoint/configs/example_deepen.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -21,16 +21,27 @@ create_info:
# checkpoint:
# model_zoo_url: https://url/to/download/checkpoint.pth
# checkpoint_path: /path/to/save/checkpoint.pth
- name: streampetr
model_config:
config_path: /workspace/work_dirs/checkpoints/streampetr_2.5.0_config.py
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/streampetr/streampetr-vov99/t4base/v2.5/streampetr_2.5.0_auto_labeling_3d_config.py
checkpoint:
checkpoint_path: /workspace/work_dirs/checkpoints/streampetr_2.5.0_model.pth
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/streampetr/streampetr-vov99/t4base/v2.5/best_NuScenesmetric_T4Metric_mAP_epoch_34.pth
- name: centerpoint
model_config: /workspace/projects/CenterPoint/configs/t4dataset/Centerpoint/second_secfpn_4xb16_121m_j6gen2_base_t4metric_v2.py
model_config:
config_path: /workspace/work_dirs/checkpoints/centerpoint_2.5.1_config.py
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/centerpoint/centerpoint/j6gen2/v2.5.1/centerpoint_2.5.1_auto_labeling_3d_config.py
checkpoint:
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/centerpoint/centerpoint/j6gen2/v2.3.1/best_NuScenes_metric_T4Metric_mAP_epoch_29.pth
checkpoint_path: /workspace/work_dirs/checkpoints/example_model.pth
checkpoint_path: /workspace/work_dirs/checkpoints/centerpoint_2.5.1_model.pth
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/centerpoint/centerpoint/j6gen2/v2.5.1/best_NuScenes%20metric_T4Metric_mAP_epoch_28.pth
- name: bevfusion
model_config: /workspace/projects/BEVFusion/configs/t4dataset/BEVFusion-CL/bevfusion_camera_lidar_voxel_second_secfpn_4xb8_gen2_base.py
model_config:
config_path: /workspace/work_dirs/checkpoints/bevfusion_L_2.5.1_config.py
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/bevfusion/bevfusion-l/j6gen2/2.5.1/bevfusion_L_2.5.1_auto_labeling_3d_config.py
checkpoint:
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/bevfusion/bevfusion-cl/t4base/v2.0.0/best_NuScenes_metric_T4Metric_mAP_epoch_48.pth
checkpoint_path: /workspace/work_dirs/checkpoints/example_model_bevfusion.pth
checkpoint_path: /workspace/work_dirs/checkpoints/bevfusion_L_2.5.1_model.pth
model_zoo_url: https://download.autoware-ml-model-zoo.tier4.jp/autoware-ml/models/bevfusion/bevfusion-l/j6gen2/2.5.1/best_NuScenes%20metric_T4Metric_mAP_epoch_30.pth

# ensemble_infos configuration
# Please update the config file for ensemble_infos when changing the latest model_config in create_info
Expand Down
38 changes: 18 additions & 20 deletions tools/auto_labeling_3d/filter_objects/config/ensemble_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,10 @@
type="ThresholdFilter",
confidence_thresholds={
"car": 0.35,
"truck": 0.35,
"bus": 0.35,
"bicycle": 0.35,
"pedestrian": 0.35,
"truck": 0.4,
"bus": 0.4,
"bicycle": 0.4,
"pedestrian": 0.4,
},
use_label=["car", "truck", "bus", "bicycle", "pedestrian"],
),
Expand All @@ -22,10 +22,10 @@
type="ThresholdFilter",
confidence_thresholds={
"car": 0.35,
"truck": 0.35,
"bus": 0.35,
"bicycle": 0.35,
"pedestrian": 0.35,
"truck": 0.4,
"bus": 0.4,
"bicycle": 0.4,
"pedestrian": 0.4,
},
use_label=["car", "truck", "bus", "bicycle", "pedestrian"],
),
Expand All @@ -50,33 +50,31 @@
config=dict(
type="NMSEnsembleModel",
ensemble_setting=dict(
weights=[1.0, 1.0, 1.0],
iou_threshold=0.55,
weights=[0.9, 1.0, 1.0],
iou_threshold=0.20,
# Ensemble label groups. Each group is processed as one ensemble unit.
ensemble_label_groups=[
["car"],
["truck"],
["bus"],
["car", "truck", "bus"],
["pedestrian"],
["bicycle"],
],
),
),
inputs=[
dict(
name="streampetr",
info_path="/workspace/data/t4dataset/info/pseudo_infos_raw_streampetr.pkl",
filter_pipeline=streampetr_pipeline,
),
dict(
name="centerpoint",
info_path="./data/t4dataset/info/pseudo_infos_raw_centerpoint.pkl",
info_path="/workspace/data/t4dataset/info/pseudo_infos_raw_centerpoint.pkl",
filter_pipeline=centerpoint_pipeline,
),
dict(
name="bevfusion",
info_path="./data/t4dataset/info/pseudo_infos_raw_bevfusion.pkl",
info_path="/workspace/data/t4dataset/info/pseudo_infos_raw_bevfusion.pkl",
filter_pipeline=bevfusion_pipeline,
),
dict(
name="streampetr",
info_path="./data/t4dataset/info/pseudo_infos_raw_streampetr.pkl",
filter_pipeline=streampetr_pipeline,
),
],
)
Loading