From afa6adf1c133ac1b15b1a0ec0d9b5f26f59bb111 Mon Sep 17 00:00:00 2001 From: jihanyang Date: Sat, 18 Dec 2021 14:13:09 +0800 Subject: [PATCH 1/5] support lyft dataset --- pcdet/datasets/__init__.py | 4 +- pcdet/datasets/dataset.py | 7 +- pcdet/datasets/kitti/kitti_utils.py | 5 + pcdet/datasets/lyft/lyft_dataset.py | 345 ++++++++++++++ .../datasets/lyft/lyft_mAP_eval/lyft_eval.py | 435 ++++++++++++++++++ pcdet/datasets/lyft/lyft_utils.py | 332 +++++++++++++ 6 files changed, 1124 insertions(+), 4 deletions(-) create mode 100644 pcdet/datasets/lyft/lyft_dataset.py create mode 100644 pcdet/datasets/lyft/lyft_mAP_eval/lyft_eval.py create mode 100644 pcdet/datasets/lyft/lyft_utils.py diff --git a/pcdet/datasets/__init__.py b/pcdet/datasets/__init__.py index af43d1353..6eee564f9 100644 --- a/pcdet/datasets/__init__.py +++ b/pcdet/datasets/__init__.py @@ -9,13 +9,15 @@ from .nuscenes.nuscenes_dataset import NuScenesDataset from .waymo.waymo_dataset import WaymoDataset from .pandaset.pandaset_dataset import PandasetDataset +from .lyft.lyft_dataset import LyftDataset __all__ = { 'DatasetTemplate': DatasetTemplate, 'KittiDataset': KittiDataset, 'NuScenesDataset': NuScenesDataset, 'WaymoDataset': WaymoDataset, - 'PandasetDataset': PandasetDataset + 'PandasetDataset': PandasetDataset, + 'LyftDataset': LyftDataset } diff --git a/pcdet/datasets/dataset.py b/pcdet/datasets/dataset.py index a24a37e3e..164bac2c9 100644 --- a/pcdet/datasets/dataset.py +++ b/pcdet/datasets/dataset.py @@ -141,14 +141,15 @@ def prepare_data(self, data_dict): if data_dict.get('gt_boxes2d', None) is not None: data_dict['gt_boxes2d'] = data_dict['gt_boxes2d'][selected] - + if 'timestamp' in self.dataset_cfg.POINT_FEATURE_ENCODING.get('src_feature_list'): if data_dict.get('points', None) is not None: max_sweeps = self.dataset_cfg.get('MAX_SWEEPS', 1) idx = self.dataset_cfg.POINT_FEATURE_ENCODING.get('src_feature_list').index('timestamp') dt = np.round(data_dict['points'][:, idx], 2) - max_dt = sorted(np.unique(dt))[max_sweeps-1] - data_dict['points'] = data_dict['points'][dt <= max_dt] + if np.unique(dt).shape[0] == max_sweeps: + max_dt = sorted(np.unique(dt))[max_sweeps-1] + data_dict['points'] = data_dict['points'][dt <= max_dt] if data_dict.get('points', None) is not None: data_dict = self.point_feature_encoder.forward(data_dict) diff --git a/pcdet/datasets/kitti/kitti_utils.py b/pcdet/datasets/kitti/kitti_utils.py index 33dcd512f..62b487806 100644 --- a/pcdet/datasets/kitti/kitti_utils.py +++ b/pcdet/datasets/kitti/kitti_utils.py @@ -12,6 +12,11 @@ def transform_annotations_to_kitti_format(annos, map_name_to_kitti=None, info_wi """ for anno in annos: + # For lyft and nuscenes, different anno key in info + if 'name' not in anno: + anno['name'] = anno['gt_names'] + anno.pop('gt_names') + for k in range(anno['name'].shape[0]): anno['name'][k] = map_name_to_kitti[anno['name'][k]] diff --git a/pcdet/datasets/lyft/lyft_dataset.py b/pcdet/datasets/lyft/lyft_dataset.py new file mode 100644 index 000000000..efa577afb --- /dev/null +++ b/pcdet/datasets/lyft/lyft_dataset.py @@ -0,0 +1,345 @@ +import copy +import pickle +from pathlib import Path + +import numpy as np +from tqdm import tqdm + +from ...ops.roiaware_pool3d import roiaware_pool3d_utils +from ...utils import common_utils, box_utils +from ..dataset import DatasetTemplate + + +class LyftDataset(DatasetTemplate): + def __init__(self, dataset_cfg, class_names, training=True, root_path=None, logger=None): + self.root_path = (root_path if root_path is not None else Path(dataset_cfg.DATA_PATH)) / dataset_cfg.VERSION + super().__init__( + dataset_cfg=dataset_cfg, class_names=class_names, training=training, root_path=self.root_path, logger=logger + ) + self.infos = [] + self.include_lyft_data(self.mode) + + def include_lyft_data(self, mode): + self.logger.info('Loading lyft dataset') + lyft_infos = [] + + for info_path in self.dataset_cfg.INFO_PATH[mode]: + info_path = self.root_path / info_path + if not info_path.exists(): + continue + with open(info_path, 'rb') as f: + infos = pickle.load(f) + lyft_infos.extend(infos) + + self.infos.extend(lyft_infos) + self.logger.info('Total samples for lyft dataset: %d' % (len(lyft_infos))) + + @staticmethod + def remove_ego_points(points, center_radius=1.0): + mask = ~((np.abs(points[:, 0]) < center_radius*1.5) & (np.abs(points[:, 1]) < center_radius)) + return points[mask] + + def get_sweep(self, sweep_info): + lidar_path = self.root_path / sweep_info['lidar_path'] + points_sweep = np.fromfile(str(lidar_path), dtype=np.float32, count=-1) + if points_sweep.shape[0] % 5 != 0: + points_sweep = points_sweep[: points_sweep.shape[0] - (points_sweep.shape[0] % 5)] + points_sweep = points_sweep.reshape([-1, 5])[:, :4] + + points_sweep = self.remove_ego_points(points_sweep).T + if sweep_info['transform_matrix'] is not None: + num_points = points_sweep.shape[1] + points_sweep[:3, :] = sweep_info['transform_matrix'].dot( + np.vstack((points_sweep[:3, :], np.ones(num_points))))[:3, :] + + cur_times = sweep_info['time_lag'] * np.ones((1, points_sweep.shape[1])) + return points_sweep.T, cur_times.T + + def get_lidar_with_sweeps(self, index, max_sweeps=1): + info = self.infos[index] + lidar_path = self.root_path / info['lidar_path'] + points = np.fromfile(str(lidar_path), dtype=np.float32, count=-1) + if points.shape[0] % 5 != 0: + points = points[: points.shape[0] - (points.shape[0] % 5)] + points = points.reshape([-1, 5])[:, :4] + + sweep_points_list = [points] + sweep_times_list = [np.zeros((points.shape[0], 1))] + + for k in np.random.choice(len(info['sweeps']), max_sweeps - 1, replace=False): + points_sweep, times_sweep = self.get_sweep(info['sweeps'][k]) + sweep_points_list.append(points_sweep) + sweep_times_list.append(times_sweep) + + points = np.concatenate(sweep_points_list, axis=0) + times = np.concatenate(sweep_times_list, axis=0).astype(points.dtype) + + points = np.concatenate((points, times), axis=1) + return points + + def __len__(self): + if self._merge_all_iters_to_one_epoch: + return len(self.infos) * self.total_epochs + + return len(self.infos) + + def __getitem__(self, index): + if self._merge_all_iters_to_one_epoch: + index = index % len(self.infos) + + info = copy.deepcopy(self.infos[index]) + points = self.get_lidar_with_sweeps(index, max_sweeps=self.dataset_cfg.MAX_SWEEPS) + + input_dict = { + 'points': points, + 'frame_id': Path(info['lidar_path']).stem, + 'metadata': {'token': info['token']} + } + + if 'gt_boxes' in info: + input_dict.update({ + 'gt_boxes': info['gt_boxes'], + 'gt_names': info['gt_names'] + }) + + data_dict = self.prepare_data(data_dict=input_dict) + + return data_dict + + def generate_prediction_dicts(self, batch_dict, pred_dicts, class_names, output_path=None): + """ + Args: + batch_dict: + frame_id: + pred_dicts: list of pred_dicts + pred_boxes: (N, 7), Tensor + pred_scores: (N), Tensor + pred_labels: (N), Tensor + class_names: + output_path: + Returns: + """ + def get_template_prediction(num_samples): + ret_dict = { + 'name': np.zeros(num_samples), 'score': np.zeros(num_samples), + 'boxes_lidar': np.zeros([num_samples, 7]), 'pred_labels': np.zeros(num_samples) + } + return ret_dict + + def generate_single_sample_dict(box_dict): + pred_scores = box_dict['pred_scores'].cpu().numpy() + pred_boxes = box_dict['pred_boxes'].cpu().numpy() + pred_labels = box_dict['pred_labels'].cpu().numpy() + pred_dict = get_template_prediction(pred_scores.shape[0]) + if pred_scores.shape[0] == 0: + return pred_dict + + pred_dict['name'] = np.array(class_names)[pred_labels - 1] + pred_dict['score'] = pred_scores + pred_dict['boxes_lidar'] = pred_boxes + pred_dict['pred_labels'] = pred_labels + + return pred_dict + + annos = [] + for index, box_dict in enumerate(pred_dicts): + single_pred_dict = generate_single_sample_dict(box_dict) + single_pred_dict['frame_id'] = batch_dict['frame_id'][index] + single_pred_dict['metadata'] = batch_dict['metadata'][index] + annos.append(single_pred_dict) + + return annos + + def kitti_eval(self, eval_det_annos, eval_gt_annos, class_names): + from ..kitti.kitti_object_eval_python import eval as kitti_eval + from ..kitti import kitti_utils + + map_name_to_kitti = { + 'car': 'Car', + 'pedestrian': 'Pedestrian', + 'truck': 'Truck', + 'bicycle': 'Cyclist', + 'motorcycle': 'Cyclist' + } + + kitti_utils.transform_to_kitti_format(eval_det_annos, map_name_to_kitti=map_name_to_kitti) + kitti_utils.transform_to_kitti_format( + eval_gt_annos, map_name_to_kitti=map_name_to_kitti, + info_with_fakelidar=self.dataset_cfg.get('INFO_WITH_FAKELIDAR', False) + ) + + kitti_class_names = [map_name_to_kitti[x] for x in class_names] + + ap_result_str, ap_dict = kitti_eval.get_official_eval_result( + gt_annos=eval_gt_annos, dt_annos=eval_det_annos, current_classes=kitti_class_names + ) + return ap_result_str, ap_dict + + def evaluation(self, det_annos, class_names, **kwargs): + if kwargs['eval_metric'] == 'kitti': + eval_det_annos = copy.deepcopy(det_annos) + eval_gt_annos = copy.deepcopy(self.infos) + return self.kitti_eval(eval_det_annos, eval_gt_annos, class_names) + elif kwargs['eval_metric'] == 'lyft': + return self.lyft_eval(det_annos, class_names, + iou_thresholds=self.dataset_cfg.EVAL_LYFT_IOU_LIST) + else: + raise NotImplementedError + + def lyft_eval(self, det_annos, class_names, iou_thresholds=[0.5]): + from lyft_dataset_sdk.lyftdataset import LyftDataset as Lyft + from . import lyft_utils + # from lyft_dataset_sdk.eval.detection.mAP_evaluation import get_average_precisions + from .lyft_mAP_eval.lyft_eval import get_average_precisions + + lyft = Lyft(json_path=self.root_path / 'data', data_path=self.root_path, verbose=True) + + det_lyft_boxes, sample_tokens = lyft_utils.convert_det_to_lyft_format(lyft, det_annos) + gt_lyft_boxes = lyft_utils.load_lyft_gt_by_tokens(lyft, sample_tokens) + + average_precisions = get_average_precisions(gt_lyft_boxes, det_lyft_boxes, class_names, iou_thresholds) + + ap_result_str, ap_dict = lyft_utils.format_lyft_results(average_precisions, class_names, iou_thresholds, version=self.dataset_cfg.VERSION) + + return ap_result_str, ap_dict + + def create_groundtruth_database(self, used_classes=None, max_sweeps=10): + import torch + + database_save_path = self.root_path / f'gt_database' + db_info_save_path = self.root_path / f'lyft_dbinfos_{max_sweeps}sweeps.pkl' + + database_save_path.mkdir(parents=True, exist_ok=True) + all_db_infos = {} + + for idx in tqdm(range(len(self.infos))): + sample_idx = idx + info = self.infos[idx] + points = self.get_lidar_with_sweeps(idx, max_sweeps=max_sweeps) + gt_boxes = info['gt_boxes'] + gt_names = info['gt_names'] + + box_idxs_of_pts = roiaware_pool3d_utils.points_in_boxes_gpu( + torch.from_numpy(points[:, 0:3]).unsqueeze(dim=0).float().cuda(), + torch.from_numpy(gt_boxes[:, 0:7]).unsqueeze(dim=0).float().cuda() + ).long().squeeze(dim=0).cpu().numpy() + + for i in range(gt_boxes.shape[0]): + filename = '%s_%s_%d.bin' % (sample_idx, gt_names[i], i) + filepath = database_save_path / filename + gt_points = points[box_idxs_of_pts == i] + + gt_points[:, :3] -= gt_boxes[i, :3] + with open(filepath, 'w') as f: + gt_points.tofile(f) + + if (used_classes is None) or gt_names[i] in used_classes: + db_path = str(filepath.relative_to(self.root_path)) # gt_database/xxxxx.bin + db_info = {'name': gt_names[i], 'path': db_path, 'image_idx': sample_idx, 'gt_idx': i, + 'box3d_lidar': gt_boxes[i], 'num_points_in_gt': gt_points.shape[0]} + if gt_names[i] in all_db_infos: + all_db_infos[gt_names[i]].append(db_info) + else: + all_db_infos[gt_names[i]] = [db_info] + for k, v in all_db_infos.items(): + print('Database %s: %d' % (k, len(v))) + + with open(db_info_save_path, 'wb') as f: + pickle.dump(all_db_infos, f) + + +def create_lyft_info(version, data_path, save_path, split, max_sweeps=10): + from lyft_dataset_sdk.lyftdataset import LyftDataset + from . import lyft_utils + data_path = data_path / version + save_path = save_path / version + split_path = data_path.parent / 'ImageSets' + + if split is not None: + save_path = save_path / split + split_path = split_path / split + + save_path.mkdir(exist_ok=True) + + assert version in ['trainval', 'one_scene', 'test'] + + if version == 'trainval': + train_split_path = split_path / 'train.txt' + val_split_path = split_path / 'val.txt' + elif version == 'test': + train_split_path = split_path / 'test.txt' + val_split_path = None + elif version == 'one_scene': + train_split_path = split_path / 'one_scene.txt' + val_split_path = split_path / 'one_scene.txt' + else: + raise NotImplementedError + + train_scenes = [x.strip() for x in open(train_split_path).readlines()] if train_split_path.exists() else [] + val_scenes = [x.strip() for x in open(val_split_path).readlines()] if val_split_path.exists() else [] + + lyft = LyftDataset(json_path=data_path / 'data', data_path=data_path, verbose=True) + + available_scenes = lyft_utils.get_available_scenes(lyft) + available_scene_names = [s['name'] for s in available_scenes] + train_scenes = list(filter(lambda x: x in available_scene_names, train_scenes)) + val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes)) + train_scenes = set([available_scenes[available_scene_names.index(s)]['token'] for s in train_scenes]) + val_scenes = set([available_scenes[available_scene_names.index(s)]['token'] for s in val_scenes]) + + print('%s: train scene(%d), val scene(%d)' % (version, len(train_scenes), len(val_scenes))) + + train_lyft_infos, val_lyft_infos = lyft_utils.fill_trainval_infos( + data_path=data_path, lyft=lyft, train_scenes=train_scenes, val_scenes=val_scenes, + test='test' in version, max_sweeps=max_sweeps + ) + + if version == 'test': + print('test sample: %d' % len(train_lyft_infos)) + with open(save_path / f'lyft_infos_test.pkl', 'wb') as f: + pickle.dump(train_lyft_infos, f) + else: + print('train sample: %d, val sample: %d' % (len(train_lyft_infos), len(val_lyft_infos))) + with open(save_path / f'lyft_infos_train.pkl', 'wb') as f: + pickle.dump(train_lyft_infos, f) + with open(save_path / f'lyft_infos_val.pkl', 'wb') as f: + pickle.dump(val_lyft_infos, f) + + +if __name__ == '__main__': + import yaml + import argparse + from pathlib import Path + from easydict import EasyDict + + parser = argparse.ArgumentParser(description='arg parser') + parser.add_argument('--cfg_file', type=str, default=None, help='specify the config of dataset') + parser.add_argument('--func', type=str, default='create_lyft_infos', help='') + parser.add_argument('--version', type=str, default='trainval', help='') + parser.add_argument('--split', type=str, default=None, help='') + parser.add_argument('--max_sweeps', type=int, default=10, help='') + args = parser.parse_args() + + if args.func == 'create_lyft_infos': + try: + yaml_config = yaml.safe_load(open(args.cfg_file), Loader=yaml.FullLoader) + except: + yaml_config = yaml.safe_load(open(args.cfg_file)) + dataset_cfg = EasyDict(yaml_config) + ROOT_DIR = (Path(__file__).resolve().parent / '../../../').resolve() + dataset_cfg.VERSION = args.version + dataset_cfg.MAX_SWEEPS = args.max_sweeps + create_lyft_info( + version=dataset_cfg.VERSION, + data_path=ROOT_DIR / 'data' / 'lyft', + save_path=ROOT_DIR / 'data' / 'lyft', + split=args.split, + max_sweeps=dataset_cfg.MAX_SWEEPS + ) + + lyft_dataset = LyftDataset( + dataset_cfg=dataset_cfg, class_names=None, + root_path=ROOT_DIR / 'data' / 'lyft', + logger=common_utils.create_logger(), training=True + ) + lyft_dataset.create_groundtruth_database(max_sweeps=dataset_cfg.MAX_SWEEPS) diff --git a/pcdet/datasets/lyft/lyft_mAP_eval/lyft_eval.py b/pcdet/datasets/lyft/lyft_mAP_eval/lyft_eval.py new file mode 100644 index 000000000..872476ae3 --- /dev/null +++ b/pcdet/datasets/lyft/lyft_mAP_eval/lyft_eval.py @@ -0,0 +1,435 @@ +""" +modified from lyft toolkit https://github.com/lyft/nuscenes-devkit.git +""" + +""" +mAP 3D calculation for the data in nuScenes format. + + +The intput files expected to have the format: + +Expected fields: + + +gt = [{ + 'sample_token': '0f0e3ce89d2324d8b45aa55a7b4f8207fbb039a550991a5149214f98cec136ac', + 'translation': [974.2811881299899, 1714.6815014457964, -23.689857123368846], + 'size': [1.796, 4.488, 1.664], + 'rotation': [0.14882026466054782, 0, 0, 0.9888642620837121], + 'name': 'car' +}] + +prediction_result = { + 'sample_token': '0f0e3ce89d2324d8b45aa55a7b4f8207fbb039a550991a5149214f98cec136ac', + 'translation': [971.8343488872263, 1713.6816097857359, -25.82534357061308], + 'size': [2.519726579986132, 7.810161372666739, 3.483438286096803], + 'rotation': [0.10913582721095375, 0.04099572636992043, 0.01927712319721745, 1.029328402625659], + 'name': 'car', + 'score': 0.3077029437237213 +} + + +input arguments: + +--pred_file: file with predictions +--gt_file: ground truth file +--iou_threshold: IOU threshold + + +In general we would be interested in average of mAP at thresholds [0.5, 0.55, 0.6, 0.65,...0.95], similar to the +standard COCO => one needs to run this file N times for every IOU threshold independently. + +""" + +import argparse +import json +from collections import defaultdict +from pathlib import Path + +import numpy as np +from pyquaternion import Quaternion +from shapely.geometry import Polygon + + +class Box3D: + """Data class used during detection evaluation. Can be a prediction or ground truth.""" + + def __init__(self, **kwargs): + sample_token = kwargs["sample_token"] + translation = kwargs["translation"] + size = kwargs["size"] + rotation = kwargs["rotation"] + name = kwargs["name"] + score = kwargs.get("score", -1) + + if not isinstance(sample_token, str): + raise TypeError("Sample_token must be a string!") + + if not len(translation) == 3: + raise ValueError("Translation must have 3 elements!") + + if np.any(np.isnan(translation)): + raise ValueError("Translation may not be NaN!") + + if not len(size) == 3: + raise ValueError("Size must have 3 elements!") + + if np.any(np.isnan(size)): + raise ValueError("Size may not be NaN!") + + if not len(rotation) == 4: + raise ValueError("Rotation must have 4 elements!") + + if np.any(np.isnan(rotation)): + raise ValueError("Rotation may not be NaN!") + + if name is None: + raise ValueError("Name cannot be empty!") + + # Assign. + self.sample_token = sample_token + self.translation = translation + self.size = size + self.volume = np.prod(self.size) + self.score = score + + assert np.all([x > 0 for x in size]) + self.rotation = rotation + self.name = name + self.quaternion = Quaternion(self.rotation) + + self.width, self.length, self.height = size + + self.center_x, self.center_y, self.center_z = self.translation + + self.min_z = self.center_z - self.height / 2 + self.max_z = self.center_z + self.height / 2 + + self.ground_bbox_coords = None + self.ground_bbox_coords = self.get_ground_bbox_coords() + + @staticmethod + def check_orthogonal(a, b, c): + """Check that vector (b - a) is orthogonal to the vector (c - a).""" + return np.isclose((b[0] - a[0]) * (c[0] - a[0]) + (b[1] - a[1]) * (c[1] - a[1]), 0) + + def get_ground_bbox_coords(self): + if self.ground_bbox_coords is not None: + return self.ground_bbox_coords + return self.calculate_ground_bbox_coords() + + def calculate_ground_bbox_coords(self): + """We assume that the 3D box has lower plane parallel to the ground. + + Returns: Polygon with 4 points describing the base. + + """ + if self.ground_bbox_coords is not None: + return self.ground_bbox_coords + + rotation_matrix = self.quaternion.rotation_matrix + + cos_angle = rotation_matrix[0, 0] + sin_angle = rotation_matrix[1, 0] + + point_0_x = self.center_x + self.length / 2 * cos_angle + self.width / 2 * sin_angle + point_0_y = self.center_y + self.length / 2 * sin_angle - self.width / 2 * cos_angle + + point_1_x = self.center_x + self.length / 2 * cos_angle - self.width / 2 * sin_angle + point_1_y = self.center_y + self.length / 2 * sin_angle + self.width / 2 * cos_angle + + point_2_x = self.center_x - self.length / 2 * cos_angle - self.width / 2 * sin_angle + point_2_y = self.center_y - self.length / 2 * sin_angle + self.width / 2 * cos_angle + + point_3_x = self.center_x - self.length / 2 * cos_angle + self.width / 2 * sin_angle + point_3_y = self.center_y - self.length / 2 * sin_angle - self.width / 2 * cos_angle + + point_0 = point_0_x, point_0_y + point_1 = point_1_x, point_1_y + point_2 = point_2_x, point_2_y + point_3 = point_3_x, point_3_y + + assert self.check_orthogonal(point_0, point_1, point_3) + assert self.check_orthogonal(point_1, point_0, point_2) + assert self.check_orthogonal(point_2, point_1, point_3) + assert self.check_orthogonal(point_3, point_0, point_2) + + self.ground_bbox_coords = Polygon( + [ + (point_0_x, point_0_y), + (point_1_x, point_1_y), + (point_2_x, point_2_y), + (point_3_x, point_3_y), + (point_0_x, point_0_y), + ] + ) + + return self.ground_bbox_coords + + def get_height_intersection(self, other): + min_z = max(other.min_z, self.min_z) + max_z = min(other.max_z, self.max_z) + + return max(0, max_z - min_z) + + def get_area_intersection(self, other) -> float: + result = self.ground_bbox_coords.intersection(other.ground_bbox_coords).area + + assert result <= self.width * self.length + + return result + + def get_intersection(self, other) -> float: + height_intersection = self.get_height_intersection(other) + + area_intersection = self.ground_bbox_coords.intersection(other.ground_bbox_coords).area + + return height_intersection * area_intersection + + def get_iou(self, other): + intersection = self.get_intersection(other) + union = self.volume + other.volume - intersection + + iou = np.clip(intersection / union, 0, 1) + + return iou + + def __repr__(self): + return str(self.serialize()) + + def serialize(self) -> dict: + """Returns: Serialized instance as dict.""" + + return { + "sample_token": self.sample_token, + "translation": self.translation, + "size": self.size, + "rotation": self.rotation, + "name": self.name, + "volume": self.volume, + "score": self.score, + } + + +def group_by_key(detections, key): + groups = defaultdict(list) + for detection in detections: + groups[detection[key]].append(detection) + return groups + + +def wrap_in_box(input): + result = {} + for key, value in input.items(): + result[key] = [Box3D(**x) for x in value] + + return result + + +def get_envelope(precisions): + """Compute the precision envelope. + + Args: + precisions: + + Returns: + + """ + for i in range(precisions.size - 1, 0, -1): + precisions[i - 1] = np.maximum(precisions[i - 1], precisions[i]) + return precisions + + +def get_ap(recalls, precisions): + """Calculate average precision. + + Args: + recalls: + precisions: Returns (float): average precision. + + Returns: + + """ + # correct AP calculation + # first append sentinel values at the end + recalls = np.concatenate(([0.0], recalls, [1.0])) + precisions = np.concatenate(([0.0], precisions, [0.0])) + + precisions = get_envelope(precisions) + + # to calculate area under PR curve, look for points where X axis (recall) changes value + i = np.where(recalls[1:] != recalls[:-1])[0] + + # and sum (\Delta recall) * prec + ap = np.sum((recalls[i + 1] - recalls[i]) * precisions[i + 1]) + return ap + + +def get_ious(gt_boxes, predicted_box): + return [predicted_box.get_iou(x) for x in gt_boxes] + + +def recall_precision(gt, predictions, iou_threshold_list): + num_gts = len(gt) + + if num_gts == 0: + return -1, -1, -1 + + image_gts = group_by_key(gt, "sample_token") + image_gts = wrap_in_box(image_gts) + + sample_gt_checked = {sample_token: np.zeros((len(boxes), len(iou_threshold_list))) for sample_token, boxes in image_gts.items()} + + predictions = sorted(predictions, key=lambda x: x["score"], reverse=True) + + # go down dets and mark TPs and FPs + num_predictions = len(predictions) + tp = np.zeros((num_predictions, len(iou_threshold_list))) + fp = np.zeros((num_predictions, len(iou_threshold_list))) + + for prediction_index, prediction in enumerate(predictions): + predicted_box = Box3D(**prediction) + + sample_token = prediction["sample_token"] + + max_overlap = -np.inf + jmax = -1 + + try: + gt_boxes = image_gts[sample_token] # gt_boxes per sample + gt_checked = sample_gt_checked[sample_token] # gt flags per sample + except KeyError: + gt_boxes = [] + gt_checked = None + + if len(gt_boxes) > 0: + overlaps = get_ious(gt_boxes, predicted_box) + + max_overlap = np.max(overlaps) + + jmax = np.argmax(overlaps) + + for i, iou_threshold in enumerate(iou_threshold_list): + if max_overlap > iou_threshold: + if gt_checked[jmax, i] == 0: + tp[prediction_index, i] = 1.0 + gt_checked[jmax, i] = 1 + else: + fp[prediction_index, i] = 1.0 + else: + fp[prediction_index, i] = 1.0 + + # compute precision recall + fp = np.cumsum(fp, axis=0) + tp = np.cumsum(tp, axis=0) + + recalls = tp / float(num_gts) + + assert np.all(0 <= recalls) & np.all(recalls <= 1) + + # avoid divide by zero in case the first detection matches a difficult ground truth + precisions = tp / np.maximum(tp + fp, np.finfo(np.float64).eps) + + assert np.all(0 <= precisions) & np.all(precisions <= 1) + + ap_list = [] + for i in range(len(iou_threshold_list)): + recall = recalls[:, i] + precision = precisions[:, i] + ap = get_ap(recall, precision) + ap_list.append(ap) + + return recalls, precisions, ap_list + + +def get_average_precisions(gt: list, predictions: list, class_names: list, iou_thresholds: list) -> np.array: + """Returns an array with an average precision per class. + + + Args: + gt: list of dictionaries in the format described below. + predictions: list of dictionaries in the format described below. + class_names: list of the class names. + iou_threshold: list of IOU thresholds used to calculate TP / FN + + Returns an array with an average precision per class. + + + Ground truth and predictions should have schema: + + gt = [{ + 'sample_token': '0f0e3ce89d2324d8b45aa55a7b4f8207fbb039a550991a5149214f98cec136ac', + 'translation': [974.2811881299899, 1714.6815014457964, -23.689857123368846], + 'size': [1.796, 4.488, 1.664], + 'rotation': [0.14882026466054782, 0, 0, 0.9888642620837121], + 'name': 'car' + }] + + predictions = [{ + 'sample_token': '0f0e3ce89d2324d8b45aa55a7b4f8207fbb039a550991a5149214f98cec136ac', + 'translation': [971.8343488872263, 1713.6816097857359, -25.82534357061308], + 'size': [2.519726579986132, 7.810161372666739, 3.483438286096803], + 'rotation': [0.10913582721095375, 0.04099572636992043, 0.01927712319721745, 1.029328402625659], + 'name': 'car', + 'score': 0.3077029437237213 + }] + + """ + assert all([0 <= iou_th <= 1 for iou_th in iou_thresholds]) + + gt_by_class_name = group_by_key(gt, "name") + pred_by_class_name = group_by_key(predictions, "name") + + average_precisions = np.zeros(len(class_names)) + + for class_id, class_name in enumerate(class_names): + if class_name in pred_by_class_name: + recalls, precisions, ap_list = recall_precision( + gt_by_class_name[class_name], pred_by_class_name[class_name], iou_thresholds + ) + aps = np.mean(ap_list) + average_precisions[class_id] = aps + + return average_precisions + + +def get_class_names(gt: dict) -> list: + """Get sorted list of class names. + + Args: + gt: + + Returns: Sorted list of class names. + + """ + return sorted(list(set([x["name"] for x in gt]))) + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + arg = parser.add_argument + arg("-p", "--pred_file", type=str, help="Path to the predictions file.", required=True) + arg("-g", "--gt_file", type=str, help="Path to the ground truth file.", required=True) + arg("-t", "--iou_threshold", type=float, help="iou threshold", default=0.5) + + args = parser.parse_args() + + gt_path = Path(args.gt_file) + pred_path = Path(args.pred_file) + + with open(args.pred_file) as f: + predictions = json.load(f) + + with open(args.gt_file) as f: + gt = json.load(f) + + class_names = get_class_names(gt) + print("Class_names = ", class_names) + + average_precisions = get_average_precisions(gt, predictions, class_names, args.iou_threshold) + + mAP = np.mean(average_precisions) + print("Average per class mean average precision = ", mAP) + + for class_id in sorted(list(zip(class_names, average_precisions.flatten().tolist()))): + print(class_id) diff --git a/pcdet/datasets/lyft/lyft_utils.py b/pcdet/datasets/lyft/lyft_utils.py new file mode 100644 index 000000000..30e057ef9 --- /dev/null +++ b/pcdet/datasets/lyft/lyft_utils.py @@ -0,0 +1,332 @@ +""" +The Lyft data pre-processing and evaluation is modified from +https://github.com/poodarchu/Det3D +""" + +import operator +from functools import reduce +from pathlib import Path + +import numpy as np +import tqdm +from lyft_dataset_sdk.utils.data_classes import Box, Quaternion +from lyft_dataset_sdk.lyftdataset import LyftDataset +from lyft_dataset_sdk.utils.geometry_utils import transform_matrix +from lyft_dataset_sdk.eval.detection.mAP_evaluation import Box3D + + +def get_available_scenes(lyft): + available_scenes = [] + print('total scene num:', len(lyft.scene)) + for scene in lyft.scene: + scene_token = scene['token'] + scene_rec = lyft.get('scene', scene_token) + sample_rec = lyft.get('sample', scene_rec['first_sample_token']) + sd_rec = lyft.get('sample_data', sample_rec['data']['LIDAR_TOP']) + has_more_frames = True + scene_not_exist = False + while has_more_frames: + lidar_path, boxes, _ = lyft.get_sample_data(sd_rec['token']) + if not Path(lidar_path).exists(): + scene_not_exist = True + break + else: + break + # if not sd_rec['next'] == '': + # sd_rec = nusc.get('sample_data', sd_rec['next']) + # else: + # has_more_frames = False + if scene_not_exist: + continue + available_scenes.append(scene) + print('exist scene num:', len(available_scenes)) + return available_scenes + + +def get_sample_data(lyft, sample_data_token): + sd_rec = lyft.get("sample_data", sample_data_token) + cs_rec = lyft.get("calibrated_sensor", sd_rec["calibrated_sensor_token"]) + + sensor_rec = lyft.get("sensor", cs_rec["sensor_token"]) + pose_rec = lyft.get("ego_pose", sd_rec["ego_pose_token"]) + + boxes = lyft.get_boxes(sample_data_token) + + box_list = [] + for box in boxes: + box.translate(-np.array(pose_rec["translation"])) + box.rotate(Quaternion(pose_rec["rotation"]).inverse) + + box.translate(-np.array(cs_rec["translation"])) + box.rotate(Quaternion(cs_rec["rotation"]).inverse) + + box_list.append(box) + + return box_list, pose_rec + + +def quaternion_yaw(q: Quaternion) -> float: + """ + Calculate the yaw angle from a quaternion. + Note that this only works for a quaternion that represents a box in lidar or global coordinate frame. + It does not work for a box in the camera frame. + :param q: Quaternion of interest. + :return: Yaw angle in radians. + """ + + # Project into xy plane. + v = np.dot(q.rotation_matrix, np.array([1, 0, 0])) + + # Measure yaw using arctan. + yaw = np.arctan2(v[1], v[0]) + + return yaw + + +def fill_trainval_infos(data_path, lyft, train_scenes, val_scenes, test=False, max_sweeps=10): + train_lyft_infos = [] + val_lyft_infos = [] + progress_bar = tqdm.tqdm(total=len(lyft.sample), desc='create_info', dynamic_ncols=True) + + # ref_chans = ["LIDAR_TOP", "LIDAR_FRONT_LEFT", "LIDAR_FRONT_RIGHT"] + ref_chan = "LIDAR_TOP" + + for index, sample in enumerate(lyft.sample): + progress_bar.update() + + ref_info = {} + ref_sd_token = sample["data"][ref_chan] + ref_sd_rec = lyft.get("sample_data", ref_sd_token) + ref_cs_token = ref_sd_rec["calibrated_sensor_token"] + ref_cs_rec = lyft.get("calibrated_sensor", ref_cs_token) + + ref_to_car = transform_matrix( + ref_cs_rec["translation"], + Quaternion(ref_cs_rec["rotation"]), + inverse=False, + ) + + ref_from_car = transform_matrix( + ref_cs_rec["translation"], + Quaternion(ref_cs_rec["rotation"]), + inverse=True, + ) + + ref_lidar_path = lyft.get_sample_data_path(ref_sd_token) + + ref_boxes, ref_pose_rec = get_sample_data(lyft, ref_sd_token) + ref_time = 1e-6 * ref_sd_rec["timestamp"] + car_from_global = transform_matrix( + ref_pose_rec["translation"], + Quaternion(ref_pose_rec["rotation"]), + inverse=True, + ) + + car_to_global = transform_matrix( + ref_pose_rec["translation"], + Quaternion(ref_pose_rec["rotation"]), + inverse=False, + ) + + info = { + "lidar_path": Path(ref_lidar_path).relative_to(data_path).__str__(), + "ref_from_car": ref_from_car, + "ref_to_car": ref_to_car, + 'token': sample['token'], + 'car_from_global': car_from_global, + 'car_to_global': car_to_global, + 'timestamp': ref_time, + 'sweeps': [] + } + + sample_data_token = sample['data'][ref_chan] + curr_sd_rec = lyft.get('sample_data', sample_data_token) + sweeps = [] + + while len(sweeps) < max_sweeps - 1: + if curr_sd_rec['prev'] == '': + if len(sweeps) == 0: + sweep = { + 'lidar_path': Path(ref_lidar_path).relative_to(data_path).__str__(), + 'sample_data_token': curr_sd_rec['token'], + 'transform_matrix': None, + 'time_lag': curr_sd_rec['timestamp'] * 0, + } + sweeps.append(sweep) + else: + sweeps.append(sweeps[-1]) + else: + curr_sd_rec = lyft.get('sample_data', curr_sd_rec['prev']) + + # Get past pose + current_pose_rec = lyft.get('ego_pose', curr_sd_rec['ego_pose_token']) + global_from_car = transform_matrix( + current_pose_rec['translation'], Quaternion(current_pose_rec['rotation']), inverse=False, + ) + + # Homogeneous transformation matrix from sensor coordinate frame to ego car frame. + current_cs_rec = lyft.get( + 'calibrated_sensor', curr_sd_rec['calibrated_sensor_token'] + ) + car_from_current = transform_matrix( + current_cs_rec['translation'], Quaternion(current_cs_rec['rotation']), inverse=False, + ) + + tm = reduce(np.dot, [ref_from_car, car_from_global, global_from_car, car_from_current]) + + lidar_path = lyft.get_sample_data_path(curr_sd_rec['token']) + + time_lag = ref_time - 1e-6 * curr_sd_rec['timestamp'] + + sweep = { + 'lidar_path': Path(lidar_path).relative_to(data_path).__str__(), + 'sample_data_token': curr_sd_rec['token'], + 'transform_matrix': tm, + 'global_from_car': global_from_car, + 'car_from_current': car_from_current, + 'time_lag': time_lag, + } + sweeps.append(sweep) + + info['sweeps'] = sweeps + + if not test: + annotations = [ + lyft.get("sample_annotation", token) for token in sample["anns"] + ] + + locs = np.array([b.center for b in ref_boxes]).reshape(-1, 3) + dims = np.array([b.wlh for b in ref_boxes]).reshape(-1, 3)[:, [1, 0, 2]] + rots = np.array([quaternion_yaw(b.orientation) for b in ref_boxes]).reshape( + -1, 1 + ) + velocity = np.array([b.velocity for b in ref_boxes]).reshape(-1, 3) + names = np.array([b.name for b in ref_boxes]) + tokens = np.array([b.token for b in ref_boxes]).reshape(-1, 1) + gt_boxes = np.concatenate([locs, dims, rots], axis=1) + + assert len(annotations) == len(gt_boxes) + + info["gt_boxes"] = gt_boxes + info["gt_boxes_velocity"] = velocity + info["gt_names"] = names + info["gt_boxes_token"] = tokens + + if sample["scene_token"] in train_scenes: + train_lyft_infos.append(info) + else: + val_lyft_infos.append(info) + + progress_bar.close() + return train_lyft_infos, val_lyft_infos + +def boxes_lidar_to_lyft(boxes3d, scores=None, labels=None): + box_list = [] + for k in range(boxes3d.shape[0]): + quat = Quaternion(axis=[0, 0, 1], radians=boxes3d[k, 6]) + box = Box( + boxes3d[k, :3], + boxes3d[k, [4, 3, 5]], # wlh + quat, label=labels[k] if labels is not None else np.nan, + score=scores[k] if scores is not None else np.nan, + ) + box_list.append(box) + return box_list + + +def lidar_lyft_box_to_global(lyft, boxes, sample_token): + s_record = lyft.get('sample', sample_token) + sample_data_token = s_record['data']['LIDAR_TOP'] + + sd_record = lyft.get('sample_data', sample_data_token) + cs_record = lyft.get('calibrated_sensor', sd_record['calibrated_sensor_token']) + sensor_record = lyft.get('sensor', cs_record['sensor_token']) + pose_record = lyft.get('ego_pose', sd_record['ego_pose_token']) + + box_list = [] + for box in boxes: + # Move box to ego vehicle coord system + box.rotate(Quaternion(cs_record['rotation'])) + box.translate(np.array(cs_record['translation'])) + # Move box to global coord system + box.rotate(Quaternion(pose_record['rotation'])) + box.translate(np.array(pose_record['translation'])) + box_list.append(box) + return box_list + + +def convert_det_to_lyft_format(lyft, det_annos): + sample_tokens = [] + det_lyft_box = [] + for anno in det_annos: + sample_tokens.append(anno['metadata']['token']) + + boxes_lyft_list = boxes_lidar_to_lyft(anno['boxes_lidar'], anno['score'], anno['pred_labels']) + boxes_list = lidar_lyft_box_to_global(lyft, boxes_lyft_list, anno['metadata']['token']) + + for idx, box in enumerate(boxes_list): + name = anno['name'][idx] + box3d = { + 'sample_token': anno['metadata']['token'], + 'translation': box.center.tolist(), + 'size': box.wlh.tolist(), + 'rotation': box.orientation.elements.tolist(), + 'name': name, + 'score': box.score + } + det_lyft_box.append(box3d) + + return det_lyft_box, sample_tokens + + +def load_lyft_gt_by_tokens(lyft, sample_tokens): + """ + Modify from Lyft tutorial + """ + + gt_box3ds = [] + + # Load annotations and filter predictions and annotations. + for sample_token in sample_tokens: + + sample = lyft.get('sample', sample_token) + + sample_annotation_tokens = sample['anns'] + + sample_lidar_token = sample["data"]["LIDAR_TOP"] + lidar_data = lyft.get("sample_data", sample_lidar_token) + ego_pose = lyft.get("ego_pose", lidar_data["ego_pose_token"]) + ego_translation = np.array(ego_pose['translation']) + + for sample_annotation_token in sample_annotation_tokens: + sample_annotation = lyft.get('sample_annotation', sample_annotation_token) + sample_annotation_translation = sample_annotation['translation'] + + class_name = sample_annotation['category_name'] + + box3d = { + 'sample_token': sample_token, + 'translation': sample_annotation_translation, + 'size': sample_annotation['size'], + 'rotation': sample_annotation['rotation'], + 'name': class_name + } + gt_box3ds.append(box3d) + + return gt_box3ds + + +def format_lyft_results(classwise_ap, class_names, iou_threshold_list, version='trainval'): + ret_dict = {} + result = '----------------Lyft %s results-----------------\n' % version + result += 'Average precision over IoUs: {}\n'.format(str(iou_threshold_list)) + for c_idx, class_name in enumerate(class_names): + result += '{:<20}: \t {:.4f}\n'.format(class_name, classwise_ap[c_idx]) + ret_dict[class_name] = classwise_ap[c_idx] + + result += '--------------average performance-------------\n' + mAP = np.mean(classwise_ap) + result += 'mAP:\t {:.4f}\n'.format(mAP) + + ret_dict['mAP'] = mAP + return result, ret_dict From 093efb9a81af77aac0f396b157f11cd5a197fa74 Mon Sep 17 00:00:00 2001 From: jihanyang Date: Sat, 18 Dec 2021 14:26:04 +0800 Subject: [PATCH 2/5] add lyft cfgs --- tools/cfgs/dataset_configs/lyft_dataset.yaml | 78 +++++++ .../lyft_models/cbgs_second_multihead.yaml | 215 ++++++++++++++++++ 2 files changed, 293 insertions(+) create mode 100644 tools/cfgs/dataset_configs/lyft_dataset.yaml create mode 100644 tools/cfgs/lyft_models/cbgs_second_multihead.yaml diff --git a/tools/cfgs/dataset_configs/lyft_dataset.yaml b/tools/cfgs/dataset_configs/lyft_dataset.yaml new file mode 100644 index 000000000..32da86516 --- /dev/null +++ b/tools/cfgs/dataset_configs/lyft_dataset.yaml @@ -0,0 +1,78 @@ +DATASET: 'LyftDataset' +DATA_PATH: '../data/lyft' + +VERSION: 'trainval' +SET_NAN_VELOCITY_TO_ZEROS: True +FILTER_MIN_POINTS_IN_GT: 1 +MAX_SWEEPS: 5 +EVAL_LYFT_IOU_LIST: [0.5, 0.55, 0.6, 0.65, 0.7, 0.75, 0.8, 0.85, 0.9, 0.95] + +DATA_SPLIT: { + 'train': train, + 'test': val +} + +INFO_PATH: { + 'train': [lyft_infos_train.pkl], + 'test': [lyft_infos_val.pkl], +} + +POINT_CLOUD_RANGE: [-80.0, -80.0, -5.0, 80.0, 80.0, 3.0] + +DATA_AUGMENTOR: + DISABLE_AUG_LIST: ['placeholder'] + AUG_CONFIG_LIST: + - NAME: gt_sampling + DB_INFO_PATH: + - lyft_dbinfos_10sweeps.pkl + PREPARE: { + filter_by_min_points: [ + 'car:5','pedestrian:5', 'motorcycle:5', 'bicycle:5', 'other_vehicle:5', + 'bus:5', 'truck:5', 'emergency_vehicle:5', 'animal:5' + ], + } + + SAMPLE_GROUPS: [ + 'car:3','pedestrian:3', 'motorcycle:6', 'bicycle:6', 'other_vehicle:4', + 'bus:4', 'truck:3', 'emergency_vehicle:7', 'animal:3' + ] + + NUM_POINT_FEATURES: 5 + DATABASE_WITH_FAKELIDAR: False + REMOVE_EXTRA_WIDTH: [0.0, 0.0, 0.0] + LIMIT_WHOLE_SCENE: True + + - NAME: random_world_flip + ALONG_AXIS_LIST: ['x', 'y'] + + - NAME: random_world_rotation + WORLD_ROT_ANGLE: [-0.3925, 0.3925] + + - NAME: random_world_scaling + WORLD_SCALE_RANGE: [0.95, 1.05] + + +POINT_FEATURE_ENCODING: { + encoding_type: absolute_coordinates_encoding, + used_feature_list: ['x', 'y', 'z', 'intensity', 'timestamp'], + src_feature_list: ['x', 'y', 'z', 'intensity', 'timestamp'], +} + + +DATA_PROCESSOR: + - NAME: mask_points_and_boxes_outside_range + REMOVE_OUTSIDE_BOXES: True + + - NAME: shuffle_points + SHUFFLE_ENABLED: { + 'train': True, + 'test': True + } + + - NAME: transform_points_to_voxels + VOXEL_SIZE: [0.1, 0.1, 0.2] + MAX_POINTS_PER_VOXEL: 10 + MAX_NUMBER_OF_VOXELS: { + 'train': 80000, + 'test': 80000 + } \ No newline at end of file diff --git a/tools/cfgs/lyft_models/cbgs_second_multihead.yaml b/tools/cfgs/lyft_models/cbgs_second_multihead.yaml new file mode 100644 index 000000000..f7a1c7a3a --- /dev/null +++ b/tools/cfgs/lyft_models/cbgs_second_multihead.yaml @@ -0,0 +1,215 @@ +CLASS_NAMES: ['car','truck', 'bus', 'emergency_vehicle', 'other_vehicle', + 'motorcycle', 'bicycle', 'pedestrian', 'animal'] + +DATA_CONFIG: + _BASE_CONFIG_: cfgs/dataset_configs/lyft_dataset.yaml + + +MODEL: + NAME: SECONDNet + + VFE: + NAME: MeanVFE + + BACKBONE_3D: + NAME: VoxelResBackBone8x + + MAP_TO_BEV: + NAME: HeightCompression + NUM_BEV_FEATURES: 256 + + BACKBONE_2D: + NAME: BaseBEVBackbone + + LAYER_NUMS: [5, 5] + LAYER_STRIDES: [1, 2] + NUM_FILTERS: [128, 256] + UPSAMPLE_STRIDES: [1, 2] + NUM_UPSAMPLE_FILTERS: [256, 256] + + DENSE_HEAD: + NAME: AnchorHeadMulti + CLASS_AGNOSTIC: False + + DIR_OFFSET: 0.78539 + DIR_LIMIT_OFFSET: 0.0 + NUM_DIR_BINS: 2 + + USE_MULTIHEAD: True + SEPARATE_MULTIHEAD: True + ANCHOR_GENERATOR_CONFIG: [ + { + 'class_name': car, + 'anchor_sizes': [[4.75, 1.92, 1.71]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-1.07], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.6, + 'unmatched_threshold': 0.45 + }, + { + 'class_name': truck, + 'anchor_sizes': [[10.24, 2.84, 3.44]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-0.30], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.55, + 'unmatched_threshold': 0.4 + }, + { + 'class_name': bus, + 'anchor_sizes': [[12.70, 2.92, 3.42]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-0.35], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.55, + 'unmatched_threshold': 0.4 + }, + { + 'class_name': emergency_vehicle, + 'anchor_sizes': [[6.52, 2.42, 2.34]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-0.89], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.5, + 'unmatched_threshold': 0.35 + }, + { + 'class_name': other_vehicle, + 'anchor_sizes': [[8.17, 2.75, 3.20]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-0.63], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.55, + 'unmatched_threshold': 0.4 + }, + { + 'class_name': motorcycle, + 'anchor_sizes': [[2.35, 0.96, 1.59]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-1.32], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.5, + 'unmatched_threshold': 0.3 + }, + { + 'class_name': bicycle, + 'anchor_sizes': [[1.76, 0.63, 1.44]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-1.07], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.5, + 'unmatched_threshold': 0.35 + }, + { + 'class_name': pedestrian, + 'anchor_sizes': [[0.80, 0.76, 1.76]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-0.91], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.6, + 'unmatched_threshold': 0.4 + }, + { + 'class_name': animal, + 'anchor_sizes': [[0.73, 0.35, 0.5]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-1.80], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.45, + 'unmatched_threshold': 0.3 + }, + ] + + SHARED_CONV_NUM_FILTER: 64 + RPN_HEAD_CFGS: [ + { + 'HEAD_CLS_NAME': ['car'], + }, + { + 'HEAD_CLS_NAME': ['truck', 'bus'], + }, + { + 'HEAD_CLS_NAME': ['emergency_vehicle', 'other_vehicle'], + }, + { + 'HEAD_CLS_NAME': ['motorcycle', 'bicycle'], + }, + { + 'HEAD_CLS_NAME': ['pedestrian', 'animal'], + }, + ] + + SEPARATE_REG_CONFIG: + NUM_MIDDLE_CONV: 1 + NUM_MIDDLE_FILTER: 64 + REG_LIST: ['reg:2', 'height:1', 'size:3', 'angle:2'] + + TARGET_ASSIGNER_CONFIG: + NAME: AxisAlignedTargetAssigner + POS_FRACTION: -1.0 + SAMPLE_SIZE: 512 + NORM_BY_NUM_EXAMPLES: False + MATCH_HEIGHT: False + BOX_CODER: ResidualCoder + BOX_CODER_CONFIG: { + 'code_size': 7, + 'encode_angle_by_sincos': True + } + + + LOSS_CONFIG: + REG_LOSS_TYPE: WeightedL1Loss + LOSS_WEIGHTS: { + 'pos_cls_weight': 1.0, + 'neg_cls_weight': 2.0, + 'cls_weight': 1.0, + 'loc_weight': 0.25, + 'dir_weight': 0.2, + 'code_weights': [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0] + } + + POST_PROCESSING: + RECALL_THRESH_LIST: [0.3, 0.5, 0.7] + SCORE_THRESH: 0.1 + OUTPUT_RAW_SCORE: False + + EVAL_METRIC: lyft + + NMS_CONFIG: + MULTI_CLASSES_NMS: True + NMS_TYPE: nms_gpu + NMS_THRESH: 0.2 + NMS_PRE_MAXSIZE: 1000 + NMS_POST_MAXSIZE: 83 + + +OPTIMIZATION: + BATCH_SIZE_PER_GPU: 3 + NUM_EPOCHS: 50 + + OPTIMIZER: adam_onecycle + LR: 0.003 + WEIGHT_DECAY: 0.01 + MOMENTUM: 0.9 + + MOMS: [0.95, 0.85] + PCT_START: 0.4 + DIV_FACTOR: 10 + DECAY_STEP_LIST: [35, 45] + LR_DECAY: 0.1 + LR_CLIP: 0.0000001 + + LR_WARMUP: False + WARMUP_EPOCH: 1 + + GRAD_NORM_CLIP: 10 From 75b2d0372288d213b95800e09db2a9ba3e09198e Mon Sep 17 00:00:00 2001 From: jihanyang Date: Sat, 18 Dec 2021 15:31:51 +0800 Subject: [PATCH 3/5] add lyft splits --- data/lyft/ImageSets/test.txt | 218 ++++++++++++++++++++++++++++++++++ data/lyft/ImageSets/train.txt | 150 +++++++++++++++++++++++ data/lyft/ImageSets/val.txt | 30 +++++ 3 files changed, 398 insertions(+) create mode 100644 data/lyft/ImageSets/test.txt create mode 100644 data/lyft/ImageSets/train.txt create mode 100644 data/lyft/ImageSets/val.txt diff --git a/data/lyft/ImageSets/test.txt b/data/lyft/ImageSets/test.txt new file mode 100644 index 000000000..0c3532567 --- /dev/null +++ b/data/lyft/ImageSets/test.txt @@ -0,0 +1,218 @@ +host-a004-lidar0-1233944976297786786-1233945001198600096 +host-a004-lidar0-1233941213298388436-1233941238199278096 +host-a011-lidar0-1234644740299444586-1234644765198350636 +host-a004-lidar0-1233601648198462856-1233601673098488556 +host-a011-lidar0-1232746157199035666-1232746182098240026 +host-a009-lidar0-1236017375097801876-1236017399997624556 +host-a011-lidar0-1233962329198070906-1233962354099359636 +host-a007-lidar0-1233523259198624906-1233523284098400466 +host-a004-lidar0-1233427443198938856-1233427468098241556 +host-a007-lidar0-1233952760198014706-1233952785098360666 +host-a004-lidar0-1232831114198639196-1232831139098689906 +host-a011-lidar0-1233959097298631226-1233959122199133096 +host-a011-lidar0-1232736280198893346-1232736305098557556 +host-a008-lidar0-1235757362198327706-1235757387098420756 +host-a007-lidar0-1233947142198222706-1233947167098201666 +host-a009-lidar0-1234715568198453346-1234715593098413676 +host-a004-lidar0-1232911076298600176-1232911101199054856 +host-a011-lidar0-1236103955299212856-1236103980199733906 +host-a007-lidar0-1237572884098557116-1237572908997807546 +host-a011-lidar0-1233964240298899786-1233964265199453556 +host-a004-lidar0-1233079262298510786-1233079287198908466 +host-a004-lidar0-1233687421297771586-1233687446198032636 +host-a008-lidar0-1235780110998543436-1235780135897779096 +host-a011-lidar0-1232488772298383876-1232488797198160346 +host-a004-lidar0-1231878498298402636-1231878523198702316 +host-a015-lidar0-1235952792198484436-1235952817098084116 +host-a004-lidar0-1235945794298780666-1235945819198802346 +host-a011-lidar0-1233963833297804226-1233963858199264096 +host-a004-lidar0-1233506417198072656-1233506442098833106 +host-a009-lidar0-1231801138198800186-1231801163098659866 +host-a011-lidar0-1232751280197949666-1232751305099090996 +host-a004-lidar0-1233946658298833786-1233946683199182096 +host-a004-lidar0-1233687742297900586-1233687767199090986 +host-a004-lidar0-1232905595299117226-1232905620198562226 +host-a004-lidar0-1233961285198272466-1233961310098968226 +host-a011-lidar0-1233085141298793636-1233085166198948316 +host-a010-lidar0-1232314667198394906-1232314692099896986 +host-a007-lidar0-1230931253199029066-1230931278098162746 +host-a007-lidar0-1232995403098212786-1232995427998257586 +host-a011-lidar0-1236106341198519026-1236106366098688706 +host-a004-lidar0-1233962919198446116-1233962944098602196 +host-a011-lidar0-1232744874197271346-1232744899099026346 +host-a011-lidar0-1233957289298013416-1233957314197859536 +host-a011-lidar0-1236039862198450906-1236039887099020026 +host-a011-lidar0-1233956316299257226-1233956341199458096 +host-a004-lidar0-1233521279299019346-1233521304198708656 +host-a007-lidar0-1233005263198512026-1233005288098233756 +host-a007-lidar0-1232995508097871466-1232995532998255586 +host-a011-lidar0-1232486236299484666-1232486261197508346 +host-a011-lidar0-1233959639198614466-1233959664098178176 +host-a007-lidar0-1233015278098306756-1233015302998395786 +host-a004-lidar0-1235858020298070196-1235858045199172906 +host-a011-lidar0-1236105788197720026-1236105813099285026 +host-a004-lidar0-1233439235298936546-1233439260198396226 +host-a004-lidar0-1232987587298107736-1232987612198297786 +host-a011-lidar0-1236103100299832666-1236103125199414996 +host-a015-lidar0-1235952391197848436-1235952416098412116 +host-a004-lidar0-1233521391298537346-1233521416198295656 +host-a004-lidar0-1232991769198099466-1232991794097984146 +host-a004-lidar0-1233953140198673466-1233953165099150176 +host-a004-lidar0-1233081052299073106-1233081077199184436 +host-a007-lidar0-1233956133198909706-1233956158098315666 +host-a011-lidar0-1235868868199238666-1235868893097732316 +host-a007-lidar0-1233953460198410706-1233953485098842786 +host-a011-lidar0-1233961831198549906-1233961856098369176 +host-a011-lidar0-1233514529198419226-1233514554098449346 +host-a007-lidar0-1230939239197974066-1230939264099426746 +host-a011-lidar0-1233091237198666226-1233091262098974026 +host-a004-lidar0-1233442845299348546-1233442870197585226 +host-a009-lidar0-1236020549098474856-1236020573999334586 +host-a011-lidar0-1234024976198295026-1234025001098882226 +host-a011-lidar0-1232907883299065316-1232907908199299976 +host-a004-lidar0-1233601706199079226-1233601731099035556 +host-a011-lidar0-1233082653297382196-1233082678199113346 +host-a011-lidar0-1236094968298801346-1236094993199079346 +host-a007-lidar0-1233007278198865146-1233007303098536106 +host-a004-lidar0-1232740139298853106-1232740164198443466 +host-a007-lidar0-1232840098198209026-1232840123098175986 +host-a007-lidar0-1232491902199024026-1232491927099237736 +host-a004-lidar0-1233447945198501226-1233447970098212556 +host-a004-lidar0-1233963468197846466-1233963493098405196 +host-a011-lidar0-1232497134299369316-1232497159198333026 +host-a007-lidar0-1233683913198228346-1233683938097909026 +host-a004-lidar0-1233965315199029466-1233965340097937546 +host-a011-lidar0-1236106510198830536-1236106535098940676 +host-a011-lidar0-1234031888198360146-1234031913099866226 +host-a011-lidar0-1232483258298822666-1232483283199104026 +host-a011-lidar0-1233963883298333416-1233963908199031906 +host-a011-lidar0-1232411607198546106-1232411632099155466 +host-a009-lidar0-1236120835298099026-1236120860197794756 +host-a004-lidar0-1233089444197814786-1233089469098441116 +host-a004-lidar0-1233946716298797436-1233946741199280636 +host-a004-lidar0-1233443288299030176-1233443313198834856 +host-a004-lidar0-1233088880198387436-1233088905098238096 +host-a011-lidar0-1233956935299563906-1233956960199421666 +host-a009-lidar0-1236020134098279876-1236020158999209906 +host-a011-lidar0-1236094859299152316-1236094884199534466 +host-a008-lidar0-1235758174198256146-1235758199098282106 +host-a011-lidar0-1236121184299486346-1236121209198975996 +host-a011-lidar0-1233961523199115586-1233961548099271666 +host-a004-lidar0-1234732754197914906-1234732779097924636 +host-a009-lidar0-1236121511198446736-1236121536098500436 +host-a008-lidar0-1236034565298114876-1236034590198781906 +host-a006-lidar0-1236098659198274536-1236098684097992536 +host-a009-lidar0-1236013611198536176-1236013636098119856 +host-a015-lidar0-1233957342198356906-1233957367097686986 +host-a011-lidar0-1234028898199503706-1234028923098637226 +host-a007-lidar0-1234564891198141676-1234564916098497756 +host-a011-lidar0-1233512411200132666-1233512436099006556 +host-a011-lidar0-1232839888198187226-1232839913098323346 +host-a011-lidar0-1233959147299652876-1233959172199345586 +host-a011-lidar0-1233515019199540346-1233515044098381026 +host-a007-lidar0-1233621306298394226-1233621331197987026 +host-a009-lidar0-1236018631099309906-1236018655997712116 +host-a011-lidar0-1233956770298774786-1233956795198595906 +host-a011-lidar0-1234031012198940656-1234031037098235226 +host-a011-lidar0-1232834951198260666-1232834976099168996 +host-a004-lidar0-1231810077298582906-1231810102198764586 +host-a015-lidar0-1235432061197143666-1235432086098855666 +host-a004-lidar0-1233955370199325146-1233955395099287546 +host-a007-lidar0-1232739122099041026-1232739146998701786 +host-a008-lidar0-1231272360198562866-1231272385098213606 +host-a009-lidar0-1234043856197659756-1234043881098769786 +host-a011-lidar0-1236123850299533346-1236123875199183536 +host-a004-lidar0-1232829779198385176-1232829804099132906 +host-a004-lidar0-1234046078298238146-1234046103198417226 +host-a011-lidar0-1236118880299007316-1236118905198814556 +host-a011-lidar0-1232839522198475666-1232839547098176996 +host-a004-lidar0-1233683047198434616-1233683072097863296 +host-a011-lidar0-1232483134298411316-1232483159199017026 +host-a011-lidar0-1232835366199044316-1232835391098346996 +host-a011-lidar0-1236037587198526556-1236037612099015026 +host-a004-lidar0-1233514041198025676-1233514066098168106 +host-a011-lidar0-1233514916198928666-1233514941098966346 +host-a007-lidar0-1233952607199156666-1233952632098069666 +host-a011-lidar0-1234655115198110986-1234655140099130346 +host-a015-lidar0-1236124264998206536-1236124289898560636 +host-a011-lidar0-1234644690299314096-1234644715199118176 +host-a011-lidar0-1235952056198818296-1235952081099333786 +host-a011-lidar0-1232748626199298346-1232748651098789346 +host-a007-lidar0-1232475199297946856-1232475224198641556 +host-a007-lidar0-1233525441098373116-1233525465998053546 +host-a008-lidar0-1235761573098617226-1235761597998604906 +host-a004-lidar0-1232991714198772466-1232991739097967096 +host-a004-lidar0-1233687683299064556-1233687708198041986 +host-a007-lidar0-1233013003098382226-1233013027998697786 +host-a004-lidar0-1233439306298453176-1233439331197984226 +host-a004-lidar0-1233424178198144226-1233424203098692536 +host-a006-lidar0-1236097465198430226-1236097490097938026 +host-a011-lidar0-1232841048199446666-1232841073098839996 +host-a011-lidar0-1233516714199191856-1233516739099730116 +host-a007-lidar0-1234311713998886226-1234311738898096786 +host-a007-lidar0-1233536831198375786-1233536856097999586 +host-a004-lidar0-1233429274199024876-1233429299099306906 +host-a004-lidar0-1233959153198568116-1233959178098071546 +host-a011-lidar0-1234552220298342756-1234552245199496436 +host-a011-lidar0-1233521972198420856-1233521997098456536 +host-a006-lidar0-1236097911198275876-1236097936098518536 +host-a011-lidar0-1233689347298085226-1233689372198299556 +host-a004-lidar0-1232916227198731226-1232916252098964536 +host-a004-lidar0-1235943691298894636-1235943716198114296 +host-a011-lidar0-1232905354298416876-1232905379198827346 +host-a004-lidar0-1232825454199122176-1232825479098530856 +host-a004-lidar0-1235865310198314226-1235865335098810536 +host-a007-lidar0-1233511892098885096-1233511916998404176 +host-a004-lidar0-1235952483297492666-1235952508198691346 +host-a007-lidar0-1236123864198260676-1236123889098156106 +host-a011-lidar0-1232751443198845666-1232751468099206346 +host-a011-lidar0-1233078523199259666-1233078548098819996 +host-a004-lidar0-1233618447298368586-1233618472198344666 +host-a007-lidar0-1230678335199240106-1230678360099285186 +host-a004-lidar0-1233508848199005656-1233508873098993106 +host-a011-lidar0-1233958777298868906-1233958802198879556 +host-a007-lidar0-1233507949098749096-1233507973999200196 +host-a004-lidar0-1233953506198624096-1233953531097898546 +host-a015-lidar0-1236103405197509196-1236103430098109856 +host-a007-lidar0-1233620674297428346-1233620699199028906 +host-a012-lidar0-1235936434298098786-1235936459197995466 +host-a011-lidar0-1233514154199609666-1233514179099494586 +host-a009-lidar0-1231184014198521956-1231184039098791066 +host-a004-lidar0-1236019079298483436-1236019104198926466 +host-a006-lidar0-1236037423198601636-1236037448098691666 +host-a004-lidar0-1231888238197475346-1231888263098211346 +host-a010-lidar0-1232317276099120706-1232317300998122666 +host-a004-lidar0-1232815694198030546-1232815719097692906 +host-a007-lidar0-1233954463198147636-1233954488098173786 +host-a004-lidar0-1232923791198849226-1232923816098237586 +host-a011-lidar0-1236106196198429346-1236106221098810676 +host-a015-lidar0-1236124649998497586-1236124674897796616 +host-a004-lidar0-1232386904298052116-1232386929198958786 +host-a014-lidar0-1235764007298887586-1235764032198224636 +host-a011-lidar0-1233961953198251556-1233961978098299986 +host-a015-lidar0-1234646248197843296-1234646273098426346 +host-a004-lidar0-1232823719198617196-1232823744099030906 +host-a006-lidar0-1232910084198374756-1232910109098099436 +host-a008-lidar0-1231535639098399806-1231535663998755486 +host-a006-lidar0-1232909811198488106-1232909836098046436 +host-a011-lidar0-1234472721299135436-1234472746198770146 +host-a004-lidar0-1233941123298835466-1233941148198539096 +host-a004-lidar0-1232842293198603176-1232842318098888226 +host-a011-lidar0-1235503241198830666-1235503266098892346 +host-a007-lidar0-1233007421198689676-1233007446098306106 +host-a011-lidar0-1235942334298364116-1235942359197798196 +host-a011-lidar0-1233964524299020906-1233964549198793586 +host-a011-lidar0-1236094810299383666-1236094835198207026 +host-a004-lidar0-1233439181298702546-1233439206198541786 +host-a004-lidar0-1233429602198887906-1233429627098124906 +host-a011-lidar0-1233688997299519416-1233689022199633116 +host-a011-lidar0-1233088421199045856-1233088446099117556 +host-a011-lidar0-1235866237298160096-1235866262198355986 +host-a004-lidar0-1232825508197625546-1232825533098566906 +host-a007-lidar0-1233620829298440226-1233620854197980906 +host-a011-lidar0-1233962268199095556-1233962293098293666 +host-a009-lidar0-1236017846098562856-1236017870998139586 +host-a004-lidar0-1233521339297626996-1233521364198425656 +host-a011-lidar0-1233962379199267906-1233962404098719666 +host-a007-lidar0-1234043217198181466-1234043242098437196 +host-a007-lidar0-1233952679199347706-1233952704098573316 \ No newline at end of file diff --git a/data/lyft/ImageSets/train.txt b/data/lyft/ImageSets/train.txt new file mode 100644 index 000000000..6c336d86b --- /dev/null +++ b/data/lyft/ImageSets/train.txt @@ -0,0 +1,150 @@ +host-a101-lidar0-1241893239199111666-1241893264098084346 +host-a006-lidar0-1236037883198113706-1236037908098879296 +host-a011-lidar0-1235950297199142196-1235950322099405416 +host-a012-lidar0-1235937130198577346-1235937155098071026 +host-a101-lidar0-1240875136198305786-1240875161098795094 +host-a011-lidar0-1232752461198357666-1232752486099793996 +host-a102-lidar0-1241468916398562586-1241468941298742334 +host-a009-lidar0-1236013297198927176-1236013322098616226 +host-a008-lidar0-1235777217098625786-1235777241998473466 +host-a009-lidar0-1236015606098226876-1236015630998447586 +host-a011-lidar0-1236119823299280856-1236119848199397346 +host-a011-lidar0-1233963416198495906-1233963441098571986 +host-a102-lidar0-1241904536298706586-1241904561198322666 +host-a004-lidar0-1236021339298624436-1236021364198408146 +host-a011-lidar0-1233512833198873346-1233512858098831906 +host-a007-lidar0-1232470052198454586-1232470077098888666 +host-a004-lidar0-1233961181197891466-1233961206097713176 +host-a011-lidar0-1232755934199060666-1232755959099356536 +host-a011-lidar0-1235866707299065096-1235866732198912176 +host-a007-lidar0-1234740239998520226-1234740264899399906 +host-a011-lidar0-1234031754199586656-1234031779098211226 +host-a011-lidar0-1233090630199206666-1233090655098843996 +host-a004-lidar0-1233617933297688906-1233617958198483986 +host-a004-lidar0-1233693263298064536-1233693288197865986 +host-a007-lidar0-1233510590098435146-1233510614998778546 +host-a102-lidar0-1241548686398885894-1241548711298381586 +host-a015-lidar0-1233957265198932906-1233957290097795666 +host-a009-lidar0-1236118456298488636-1236118481198250736 +host-a007-lidar0-1230936221299185986-1230936246198612066 +host-a011-lidar0-1232835293199223316-1232835318097646346 +host-a102-lidar0-1242755400298847586-1242755425198579666 +host-a004-lidar0-1233422539197434856-1233422564099152556 +host-a101-lidar0-1242580003398722214-1242580028299473214 +host-a007-lidar0-1233954992197900986-1233955017097982666 +host-a004-lidar0-1233685315298191906-1233685340197986666 +host-a008-lidar0-1236015187198059026-1236015212098657616 +host-a011-lidar0-1232905783299194316-1232905808199600976 +host-a004-lidar0-1233682997198306636-1233683022098032666 +host-a006-lidar0-1236038131197892706-1236038156098552296 +host-a007-lidar0-1233955131199105986-1233955156098128666 +host-a007-lidar0-1234737958998212856-1234737983898305906 +host-a102-lidar0-1241878200398362906-1241878225298546586 +host-a011-lidar0-1232492192198952026-1232492217098860706 +host-a009-lidar0-1231200854198312986-1231200879098460066 +host-a011-lidar0-1232839939198224316-1232839964099010996 +host-a101-lidar0-1242493624298705334-1242493649198973302 +host-a101-lidar0-1243095610299140346-1243095635198749774 +host-a011-lidar0-1234553365299813296-1234553390199271786 +host-a011-lidar0-1233087918198597316-1233087943098472996 +host-a004-lidar0-1232923266198326856-1232923291098716906 +host-a007-lidar0-1233689791098884906-1233689815997978986 +host-a011-lidar0-1232753667198514346-1232753692099110026 +host-a004-lidar0-1232987652297797736-1232987677198272416 +host-a011-lidar0-1232841333199326666-1232841358099777556 +host-a011-lidar0-1235931114299585906-1235931139198414556 +host-a004-lidar0-1234051595199019546-1234051620099157876 +host-a004-lidar0-1232815252198642176-1232815277099387856 +host-a011-lidar0-1234025165199395146-1234025190098246226 +host-a004-lidar0-1233618009298519906-1233618034198134636 +host-a004-lidar0-1235947081298918616-1235947106198383666 +host-a004-lidar0-1233535955298751556-1233535980198120666 +host-a101-lidar0-1241889710198571346-1241889735098952214 +host-a004-lidar0-1233442991299115176-1233443016198370876 +host-a007-lidar0-1233007769198478676-1233007794098024226 +host-a011-lidar0-1233688931299349876-1233688956199708556 +host-a004-lidar0-1236018644297896466-1236018669198234096 +host-a004-lidar0-1233947108297817786-1233947133198765096 +host-a004-lidar0-1235944794298214636-1235944819199047666 +host-a007-lidar0-1233524852199250466-1233524877097605116 +host-a008-lidar0-1235776284099006226-1235776308998255906 +host-a101-lidar0-1242748817298870302-1242748842198675302 +host-a007-lidar0-1233529706297796756-1233529731198779786 +host-a011-lidar0-1232909940298708666-1232909965199312906 +host-a011-lidar0-1232412236198491106-1232412261098202466 +host-a011-lidar0-1236038911199051026-1236038936099738706 +host-a008-lidar0-1236013033198326026-1236013058097878706 +host-a101-lidar0-1242753236298794334-1242753261198702302 +host-a011-lidar0-1235933627299543026-1235933652198559196 +host-a004-lidar0-1233620260298411906-1233620285198333986 +host-a101-lidar0-1242144886399176654-1242144911299066654 +host-a102-lidar0-1242684244198410786-1242684269098866094 +host-a011-lidar0-1232738595197630316-1232738620098495346 +host-a007-lidar0-1233508020098603466-1233508044998550666 +host-a102-lidar0-1242510597398871466-1242510622298829226 +host-a101-lidar0-1243102866399012786-1243102891298922466 +host-a009-lidar0-1236020733098808906-1236020757997885536 +host-a011-lidar0-1232745770199275666-1232745795099558556 +host-a101-lidar0-1241886983298988182-1241887008198992182 +host-a004-lidar0-1233693191297468536-1233693216198791636 +host-a017-lidar0-1236119797198435536-1236119822098126616 +host-a007-lidar0-1233515286998507736-1233515311898052226 +host-a007-lidar0-1230672860198383106-1230672885099108186 +host-a004-lidar0-1233014343198383656-1233014368098267106 +host-a004-lidar0-1233516150198382706-1233516175098720106 +host-a007-lidar0-1230485630199365106-1230485655099030186 +host-a004-lidar0-1232838138198668196-1232838163098533856 +host-a011-lidar0-1236037921199248346-1236037946099430676 +host-a011-lidar0-1233081021198156856-1233081046098157026 +host-a004-lidar0-1232825386198046196-1232825411098056856 +host-a017-lidar0-1236118981198431906-1236119006097572636 +host-a015-lidar0-1236103725197932106-1236103750098792856 +host-a007-lidar0-1233515591998210666-1233515616898664876 +host-a007-lidar0-1232736726098319676-1232736750999473736 +host-a004-lidar0-1233011743198634026-1233011768099043756 +host-a101-lidar0-1242749258298976334-1242749283199254466 +host-a007-lidar0-1232490767197744146-1232490792098614756 +host-a011-lidar0-1234466278299425556-1234466303199121616 +host-a011-lidar0-1236122349298071346-1236122374198621346 +host-a101-lidar0-1241216089098610756-1241216113999079830 +host-a004-lidar0-1233602012198802906-1233602037098984906 +host-a004-lidar0-1233421984198960226-1233422009098905556 +host-a004-lidar0-1233685221298830296-1233685246198471636 +host-a017-lidar0-1236118873198607026-1236118898097847616 +host-a011-lidar0-1233522430198228856-1233522455098303536 +host-a101-lidar0-1242748985299274334-1242749010198891466 +host-a004-lidar0-1234047743298156466-1234047768199244736 +host-a015-lidar0-1235423635198474636-1235423660098038666 +host-a004-lidar0-1233955731199067146-1233955756098663196 +host-a009-lidar0-1236118555299408756-1236118580198077756 +host-a007-lidar0-1234551913098444106-1234551937998728436 +host-a101-lidar0-1241472407298206026-1241472432198409706 +host-a011-lidar0-1236039783198411996-1236039808098336676 +host-a015-lidar0-1236112601097782876-1236112625998366556 +host-a012-lidar0-1237329862198269106-1237329887099105436 +host-a007-lidar0-1231093036199514746-1231093061099651426 +host-a007-lidar0-1233960442199212986-1233960467099041666 +host-a009-lidar0-1236123717198611786-1236123742097892436 +host-a009-lidar0-1237581206198345466-1237581231098504546 +host-a011-lidar0-1233964282297830226-1233964307199768556 +host-a011-lidar0-1232752778198249666-1232752803099491536 +host-a102-lidar0-1242662270298972894-1242662295198395706 +host-a011-lidar0-1232485958298280666-1232485983200054996 +host-a005-lidar0-1231201437298603426-1231201462198815506 +host-a007-lidar0-1233510205099156466-1233510229998563196 +host-a102-lidar0-1242754954298696742-1242754979198120666 +host-a004-lidar0-1233444816298625546-1233444841198302226 +host-a004-lidar0-1232842166198181226-1232842191097390226 +host-a004-lidar0-1232833308197903226-1232833333099155226 +host-a011-lidar0-1232401360198078026-1232401385098379106 +host-a011-lidar0-1236123625299234316-1236123650197952996 +host-a004-lidar0-1233427004198119856-1233427029098998676 +host-a102-lidar0-1242749461398477906-1242749486298996742 +host-a102-lidar0-1242150795498255026-1242150820398693830 +host-a011-lidar0-1232731591298977986-1232731616197888346 +host-a011-lidar0-1233964369297973906-1233964394199186906 +host-a011-lidar0-1232837612197878316-1232837637099721996 +host-a101-lidar0-1241462203298815998-1241462228198805706 +host-a009-lidar0-1236014648198307196-1236014673098985906 +host-a007-lidar0-1233956183198377616-1233956208098469296 +host-a004-lidar0-1232817645198462196-1232817670098101226 \ No newline at end of file diff --git a/data/lyft/ImageSets/val.txt b/data/lyft/ImageSets/val.txt new file mode 100644 index 000000000..920dc2779 --- /dev/null +++ b/data/lyft/ImageSets/val.txt @@ -0,0 +1,30 @@ +host-a004-lidar0-1233080749298771736-1233080774198118416 +host-a004-lidar0-1232905197298264546-1232905222198133856 +host-a011-lidar0-1232732468299489666-1232732493199050666 +host-a101-lidar0-1241561147998866622-1241561172899320654 +host-a006-lidar0-1237322885198285226-1237322910098576786 +host-a004-lidar0-1233963848198981116-1233963873098642176 +host-a011-lidar0-1232752543198025666-1232752568099126026 +host-a004-lidar0-1232842367198056546-1232842392097783226 +host-a004-lidar0-1233615989298293586-1233616014198854636 +host-a011-lidar0-1233965426299054906-1233965451199121906 +host-a011-lidar0-1236104034298928316-1236104059198988026 +host-a007-lidar0-1233946614199227636-1233946639098289666 +host-a015-lidar0-1235423696198069636-1235423721098551296 +host-a004-lidar0-1233014843199117706-1233014868098023786 +host-a011-lidar0-1236093962299300416-1236093987199363346 +host-a011-lidar0-1234639296198260986-1234639321099417316 +host-a011-lidar0-1233524871199389346-1233524896098591466 +host-a011-lidar0-1235933781298838116-1235933806199517736 +host-a011-lidar0-1233965312298542226-1233965337198958586 +host-a011-lidar0-1233090567199118316-1233090592098933996 +host-a007-lidar0-1233621256298511876-1233621281197988026 +host-a007-lidar0-1233079617197863906-1233079642098533586 +host-a015-lidar0-1236112516098396876-1236112540999028556 +host-a008-lidar0-1236016333197799906-1236016358099063636 +host-a101-lidar0-1240710366399037786-1240710391298976894 +host-a102-lidar0-1242755350298764586-1242755375198787666 +host-a101-lidar0-1240877587199107226-1240877612099413030 +host-a101-lidar0-1242583745399163026-1242583770298821706 +host-a011-lidar0-1232817034199342856-1232817059098800346 +host-a004-lidar0-1232905117299287546-1232905142198246226 \ No newline at end of file From dffbb04a35264aa657eab8e7b9dc70cd37ee967f Mon Sep 17 00:00:00 2001 From: jihanyang Date: Sat, 18 Dec 2021 15:57:48 +0800 Subject: [PATCH 4/5] add lyft model cfg --- .../cbgs_second-nores_multihead.yaml | 215 ++++++++++++++++++ 1 file changed, 215 insertions(+) create mode 100644 tools/cfgs/lyft_models/cbgs_second-nores_multihead.yaml diff --git a/tools/cfgs/lyft_models/cbgs_second-nores_multihead.yaml b/tools/cfgs/lyft_models/cbgs_second-nores_multihead.yaml new file mode 100644 index 000000000..ec51906d3 --- /dev/null +++ b/tools/cfgs/lyft_models/cbgs_second-nores_multihead.yaml @@ -0,0 +1,215 @@ +CLASS_NAMES: ['car','truck', 'bus', 'emergency_vehicle', 'other_vehicle', + 'motorcycle', 'bicycle', 'pedestrian', 'animal'] + +DATA_CONFIG: + _BASE_CONFIG_: cfgs/dataset_configs/lyft_dataset.yaml + + +MODEL: + NAME: SECONDNet + + VFE: + NAME: MeanVFE + + BACKBONE_3D: + NAME: VoxelBackBone8x + + MAP_TO_BEV: + NAME: HeightCompression + NUM_BEV_FEATURES: 256 + + BACKBONE_2D: + NAME: BaseBEVBackbone + + LAYER_NUMS: [5, 5] + LAYER_STRIDES: [1, 2] + NUM_FILTERS: [128, 256] + UPSAMPLE_STRIDES: [1, 2] + NUM_UPSAMPLE_FILTERS: [256, 256] + + DENSE_HEAD: + NAME: AnchorHeadMulti + CLASS_AGNOSTIC: False + + DIR_OFFSET: 0.78539 + DIR_LIMIT_OFFSET: 0.0 + NUM_DIR_BINS: 2 + + USE_MULTIHEAD: True + SEPARATE_MULTIHEAD: True + ANCHOR_GENERATOR_CONFIG: [ + { + 'class_name': car, + 'anchor_sizes': [[4.75, 1.92, 1.71]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-1.07], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.6, + 'unmatched_threshold': 0.45 + }, + { + 'class_name': truck, + 'anchor_sizes': [[10.24, 2.84, 3.44]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-0.30], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.55, + 'unmatched_threshold': 0.4 + }, + { + 'class_name': bus, + 'anchor_sizes': [[12.70, 2.92, 3.42]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-0.35], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.55, + 'unmatched_threshold': 0.4 + }, + { + 'class_name': emergency_vehicle, + 'anchor_sizes': [[6.52, 2.42, 2.34]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-0.89], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.5, + 'unmatched_threshold': 0.35 + }, + { + 'class_name': other_vehicle, + 'anchor_sizes': [[8.17, 2.75, 3.20]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-0.63], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.55, + 'unmatched_threshold': 0.4 + }, + { + 'class_name': motorcycle, + 'anchor_sizes': [[2.35, 0.96, 1.59]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-1.32], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.5, + 'unmatched_threshold': 0.3 + }, + { + 'class_name': bicycle, + 'anchor_sizes': [[1.76, 0.63, 1.44]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-1.07], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.5, + 'unmatched_threshold': 0.35 + }, + { + 'class_name': pedestrian, + 'anchor_sizes': [[0.80, 0.76, 1.76]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-0.91], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.6, + 'unmatched_threshold': 0.4 + }, + { + 'class_name': animal, + 'anchor_sizes': [[0.73, 0.35, 0.5]], + 'anchor_rotations': [0, 1.57], + 'anchor_bottom_heights': [-1.80], + 'align_center': False, + 'feature_map_stride': 8, + 'matched_threshold': 0.45, + 'unmatched_threshold': 0.3 + }, + ] + + SHARED_CONV_NUM_FILTER: 64 + RPN_HEAD_CFGS: [ + { + 'HEAD_CLS_NAME': ['car'], + }, + { + 'HEAD_CLS_NAME': ['truck', 'bus'], + }, + { + 'HEAD_CLS_NAME': ['emergency_vehicle', 'other_vehicle'], + }, + { + 'HEAD_CLS_NAME': ['motorcycle', 'bicycle'], + }, + { + 'HEAD_CLS_NAME': ['pedestrian', 'animal'], + }, + ] + + SEPARATE_REG_CONFIG: + NUM_MIDDLE_CONV: 1 + NUM_MIDDLE_FILTER: 64 + REG_LIST: ['reg:2', 'height:1', 'size:3', 'angle:2'] + + TARGET_ASSIGNER_CONFIG: + NAME: AxisAlignedTargetAssigner + POS_FRACTION: -1.0 + SAMPLE_SIZE: 512 + NORM_BY_NUM_EXAMPLES: False + MATCH_HEIGHT: False + BOX_CODER: ResidualCoder + BOX_CODER_CONFIG: { + 'code_size': 7, + 'encode_angle_by_sincos': True + } + + + LOSS_CONFIG: + REG_LOSS_TYPE: WeightedL1Loss + LOSS_WEIGHTS: { + 'pos_cls_weight': 1.0, + 'neg_cls_weight': 2.0, + 'cls_weight': 1.0, + 'loc_weight': 0.25, + 'dir_weight': 0.2, + 'code_weights': [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0] + } + + POST_PROCESSING: + RECALL_THRESH_LIST: [0.3, 0.5, 0.7] + SCORE_THRESH: 0.1 + OUTPUT_RAW_SCORE: False + + EVAL_METRIC: lyft + + NMS_CONFIG: + MULTI_CLASSES_NMS: True + NMS_TYPE: nms_gpu + NMS_THRESH: 0.2 + NMS_PRE_MAXSIZE: 1000 + NMS_POST_MAXSIZE: 83 + + +OPTIMIZATION: + BATCH_SIZE_PER_GPU: 3 + NUM_EPOCHS: 50 + + OPTIMIZER: adam_onecycle + LR: 0.003 + WEIGHT_DECAY: 0.01 + MOMENTUM: 0.9 + + MOMS: [0.95, 0.85] + PCT_START: 0.4 + DIV_FACTOR: 10 + DECAY_STEP_LIST: [35, 45] + LR_DECAY: 0.1 + LR_CLIP: 0.0000001 + + LR_WARMUP: False + WARMUP_EPOCH: 1 + + GRAD_NORM_CLIP: 10 From d1774307e6727218529d2b1806a6266b223e564f Mon Sep 17 00:00:00 2001 From: jihanyang Date: Sun, 19 Dec 2021 18:30:38 +0800 Subject: [PATCH 5/5] update README --- docs/GETTING_STARTED.md | 29 +++++++++++++++++++++++++++++ 1 file changed, 29 insertions(+) diff --git a/docs/GETTING_STARTED.md b/docs/GETTING_STARTED.md index 1237bd804..c14328580 100644 --- a/docs/GETTING_STARTED.md +++ b/docs/GETTING_STARTED.md @@ -98,6 +98,35 @@ python -m pcdet.datasets.waymo.waymo_dataset --func create_waymo_infos \ Note that you do not need to install `waymo-open-dataset` if you have already processed the data before and do not need to evaluate with official Waymo Metrics. + +### Lyft Dataset +* Please download the official [Lyft Level5 perception dataset](https://level-5.global/data/perception) and +organize the downloaded files as follows: +``` +OpenPCDet +├── data +│ ├── lyft +│ │ │── ImageSets +│ │ │── trainval +│ │ │ │── data & maps & images & lidar & train_lidar +├── pcdet +├── tools +``` + +* Install the `lyft-dataset-sdk` with version `0.0.8` by running the following command: +```shell script +pip install -U lyft_dataset_sdk==0.0.8 +``` + +* Generate the data infos by running the following command (it may take several hours): +```python +python -m pcdet.datasets.lyft.lyft_dataset --func create_lyft_infos \ + --cfg_file tools/cfgs/dataset_configs/lyft_dataset.yaml +``` + +* You need to check carefully since we don't provide a benchmark for it. + + ## Pretrained Models If you would like to train [CaDDN](../tools/cfgs/kitti_models/CaDDN.yaml), download the pretrained [DeepLabV3 model](https://download.pytorch.org/models/deeplabv3_resnet101_coco-586e9e4e.pth) and place within the `checkpoints` directory. Please make sure the [kornia](https://github.com/kornia/kornia) is installed since it is needed for `CaDDN`. ```