Showing preview only (3,395K chars total). Download the full file or copy to clipboard to get everything.
Repository: yichen928/SparseFusion
Branch: main
Commit: 22537781e033
Files: 516
Total size: 3.1 MB
Directory structure:
gitextract_232uyltz/
├── .gitignore
├── LICENSE
├── MANIFEST.in
├── README.md
├── README_zh-CN.md
├── configs/
│ ├── 3dssd/
│ │ ├── 3dssd_kitti-3d-car.py
│ │ └── README.md
│ ├── _base_/
│ │ ├── datasets/
│ │ │ ├── coco_instance.py
│ │ │ ├── kitti-3d-3class.py
│ │ │ ├── kitti-3d-car.py
│ │ │ ├── lyft-3d.py
│ │ │ ├── nuim_instance.py
│ │ │ ├── nus-3d.py
│ │ │ ├── range100_lyft-3d.py
│ │ │ ├── scannet-3d-18class.py
│ │ │ ├── sunrgbd-3d-10class.py
│ │ │ ├── waymoD5-3d-3class.py
│ │ │ └── waymoD5-3d-car.py
│ │ ├── default_runtime.py
│ │ ├── models/
│ │ │ ├── 3dssd.py
│ │ │ ├── cascade_mask_rcnn_r50_fpn.py
│ │ │ ├── centerpoint_01voxel_second_secfpn_nus.py
│ │ │ ├── centerpoint_02pillar_second_secfpn_nus.py
│ │ │ ├── h3dnet.py
│ │ │ ├── hv_pointpillars_fpn_lyft.py
│ │ │ ├── hv_pointpillars_fpn_nus.py
│ │ │ ├── hv_pointpillars_fpn_range100_lyft.py
│ │ │ ├── hv_pointpillars_secfpn_kitti.py
│ │ │ ├── hv_pointpillars_secfpn_waymo.py
│ │ │ ├── hv_second_secfpn_kitti.py
│ │ │ ├── hv_second_secfpn_waymo.py
│ │ │ ├── imvotenet_image.py
│ │ │ ├── mask_rcnn_r50_fpn.py
│ │ │ └── votenet.py
│ │ └── schedules/
│ │ ├── cyclic_20e.py
│ │ ├── cyclic_40e.py
│ │ ├── mmdet_schedule_1x.py
│ │ ├── schedule_2x.py
│ │ └── schedule_3x.py
│ ├── benchmark/
│ │ ├── hv_PartA2_secfpn_4x8_cyclic_80e_pcdet_kitti-3d-3class.py
│ │ ├── hv_pointpillars_secfpn_3x8_100e_det3d_kitti-3d-car.py
│ │ ├── hv_pointpillars_secfpn_4x8_80e_pcdet_kitti-3d-3class.py
│ │ └── hv_second_secfpn_4x8_80e_pcdet_kitti-3d-3class.py
│ ├── centerpoint/
│ │ ├── README.md
│ │ ├── centerpoint_0075voxel_second_secfpn_4x8_cyclic_20e_nus.py
│ │ ├── centerpoint_0075voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus.py
│ │ ├── centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_20e_nus.py
│ │ ├── centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_flip-tta_20e_nus.py
│ │ ├── centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_tta_20e_nus.py
│ │ ├── centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py
│ │ ├── centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_flip-tta_20e_nus.py
│ │ ├── centerpoint_01voxel_second_secfpn_4x8_cyclic_20e_nus.py
│ │ ├── centerpoint_01voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus.py
│ │ ├── centerpoint_01voxel_second_secfpn_dcn_4x8_cyclic_20e_nus.py
│ │ ├── centerpoint_01voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py
│ │ ├── centerpoint_02pillar_second_secfpn_4x8_cyclic_20e_nus.py
│ │ ├── centerpoint_02pillar_second_secfpn_circlenms_4x8_cyclic_20e_nus.py
│ │ ├── centerpoint_02pillar_second_secfpn_dcn_4x8_cyclic_20e_nus.py
│ │ └── centerpoint_02pillar_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py
│ ├── dynamic_voxelization/
│ │ ├── README.md
│ │ ├── dv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py
│ │ ├── dv_second_secfpn_2x8_cosine_80e_kitti-3d-3class.py
│ │ └── dv_second_secfpn_6x8_80e_kitti-3d-car.py
│ ├── fp16/
│ │ ├── README.md
│ │ ├── hv_pointpillars_fpn_sbn-all_fp16_2x8_2x_nus-3d.py
│ │ ├── hv_pointpillars_regnet-400mf_fpn_sbn-all_fp16_2x8_2x_nus-3d.py
│ │ ├── hv_pointpillars_secfpn_sbn-all_fp16_2x8_2x_nus-3d.py
│ │ ├── hv_second_secfpn_fp16_6x8_80e_kitti-3d-3class.py
│ │ └── hv_second_secfpn_fp16_6x8_80e_kitti-3d-car.py
│ ├── free_anchor/
│ │ ├── README.md
│ │ ├── hv_pointpillars_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py
│ │ ├── hv_pointpillars_regnet-1.6gf_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py
│ │ ├── hv_pointpillars_regnet-1.6gf_fpn_sbn-all_free-anchor_strong-aug_4x8_3x_nus-3d.py
│ │ ├── hv_pointpillars_regnet-3.2gf_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py
│ │ ├── hv_pointpillars_regnet-3.2gf_fpn_sbn-all_free-anchor_strong-aug_4x8_3x_nus-3d.py
│ │ └── hv_pointpillars_regnet-400mf_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py
│ ├── h3dnet/
│ │ ├── README.md
│ │ └── h3dnet_3x8_scannet-3d-18class.py
│ ├── imvotenet/
│ │ ├── README.md
│ │ ├── imvotenet_faster_rcnn_r50_fpn_2x4_sunrgbd-3d-10class.py
│ │ └── imvotenet_stage2_16x8_sunrgbd-3d-10class.py
│ ├── mvxnet/
│ │ ├── README.md
│ │ └── dv_mvx-fpn_second_secfpn_adamw_2x8_80e_kitti-3d-3class.py
│ ├── nuimages/
│ │ ├── README.md
│ │ ├── cascade_mask_rcnn_r101_fpn_1x_nuim.py
│ │ ├── cascade_mask_rcnn_r50_fpn_1x_nuim.py
│ │ ├── cascade_mask_rcnn_r50_fpn_coco-20e_1x_nuim.py
│ │ ├── cascade_mask_rcnn_r50_fpn_coco-20e_20e_nuim.py
│ │ ├── cascade_mask_rcnn_x101_32x4d_fpn_1x_nuim.py
│ │ ├── htc_r50_fpn_1x_nuim.py
│ │ ├── htc_r50_fpn_coco-20e_1x_nuim.py
│ │ ├── htc_r50_fpn_coco-20e_20e_nuim.py
│ │ ├── htc_without_semantic_r50_fpn_1x_nuim.py
│ │ ├── htc_x101_64x4d_fpn_dconv_c3-c5_coco-20e_16x1_20e_nuim.py
│ │ ├── mask_rcnn_r101_fpn_1x_nuim.py
│ │ ├── mask_rcnn_r50_caffe_fpn_1x_nuim.py
│ │ ├── mask_rcnn_r50_caffe_fpn_coco-3x_1x_nuim.py
│ │ ├── mask_rcnn_r50_caffe_fpn_coco-3x_20e_nuim.py
│ │ ├── mask_rcnn_r50_fpn_1x_nuim.py
│ │ ├── mask_rcnn_r50_fpn_coco-2x_1x_nuim.py
│ │ ├── mask_rcnn_r50_fpn_coco-2x_1x_nus-2d.py
│ │ ├── mask_rcnn_swinT_coco-2x_1x_nuim.py
│ │ └── mask_rcnn_x101_32x4d_fpn_1x_nuim.py
│ ├── nuscenes.md
│ ├── parta2/
│ │ ├── README.md
│ │ ├── hv_PartA2_secfpn_2x8_cyclic_80e_kitti-3d-3class.py
│ │ └── hv_PartA2_secfpn_2x8_cyclic_80e_kitti-3d-car.py
│ ├── pointpillars/
│ │ ├── README.md
│ │ ├── hv_pointpillars_fpn_sbn-all_2x8_2x_lyft-3d.py
│ │ ├── hv_pointpillars_fpn_sbn-all_4x8_2x_nus-3d.py
│ │ ├── hv_pointpillars_fpn_sbn-all_range100_2x8_2x_lyft-3d.py
│ │ ├── hv_pointpillars_secfpn_6x8_160e_kitti-3d-3class.py
│ │ ├── hv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py
│ │ ├── hv_pointpillars_secfpn_sbn-all_2x8_2x_lyft-3d.py
│ │ ├── hv_pointpillars_secfpn_sbn-all_4x8_2x_nus-3d.py
│ │ ├── hv_pointpillars_secfpn_sbn-all_range100_2x8_2x_lyft-3d.py
│ │ ├── hv_pointpillars_secfpn_sbn_2x16_2x_waymo-3d-3class.py
│ │ ├── hv_pointpillars_secfpn_sbn_2x16_2x_waymo-3d-car.py
│ │ ├── hv_pointpillars_secfpn_sbn_2x16_2x_waymoD5-3d-3class.py
│ │ └── hv_pointpillars_secfpn_sbn_2x16_2x_waymoD5-3d-car.py
│ ├── regnet/
│ │ ├── README.md
│ │ ├── hv_pointpillars_regnet-1.6gf_fpn_sbn-all_4x8_2x_nus-3d.py
│ │ ├── hv_pointpillars_regnet-400mf_fpn_sbn-all_2x8_2x_lyft-3d.py
│ │ ├── hv_pointpillars_regnet-400mf_fpn_sbn-all_4x8_2x_nus-3d.py
│ │ ├── hv_pointpillars_regnet-400mf_fpn_sbn-all_range100_2x8_2x_lyft-3d.py
│ │ ├── hv_pointpillars_regnet-400mf_secfpn_sbn-all_2x8_2x_lyft-3d.py
│ │ ├── hv_pointpillars_regnet-400mf_secfpn_sbn-all_4x8_2x_nus-3d.py
│ │ └── hv_pointpillars_regnet-400mf_secfpn_sbn-all_range100_2x8_2x_lyft-3d.py
│ ├── second/
│ │ ├── README.md
│ │ ├── hv_second_secfpn_6x8_80e_kitti-3d-3class.py
│ │ ├── hv_second_secfpn_6x8_80e_kitti-3d-car.py
│ │ └── hv_second_secfpn_sbn_2x16_2x_waymoD5-3d-3class.py
│ ├── sparsefusion_nusc_voxel_LC_SwinT.py
│ ├── sparsefusion_nusc_voxel_LC_r50.py
│ ├── ssn/
│ │ ├── README.md
│ │ ├── hv_ssn_regnet-400mf_secfpn_sbn-all_1x16_2x_lyft-3d.py
│ │ ├── hv_ssn_regnet-400mf_secfpn_sbn-all_2x16_2x_nus-3d.py
│ │ ├── hv_ssn_secfpn_sbn-all_2x16_2x_lyft-3d.py
│ │ └── hv_ssn_secfpn_sbn-all_2x16_2x_nus-3d.py
│ ├── transfusion_nusc_pillar_L.py
│ ├── transfusion_nusc_pillar_LC.py
│ ├── transfusion_nusc_voxel_L.py
│ ├── transfusion_nusc_voxel_LC.py
│ ├── transfusion_waymo_voxel_L.py
│ ├── transfusion_waymo_voxel_LC.py
│ ├── votenet/
│ │ ├── README.md
│ │ ├── votenet_16x8_sunrgbd-3d-10class.py
│ │ ├── votenet_8x8_scannet-3d-18class.py
│ │ └── votenet_iouloss_8x8_scannet-3d-18class.py
│ └── waymo.md
├── demo/
│ └── pcd_demo.py
├── docker/
│ └── Dockerfile
├── mmdet3d/
│ ├── __init__.py
│ ├── apis/
│ │ ├── __init__.py
│ │ ├── inference.py
│ │ └── test.py
│ ├── core/
│ │ ├── __init__.py
│ │ ├── anchor/
│ │ │ ├── __init__.py
│ │ │ └── anchor_3d_generator.py
│ │ ├── bbox/
│ │ │ ├── __init__.py
│ │ │ ├── assigners/
│ │ │ │ ├── __init__.py
│ │ │ │ └── hungarian_assigner.py
│ │ │ ├── box_np_ops.py
│ │ │ ├── coders/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── anchor_free_bbox_coder.py
│ │ │ │ ├── camera_bbox_coder.py
│ │ │ │ ├── centerpoint_bbox_coders.py
│ │ │ │ ├── delta_xyzwhlr_bbox_coder.py
│ │ │ │ ├── partial_bin_based_bbox_coder.py
│ │ │ │ └── transfusion_bbox_coder.py
│ │ │ ├── iou_calculators/
│ │ │ │ ├── __init__.py
│ │ │ │ └── iou3d_calculator.py
│ │ │ ├── samplers/
│ │ │ │ ├── __init__.py
│ │ │ │ └── iou_neg_piecewise_sampler.py
│ │ │ ├── structures/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── base_box3d.py
│ │ │ │ ├── box_3d_mode.py
│ │ │ │ ├── cam_box3d.py
│ │ │ │ ├── coord_3d_mode.py
│ │ │ │ ├── depth_box3d.py
│ │ │ │ ├── lidar_box3d.py
│ │ │ │ └── utils.py
│ │ │ └── transforms.py
│ │ ├── evaluation/
│ │ │ ├── __init__.py
│ │ │ ├── indoor_eval.py
│ │ │ ├── kitti_utils/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── eval.py
│ │ │ │ └── rotate_iou.py
│ │ │ ├── lyft_eval.py
│ │ │ ├── seg_eval.py
│ │ │ └── waymo_utils/
│ │ │ └── prediction_kitti_to_waymo.py
│ │ ├── points/
│ │ │ ├── __init__.py
│ │ │ ├── base_points.py
│ │ │ ├── cam_points.py
│ │ │ ├── depth_points.py
│ │ │ └── lidar_points.py
│ │ ├── post_processing/
│ │ │ ├── __init__.py
│ │ │ ├── box3d_nms.py
│ │ │ └── merge_augs.py
│ │ ├── utils/
│ │ │ ├── __init__.py
│ │ │ └── gaussian.py
│ │ ├── visualizer/
│ │ │ ├── __init__.py
│ │ │ ├── open3d_vis.py
│ │ │ └── show_result.py
│ │ └── voxel/
│ │ ├── __init__.py
│ │ ├── builder.py
│ │ └── voxel_generator.py
│ ├── datasets/
│ │ ├── __init__.py
│ │ ├── builder.py
│ │ ├── custom_3d.py
│ │ ├── dataset_wrappers.py
│ │ ├── kitti2d_dataset.py
│ │ ├── kitti_dataset.py
│ │ ├── lyft_dataset.py
│ │ ├── nuscenes_dataset.py
│ │ ├── nuscenes_dataset_viewInfo.py
│ │ ├── pipelines/
│ │ │ ├── __init__.py
│ │ │ ├── data_augment_utils.py
│ │ │ ├── dbsampler.py
│ │ │ ├── formating.py
│ │ │ ├── loading.py
│ │ │ ├── test_time_aug.py
│ │ │ ├── transforms_2d.py
│ │ │ └── transforms_3d.py
│ │ ├── registry.py
│ │ ├── scannet_dataset.py
│ │ ├── semantickitti_dataset.py
│ │ ├── sunrgbd_dataset.py
│ │ └── waymo_dataset.py
│ ├── models/
│ │ ├── __init__.py
│ │ ├── backbones/
│ │ │ ├── DLA.py
│ │ │ ├── __init__.py
│ │ │ ├── base_pointnet.py
│ │ │ ├── multi_backbone.py
│ │ │ ├── nostem_regnet.py
│ │ │ ├── pointnet2_sa_msg.py
│ │ │ ├── pointnet2_sa_ssg.py
│ │ │ ├── second.py
│ │ │ └── swin.py
│ │ ├── builder.py
│ │ ├── dense_heads/
│ │ │ ├── __init__.py
│ │ │ ├── anchor3d_head.py
│ │ │ ├── base_conv_bbox_head.py
│ │ │ ├── centerpoint_head.py
│ │ │ ├── free_anchor3d_head.py
│ │ │ ├── parta2_rpn_head.py
│ │ │ ├── shape_aware_head.py
│ │ │ ├── sparsefusion_head_deform.py
│ │ │ ├── ssd_3d_head.py
│ │ │ ├── train_mixins.py
│ │ │ ├── transfusion_head.py
│ │ │ └── vote_head.py
│ │ ├── detectors/
│ │ │ ├── __init__.py
│ │ │ ├── base.py
│ │ │ ├── centerpoint.py
│ │ │ ├── dynamic_voxelnet.py
│ │ │ ├── h3dnet.py
│ │ │ ├── imvotenet.py
│ │ │ ├── mvx_faster_rcnn.py
│ │ │ ├── mvx_two_stage.py
│ │ │ ├── parta2.py
│ │ │ ├── single_stage.py
│ │ │ ├── sparsefusion.py
│ │ │ ├── ssd3dnet.py
│ │ │ ├── transfusion.py
│ │ │ ├── two_stage.py
│ │ │ ├── votenet.py
│ │ │ └── voxelnet.py
│ │ ├── fusion_layers/
│ │ │ ├── __init__.py
│ │ │ ├── coord_transform.py
│ │ │ ├── point_fusion.py
│ │ │ └── vote_fusion.py
│ │ ├── losses/
│ │ │ ├── __init__.py
│ │ │ ├── axis_aligned_iou_loss.py
│ │ │ ├── chamfer_distance.py
│ │ │ └── uncertainty_loss.py
│ │ ├── middle_encoders/
│ │ │ ├── __init__.py
│ │ │ ├── pillar_scatter.py
│ │ │ ├── sparse_encoder.py
│ │ │ └── sparse_unet.py
│ │ ├── model_utils/
│ │ │ ├── __init__.py
│ │ │ └── vote_module.py
│ │ ├── necks/
│ │ │ ├── __init__.py
│ │ │ └── second_fpn.py
│ │ ├── registry.py
│ │ ├── roi_heads/
│ │ │ ├── __init__.py
│ │ │ ├── base_3droi_head.py
│ │ │ ├── bbox_heads/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── h3d_bbox_head.py
│ │ │ │ └── parta2_bbox_head.py
│ │ │ ├── h3d_roi_head.py
│ │ │ ├── mask_heads/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── pointwise_semantic_head.py
│ │ │ │ └── primitive_head.py
│ │ │ ├── part_aggregation_roi_head.py
│ │ │ └── roi_extractors/
│ │ │ ├── __init__.py
│ │ │ └── single_roiaware_extractor.py
│ │ ├── utils/
│ │ │ ├── __init__.py
│ │ │ ├── clip_sigmoid.py
│ │ │ ├── deformable_decoder.py
│ │ │ ├── depth_encoder.py
│ │ │ ├── drop.py
│ │ │ ├── ffn.py
│ │ │ ├── inverse_sigmoid.py
│ │ │ ├── mlp.py
│ │ │ ├── network_modules.py
│ │ │ ├── ops/
│ │ │ │ ├── functions/
│ │ │ │ │ ├── __init__.py
│ │ │ │ │ └── ms_deform_attn_func.py
│ │ │ │ ├── make.sh
│ │ │ │ ├── modules/
│ │ │ │ │ ├── __init__.py
│ │ │ │ │ └── ms_deform_attn.py
│ │ │ │ ├── setup.py
│ │ │ │ ├── src/
│ │ │ │ │ ├── cpu/
│ │ │ │ │ │ ├── ms_deform_attn_cpu.cpp
│ │ │ │ │ │ └── ms_deform_attn_cpu.h
│ │ │ │ │ ├── cuda/
│ │ │ │ │ │ ├── ms_deform_attn_cuda.cu
│ │ │ │ │ │ ├── ms_deform_attn_cuda.h
│ │ │ │ │ │ └── ms_deform_im2col_cuda.cuh
│ │ │ │ │ ├── ms_deform_attn.h
│ │ │ │ │ └── vision.cpp
│ │ │ │ └── test.py
│ │ │ ├── projection.py
│ │ │ ├── sparsefusion_models.py
│ │ │ ├── transformer.py
│ │ │ └── transformerdecoder.py
│ │ └── voxel_encoders/
│ │ ├── __init__.py
│ │ ├── pillar_encoder.py
│ │ ├── utils.py
│ │ └── voxel_encoder.py
│ ├── ops/
│ │ ├── __init__.py
│ │ ├── ball_query/
│ │ │ ├── __init__.py
│ │ │ ├── ball_query.py
│ │ │ └── src/
│ │ │ ├── ball_query.cpp
│ │ │ └── ball_query_cuda.cu
│ │ ├── furthest_point_sample/
│ │ │ ├── __init__.py
│ │ │ ├── furthest_point_sample.py
│ │ │ ├── points_sampler.py
│ │ │ ├── src/
│ │ │ │ ├── furthest_point_sample.cpp
│ │ │ │ └── furthest_point_sample_cuda.cu
│ │ │ └── utils.py
│ │ ├── gather_points/
│ │ │ ├── __init__.py
│ │ │ ├── gather_points.py
│ │ │ └── src/
│ │ │ ├── gather_points.cpp
│ │ │ └── gather_points_cuda.cu
│ │ ├── group_points/
│ │ │ ├── __init__.py
│ │ │ ├── group_points.py
│ │ │ └── src/
│ │ │ ├── group_points.cpp
│ │ │ └── group_points_cuda.cu
│ │ ├── interpolate/
│ │ │ ├── __init__.py
│ │ │ ├── src/
│ │ │ │ ├── interpolate.cpp
│ │ │ │ ├── three_interpolate_cuda.cu
│ │ │ │ └── three_nn_cuda.cu
│ │ │ ├── three_interpolate.py
│ │ │ └── three_nn.py
│ │ ├── iou3d/
│ │ │ ├── __init__.py
│ │ │ ├── iou3d_utils.py
│ │ │ └── src/
│ │ │ ├── iou3d.cpp
│ │ │ └── iou3d_kernel.cu
│ │ ├── knn/
│ │ │ ├── __init__.py
│ │ │ ├── knn.py
│ │ │ └── src/
│ │ │ ├── knn.cpp
│ │ │ └── knn_cuda.cu
│ │ ├── norm.py
│ │ ├── pointnet_modules/
│ │ │ ├── __init__.py
│ │ │ ├── builder.py
│ │ │ ├── point_fp_module.py
│ │ │ ├── point_sa_module.py
│ │ │ └── registry.py
│ │ ├── roiaware_pool3d/
│ │ │ ├── __init__.py
│ │ │ ├── points_in_boxes.py
│ │ │ ├── roiaware_pool3d.py
│ │ │ └── src/
│ │ │ ├── points_in_boxes_cpu.cpp
│ │ │ ├── points_in_boxes_cuda.cu
│ │ │ ├── roiaware_pool3d.cpp
│ │ │ └── roiaware_pool3d_kernel.cu
│ │ ├── sparse_block.py
│ │ ├── spconv/
│ │ │ ├── __init__.py
│ │ │ ├── conv.py
│ │ │ ├── functional.py
│ │ │ ├── include/
│ │ │ │ ├── paramsgrid.h
│ │ │ │ ├── prettyprint.h
│ │ │ │ ├── pybind11_utils.h
│ │ │ │ ├── spconv/
│ │ │ │ │ ├── fused_spconv_ops.h
│ │ │ │ │ ├── geometry.h
│ │ │ │ │ ├── indice.cu.h
│ │ │ │ │ ├── indice.h
│ │ │ │ │ ├── maxpool.h
│ │ │ │ │ ├── mp_helper.h
│ │ │ │ │ ├── point2voxel.h
│ │ │ │ │ ├── pool_ops.h
│ │ │ │ │ ├── reordering.cu.h
│ │ │ │ │ ├── reordering.h
│ │ │ │ │ └── spconv_ops.h
│ │ │ │ ├── tensorview/
│ │ │ │ │ ├── helper_kernel.cu.h
│ │ │ │ │ ├── helper_launch.h
│ │ │ │ │ └── tensorview.h
│ │ │ │ ├── torch_utils.h
│ │ │ │ └── utility/
│ │ │ │ └── timer.h
│ │ │ ├── modules.py
│ │ │ ├── ops.py
│ │ │ ├── overwrite_spconv/
│ │ │ │ └── write_spconv2.py
│ │ │ ├── pool.py
│ │ │ ├── src/
│ │ │ │ ├── all.cc
│ │ │ │ ├── indice.cc
│ │ │ │ ├── indice_cuda.cu
│ │ │ │ ├── maxpool.cc
│ │ │ │ ├── maxpool_cuda.cu
│ │ │ │ ├── reordering.cc
│ │ │ │ └── reordering_cuda.cu
│ │ │ ├── structure.py
│ │ │ └── test_utils.py
│ │ └── voxel/
│ │ ├── __init__.py
│ │ ├── scatter_points.py
│ │ ├── src/
│ │ │ ├── scatter_points_cpu.cpp
│ │ │ ├── scatter_points_cuda.cu
│ │ │ ├── voxelization.cpp
│ │ │ ├── voxelization.h
│ │ │ ├── voxelization_cpu.cpp
│ │ │ └── voxelization_cuda.cu
│ │ └── voxelize.py
│ ├── utils/
│ │ ├── __init__.py
│ │ └── collect_env.py
│ └── version.py
├── requirements/
│ ├── build.txt
│ ├── docs.txt
│ ├── optional.txt
│ ├── readthedocs.txt
│ ├── runtime.txt
│ └── tests.txt
├── requirements.txt
├── setup.cfg
├── setup.py
├── tests/
│ ├── test_data/
│ │ ├── test_datasets/
│ │ │ ├── test_dataset_wrappers.py
│ │ │ ├── test_kitti_dataset.py
│ │ │ ├── test_lyft_dataset.py
│ │ │ ├── test_nuscene_dataset.py
│ │ │ ├── test_scannet_dataset.py
│ │ │ ├── test_semantickitti_dataset.py
│ │ │ └── test_sunrgbd_dataset.py
│ │ └── test_pipelines/
│ │ ├── test_augmentations/
│ │ │ ├── test_data_augment_utils.py
│ │ │ ├── test_test_augment_utils.py
│ │ │ └── test_transforms_3d.py
│ │ ├── test_indoor_pipeline.py
│ │ ├── test_indoor_sample.py
│ │ ├── test_loadings/
│ │ │ ├── test_load_points_from_multi_sweeps.py
│ │ │ └── test_loading.py
│ │ └── test_outdoor_pipeline.py
│ ├── test_metrics/
│ │ ├── test_indoor_eval.py
│ │ ├── test_kitti_eval.py
│ │ ├── test_losses.py
│ │ └── test_seg_eval.py
│ ├── test_models/
│ │ ├── test_backbones.py
│ │ ├── test_common_modules/
│ │ │ ├── test_middle_encoders.py
│ │ │ ├── test_pointnet_modules.py
│ │ │ ├── test_pointnet_ops.py
│ │ │ ├── test_roiaware_pool3d.py
│ │ │ ├── test_sparse_unet.py
│ │ │ └── test_vote_module.py
│ │ ├── test_detectors.py
│ │ ├── test_forward.py
│ │ ├── test_fusion/
│ │ │ ├── test_fusion_coord_trans.py
│ │ │ ├── test_point_fusion.py
│ │ │ └── test_vote_fusion.py
│ │ ├── test_heads/
│ │ │ ├── test_heads.py
│ │ │ ├── test_parta2_bbox_head.py
│ │ │ ├── test_roi_extractors.py
│ │ │ └── test_semantic_heads.py
│ │ ├── test_necks/
│ │ │ ├── test_fpn.py
│ │ │ └── test_necks.py
│ │ └── test_voxel_encoder/
│ │ ├── test_dynamic_scatter.py
│ │ ├── test_voxel_encoders.py
│ │ ├── test_voxel_generator.py
│ │ └── test_voxelize.py
│ ├── test_runtime/
│ │ ├── test_apis.py
│ │ └── test_config.py
│ ├── test_samples/
│ │ └── parta2_roihead_inputs.npz
│ └── test_utils/
│ ├── test_anchors.py
│ ├── test_assigners.py
│ ├── test_bbox_coders.py
│ ├── test_box3d.py
│ ├── test_box_np_ops.py
│ ├── test_coord_3d_mode.py
│ ├── test_merge_augs.py
│ ├── test_nms.py
│ ├── test_points.py
│ ├── test_samplers.py
│ └── test_utils.py
├── tools/
│ ├── analysis_tools/
│ │ ├── analyze_logs.py
│ │ ├── benchmark.py
│ │ └── get_flops.py
│ ├── combine_view_info.py
│ ├── create_data.py
│ ├── create_data.sh
│ ├── data_converter/
│ │ ├── __init__.py
│ │ ├── create_gt_database.py
│ │ ├── indoor_converter.py
│ │ ├── kitti_converter.py
│ │ ├── kitti_data_utils.py
│ │ ├── lyft_converter.py
│ │ ├── nuimage_converter.py
│ │ ├── nuscenes_converter.py
│ │ ├── scannet_data_utils.py
│ │ ├── sunrgbd_data_utils.py
│ │ └── waymo_converter.py
│ ├── dist_test.sh
│ ├── dist_train.sh
│ ├── misc/
│ │ ├── fuse_conv_bn.py
│ │ ├── print_config.py
│ │ └── visualize_results.py
│ ├── model_converters/
│ │ ├── convert_votenet_checkpoints.py
│ │ ├── publish_model.py
│ │ └── regnet2mmdet.py
│ ├── slurm_test.sh
│ ├── slurm_train.sh
│ ├── test.py
│ └── train.py
└── train.sh
================================================
FILE CONTENTS
================================================
================================================
FILE: .gitignore
================================================
# Byte-compiled / optimized / DLL files
__pycache__/
*.py[cod]
*$py.class
*.ipynb
# C extensions
*.so
# Distribution / packaging
.Python
build/
develop-eggs/
dist/
downloads/
eggs/
.eggs/
lib/
lib64/
parts/
sdist/
var/
wheels/
*.egg-info/
.installed.cfg
*.egg
MANIFEST
# PyInstaller
# Usually these files are written by a python script from a template
# before PyInstaller builds the exe, so as to inject date/other infos into it.
*.manifest
*.spec
# Installer logs
pip-log.txt
pip-delete-this-directory.txt
# Unit test / coverage reports
htmlcov/
.tox/
.coverage
.coverage.*
.cache
nosetests.xml
coverage.xml
*.cover
.hypothesis/
.pytest_cache/
# Translations
*.mo
*.pot
# Django stuff:
*.log
local_settings.py
db.sqlite3
# Flask stuff:
instance/
.webassets-cache
# Scrapy stuff:
.scrapy
# Sphinx documentation
docs/_build/
# PyBuilder
target/
# Jupyter Notebook
.ipynb_checkpoints
# pyenv
.python-version
# celery beat schedule file
celerybeat-schedule
# SageMath parsed files
*.sage.py
# Environments
.env
.venv
env/
venv/
ENV/
env.bak/
venv.bak/
# Spyder project settings
.spyderproject
.spyproject
# Rope project settings
.ropeproject
# mkdocs documentation
/site
# mypy
.mypy_cache/
# cython generated cpp
data
.vscode
.idea
# custom
*.pkl
*.pkl.json
*.log.json
work_dirs/
exps/
*~
# Pytorch
*.pth
# demo
*.jpg
*.png
/data/scannet/scans/
/data/sunrgbd/OFFICIAL_SUNRGBD/
*.obj
*.ply
================================================
FILE: LICENSE
================================================
Copyright 2018-2019 Open-MMLab. All rights reserved.
Apache License
Version 2.0, January 2004
http://www.apache.org/licenses/
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
1. Definitions.
"License" shall mean the terms and conditions for use, reproduction,
and distribution as defined by Sections 1 through 9 of this document.
"Licensor" shall mean the copyright owner or entity authorized by
the copyright owner that is granting the License.
"Legal Entity" shall mean the union of the acting entity and all
other entities that control, are controlled by, or are under common
control with that entity. For the purposes of this definition,
"control" means (i) the power, direct or indirect, to cause the
direction or management of such entity, whether by contract or
otherwise, or (ii) ownership of fifty percent (50%) or more of the
outstanding shares, or (iii) beneficial ownership of such entity.
"You" (or "Your") shall mean an individual or Legal Entity
exercising permissions granted by this License.
"Source" form shall mean the preferred form for making modifications,
including but not limited to software source code, documentation
source, and configuration files.
"Object" form shall mean any form resulting from mechanical
transformation or translation of a Source form, including but
not limited to compiled object code, generated documentation,
and conversions to other media types.
"Work" shall mean the work of authorship, whether in Source or
Object form, made available under the License, as indicated by a
copyright notice that is included in or attached to the work
(an example is provided in the Appendix below).
"Derivative Works" shall mean any work, whether in Source or Object
form, that is based on (or derived from) the Work and for which the
editorial revisions, annotations, elaborations, or other modifications
represent, as a whole, an original work of authorship. For the purposes
of this License, Derivative Works shall not include works that remain
separable from, or merely link (or bind by name) to the interfaces of,
the Work and Derivative Works thereof.
"Contribution" shall mean any work of authorship, including
the original version of the Work and any modifications or additions
to that Work or Derivative Works thereof, that is intentionally
submitted to Licensor for inclusion in the Work by the copyright owner
or by an individual or Legal Entity authorized to submit on behalf of
the copyright owner. For the purposes of this definition, "submitted"
means any form of electronic, verbal, or written communication sent
to the Licensor or its representatives, including but not limited to
communication on electronic mailing lists, source code control systems,
and issue tracking systems that are managed by, or on behalf of, the
Licensor for the purpose of discussing and improving the Work, but
excluding communication that is conspicuously marked or otherwise
designated in writing by the copyright owner as "Not a Contribution."
"Contributor" shall mean Licensor and any individual or Legal Entity
on behalf of whom a Contribution has been received by Licensor and
subsequently incorporated within the Work.
2. Grant of Copyright License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
copyright license to reproduce, prepare Derivative Works of,
publicly display, publicly perform, sublicense, and distribute the
Work and such Derivative Works in Source or Object form.
3. Grant of Patent License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
(except as stated in this section) patent license to make, have made,
use, offer to sell, sell, import, and otherwise transfer the Work,
where such license applies only to those patent claims licensable
by such Contributor that are necessarily infringed by their
Contribution(s) alone or by combination of their Contribution(s)
with the Work to which such Contribution(s) was submitted. If You
institute patent litigation against any entity (including a
cross-claim or counterclaim in a lawsuit) alleging that the Work
or a Contribution incorporated within the Work constitutes direct
or contributory patent infringement, then any patent licenses
granted to You under this License for that Work shall terminate
as of the date such litigation is filed.
4. Redistribution. You may reproduce and distribute copies of the
Work or Derivative Works thereof in any medium, with or without
modifications, and in Source or Object form, provided that You
meet the following conditions:
(a) You must give any other recipients of the Work or
Derivative Works a copy of this License; and
(b) You must cause any modified files to carry prominent notices
stating that You changed the files; and
(c) You must retain, in the Source form of any Derivative Works
that You distribute, all copyright, patent, trademark, and
attribution notices from the Source form of the Work,
excluding those notices that do not pertain to any part of
the Derivative Works; and
(d) If the Work includes a "NOTICE" text file as part of its
distribution, then any Derivative Works that You distribute must
include a readable copy of the attribution notices contained
within such NOTICE file, excluding those notices that do not
pertain to any part of the Derivative Works, in at least one
of the following places: within a NOTICE text file distributed
as part of the Derivative Works; within the Source form or
documentation, if provided along with the Derivative Works; or,
within a display generated by the Derivative Works, if and
wherever such third-party notices normally appear. The contents
of the NOTICE file are for informational purposes only and
do not modify the License. You may add Your own attribution
notices within Derivative Works that You distribute, alongside
or as an addendum to the NOTICE text from the Work, provided
that such additional attribution notices cannot be construed
as modifying the License.
You may add Your own copyright statement to Your modifications and
may provide additional or different license terms and conditions
for use, reproduction, or distribution of Your modifications, or
for any such Derivative Works as a whole, provided Your use,
reproduction, and distribution of the Work otherwise complies with
the conditions stated in this License.
5. Submission of Contributions. Unless You explicitly state otherwise,
any Contribution intentionally submitted for inclusion in the Work
by You to the Licensor shall be under the terms and conditions of
this License, without any additional terms or conditions.
Notwithstanding the above, nothing herein shall supersede or modify
the terms of any separate license agreement you may have executed
with Licensor regarding such Contributions.
6. Trademarks. This License does not grant permission to use the trade
names, trademarks, service marks, or product names of the Licensor,
except as required for reasonable and customary use in describing the
origin of the Work and reproducing the content of the NOTICE file.
7. Disclaimer of Warranty. Unless required by applicable law or
agreed to in writing, Licensor provides the Work (and each
Contributor provides its Contributions) on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
implied, including, without limitation, any warranties or conditions
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
PARTICULAR PURPOSE. You are solely responsible for determining the
appropriateness of using or redistributing the Work and assume any
risks associated with Your exercise of permissions under this License.
8. Limitation of Liability. In no event and under no legal theory,
whether in tort (including negligence), contract, or otherwise,
unless required by applicable law (such as deliberate and grossly
negligent acts) or agreed to in writing, shall any Contributor be
liable to You for damages, including any direct, indirect, special,
incidental, or consequential damages of any character arising as a
result of this License or out of the use or inability to use the
Work (including but not limited to damages for loss of goodwill,
work stoppage, computer failure or malfunction, or any and all
other commercial damages or losses), even if such Contributor
has been advised of the possibility of such damages.
9. Accepting Warranty or Additional Liability. While redistributing
the Work or Derivative Works thereof, You may choose to offer,
and charge a fee for, acceptance of support, warranty, indemnity,
or other liability obligations and/or rights consistent with this
License. However, in accepting such obligations, You may act only
on Your own behalf and on Your sole responsibility, not on behalf
of any other Contributor, and only if You agree to indemnify,
defend, and hold each Contributor harmless for any liability
incurred by, or claims asserted against, such Contributor by reason
of your accepting any such warranty or additional liability.
END OF TERMS AND CONDITIONS
APPENDIX: How to apply the Apache License to your work.
To apply the Apache License to your work, attach the following
boilerplate notice, with the fields enclosed by brackets "[]"
replaced with your own identifying information. (Don't include
the brackets!) The text should be enclosed in the appropriate
comment syntax for the file format. We also recommend that a
file or class name and description of purpose be included on the
same "printed page" as the copyright notice for easier
identification within third-party archives.
Copyright 2018-2019 Open-MMLab.
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
================================================
FILE: MANIFEST.in
================================================
include requirements/*.txt
include mmdet3d/ops/**/*.cpp mmdet3d/ops/**/*.cu
include mmdet3d/ops/**/*.h mmdet3d/ops/**/*.cc
include mmdet3d/VERSION
================================================
FILE: README.md
================================================
# [ICCV 2023] SparseFusion: Fusing Multi-Modal Sparse Representations for Multi-Sensor 3D Object Detection

## Abstract
We propose SparseFusion, a novel multi-sensor 3D detection method that exclusively uses sparse candidates and sparse representations. Specifically, SparseFusion utilizes the outputs of parallel detectors in the LiDAR and camera modalities as sparse candidates for fusion. We transform the camera candidates into the LiDAR coordinate space by disentangling the object representations. Then, we can fuse the multi-modality candidates in a unified 3D space by a lightweight self-attention module. To mitigate negative transfer between modalities, we propose novel semantic and geometric cross-modality transfer modules that are applied prior to the modality-specific detectors. SparseFusion achieves state-of-the-art performance on the nuScenes benchmark while also running at the fastest speed.
[[paper link]](https://openaccess.thecvf.com/content/ICCV2023/papers/Xie_SparseFusion_Fusing_Multi-Modal_Sparse_Representations_for_Multi-Sensor_3D_Object_Detection_ICCV_2023_paper.pdf) [[Chinese summary (自动驾驶之心)]](https://zhuanlan.zhihu.com/p/671293323)
## Updates
[2023-8-21] Much better training GPU memory efficiency (45GB -> 29GB) with no hurt to the performance and speed!
[2023-7-13] 🔥SparseFusion has been accepted to ICCV 2023!🔥
[2023-3-21] We release the first version code of SparseFusion.
## Overview

Compared to existing fusion algorithms, SparseFusion achieves state-of-the-art performance as well as the fastest inference speed on nuScenes test set. †: Official [repository](https://github.com/zehuichen123/AutoAlignV2) of AutoAlignV2 uses flip as test-time augmentation. ‡: We use BEVFusion-base results in the official [repository](https://github.com/mit-han-lab/bevfusion) of BEVFusion to match the input resolutions of other methods. $\S:$ Swin-T is adopted as image backbone.
## NuScene Performance
We do not use any test-time augmentations or model ensembles to get these results. We have released the configure files and pretrained checkpoints to reproduce our results.
#### Validation Set
| Image Backbone | Point Cloud Backbone | mAP | NDS | Link |
| --------- | ------ | ------ | --------- | --------- |
| ResNet50 | VoxelNet | 70.5 | 72.8 | [config](configs/sparsefusion_nusc_voxel_LC_r50.py)/[ckpt](https://drive.google.com/file/d/1NZIrg7s-VwxkwuPHTTWSQQO7T7IILBGC/view?usp=share_link) |
| Swin-T | VoxelNet | 71.0 | 73.1 | [config](configs/sparsefusion_nusc_voxel_LC_SwinT.py)/[ckpt](https://drive.google.com/file/d/1dAhOKtbLd1e3I5jwk_3E1gzbl61P24qy/view?usp=share_link) |
#### Test Set
| Image Backbone | Point Cloud Backbone | mAP | NDS |
| --------- | ------ | ------ | --------- |
| ResNet50 | VoxelNet | 72.0 | 73.8 |
## Usage
#### Installation
+ We test our code on an environment with CUDA 11.5, python 3.7, PyTorch 1.7.1, TorchVision 0.8.2, NumPy 1.20.0, and numba 0.48.0.
+ We use `mmdet==2.10.0, mmcv==1.2.7` for our code. Please refer to their official instructions for installation.
+ You can install `mmdet3d==0.11.0` directly from our repo by
```
cd SparseFusion
pip install -e .
```
+ We use `spconv==2.3.3`. Please follow the [official instruction](https://github.com/traveller59/spconv) to install it based on your CUDA version.
```
pip install spconv-cuxxx
# e.g. pip install spconv-cu114
```
+ You also need to install the deformable attention module with the following command.
```
pip install ./mmdet3d/models/utils/ops
```
#### Data Preparation
Download nuScenes full dataset from the [official website](https://www.nuscenes.org/download). You should have a folder structure like this:
```
SparseFusion
├── mmdet3d
├── tools
├── configs
├── data
│ ├── nuscenes
│ │ ├── maps
│ │ ├── samples
│ │ ├── sweeps
│ │ ├── v1.0-test
| | ├── v1.0-trainval
```
Then, you can select **either** of the two ways to preprocess the data.
1. Run the following two commands sequentially.
```
python tools/create_data.py nuscenes --root-path ./data/nuscenes --out-dir ./data/nuscenes --extra-tag nuscenes
python tools/combine_view_info.py
```
2. Alternatively, you may directly download our preprocessed data from [Google Drive](https://drive.google.com/drive/folders/1L5lvLsNWBA0vfTlNSMa4OXXBLoZgJbg4?usp=share_link), and put these files in `data/nuscenes`.
#### Initial Weights
Please download the [initial weights](https://drive.google.com/drive/folders/1wmYBi3PBprdcegF843AU-22q2OwDgoZk?usp=share_link) for model training, and put them in `checkpoints/`.
#### Train & Test
In our default setting, we train the model with 4 GPUs.
```
# training
bash tools/dist_train.sh configs/sparsefusion_nusc_voxel_LC_r50.py 4 --work-dir work_dirs/sparsefusion_nusc_voxel_LC_r50
# test
bash tools/dist_test.sh configs/sparsefusion_nusc_voxel_LC_r50.py ${CHECKPOINT_FILE} 4 --eval=bbox
```
Note: We use A6000 GPUs (48GB per-GPU memory) for model training. The training of SparseFusion model (ResNet50 backbone) requires ~29 GB per-GPU memory.
## Contact
If you have any questions, feel free to open an issue or contact us at yichen_xie@berkeley.edu.
## Acknowledgments
We sincerely thank the authors of [mmdetection3d](https://github.com/open-mmlab/mmdetection3d), [TransFusion](https://github.com/XuyangBai/TransFusion), [BEVFusion](https://github.com/mit-han-lab/bevfusion), [MSMDFusion](https://github.com/SxJyJay/MSMDFusion), and [DeepInteraction](https://github.com/fudan-zvg/DeepInteraction) for providing their codes or pretrained weights.
## Reference
If you find our work useful, please consider citing the following paper:
```
@article{xie2023sparsefusion,
title={SparseFusion: Fusing Multi-Modal Sparse Representations for Multi-Sensor 3D Object Detection},
author={Xie, Yichen and Xu, Chenfeng and Rakotosaona, Marie-Julie and Rim, Patrick and Tombari, Federico and Keutzer, Kurt and Tomizuka, Masayoshi and Zhan, Wei},
journal={arXiv preprint arXiv:2304.14340},
year={2023}
}
```
================================================
FILE: README_zh-CN.md
================================================
<div align="center">
<img src="resources/mmdet3d-logo.png" width="600"/>
</div>
[](https://mmdetection3d.readthedocs.io/en/latest/)
[](https://github.com/open-mmlab/mmdetection3d/actions)
[](https://codecov.io/gh/open-mmlab/mmdetection3d)
[](https://github.com/open-mmlab/mmdetection3d/blob/master/LICENSE)
**新闻**: 我们发布了版本v0.11.0.
在第三届[ nuScenes 3D 检测挑战赛](https://www.nuscenes.org/object-detection?externalData=all&mapData=all&modalities=Any)(第五届 AI Driving Olympics, NeurIPS 2020)中,我们获得了最佳 PKL 奖、第三名和最好的纯视觉的结果,相关的代码和模型将会在不久后发布。
文档: https://mmdetection3d.readthedocs.io/
## 简介
[English](README.md) | 简体中文
主分支代码目前支持 PyTorch 1.3 以上的版本。
MMDetection3D 是一个基于 PyTorch 的目标检测开源工具箱, 下一代面向3D检测的平台. 它是 OpenMMlab 项目的一部分,这个项目由香港中文大学多媒体实验室和商汤科技联合发起.

### 主要特性
- **支持多模态/单模态的检测器**
支持多模态/单模态检测器,包括 MVXNet,VoteNet,PointPillars 等。
- **支持户内/户外的数据集**
支持室内/室外的3D检测数据集,包括 ScanNet, SUNRGB-D, Waymo, nuScenes, Lyft, KITTI.
对于 nuScenes 数据集, 我们也支持 [nuImages 数据集](https://github.com/open-mmlab/mmdetection3d/tree/master/configs/nuimages).
- **与 2D 检测器的自然整合**
[MMDetection](https://github.com/open-mmlab/mmdetection/blob/master/docs/model_zoo.md) 支持的**300+个模型 , 40+的论文算法**, 和相关模块都可以在此代码库中训练或使用。
- **性能高**
训练速度比其他代码库更快。下表可见主要的对比结果。更多的细节可见[基准测评文档](./docs/benchmarks.md)。我们对比了每秒训练的样本数(值越高越好)。其他代码库不支持的模型被标记为 `×`。
| Methods | MMDetection3D | [OpenPCDet](https://github.com/open-mmlab/OpenPCDet) |[votenet](https://github.com/facebookresearch/votenet)| [Det3D](https://github.com/poodarchu/Det3D) |
|:-------:|:-------------:|:---------:|:-----:|:-----:|
| VoteNet | 358 | × | 77 | × |
| PointPillars-car| 141 | × | × | 140 |
| PointPillars-3class| 107 |44 | × | × |
| SECOND| 40 |30 | × | × |
| Part-A2| 17 |14 | × | × |
和 [MMDetection](https://github.com/open-mmlab/mmdetection),[MMCV](https://github.com/open-mmlab/mmcv) 一样, MMDetection3D 也可以作为一个库去支持各式各样的项目.
## 开源许可证
该项目采用 [Apache 2.0 开源许可证](LICENSE)。
## 更新日志
最新的版本 v0.11.0 在 2021.03.01发布。
如果想了解更多版本更新细节和历史信息,请阅读[更新日志](docs/changelog.md)。
## 基准测试和模型库
测试结果和模型可以在[模型库](docs/model_zoo.md)中找到。
已支持的骨干网络:
- [x] PointNet (CVPR'2017)
- [x] PointNet++ (NeurIPS'2017)
- [x] RegNet (CVPR'2020)
已支持的算法:
- [x] [SECOND (Sensor'2018)](configs/second/README.md)
- [x] [PointPillars (CVPR'2019)](configs/pointpillars/README.md)
- [x] [FreeAnchor (NeurIPS'2019)](configs/free_anchor/README.md)
- [x] [VoteNet (ICCV'2019)](configs/votenet/README.md)
- [x] [H3DNet (ECCV'2020)](configs/h3dnet/README.md)
- [x] [3DSSD (CVPR'2020)](configs/3dssd/README.md)
- [x] [Part-A2 (TPAMI'2020)](configs/parta2/README.md)
- [x] [MVXNet (ICRA'2019)](configs/mvxnet/README.md)
- [x] [CenterPoint (CVPR'2021)](configs/centerpoint/README.md)
- [x] [SSN (ECCV'2020)](configs/ssn/README.md)
- [x] [ImVoteNet (CVPR'2020)](configs/imvotenet/README.md)
| | ResNet | ResNeXt | SENet |PointNet++ | HRNet | RegNetX | Res2Net |
|--------------------|:--------:|:--------:|:--------:|:---------:|:-----:|:--------:|:-----:|
| SECOND | ☐ | ☐ | ☐ | ✗ | ☐ | ✓ | ☐ |
| PointPillars | ☐ | ☐ | ☐ | ✗ | ☐ | ✓ | ☐ |
| FreeAnchor | ☐ | ☐ | ☐ | ✗ | ☐ | ✓ | ☐ |
| VoteNet | ✗ | ✗ | ✗ | ✓ | ✗ | ✗ | ✗ |
| H3DNet | ✗ | ✗ | ✗ | ✓ | ✗ | ✗ | ✗ |
| 3DSSD | ✗ | ✗ | ✗ | ✓ | ✗ | ✗ | ✗ |
| Part-A2 | ☐ | ☐ | ☐ | ✗ | ☐ | ✓ | ☐ |
| MVXNet | ☐ | ☐ | ☐ | ✗ | ☐ | ✓ | ☐ |
| CenterPoint | ☐ | ☐ | ☐ | ✗ | ☐ | ✓ | ☐ |
| SSN | ☐ | ☐ | ☐ | ✗ | ☐ | ✓ | ☐ |
| ImVoteNet | ✗ | ✗ | ✗ | ✓ | ✗ | ✗ | ✗ |
其他特性
- [x] [Dynamic Voxelization](configs/dynamic_voxelization/README.md)
**注意:** [MMDetection](https://github.com/open-mmlab/mmdetection/blob/master/docs/model_zoo.md) 支持的基于2D检测的**300+个模型 , 40+的论文算法**在 MMDetection3D 中都可以被训练或使用。
## 安装
请参考[快速入门文档](docs/get_started.md)进行安装。
## 快速入门
请参考[快速入门文档](docs/get_started.md)学习 MMDetection3D 的基本使用。 我们为新手提供了分别针对[已有数据集](docs/1_exist_data_model.md)和[新数据集](docs/2_new_data_model.md)的使用指南。我们也提供了一些进阶教程,内容覆盖了[学习配置文件](docs/tutorials/config.md), [增加数据集支持](docs/tutorials/customize_dataset.md), [设计新的数据预处理流程](docs/tutorials/data_pipeline.md), [增加自定义模型](docs/tutorials/customize_models.md), [增加自定义的运行时配置](docs/tutorials/customize_runtime.md)和 [Waymo 数据集](docs/tutorials/waymo.md).
## 引用
如果你觉得本项目对你的研究工作有所帮助,请参考如下 bibtex 引用 MMdetection3D
```latex
@misc{mmdet3d2020,
title={{MMDetection3D: OpenMMLab} next-generation platform for general {3D} object detection},
author={MMDetection3D Contributors},
howpublished = {\url{https://github.com/open-mmlab/mmdetection3d}},
year={2020}
}
```
## 贡献指南
我们感谢所有的贡献者为改进和提升 MMDetection3D 所作出的努力。请参考[贡献指南](.github/CONTRIBUTING.md)来了解参与项目贡献的相关指引。
## 致谢
MMDetection3D 是一款由来自不同高校和企业的研发人员共同参与贡献的开源项目。我们感谢所有为项目提供算法复现和新功能支持的贡献者,以及提供宝贵反馈的用户。我们希望这个工具箱和基准测试可以为社区提供灵活的代码工具,供用户复现已有算法并开发自己的新的 3D 检测模型。
## OpenMMLab 的其他项目
- [MMCV](https://github.com/open-mmlab/mmcv): OpenMMLab 计算机视觉基础库
- [MMClassification](https://github.com/open-mmlab/mmclassification): OpenMMLab 图像分类工具箱
- [MMDetection](https://github.com/open-mmlab/mmdetection): OpenMMLab 目标检测工具箱
- [MMDetection3D](https://github.com/open-mmlab/mmdetection3d): OpenMMLab 新一代通用 3D 目标检测平台
- [MMSegmentation](https://github.com/open-mmlab/mmsegmentation): OpenMMLab 语义分割工具箱
- [MMAction2](https://github.com/open-mmlab/mmaction2): OpenMMLab 新一代视频理解工具箱
- [MMTracking](https://github.com/open-mmlab/mmtracking): OpenMMLab 一体化视频目标感知平台
- [MMPose](https://github.com/open-mmlab/mmpose): OpenMMLab 姿态估计工具箱
- [MMEditing](https://github.com/open-mmlab/mmediting): OpenMMLab 图像视频编辑工具箱
================================================
FILE: configs/3dssd/3dssd_kitti-3d-car.py
================================================
_base_ = [
'../_base_/models/3dssd.py', '../_base_/datasets/kitti-3d-car.py',
'../_base_/default_runtime.py'
]
# dataset settings
dataset_type = 'KittiDataset'
data_root = 'data/kitti/'
class_names = ['Car']
point_cloud_range = [0, -40, -5, 70, 40, 3]
input_modality = dict(use_lidar=True, use_camera=False)
db_sampler = dict(
data_root=data_root,
info_path=data_root + 'kitti_dbinfos_train.pkl',
rate=1.0,
prepare=dict(filter_by_difficulty=[-1], filter_by_min_points=dict(Car=5)),
classes=class_names,
sample_groups=dict(Car=15))
file_client_args = dict(backend='disk')
# Uncomment the following if use ceph or other file clients.
# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient
# for more details.
# file_client_args = dict(
# backend='petrel', path_mapping=dict(data='s3://kitti_data/'))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4,
file_client_args=file_client_args),
dict(
type='LoadAnnotations3D',
with_bbox_3d=True,
with_label_3d=True,
file_client_args=file_client_args),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectSample', db_sampler=db_sampler),
dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
dict(
type='ObjectNoise',
num_try=100,
translation_std=[1.0, 1.0, 0],
global_rot_range=[0.0, 0.0],
rot_range=[-1.0471975511965976, 1.0471975511965976]),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.78539816, 0.78539816],
scale_ratio_range=[0.9, 1.1]),
dict(type='BackgroundPointsFilter', bbox_enlarge_range=(0.5, 2.0, 0.5)),
dict(type='IndoorPointSample', num_points=16384),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4,
file_client_args=file_client_args),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='IndoorPointSample', num_points=16384),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=4,
workers_per_gpu=4,
train=dict(dataset=dict(pipeline=train_pipeline)),
val=dict(pipeline=test_pipeline),
test=dict(pipeline=test_pipeline))
evaluation = dict(interval=2)
# model settings
model = dict(
bbox_head=dict(
num_classes=1,
bbox_coder=dict(
type='AnchorFreeBBoxCoder', num_dir_bins=12, with_rot=True)))
# optimizer
lr = 0.002 # max learning rate
optimizer = dict(type='AdamW', lr=lr, weight_decay=0)
optimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))
lr_config = dict(policy='step', warmup=None, step=[80, 120])
# runtime settings
total_epochs = 150
# yapf:disable
log_config = dict(
interval=30,
hooks=[
dict(type='TextLoggerHook'),
dict(type='TensorboardLoggerHook')
])
# yapf:enable
================================================
FILE: configs/3dssd/README.md
================================================
# 3DSSD: Point-based 3D Single Stage Object Detector
## Introduction
[ALGORITHM]
We implement 3DSSD and provide the results and checkpoints on KITTI datasets.
```
@inproceedings{yang20203dssd,
author = {Zetong Yang and Yanan Sun and Shu Liu and Jiaya Jia},
title = {3DSSD: Point-based 3D Single Stage Object Detector},
booktitle = {Proceedings of the IEEE/CVF Conference on Computer Vision and Pattern Recognition},
year = {2020}
}
```
### Experiment details on KITTI datasets
Some settings in our implementation are different from the [official implementation](https://github.com/Jia-Research-Lab/3DSSD), which bring marginal differences to the performance on KITTI datasets in our experiments. To simplify and unify the models of our implementation, we skip them in our models. These differences are listed as below:
1. We keep the scenes without any object while the official code skips these scenes in training. In the official implementation, only 3229 and 3394 samples are used as training and validation sets, respectively. In our implementation, we keep using 3712 and 3769 samples as training and validation sets, respectively, as those used for all the other models in our implementation on KITTI datasets.
2. We do not modify the decay of `batch normalization` during training.
3. While using [`DataBaseSampler`](https://github.com/open-mmlab/mmdetection3d/blob/master/mmdet3d/datasets/pipelines/dbsampler.py#L80) for data augmentation, the official code uses road planes as reference to place the sampled objects while we do not.
4. We perform detection using LIDAR coordinates while the official code uses camera coordinates.
## Results
### KITTI
| Backbone |Class| Lr schd | Mem (GB) | Inf time (fps) | mAP |Download |
| :---------: | :-----: | :------: | :------------: | :----: |:----: | :------: |
| [PointNet2SAMSG](./3dssd_kitti-3d-car.py)| Car |72e|4.7||78.39(81.00)<sup>1</sup>|[model](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/3dssd/3dssd_kitti-3d-car_20210324_122002-07e9a19b.pth) | [log](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/3dssd/3dssd_kitti-3d-car_20210324_122002.log.json)|
[1]: We report two different 3D object detection performance here. 78.39mAP is evaluated by our evaluation code and 81.00mAP is evaluated by the official development kit (so as that used in the paper and official code of 3DSSD ). We found that the commonly used Python implementation of [`rotate_iou`](https://github.com/traveller59/second.pytorch/blob/e42e4a0e17262ab7d180ee96a0a36427f2c20a44/second/core/non_max_suppression/nms_gpu.py#L605) which is used in our KITTI dataset evaluation, is different from the official implemention in [KITTI benchmark](http://www.cvlibs.net/datasets/kitti/eval_object.php?obj_benchmark=3d).
================================================
FILE: configs/_base_/datasets/coco_instance.py
================================================
dataset_type = 'CocoDataset'
data_root = 'data/coco/'
img_norm_cfg = dict(
mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)
train_pipeline = [
dict(type='LoadImageFromFile'),
dict(type='LoadAnnotations', with_bbox=True, with_mask=True),
dict(type='Resize', img_scale=(1333, 800), keep_ratio=True),
dict(type='RandomFlip', flip_ratio=0.5),
dict(type='Normalize', **img_norm_cfg),
dict(type='Pad', size_divisor=32),
dict(type='DefaultFormatBundle'),
dict(type='Collect', keys=['img', 'gt_bboxes', 'gt_labels', 'gt_masks']),
]
test_pipeline = [
dict(type='LoadImageFromFile'),
dict(
type='MultiScaleFlipAug',
img_scale=(1333, 800),
flip=False,
transforms=[
dict(type='Resize', keep_ratio=True),
dict(type='RandomFlip'),
dict(type='Normalize', **img_norm_cfg),
dict(type='Pad', size_divisor=32),
dict(type='ImageToTensor', keys=['img']),
dict(type='Collect', keys=['img']),
])
]
data = dict(
samples_per_gpu=2,
workers_per_gpu=2,
train=dict(
type=dataset_type,
ann_file=data_root + 'annotations/instances_train2017.json',
img_prefix=data_root + 'train2017/',
pipeline=train_pipeline),
val=dict(
type=dataset_type,
ann_file=data_root + 'annotations/instances_val2017.json',
img_prefix=data_root + 'val2017/',
pipeline=test_pipeline),
test=dict(
type=dataset_type,
ann_file=data_root + 'annotations/instances_val2017.json',
img_prefix=data_root + 'val2017/',
pipeline=test_pipeline))
evaluation = dict(metric=['bbox', 'segm'])
================================================
FILE: configs/_base_/datasets/kitti-3d-3class.py
================================================
# dataset settings
dataset_type = 'KittiDataset'
data_root = 'data/kitti/'
class_names = ['Pedestrian', 'Cyclist', 'Car']
point_cloud_range = [0, -40, -3, 70.4, 40, 1]
input_modality = dict(use_lidar=True, use_camera=False)
db_sampler = dict(
data_root=data_root,
info_path=data_root + 'kitti_dbinfos_train.pkl',
rate=1.0,
prepare=dict(
filter_by_difficulty=[-1],
filter_by_min_points=dict(Car=5, Pedestrian=10, Cyclist=10)),
classes=class_names,
sample_groups=dict(Car=12, Pedestrian=6, Cyclist=6))
file_client_args = dict(backend='disk')
# Uncomment the following if use ceph or other file clients.
# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient
# for more details.
# file_client_args = dict(
# backend='petrel', path_mapping=dict(data='s3://kitti_data/'))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4,
file_client_args=file_client_args),
dict(
type='LoadAnnotations3D',
with_bbox_3d=True,
with_label_3d=True,
file_client_args=file_client_args),
dict(type='ObjectSample', db_sampler=db_sampler),
dict(
type='ObjectNoise',
num_try=100,
translation_std=[1.0, 1.0, 0.5],
global_rot_range=[0.0, 0.0],
rot_range=[-0.78539816, 0.78539816]),
dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.78539816, 0.78539816],
scale_ratio_range=[0.95, 1.05]),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4,
file_client_args=file_client_args),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=6,
workers_per_gpu=4,
train=dict(
type='RepeatDataset',
times=2,
dataset=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_train.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=train_pipeline,
modality=input_modality,
classes=class_names,
test_mode=False,
# we use box_type_3d='LiDAR' in kitti and nuscenes dataset
# and box_type_3d='Depth' in sunrgbd and scannet dataset.
box_type_3d='LiDAR')),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True,
box_type_3d='LiDAR'),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True,
box_type_3d='LiDAR'))
evaluation = dict(interval=1)
================================================
FILE: configs/_base_/datasets/kitti-3d-car.py
================================================
# dataset settings
dataset_type = 'KittiDataset'
data_root = 'data/kitti/'
class_names = ['Car']
point_cloud_range = [0, -40, -3, 70.4, 40, 1]
input_modality = dict(use_lidar=True, use_camera=False)
db_sampler = dict(
data_root=data_root,
info_path=data_root + 'kitti_dbinfos_train.pkl',
rate=1.0,
prepare=dict(filter_by_difficulty=[-1], filter_by_min_points=dict(Car=5)),
classes=class_names,
sample_groups=dict(Car=15))
file_client_args = dict(backend='disk')
# Uncomment the following if use ceph or other file clients.
# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient
# for more details.
# file_client_args = dict(
# backend='petrel', path_mapping=dict(data='s3://kitti_data/'))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4,
file_client_args=file_client_args),
dict(
type='LoadAnnotations3D',
with_bbox_3d=True,
with_label_3d=True,
file_client_args=file_client_args),
dict(type='ObjectSample', db_sampler=db_sampler),
dict(
type='ObjectNoise',
num_try=100,
translation_std=[1.0, 1.0, 0.5],
global_rot_range=[0.0, 0.0],
rot_range=[-0.78539816, 0.78539816]),
dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.78539816, 0.78539816],
scale_ratio_range=[0.95, 1.05]),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4,
file_client_args=file_client_args),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=6,
workers_per_gpu=4,
train=dict(
type='RepeatDataset',
times=2,
dataset=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_train.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=train_pipeline,
modality=input_modality,
classes=class_names,
test_mode=False,
# we use box_type_3d='LiDAR' in kitti and nuscenes dataset
# and box_type_3d='Depth' in sunrgbd and scannet dataset.
box_type_3d='LiDAR')),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True,
box_type_3d='LiDAR'),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True,
box_type_3d='LiDAR'))
evaluation = dict(interval=1)
================================================
FILE: configs/_base_/datasets/lyft-3d.py
================================================
# If point cloud range is changed, the models should also change their point
# cloud range accordingly
point_cloud_range = [-80, -80, -5, 80, 80, 3]
# For Lyft we usually do 9-class detection
class_names = [
'car', 'truck', 'bus', 'emergency_vehicle', 'other_vehicle', 'motorcycle',
'bicycle', 'pedestrian', 'animal'
]
dataset_type = 'LyftDataset'
data_root = 'data/lyft/'
# Input modality for Lyft dataset, this is consistent with the submission
# format which requires the information in input_modality.
input_modality = dict(
use_lidar=True,
use_camera=False,
use_radar=False,
use_map=False,
use_external=False)
file_client_args = dict(backend='disk')
# Uncomment the following if use ceph or other file clients.
# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient
# for more details.
# file_client_args = dict(
# backend='petrel',
# path_mapping=dict({
# './data/lyft/': 's3://lyft/lyft/',
# 'data/lyft/': 's3://lyft/lyft/'
# }))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=10,
file_client_args=file_client_args),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.3925, 0.3925],
scale_ratio_range=[0.95, 1.05],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=10,
file_client_args=file_client_args),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=2,
workers_per_gpu=2,
train=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'lyft_infos_train.pkl',
pipeline=train_pipeline,
classes=class_names,
modality=input_modality,
test_mode=False),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'lyft_infos_val.pkl',
pipeline=test_pipeline,
classes=class_names,
modality=input_modality,
test_mode=True),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'lyft_infos_test.pkl',
pipeline=test_pipeline,
classes=class_names,
modality=input_modality,
test_mode=True))
# For Lyft dataset, we usually evaluate the model at the end of training.
# Since the models are trained by 24 epochs by default, we set evaluation
# interval to be 24. Please change the interval accordingly if you do not
# use a default schedule.
evaluation = dict(interval=24)
================================================
FILE: configs/_base_/datasets/nuim_instance.py
================================================
dataset_type = 'CocoDataset'
data_root = 'data/nuimages/'
class_names = [
'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',
'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'
]
img_norm_cfg = dict(
mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)
train_pipeline = [
dict(type='LoadImageFromFile'),
dict(type='LoadAnnotations', with_bbox=True, with_mask=True),
dict(
type='Resize',
img_scale=[(1280, 720), (1920, 1080)],
multiscale_mode='range',
keep_ratio=True),
dict(type='RandomFlip', flip_ratio=0.5),
dict(type='Normalize', **img_norm_cfg),
dict(type='Pad', size_divisor=32),
dict(type='DefaultFormatBundle'),
dict(type='Collect', keys=['img', 'gt_bboxes', 'gt_labels', 'gt_masks']),
]
test_pipeline = [
dict(type='LoadImageFromFile'),
dict(
type='MultiScaleFlipAug',
img_scale=(1600, 900),
flip=False,
transforms=[
dict(type='Resize', keep_ratio=True),
dict(type='RandomFlip'),
dict(type='Normalize', **img_norm_cfg),
dict(type='Pad', size_divisor=32),
dict(type='ImageToTensor', keys=['img']),
dict(type='Collect', keys=['img']),
])
]
data = dict(
samples_per_gpu=2,
workers_per_gpu=2,
train=dict(
type=dataset_type,
ann_file=data_root + 'annotations/nuimages_v1.0-train.json',
img_prefix=data_root,
classes=class_names,
pipeline=train_pipeline),
val=dict(
type=dataset_type,
ann_file=data_root + 'annotations/nuimages_v1.0-val.json',
img_prefix=data_root,
classes=class_names,
pipeline=test_pipeline),
test=dict(
type=dataset_type,
ann_file=data_root + 'annotations/nuimages_v1.0-val.json',
img_prefix=data_root,
classes=class_names,
pipeline=test_pipeline))
evaluation = dict(metric=['bbox', 'segm'])
================================================
FILE: configs/_base_/datasets/nus-3d.py
================================================
# If point cloud range is changed, the models should also change their point
# cloud range accordingly
point_cloud_range = [-50, -50, -5, 50, 50, 3]
# For nuScenes we usually do 10-class detection
class_names = [
'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',
'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'
]
dataset_type = 'NuScenesDataset'
data_root = 'data/nuscenes/'
# Input modality for nuScenes dataset, this is consistent with the submission
# format which requires the information in input_modality.
input_modality = dict(
use_lidar=True,
use_camera=False,
use_radar=False,
use_map=False,
use_external=False)
file_client_args = dict(backend='disk')
# Uncomment the following if use ceph or other file clients.
# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient
# for more details.
# file_client_args = dict(
# backend='petrel',
# path_mapping=dict({
# './data/nuscenes/': 's3://nuscenes/nuscenes/',
# 'data/nuscenes/': 's3://nuscenes/nuscenes/'
# }))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=10,
file_client_args=file_client_args),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.3925, 0.3925],
scale_ratio_range=[0.95, 1.05],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=10,
file_client_args=file_client_args),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=4,
workers_per_gpu=4,
train=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'nuscenes_infos_train.pkl',
pipeline=train_pipeline,
classes=class_names,
modality=input_modality,
test_mode=False,
# we use box_type_3d='LiDAR' in kitti and nuscenes dataset
# and box_type_3d='Depth' in sunrgbd and scannet dataset.
box_type_3d='LiDAR'),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'nuscenes_infos_val.pkl',
pipeline=test_pipeline,
classes=class_names,
modality=input_modality,
test_mode=True,
box_type_3d='LiDAR'),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'nuscenes_infos_val.pkl',
pipeline=test_pipeline,
classes=class_names,
modality=input_modality,
test_mode=True,
box_type_3d='LiDAR'))
# For nuScenes dataset, we usually evaluate the model at the end of training.
# Since the models are trained by 24 epochs by default, we set evaluation
# interval to be 24. Please change the interval accordingly if you do not
# use a default schedule.
evaluation = dict(interval=24)
================================================
FILE: configs/_base_/datasets/range100_lyft-3d.py
================================================
# If point cloud range is changed, the models should also change their point
# cloud range accordingly
point_cloud_range = [-100, -100, -5, 100, 100, 3]
# For Lyft we usually do 9-class detection
class_names = [
'car', 'truck', 'bus', 'emergency_vehicle', 'other_vehicle', 'motorcycle',
'bicycle', 'pedestrian', 'animal'
]
dataset_type = 'LyftDataset'
data_root = 'data/lyft/'
# Input modality for Lyft dataset, this is consistent with the submission
# format which requires the information in input_modality.
input_modality = dict(
use_lidar=True,
use_camera=False,
use_radar=False,
use_map=False,
use_external=False)
file_client_args = dict(backend='disk')
# Uncomment the following if use ceph or other file clients.
# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient
# for more details.
# file_client_args = dict(
# backend='petrel',
# path_mapping=dict({
# './data/lyft/': 's3://lyft/lyft/',
# 'data/lyft/': 's3://lyft/lyft/'
# }))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=10,
file_client_args=file_client_args),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.3925, 0.3925],
scale_ratio_range=[0.95, 1.05],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=10,
file_client_args=file_client_args),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=2,
workers_per_gpu=2,
train=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'lyft_infos_train.pkl',
pipeline=train_pipeline,
classes=class_names,
modality=input_modality,
test_mode=False),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'lyft_infos_val.pkl',
pipeline=test_pipeline,
classes=class_names,
modality=input_modality,
test_mode=True),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'lyft_infos_test.pkl',
pipeline=test_pipeline,
classes=class_names,
modality=input_modality,
test_mode=True))
# For Lyft dataset, we usually evaluate the model at the end of training.
# Since the models are trained by 24 epochs by default, we set evaluation
# interval to be 24. Please change the interval accordingly if you do not
# use a default schedule.
evaluation = dict(interval=24)
================================================
FILE: configs/_base_/datasets/scannet-3d-18class.py
================================================
# dataset settings
dataset_type = 'ScanNetDataset'
data_root = './data/scannet/'
class_names = ('cabinet', 'bed', 'chair', 'sofa', 'table', 'door', 'window',
'bookshelf', 'picture', 'counter', 'desk', 'curtain',
'refrigerator', 'showercurtrain', 'toilet', 'sink', 'bathtub',
'garbagebin')
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=True,
load_dim=6,
use_dim=[0, 1, 2]),
dict(
type='LoadAnnotations3D',
with_bbox_3d=True,
with_label_3d=True,
with_mask_3d=True,
with_seg_3d=True),
dict(
type='PointSegClassMapping',
valid_cat_ids=(3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24, 28, 33, 34,
36, 39)),
dict(type='IndoorPointSample', num_points=40000),
dict(
type='RandomFlip3D',
sync_2d=False,
flip_ratio_bev_horizontal=0.5,
flip_ratio_bev_vertical=0.5),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.087266, 0.087266],
scale_ratio_range=[1.0, 1.0],
shift_height=True),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(
type='Collect3D',
keys=[
'points', 'gt_bboxes_3d', 'gt_labels_3d', 'pts_semantic_mask',
'pts_instance_mask'
])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=True,
load_dim=6,
use_dim=[0, 1, 2]),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(
type='RandomFlip3D',
sync_2d=False,
flip_ratio_bev_horizontal=0.5,
flip_ratio_bev_vertical=0.5),
dict(type='IndoorPointSample', num_points=40000),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=8,
workers_per_gpu=4,
train=dict(
type='RepeatDataset',
times=5,
dataset=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'scannet_infos_train.pkl',
pipeline=train_pipeline,
filter_empty_gt=False,
classes=class_names,
# we use box_type_3d='LiDAR' in kitti and nuscenes dataset
# and box_type_3d='Depth' in sunrgbd and scannet dataset.
box_type_3d='Depth')),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'scannet_infos_val.pkl',
pipeline=test_pipeline,
classes=class_names,
test_mode=True,
box_type_3d='Depth'),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'scannet_infos_val.pkl',
pipeline=test_pipeline,
classes=class_names,
test_mode=True,
box_type_3d='Depth'))
================================================
FILE: configs/_base_/datasets/sunrgbd-3d-10class.py
================================================
dataset_type = 'SUNRGBDDataset'
data_root = 'data/sunrgbd/'
class_names = ('bed', 'table', 'sofa', 'chair', 'toilet', 'desk', 'dresser',
'night_stand', 'bookshelf', 'bathtub')
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=True,
load_dim=6,
use_dim=[0, 1, 2]),
dict(type='LoadAnnotations3D'),
dict(
type='RandomFlip3D',
sync_2d=False,
flip_ratio_bev_horizontal=0.5,
),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.523599, 0.523599],
scale_ratio_range=[0.85, 1.15],
shift_height=True),
dict(type='IndoorPointSample', num_points=20000),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=True,
load_dim=6,
use_dim=[0, 1, 2]),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(
type='RandomFlip3D',
sync_2d=False,
flip_ratio_bev_horizontal=0.5,
),
dict(type='IndoorPointSample', num_points=20000),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=16,
workers_per_gpu=4,
train=dict(
type='RepeatDataset',
times=5,
dataset=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'sunrgbd_infos_train.pkl',
pipeline=train_pipeline,
classes=class_names,
filter_empty_gt=False,
# we use box_type_3d='LiDAR' in kitti and nuscenes dataset
# and box_type_3d='Depth' in sunrgbd and scannet dataset.
box_type_3d='Depth')),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'sunrgbd_infos_val.pkl',
pipeline=test_pipeline,
classes=class_names,
test_mode=True,
box_type_3d='Depth'),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'sunrgbd_infos_val.pkl',
pipeline=test_pipeline,
classes=class_names,
test_mode=True,
box_type_3d='Depth'))
================================================
FILE: configs/_base_/datasets/waymoD5-3d-3class.py
================================================
# dataset settings
# D5 in the config name means the whole dataset is divided into 5 folds
# We only use one fold for efficient experiments
dataset_type = 'WaymoDataset'
data_root = 'data/waymo/kitti_format/'
file_client_args = dict(backend='disk')
# Uncomment the following if use ceph or other file clients.
# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient
# for more details.
# file_client_args = dict(
# backend='petrel', path_mapping=dict(data='s3://waymo_data/'))
class_names = ['Car', 'Pedestrian', 'Cyclist']
point_cloud_range = [-74.88, -74.88, -2, 74.88, 74.88, 4]
input_modality = dict(use_lidar=True, use_camera=False)
db_sampler = dict(
data_root=data_root,
info_path=data_root + 'waymo_dbinfos_train.pkl',
rate=1.0,
prepare=dict(
filter_by_difficulty=[-1],
filter_by_min_points=dict(Car=5, Pedestrian=10, Cyclist=10)),
classes=class_names,
sample_groups=dict(Car=15, Pedestrian=10, Cyclist=10),
points_loader=dict(
type='LoadPointsFromFile',
load_dim=5,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=6,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadAnnotations3D',
with_bbox_3d=True,
with_label_3d=True,
file_client_args=file_client_args),
dict(type='ObjectSample', db_sampler=db_sampler),
dict(
type='RandomFlip3D',
sync_2d=False,
flip_ratio_bev_horizontal=0.5,
flip_ratio_bev_vertical=0.5),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.78539816, 0.78539816],
scale_ratio_range=[0.95, 1.05]),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=6,
use_dim=5,
file_client_args=file_client_args),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=2,
workers_per_gpu=4,
train=dict(
type='RepeatDataset',
times=2,
dataset=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'waymo_infos_train.pkl',
split='training',
pipeline=train_pipeline,
modality=input_modality,
classes=class_names,
test_mode=False,
# we use box_type_3d='LiDAR' in kitti and nuscenes dataset
# and box_type_3d='Depth' in sunrgbd and scannet dataset.
box_type_3d='LiDAR',
# load one frame every five frames
load_interval=5)),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'waymo_infos_val.pkl',
split='training',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True,
box_type_3d='LiDAR'),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'waymo_infos_val.pkl',
split='training',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True,
box_type_3d='LiDAR'))
evaluation = dict(interval=24)
================================================
FILE: configs/_base_/datasets/waymoD5-3d-car.py
================================================
# dataset settings
# D5 in the config name means the whole dataset is divided into 5 folds
# We only use one fold for efficient experiments
dataset_type = 'WaymoDataset'
data_root = 'data/waymo/kitti_format/'
file_client_args = dict(backend='disk')
# Uncomment the following if use ceph or other file clients.
# See https://mmcv.readthedocs.io/en/latest/api.html#mmcv.fileio.FileClient
# for more details.
# file_client_args = dict(
# backend='petrel', path_mapping=dict(data='s3://waymo_data/'))
class_names = ['Car']
point_cloud_range = [-74.88, -74.88, -2, 74.88, 74.88, 4]
input_modality = dict(use_lidar=True, use_camera=False)
db_sampler = dict(
data_root=data_root,
info_path=data_root + 'waymo_dbinfos_train.pkl',
rate=1.0,
prepare=dict(filter_by_difficulty=[-1], filter_by_min_points=dict(Car=5)),
classes=class_names,
sample_groups=dict(Car=15),
points_loader=dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=6,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadAnnotations3D',
with_bbox_3d=True,
with_label_3d=True,
file_client_args=file_client_args),
dict(type='ObjectSample', db_sampler=db_sampler),
dict(
type='RandomFlip3D',
sync_2d=False,
flip_ratio_bev_horizontal=0.5,
flip_ratio_bev_vertical=0.5),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.78539816, 0.78539816],
scale_ratio_range=[0.95, 1.05]),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=6,
use_dim=5,
file_client_args=file_client_args),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=2,
workers_per_gpu=4,
train=dict(
type='RepeatDataset',
times=2,
dataset=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'waymo_infos_train.pkl',
split='training',
pipeline=train_pipeline,
modality=input_modality,
classes=class_names,
test_mode=False,
# we use box_type_3d='LiDAR' in kitti and nuscenes dataset
# and box_type_3d='Depth' in sunrgbd and scannet dataset.
box_type_3d='LiDAR',
# load one frame every five frames
load_interval=5)),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'waymo_infos_val.pkl',
split='training',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True,
box_type_3d='LiDAR'),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'waymo_infos_val.pkl',
split='training',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True,
box_type_3d='LiDAR'))
evaluation = dict(interval=24)
================================================
FILE: configs/_base_/default_runtime.py
================================================
checkpoint_config = dict(interval=1)
# yapf:disable push
# By default we use textlogger hook and tensorboard
# For more loggers see
# https://mmcv.readthedocs.io/en/latest/api.html#mmcv.runner.LoggerHook
log_config = dict(
interval=50,
hooks=[
dict(type='TextLoggerHook'),
dict(type='TensorboardLoggerHook')
])
# yapf:enable
dist_params = dict(backend='nccl')
log_level = 'INFO'
work_dir = None
load_from = None
resume_from = None
workflow = [('train', 1)]
================================================
FILE: configs/_base_/models/3dssd.py
================================================
model = dict(
type='SSD3DNet',
backbone=dict(
type='PointNet2SAMSG',
in_channels=4,
num_points=(4096, 512, (256, 256)),
radii=((0.2, 0.4, 0.8), (0.4, 0.8, 1.6), (1.6, 3.2, 4.8)),
num_samples=((32, 32, 64), (32, 32, 64), (32, 32, 32)),
sa_channels=(((16, 16, 32), (16, 16, 32), (32, 32, 64)),
((64, 64, 128), (64, 64, 128), (64, 96, 128)),
((128, 128, 256), (128, 192, 256), (128, 256, 256))),
aggregation_channels=(64, 128, 256),
fps_mods=(('D-FPS'), ('FS'), ('F-FPS', 'D-FPS')),
fps_sample_range_lists=((-1), (-1), (512, -1)),
norm_cfg=dict(type='BN2d', eps=1e-3, momentum=0.1),
sa_cfg=dict(
type='PointSAModuleMSG',
pool_mod='max',
use_xyz=True,
normalize_xyz=False)),
bbox_head=dict(
type='SSD3DHead',
in_channels=256,
vote_module_cfg=dict(
in_channels=256,
num_points=256,
gt_per_seed=1,
conv_channels=(128, ),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.1),
with_res_feat=False,
vote_xyz_range=(3.0, 3.0, 2.0)),
vote_aggregation_cfg=dict(
type='PointSAModuleMSG',
num_point=256,
radii=(4.8, 6.4),
sample_nums=(16, 32),
mlp_channels=((256, 256, 256, 512), (256, 256, 512, 1024)),
norm_cfg=dict(type='BN2d', eps=1e-3, momentum=0.1),
use_xyz=True,
normalize_xyz=False,
bias=True),
pred_layer_cfg=dict(
in_channels=1536,
shared_conv_channels=(512, 128),
cls_conv_channels=(128, ),
reg_conv_channels=(128, ),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.1),
bias=True),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.1),
objectness_loss=dict(
type='CrossEntropyLoss',
use_sigmoid=True,
reduction='sum',
loss_weight=1.0),
center_loss=dict(
type='SmoothL1Loss', reduction='sum', loss_weight=1.0),
dir_class_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),
dir_res_loss=dict(
type='SmoothL1Loss', reduction='sum', loss_weight=1.0),
size_res_loss=dict(
type='SmoothL1Loss', reduction='sum', loss_weight=1.0),
corner_loss=dict(
type='SmoothL1Loss', reduction='sum', loss_weight=1.0),
vote_loss=dict(type='SmoothL1Loss', reduction='sum', loss_weight=1.0)),
# model training and testing settings
train_cfg=dict(
sample_mod='spec', pos_distance_thr=10.0, expand_dims_length=0.05),
test_cfg=dict(
nms_cfg=dict(type='nms', iou_thr=0.1),
sample_mod='spec',
score_thr=0.0,
per_class_proposal=True,
max_output_num=100))
# optimizer
# This schedule is mainly used by models on indoor dataset,
# e.g., VoteNet on SUNRGBD and ScanNet
lr = 0.002 # max learning rate
optimizer = dict(type='AdamW', lr=lr, weight_decay=0)
optimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))
lr_config = dict(policy='step', warmup=None, step=[80, 120])
# runtime settings
total_epochs = 150
================================================
FILE: configs/_base_/models/cascade_mask_rcnn_r50_fpn.py
================================================
# model settings
model = dict(
type='CascadeRCNN',
pretrained='torchvision://resnet50',
backbone=dict(
type='ResNet',
depth=50,
num_stages=4,
out_indices=(0, 1, 2, 3),
frozen_stages=1,
norm_cfg=dict(type='BN', requires_grad=True),
norm_eval=True,
style='pytorch'),
neck=dict(
type='FPN',
in_channels=[256, 512, 1024, 2048],
out_channels=256,
num_outs=5),
rpn_head=dict(
type='RPNHead',
in_channels=256,
feat_channels=256,
anchor_generator=dict(
type='AnchorGenerator',
scales=[8],
ratios=[0.5, 1.0, 2.0],
strides=[4, 8, 16, 32, 64]),
bbox_coder=dict(
type='DeltaXYWHBBoxCoder',
target_means=[.0, .0, .0, .0],
target_stds=[1.0, 1.0, 1.0, 1.0]),
loss_cls=dict(
type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0)),
roi_head=dict(
type='CascadeRoIHead',
num_stages=3,
stage_loss_weights=[1, 0.5, 0.25],
bbox_roi_extractor=dict(
type='SingleRoIExtractor',
roi_layer=dict(type='RoIAlign', output_size=7, sampling_ratio=0),
out_channels=256,
featmap_strides=[4, 8, 16, 32]),
bbox_head=[
dict(
type='Shared2FCBBoxHead',
in_channels=256,
fc_out_channels=1024,
roi_feat_size=7,
num_classes=80,
bbox_coder=dict(
type='DeltaXYWHBBoxCoder',
target_means=[0., 0., 0., 0.],
target_stds=[0.1, 0.1, 0.2, 0.2]),
reg_class_agnostic=True,
loss_cls=dict(
type='CrossEntropyLoss',
use_sigmoid=False,
loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0,
loss_weight=1.0)),
dict(
type='Shared2FCBBoxHead',
in_channels=256,
fc_out_channels=1024,
roi_feat_size=7,
num_classes=80,
bbox_coder=dict(
type='DeltaXYWHBBoxCoder',
target_means=[0., 0., 0., 0.],
target_stds=[0.05, 0.05, 0.1, 0.1]),
reg_class_agnostic=True,
loss_cls=dict(
type='CrossEntropyLoss',
use_sigmoid=False,
loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0,
loss_weight=1.0)),
dict(
type='Shared2FCBBoxHead',
in_channels=256,
fc_out_channels=1024,
roi_feat_size=7,
num_classes=80,
bbox_coder=dict(
type='DeltaXYWHBBoxCoder',
target_means=[0., 0., 0., 0.],
target_stds=[0.033, 0.033, 0.067, 0.067]),
reg_class_agnostic=True,
loss_cls=dict(
type='CrossEntropyLoss',
use_sigmoid=False,
loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0, loss_weight=1.0))
],
mask_roi_extractor=dict(
type='SingleRoIExtractor',
roi_layer=dict(type='RoIAlign', output_size=14, sampling_ratio=0),
out_channels=256,
featmap_strides=[4, 8, 16, 32]),
mask_head=dict(
type='FCNMaskHead',
num_convs=4,
in_channels=256,
conv_out_channels=256,
num_classes=80,
loss_mask=dict(
type='CrossEntropyLoss', use_mask=True, loss_weight=1.0))),
# model training and testing settings
train_cfg=dict(
rpn=dict(
assigner=dict(
type='MaxIoUAssigner',
pos_iou_thr=0.7,
neg_iou_thr=0.3,
min_pos_iou=0.3,
match_low_quality=True,
ignore_iof_thr=-1),
sampler=dict(
type='RandomSampler',
num=256,
pos_fraction=0.5,
neg_pos_ub=-1,
add_gt_as_proposals=False),
allowed_border=0,
pos_weight=-1,
debug=False),
rpn_proposal=dict(
nms_across_levels=False,
nms_pre=2000,
nms_post=2000,
max_num=2000,
nms_thr=0.7,
min_bbox_size=0),
rcnn=[
dict(
assigner=dict(
type='MaxIoUAssigner',
pos_iou_thr=0.5,
neg_iou_thr=0.5,
min_pos_iou=0.5,
match_low_quality=False,
ignore_iof_thr=-1),
sampler=dict(
type='RandomSampler',
num=512,
pos_fraction=0.25,
neg_pos_ub=-1,
add_gt_as_proposals=True),
mask_size=28,
pos_weight=-1,
debug=False),
dict(
assigner=dict(
type='MaxIoUAssigner',
pos_iou_thr=0.6,
neg_iou_thr=0.6,
min_pos_iou=0.6,
match_low_quality=False,
ignore_iof_thr=-1),
sampler=dict(
type='RandomSampler',
num=512,
pos_fraction=0.25,
neg_pos_ub=-1,
add_gt_as_proposals=True),
mask_size=28,
pos_weight=-1,
debug=False),
dict(
assigner=dict(
type='MaxIoUAssigner',
pos_iou_thr=0.7,
neg_iou_thr=0.7,
min_pos_iou=0.7,
match_low_quality=False,
ignore_iof_thr=-1),
sampler=dict(
type='RandomSampler',
num=512,
pos_fraction=0.25,
neg_pos_ub=-1,
add_gt_as_proposals=True),
mask_size=28,
pos_weight=-1,
debug=False)
]),
test_cfg=dict(
rpn=dict(
nms_across_levels=False,
nms_pre=1000,
nms_post=1000,
max_num=1000,
nms_thr=0.7,
min_bbox_size=0),
rcnn=dict(
score_thr=0.05,
nms=dict(type='nms', iou_threshold=0.5),
max_per_img=100,
mask_thr_binary=0.5)))
================================================
FILE: configs/_base_/models/centerpoint_01voxel_second_secfpn_nus.py
================================================
voxel_size = [0.1, 0.1, 0.2]
model = dict(
type='CenterPoint',
pts_voxel_layer=dict(
max_num_points=10, voxel_size=voxel_size, max_voxels=(90000, 120000)),
pts_voxel_encoder=dict(type='HardSimpleVFE', num_features=5),
pts_middle_encoder=dict(
type='SparseEncoder',
in_channels=5,
sparse_shape=[41, 1024, 1024],
output_channels=128,
order=('conv', 'norm', 'act'),
encoder_channels=((16, 16, 32), (32, 32, 64), (64, 64, 128), (128,
128)),
encoder_paddings=((0, 0, 1), (0, 0, 1), (0, 0, [0, 1, 1]), (0, 0)),
block_type='basicblock'),
pts_backbone=dict(
type='SECOND',
in_channels=256,
out_channels=[128, 256],
layer_nums=[5, 5],
layer_strides=[1, 2],
norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),
conv_cfg=dict(type='Conv2d', bias=False)),
pts_neck=dict(
type='SECONDFPN',
in_channels=[128, 256],
out_channels=[256, 256],
upsample_strides=[1, 2],
norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),
upsample_cfg=dict(type='deconv', bias=False),
use_conv_for_no_stride=True),
pts_bbox_head=dict(
type='CenterHead',
in_channels=sum([256, 256]),
tasks=[
dict(num_class=1, class_names=['car']),
dict(num_class=2, class_names=['truck', 'construction_vehicle']),
dict(num_class=2, class_names=['bus', 'trailer']),
dict(num_class=1, class_names=['barrier']),
dict(num_class=2, class_names=['motorcycle', 'bicycle']),
dict(num_class=2, class_names=['pedestrian', 'traffic_cone']),
],
common_heads=dict(
reg=(2, 2), height=(1, 2), dim=(3, 2), rot=(2, 2), vel=(2, 2)),
share_conv_channel=64,
bbox_coder=dict(
type='CenterPointBBoxCoder',
post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],
max_num=500,
score_threshold=0.1,
out_size_factor=8,
voxel_size=voxel_size[:2],
code_size=9),
separate_head=dict(
type='SeparateHead', init_bias=-2.19, final_kernel=3),
loss_cls=dict(type='GaussianFocalLoss', reduction='mean'),
loss_bbox=dict(type='L1Loss', reduction='mean', loss_weight=0.25),
norm_bbox=True),
# model training and testing settings
train_cfg=dict(
pts=dict(
grid_size=[1024, 1024, 40],
voxel_size=voxel_size,
out_size_factor=8,
dense_reg=1,
gaussian_overlap=0.1,
max_objs=500,
min_radius=2,
code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2])),
test_cfg=dict(
pts=dict(
post_center_limit_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],
max_per_img=500,
max_pool_nms=False,
min_radius=[4, 12, 10, 1, 0.85, 0.175],
score_threshold=0.1,
out_size_factor=8,
voxel_size=voxel_size[:2],
nms_type='rotate',
pre_max_size=1000,
post_max_size=83,
nms_thr=0.2)))
================================================
FILE: configs/_base_/models/centerpoint_02pillar_second_secfpn_nus.py
================================================
voxel_size = [0.2, 0.2, 8]
model = dict(
type='CenterPoint',
pts_voxel_layer=dict(
max_num_points=20, voxel_size=voxel_size, max_voxels=(30000, 40000)),
pts_voxel_encoder=dict(
type='PillarFeatureNet',
in_channels=5,
feat_channels=[64],
with_distance=False,
voxel_size=(0.2, 0.2, 8),
norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.01),
legacy=False),
pts_middle_encoder=dict(
type='PointPillarsScatter', in_channels=64, output_shape=(512, 512)),
pts_backbone=dict(
type='SECOND',
in_channels=64,
out_channels=[64, 128, 256],
layer_nums=[3, 5, 5],
layer_strides=[2, 2, 2],
norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),
conv_cfg=dict(type='Conv2d', bias=False)),
pts_neck=dict(
type='SECONDFPN',
in_channels=[64, 128, 256],
out_channels=[128, 128, 128],
upsample_strides=[0.5, 1, 2],
norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),
upsample_cfg=dict(type='deconv', bias=False),
use_conv_for_no_stride=True),
pts_bbox_head=dict(
type='CenterHead',
in_channels=sum([128, 128, 128]),
tasks=[
dict(num_class=1, class_names=['car']),
dict(num_class=2, class_names=['truck', 'construction_vehicle']),
dict(num_class=2, class_names=['bus', 'trailer']),
dict(num_class=1, class_names=['barrier']),
dict(num_class=2, class_names=['motorcycle', 'bicycle']),
dict(num_class=2, class_names=['pedestrian', 'traffic_cone']),
],
common_heads=dict(
reg=(2, 2), height=(1, 2), dim=(3, 2), rot=(2, 2), vel=(2, 2)),
share_conv_channel=64,
bbox_coder=dict(
type='CenterPointBBoxCoder',
post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],
max_num=500,
score_threshold=0.1,
out_size_factor=4,
voxel_size=voxel_size[:2],
code_size=9),
separate_head=dict(
type='SeparateHead', init_bias=-2.19, final_kernel=3),
loss_cls=dict(type='GaussianFocalLoss', reduction='mean'),
loss_bbox=dict(type='L1Loss', reduction='mean', loss_weight=0.25),
norm_bbox=True),
# model training and testing settings
train_cfg=dict(
pts=dict(
grid_size=[512, 512, 1],
voxel_size=voxel_size,
out_size_factor=4,
dense_reg=1,
gaussian_overlap=0.1,
max_objs=500,
min_radius=2,
code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2])),
test_cfg=dict(
pts=dict(
post_center_limit_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],
max_per_img=500,
max_pool_nms=False,
min_radius=[4, 12, 10, 1, 0.85, 0.175],
score_threshold=0.1,
pc_range=[-51.2, -51.2],
out_size_factor=4,
voxel_size=voxel_size[:2],
nms_type='rotate',
pre_max_size=1000,
post_max_size=83,
nms_thr=0.2)))
================================================
FILE: configs/_base_/models/h3dnet.py
================================================
primitive_z_cfg = dict(
type='PrimitiveHead',
num_dims=2,
num_classes=18,
primitive_mode='z',
upper_thresh=100.0,
surface_thresh=0.5,
vote_module_cfg=dict(
in_channels=256,
vote_per_seed=1,
gt_per_seed=1,
conv_channels=(256, 256),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
norm_feats=True,
vote_loss=dict(
type='ChamferDistance',
mode='l1',
reduction='none',
loss_dst_weight=10.0)),
vote_aggregation_cfg=dict(
type='PointSAModule',
num_point=1024,
radius=0.3,
num_sample=16,
mlp_channels=[256, 128, 128, 128],
use_xyz=True,
normalize_xyz=True),
feat_channels=(128, 128),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
objectness_loss=dict(
type='CrossEntropyLoss',
class_weight=[0.4, 0.6],
reduction='mean',
loss_weight=30.0),
center_loss=dict(
type='ChamferDistance',
mode='l1',
reduction='sum',
loss_src_weight=0.5,
loss_dst_weight=0.5),
semantic_reg_loss=dict(
type='ChamferDistance',
mode='l1',
reduction='sum',
loss_src_weight=0.5,
loss_dst_weight=0.5),
semantic_cls_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),
train_cfg=dict(
dist_thresh=0.2,
var_thresh=1e-2,
lower_thresh=1e-6,
num_point=100,
num_point_line=10,
line_thresh=0.2))
primitive_xy_cfg = dict(
type='PrimitiveHead',
num_dims=1,
num_classes=18,
primitive_mode='xy',
upper_thresh=100.0,
surface_thresh=0.5,
vote_module_cfg=dict(
in_channels=256,
vote_per_seed=1,
gt_per_seed=1,
conv_channels=(256, 256),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
norm_feats=True,
vote_loss=dict(
type='ChamferDistance',
mode='l1',
reduction='none',
loss_dst_weight=10.0)),
vote_aggregation_cfg=dict(
type='PointSAModule',
num_point=1024,
radius=0.3,
num_sample=16,
mlp_channels=[256, 128, 128, 128],
use_xyz=True,
normalize_xyz=True),
feat_channels=(128, 128),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
objectness_loss=dict(
type='CrossEntropyLoss',
class_weight=[0.4, 0.6],
reduction='mean',
loss_weight=30.0),
center_loss=dict(
type='ChamferDistance',
mode='l1',
reduction='sum',
loss_src_weight=0.5,
loss_dst_weight=0.5),
semantic_reg_loss=dict(
type='ChamferDistance',
mode='l1',
reduction='sum',
loss_src_weight=0.5,
loss_dst_weight=0.5),
semantic_cls_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),
train_cfg=dict(
dist_thresh=0.2,
var_thresh=1e-2,
lower_thresh=1e-6,
num_point=100,
num_point_line=10,
line_thresh=0.2))
primitive_line_cfg = dict(
type='PrimitiveHead',
num_dims=0,
num_classes=18,
primitive_mode='line',
upper_thresh=100.0,
surface_thresh=0.5,
vote_module_cfg=dict(
in_channels=256,
vote_per_seed=1,
gt_per_seed=1,
conv_channels=(256, 256),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
norm_feats=True,
vote_loss=dict(
type='ChamferDistance',
mode='l1',
reduction='none',
loss_dst_weight=10.0)),
vote_aggregation_cfg=dict(
type='PointSAModule',
num_point=1024,
radius=0.3,
num_sample=16,
mlp_channels=[256, 128, 128, 128],
use_xyz=True,
normalize_xyz=True),
feat_channels=(128, 128),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
objectness_loss=dict(
type='CrossEntropyLoss',
class_weight=[0.4, 0.6],
reduction='mean',
loss_weight=30.0),
center_loss=dict(
type='ChamferDistance',
mode='l1',
reduction='sum',
loss_src_weight=1.0,
loss_dst_weight=1.0),
semantic_reg_loss=dict(
type='ChamferDistance',
mode='l1',
reduction='sum',
loss_src_weight=1.0,
loss_dst_weight=1.0),
semantic_cls_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=2.0),
train_cfg=dict(
dist_thresh=0.2,
var_thresh=1e-2,
lower_thresh=1e-6,
num_point=100,
num_point_line=10,
line_thresh=0.2))
model = dict(
type='H3DNet',
backbone=dict(
type='MultiBackbone',
num_streams=4,
suffixes=['net0', 'net1', 'net2', 'net3'],
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d', eps=1e-5, momentum=0.01),
act_cfg=dict(type='ReLU'),
backbones=dict(
type='PointNet2SASSG',
in_channels=4,
num_points=(2048, 1024, 512, 256),
radius=(0.2, 0.4, 0.8, 1.2),
num_samples=(64, 32, 16, 16),
sa_channels=((64, 64, 128), (128, 128, 256), (128, 128, 256),
(128, 128, 256)),
fp_channels=((256, 256), (256, 256)),
norm_cfg=dict(type='BN2d'),
sa_cfg=dict(
type='PointSAModule',
pool_mod='max',
use_xyz=True,
normalize_xyz=True))),
rpn_head=dict(
type='VoteHead',
vote_module_cfg=dict(
in_channels=256,
vote_per_seed=1,
gt_per_seed=3,
conv_channels=(256, 256),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
norm_feats=True,
vote_loss=dict(
type='ChamferDistance',
mode='l1',
reduction='none',
loss_dst_weight=10.0)),
vote_aggregation_cfg=dict(
type='PointSAModule',
num_point=256,
radius=0.3,
num_sample=16,
mlp_channels=[256, 128, 128, 128],
use_xyz=True,
normalize_xyz=True),
pred_layer_cfg=dict(
in_channels=128, shared_conv_channels=(128, 128), bias=True),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
objectness_loss=dict(
type='CrossEntropyLoss',
class_weight=[0.2, 0.8],
reduction='sum',
loss_weight=5.0),
center_loss=dict(
type='ChamferDistance',
mode='l2',
reduction='sum',
loss_src_weight=10.0,
loss_dst_weight=10.0),
dir_class_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),
dir_res_loss=dict(
type='SmoothL1Loss', reduction='sum', loss_weight=10.0),
size_class_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),
size_res_loss=dict(
type='SmoothL1Loss', reduction='sum', loss_weight=10.0),
semantic_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=1.0)),
roi_head=dict(
type='H3DRoIHead',
primitive_list=[primitive_z_cfg, primitive_xy_cfg, primitive_line_cfg],
bbox_head=dict(
type='H3DBboxHead',
gt_per_seed=3,
num_proposal=256,
suface_matching_cfg=dict(
type='PointSAModule',
num_point=256 * 6,
radius=0.5,
num_sample=32,
mlp_channels=[128 + 6, 128, 64, 32],
use_xyz=True,
normalize_xyz=True),
line_matching_cfg=dict(
type='PointSAModule',
num_point=256 * 12,
radius=0.5,
num_sample=32,
mlp_channels=[128 + 12, 128, 64, 32],
use_xyz=True,
normalize_xyz=True),
feat_channels=(128, 128),
primitive_refine_channels=[128, 128, 128],
upper_thresh=100.0,
surface_thresh=0.5,
line_thresh=0.5,
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
objectness_loss=dict(
type='CrossEntropyLoss',
class_weight=[0.2, 0.8],
reduction='sum',
loss_weight=5.0),
center_loss=dict(
type='ChamferDistance',
mode='l2',
reduction='sum',
loss_src_weight=10.0,
loss_dst_weight=10.0),
dir_class_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=0.1),
dir_res_loss=dict(
type='SmoothL1Loss', reduction='sum', loss_weight=10.0),
size_class_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=0.1),
size_res_loss=dict(
type='SmoothL1Loss', reduction='sum', loss_weight=10.0),
semantic_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=0.1),
cues_objectness_loss=dict(
type='CrossEntropyLoss',
class_weight=[0.3, 0.7],
reduction='mean',
loss_weight=5.0),
cues_semantic_loss=dict(
type='CrossEntropyLoss',
class_weight=[0.3, 0.7],
reduction='mean',
loss_weight=5.0),
proposal_objectness_loss=dict(
type='CrossEntropyLoss',
class_weight=[0.2, 0.8],
reduction='none',
loss_weight=5.0),
primitive_center_loss=dict(
type='MSELoss', reduction='none', loss_weight=1.0))),
# model training and testing settings
train_cfg=dict(
rpn=dict(
pos_distance_thr=0.3, neg_distance_thr=0.6, sample_mod='vote'),
rpn_proposal=dict(use_nms=False),
rcnn=dict(
pos_distance_thr=0.3,
neg_distance_thr=0.6,
sample_mod='vote',
far_threshold=0.6,
near_threshold=0.3,
mask_surface_threshold=0.3,
label_surface_threshold=0.3,
mask_line_threshold=0.3,
label_line_threshold=0.3)),
test_cfg=dict(
rpn=dict(
sample_mod='seed',
nms_thr=0.25,
score_thr=0.05,
per_class_proposal=True,
use_nms=False),
rcnn=dict(
sample_mod='seed',
nms_thr=0.25,
score_thr=0.05,
per_class_proposal=True)))
================================================
FILE: configs/_base_/models/hv_pointpillars_fpn_lyft.py
================================================
_base_ = './hv_pointpillars_fpn_nus.py'
# model settings (based on nuScenes model settings)
# Voxel size for voxel encoder
# Usually voxel size is changed consistently with the point cloud range
# If point cloud range is modified, do remember to change all related
# keys in the config.
model = dict(
pts_voxel_layer=dict(
max_num_points=20,
point_cloud_range=[-80, -80, -5, 80, 80, 3],
max_voxels=(60000, 60000)),
pts_voxel_encoder=dict(
feat_channels=[64], point_cloud_range=[-80, -80, -5, 80, 80, 3]),
pts_middle_encoder=dict(output_shape=[640, 640]),
pts_bbox_head=dict(
num_classes=9,
anchor_generator=dict(
ranges=[[-80, -80, -1.8, 80, 80, -1.8]], custom_values=[]),
bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=7)),
# model training settings (based on nuScenes model settings)
train_cfg=dict(pts=dict(code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0])))
================================================
FILE: configs/_base_/models/hv_pointpillars_fpn_nus.py
================================================
# model settings
# Voxel size for voxel encoder
# Usually voxel size is changed consistently with the point cloud range
# If point cloud range is modified, do remember to change all related
# keys in the config.
voxel_size = [0.25, 0.25, 8]
model = dict(
type='MVXFasterRCNN',
pts_voxel_layer=dict(
max_num_points=64,
point_cloud_range=[-50, -50, -5, 50, 50, 3],
voxel_size=voxel_size,
max_voxels=(30000, 40000)),
pts_voxel_encoder=dict(
type='HardVFE',
in_channels=4,
feat_channels=[64, 64],
with_distance=False,
voxel_size=voxel_size,
with_cluster_center=True,
with_voxel_center=True,
point_cloud_range=[-50, -50, -5, 50, 50, 3],
norm_cfg=dict(type='naiveSyncBN1d', eps=1e-3, momentum=0.01)),
pts_middle_encoder=dict(
type='PointPillarsScatter', in_channels=64, output_shape=[400, 400]),
pts_backbone=dict(
type='SECOND',
in_channels=64,
norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),
layer_nums=[3, 5, 5],
layer_strides=[2, 2, 2],
out_channels=[64, 128, 256]),
pts_neck=dict(
type='FPN',
norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),
act_cfg=dict(type='ReLU'),
in_channels=[64, 128, 256],
out_channels=256,
start_level=0,
num_outs=3),
pts_bbox_head=dict(
type='Anchor3DHead',
num_classes=10,
in_channels=256,
feat_channels=256,
use_direction_classifier=True,
anchor_generator=dict(
type='AlignedAnchor3DRangeGenerator',
ranges=[[-50, -50, -1.8, 50, 50, -1.8]],
scales=[1, 2, 4],
sizes=[
[0.8660, 2.5981, 1.], # 1.5/sqrt(3)
[0.5774, 1.7321, 1.], # 1/sqrt(3)
[1., 1., 1.],
[0.4, 0.4, 1],
],
custom_values=[0, 0],
rotations=[0, 1.57],
reshape_out=True),
assigner_per_size=False,
diff_rad_by_sin=True,
dir_offset=0.7854, # pi/4
dir_limit_offset=0,
bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=9),
loss_cls=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0),
loss_dir=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),
# model training and testing settings
train_cfg=dict(
pts=dict(
assigner=dict(
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.6,
neg_iou_thr=0.3,
min_pos_iou=0.3,
ignore_iof_thr=-1),
allowed_border=0,
code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2],
pos_weight=-1,
debug=False)),
test_cfg=dict(
pts=dict(
use_rotate_nms=True,
nms_across_levels=False,
nms_pre=1000,
nms_thr=0.2,
score_thr=0.05,
min_bbox_size=0,
max_num=500)))
================================================
FILE: configs/_base_/models/hv_pointpillars_fpn_range100_lyft.py
================================================
_base_ = './hv_pointpillars_fpn_nus.py'
# model settings (based on nuScenes model settings)
# Voxel size for voxel encoder
# Usually voxel size is changed consistently with the point cloud range
# If point cloud range is modified, do remember to change all related
# keys in the config.
model = dict(
pts_voxel_layer=dict(
max_num_points=20,
point_cloud_range=[-100, -100, -5, 100, 100, 3],
max_voxels=(60000, 60000)),
pts_voxel_encoder=dict(
feat_channels=[64], point_cloud_range=[-100, -100, -5, 100, 100, 3]),
pts_middle_encoder=dict(output_shape=[800, 800]),
pts_bbox_head=dict(
num_classes=9,
anchor_generator=dict(
ranges=[[-100, -100, -1.8, 100, 100, -1.8]], custom_values=[]),
bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=7)),
# model training settings (based on nuScenes model settings)
train_cfg=dict(pts=dict(code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0])))
================================================
FILE: configs/_base_/models/hv_pointpillars_secfpn_kitti.py
================================================
voxel_size = [0.16, 0.16, 4]
model = dict(
type='VoxelNet',
voxel_layer=dict(
max_num_points=32,
point_cloud_range=[0, -39.68, -3, 69.12, 39.68, 1],
voxel_size=voxel_size,
max_voxels=(16000, 40000)),
voxel_encoder=dict(
type='PillarFeatureNet',
in_channels=4,
feat_channels=[64],
with_distance=False,
voxel_size=voxel_size,
point_cloud_range=[0, -39.68, -3, 69.12, 39.68, 1]),
middle_encoder=dict(
type='PointPillarsScatter', in_channels=64, output_shape=[496, 432]),
backbone=dict(
type='SECOND',
in_channels=64,
layer_nums=[3, 5, 5],
layer_strides=[2, 2, 2],
out_channels=[64, 128, 256]),
neck=dict(
type='SECONDFPN',
in_channels=[64, 128, 256],
upsample_strides=[1, 2, 4],
out_channels=[128, 128, 128]),
bbox_head=dict(
type='Anchor3DHead',
num_classes=3,
in_channels=384,
feat_channels=384,
use_direction_classifier=True,
anchor_generator=dict(
type='Anchor3DRangeGenerator',
ranges=[
[0, -39.68, -0.6, 70.4, 39.68, -0.6],
[0, -39.68, -0.6, 70.4, 39.68, -0.6],
[0, -39.68, -1.78, 70.4, 39.68, -1.78],
],
sizes=[[0.6, 0.8, 1.73], [0.6, 1.76, 1.73], [1.6, 3.9, 1.56]],
rotations=[0, 1.57],
reshape_out=False),
diff_rad_by_sin=True,
bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),
loss_cls=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),
loss_dir=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),
# model training and testing settings
train_cfg=dict(
assigner=[
dict( # for Pedestrian
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.5,
neg_iou_thr=0.35,
min_pos_iou=0.35,
ignore_iof_thr=-1),
dict( # for Cyclist
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.5,
neg_iou_thr=0.35,
min_pos_iou=0.35,
ignore_iof_thr=-1),
dict( # for Car
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.6,
neg_iou_thr=0.45,
min_pos_iou=0.45,
ignore_iof_thr=-1),
],
allowed_border=0,
pos_weight=-1,
debug=False),
test_cfg=dict(
use_rotate_nms=True,
nms_across_levels=False,
nms_thr=0.01,
score_thr=0.1,
min_bbox_size=0,
nms_pre=100,
max_num=50))
================================================
FILE: configs/_base_/models/hv_pointpillars_secfpn_waymo.py
================================================
# model settings
# Voxel size for voxel encoder
# Usually voxel size is changed consistently with the point cloud range
# If point cloud range is modified, do remember to change all related
# keys in the config.
voxel_size = [0.32, 0.32, 6]
model = dict(
type='MVXFasterRCNN',
pts_voxel_layer=dict(
max_num_points=20,
point_cloud_range=[-74.88, -74.88, -2, 74.88, 74.88, 4],
voxel_size=voxel_size,
max_voxels=(32000, 32000)),
pts_voxel_encoder=dict(
type='HardVFE',
in_channels=5,
feat_channels=[64],
with_distance=False,
voxel_size=voxel_size,
with_cluster_center=True,
with_voxel_center=True,
point_cloud_range=[-74.88, -74.88, -2, 74.88, 74.88, 4],
norm_cfg=dict(type='naiveSyncBN1d', eps=1e-3, momentum=0.01)),
pts_middle_encoder=dict(
type='PointPillarsScatter', in_channels=64, output_shape=[468, 468]),
pts_backbone=dict(
type='SECOND',
in_channels=64,
norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),
layer_nums=[3, 5, 5],
layer_strides=[1, 2, 2],
out_channels=[64, 128, 256]),
pts_neck=dict(
type='SECONDFPN',
norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),
in_channels=[64, 128, 256],
upsample_strides=[1, 2, 4],
out_channels=[128, 128, 128]),
pts_bbox_head=dict(
type='Anchor3DHead',
num_classes=3,
in_channels=384,
feat_channels=384,
use_direction_classifier=True,
anchor_generator=dict(
type='AlignedAnchor3DRangeGenerator',
ranges=[[-74.88, -74.88, -0.0345, 74.88, 74.88, -0.0345],
[-74.88, -74.88, -0.1188, 74.88, 74.88, -0.1188],
[-74.88, -74.88, 0, 74.88, 74.88, 0]],
sizes=[
[2.08, 4.73, 1.77], # car
[0.84, 1.81, 1.77], # cyclist
[0.84, 0.91, 1.74] # pedestrian
],
rotations=[0, 1.57],
reshape_out=False),
diff_rad_by_sin=True,
dir_offset=0.7854, # pi/4
dir_limit_offset=0,
bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=7),
loss_cls=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0),
loss_dir=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),
# model training and testing settings
train_cfg=dict(
pts=dict(
assigner=[
dict( # car
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.55,
neg_iou_thr=0.4,
min_pos_iou=0.4,
ignore_iof_thr=-1),
dict( # cyclist
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.5,
neg_iou_thr=0.3,
min_pos_iou=0.3,
ignore_iof_thr=-1),
dict( # pedestrian
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.5,
neg_iou_thr=0.3,
min_pos_iou=0.3,
ignore_iof_thr=-1),
],
allowed_border=0,
code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0],
pos_weight=-1,
debug=False)),
test_cfg=dict(
pts=dict(
use_rotate_nms=True,
nms_across_levels=False,
nms_pre=4096,
nms_thr=0.25,
score_thr=0.1,
min_bbox_size=0,
max_num=500)))
================================================
FILE: configs/_base_/models/hv_second_secfpn_kitti.py
================================================
model = dict(
type='VoxelNet',
voxel_layer=dict(
max_num_points=5,
point_cloud_range=[0, -40, -3, 70.4, 40, 1],
voxel_size=[0.05, 0.05, 0.1],
max_voxels=(16000, 40000)),
voxel_encoder=dict(type='HardSimpleVFE'),
middle_encoder=dict(
type='SparseEncoder',
in_channels=4,
sparse_shape=[41, 1600, 1408],
order=('conv', 'norm', 'act')),
backbone=dict(
type='SECOND',
in_channels=256,
layer_nums=[5, 5],
layer_strides=[1, 2],
out_channels=[128, 256]),
neck=dict(
type='SECONDFPN',
in_channels=[128, 256],
upsample_strides=[1, 2],
out_channels=[256, 256]),
bbox_head=dict(
type='Anchor3DHead',
num_classes=3,
in_channels=512,
feat_channels=512,
use_direction_classifier=True,
anchor_generator=dict(
type='Anchor3DRangeGenerator',
ranges=[
[0, -40.0, -0.6, 70.4, 40.0, -0.6],
[0, -40.0, -0.6, 70.4, 40.0, -0.6],
[0, -40.0, -1.78, 70.4, 40.0, -1.78],
],
sizes=[[0.6, 0.8, 1.73], [0.6, 1.76, 1.73], [1.6, 3.9, 1.56]],
rotations=[0, 1.57],
reshape_out=False),
diff_rad_by_sin=True,
bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),
loss_cls=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),
loss_dir=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),
# model training and testing settings
train_cfg=dict(
assigner=[
dict( # for Pedestrian
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.35,
neg_iou_thr=0.2,
min_pos_iou=0.2,
ignore_iof_thr=-1),
dict( # for Cyclist
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.35,
neg_iou_thr=0.2,
min_pos_iou=0.2,
ignore_iof_thr=-1),
dict( # for Car
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.6,
neg_iou_thr=0.45,
min_pos_iou=0.45,
ignore_iof_thr=-1),
],
allowed_border=0,
pos_weight=-1,
debug=False),
test_cfg=dict(
use_rotate_nms=True,
nms_across_levels=False,
nms_thr=0.01,
score_thr=0.1,
min_bbox_size=0,
nms_pre=100,
max_num=50))
================================================
FILE: configs/_base_/models/hv_second_secfpn_waymo.py
================================================
# model settings
# Voxel size for voxel encoder
# Usually voxel size is changed consistently with the point cloud range
# If point cloud range is modified, do remember to change all related
# keys in the config.
voxel_size = [0.08, 0.08, 0.1]
model = dict(
type='VoxelNet',
voxel_layer=dict(
max_num_points=10,
point_cloud_range=[-76.8, -51.2, -2, 76.8, 51.2, 4],
voxel_size=voxel_size,
max_voxels=(80000, 90000)),
voxel_encoder=dict(type='HardSimpleVFE', num_features=5),
middle_encoder=dict(
type='SparseEncoder',
in_channels=5,
sparse_shape=[61, 1280, 1920],
order=('conv', 'norm', 'act')),
backbone=dict(
type='SECOND',
in_channels=384,
norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),
layer_nums=[5, 5],
layer_strides=[1, 2],
out_channels=[128, 256]),
neck=dict(
type='SECONDFPN',
norm_cfg=dict(type='naiveSyncBN2d', eps=1e-3, momentum=0.01),
in_channels=[128, 256],
upsample_strides=[1, 2],
out_channels=[256, 256]),
bbox_head=dict(
type='Anchor3DHead',
num_classes=3,
in_channels=512,
feat_channels=512,
use_direction_classifier=True,
anchor_generator=dict(
type='AlignedAnchor3DRangeGenerator',
ranges=[[-76.8, -51.2, -0.0345, 76.8, 51.2, -0.0345],
[-76.8, -51.2, 0, 76.8, 51.2, 0],
[-76.8, -51.2, -0.1188, 76.8, 51.2, -0.1188]],
sizes=[
[2.08, 4.73, 1.77], # car
[0.84, 0.91, 1.74], # pedestrian
[0.84, 1.81, 1.77] # cyclist
],
rotations=[0, 1.57],
reshape_out=False),
diff_rad_by_sin=True,
dir_offset=0.7854, # pi/4
dir_limit_offset=0,
bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder', code_size=7),
loss_cls=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=1.0),
loss_dir=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),
# model training and testing settings
train_cfg=dict(
assigner=[
dict( # car
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.55,
neg_iou_thr=0.4,
min_pos_iou=0.4,
ignore_iof_thr=-1),
dict( # pedestrian
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.5,
neg_iou_thr=0.3,
min_pos_iou=0.3,
ignore_iof_thr=-1),
dict( # cyclist
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.5,
neg_iou_thr=0.3,
min_pos_iou=0.3,
ignore_iof_thr=-1)
],
allowed_border=0,
code_weight=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0],
pos_weight=-1,
debug=False),
test_cfg=dict(
use_rotate_nms=True,
nms_across_levels=False,
nms_pre=4096,
nms_thr=0.25,
score_thr=0.1,
min_bbox_size=0,
max_num=500))
================================================
FILE: configs/_base_/models/imvotenet_image.py
================================================
model = dict(
type='ImVoteNet',
img_backbone=dict(
type='ResNet',
depth=50,
num_stages=4,
out_indices=(0, 1, 2, 3),
frozen_stages=1,
norm_cfg=dict(type='BN', requires_grad=False),
norm_eval=True,
style='caffe'),
img_neck=dict(
type='FPN',
in_channels=[256, 512, 1024, 2048],
out_channels=256,
num_outs=5),
img_rpn_head=dict(
type='RPNHead',
in_channels=256,
feat_channels=256,
anchor_generator=dict(
type='AnchorGenerator',
scales=[8],
ratios=[0.5, 1.0, 2.0],
strides=[4, 8, 16, 32, 64]),
bbox_coder=dict(
type='DeltaXYWHBBoxCoder',
target_means=[.0, .0, .0, .0],
target_stds=[1.0, 1.0, 1.0, 1.0]),
loss_cls=dict(
type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),
loss_bbox=dict(type='L1Loss', loss_weight=1.0)),
img_roi_head=dict(
type='StandardRoIHead',
bbox_roi_extractor=dict(
type='SingleRoIExtractor',
roi_layer=dict(type='RoIAlign', output_size=7, sampling_ratio=0),
out_channels=256,
featmap_strides=[4, 8, 16, 32]),
bbox_head=dict(
type='Shared2FCBBoxHead',
in_channels=256,
fc_out_channels=1024,
roi_feat_size=7,
num_classes=10,
bbox_coder=dict(
type='DeltaXYWHBBoxCoder',
target_means=[0., 0., 0., 0.],
target_stds=[0.1, 0.1, 0.2, 0.2]),
reg_class_agnostic=False,
loss_cls=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),
loss_bbox=dict(type='L1Loss', loss_weight=1.0))),
# model training and testing settings
train_cfg=dict(
img_rpn=dict(
assigner=dict(
type='MaxIoUAssigner',
pos_iou_thr=0.7,
neg_iou_thr=0.3,
min_pos_iou=0.3,
match_low_quality=True,
ignore_iof_thr=-1),
sampler=dict(
type='RandomSampler',
num=256,
pos_fraction=0.5,
neg_pos_ub=-1,
add_gt_as_proposals=False),
allowed_border=-1,
pos_weight=-1,
debug=False),
img_rpn_proposal=dict(
nms_across_levels=False,
nms_pre=2000,
nms_post=1000,
max_num=1000,
nms_thr=0.7,
min_bbox_size=0),
img_rcnn=dict(
assigner=dict(
type='MaxIoUAssigner',
pos_iou_thr=0.5,
neg_iou_thr=0.5,
min_pos_iou=0.5,
match_low_quality=False,
ignore_iof_thr=-1),
sampler=dict(
type='RandomSampler',
num=512,
pos_fraction=0.25,
neg_pos_ub=-1,
add_gt_as_proposals=True),
pos_weight=-1,
debug=False)),
test_cfg=dict(
img_rpn=dict(
nms_across_levels=False,
nms_pre=1000,
nms_post=1000,
max_num=1000,
nms_thr=0.7,
min_bbox_size=0),
img_rcnn=dict(
score_thr=0.05,
nms=dict(type='nms', iou_threshold=0.5),
max_per_img=100)))
================================================
FILE: configs/_base_/models/mask_rcnn_r50_fpn.py
================================================
# model settings
model = dict(
type='MaskRCNN',
pretrained='torchvision://resnet50',
backbone=dict(
type='ResNet',
depth=50,
num_stages=4,
out_indices=(0, 1, 2, 3),
frozen_stages=1,
norm_cfg=dict(type='BN', requires_grad=True),
norm_eval=True,
style='pytorch'),
neck=dict(
type='FPN',
in_channels=[256, 512, 1024, 2048],
out_channels=256,
num_outs=5),
rpn_head=dict(
type='RPNHead',
in_channels=256,
feat_channels=256,
anchor_generator=dict(
type='AnchorGenerator',
scales=[8],
ratios=[0.5, 1.0, 2.0],
strides=[4, 8, 16, 32, 64]),
bbox_coder=dict(
type='DeltaXYWHBBoxCoder',
target_means=[.0, .0, .0, .0],
target_stds=[1.0, 1.0, 1.0, 1.0]),
loss_cls=dict(
type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),
loss_bbox=dict(type='L1Loss', loss_weight=1.0)),
roi_head=dict(
type='StandardRoIHead',
bbox_roi_extractor=dict(
type='SingleRoIExtractor',
roi_layer=dict(type='RoIAlign', output_size=7, sampling_ratio=0),
out_channels=256,
featmap_strides=[4, 8, 16, 32]),
bbox_head=dict(
type='Shared2FCBBoxHead',
in_channels=256,
fc_out_channels=1024,
roi_feat_size=7,
num_classes=80,
bbox_coder=dict(
type='DeltaXYWHBBoxCoder',
target_means=[0., 0., 0., 0.],
target_stds=[0.1, 0.1, 0.2, 0.2]),
reg_class_agnostic=False,
loss_cls=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),
loss_bbox=dict(type='L1Loss', loss_weight=1.0)),
mask_roi_extractor=dict(
type='SingleRoIExtractor',
roi_layer=dict(type='RoIAlign', output_size=14, sampling_ratio=0),
out_channels=256,
featmap_strides=[4, 8, 16, 32]),
mask_head=dict(
type='FCNMaskHead',
num_convs=4,
in_channels=256,
conv_out_channels=256,
num_classes=80,
loss_mask=dict(
type='CrossEntropyLoss', use_mask=True, loss_weight=1.0))),
# model training and testing settings
train_cfg=dict(
rpn=dict(
assigner=dict(
type='MaxIoUAssigner',
pos_iou_thr=0.7,
neg_iou_thr=0.3,
min_pos_iou=0.3,
match_low_quality=True,
ignore_iof_thr=-1),
sampler=dict(
type='RandomSampler',
num=256,
pos_fraction=0.5,
neg_pos_ub=-1,
add_gt_as_proposals=False),
allowed_border=-1,
pos_weight=-1,
debug=False),
rpn_proposal=dict(
nms_across_levels=False,
nms_pre=2000,
nms_post=1000,
max_num=1000,
nms_thr=0.7,
min_bbox_size=0),
rcnn=dict(
assigner=dict(
type='MaxIoUAssigner',
pos_iou_thr=0.5,
neg_iou_thr=0.5,
min_pos_iou=0.5,
match_low_quality=True,
ignore_iof_thr=-1),
sampler=dict(
type='RandomSampler',
num=512,
pos_fraction=0.25,
neg_pos_ub=-1,
add_gt_as_proposals=True),
mask_size=28,
pos_weight=-1,
debug=False)),
test_cfg=dict(
rpn=dict(
nms_across_levels=False,
nms_pre=1000,
nms_post=1000,
max_num=1000,
nms_thr=0.7,
min_bbox_size=0),
rcnn=dict(
score_thr=0.05,
nms=dict(type='nms', iou_threshold=0.5),
max_per_img=100,
mask_thr_binary=0.5)))
================================================
FILE: configs/_base_/models/votenet.py
================================================
model = dict(
type='VoteNet',
backbone=dict(
type='PointNet2SASSG',
in_channels=4,
num_points=(2048, 1024, 512, 256),
radius=(0.2, 0.4, 0.8, 1.2),
num_samples=(64, 32, 16, 16),
sa_channels=((64, 64, 128), (128, 128, 256), (128, 128, 256),
(128, 128, 256)),
fp_channels=((256, 256), (256, 256)),
norm_cfg=dict(type='BN2d'),
sa_cfg=dict(
type='PointSAModule',
pool_mod='max',
use_xyz=True,
normalize_xyz=True)),
bbox_head=dict(
type='VoteHead',
vote_module_cfg=dict(
in_channels=256,
vote_per_seed=1,
gt_per_seed=3,
conv_channels=(256, 256),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
norm_feats=True,
vote_loss=dict(
type='ChamferDistance',
mode='l1',
reduction='none',
loss_dst_weight=10.0)),
vote_aggregation_cfg=dict(
type='PointSAModule',
num_point=256,
radius=0.3,
num_sample=16,
mlp_channels=[256, 128, 128, 128],
use_xyz=True,
normalize_xyz=True),
pred_layer_cfg=dict(
in_channels=128, shared_conv_channels=(128, 128), bias=True),
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
objectness_loss=dict(
type='CrossEntropyLoss',
class_weight=[0.2, 0.8],
reduction='sum',
loss_weight=5.0),
center_loss=dict(
type='ChamferDistance',
mode='l2',
reduction='sum',
loss_src_weight=10.0,
loss_dst_weight=10.0),
dir_class_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),
dir_res_loss=dict(
type='SmoothL1Loss', reduction='sum', loss_weight=10.0),
size_class_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=1.0),
size_res_loss=dict(
type='SmoothL1Loss', reduction='sum', loss_weight=10.0 / 3.0),
semantic_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=1.0)),
# model training and testing settings
train_cfg=dict(
pos_distance_thr=0.3, neg_distance_thr=0.6, sample_mod='vote'),
test_cfg=dict(
sample_mod='seed',
nms_thr=0.25,
score_thr=0.05,
per_class_proposal=True))
================================================
FILE: configs/_base_/schedules/cyclic_20e.py
================================================
# For nuScenes dataset, we usually evaluate the model at the end of training.
# Since the models are trained by 24 epochs by default, we set evaluation
# interval to be 20. Please change the interval accordingly if you do not
# use a default schedule.
# optimizer
# This schedule is mainly used by models on nuScenes dataset
optimizer = dict(type='AdamW', lr=1e-4, weight_decay=0.01)
# max_norm=10 is better for SECOND
optimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))
lr_config = dict(
policy='cyclic',
target_ratio=(10, 1e-4),
cyclic_times=1,
step_ratio_up=0.4,
)
momentum_config = dict(
policy='cyclic',
target_ratio=(0.85 / 0.95, 1),
cyclic_times=1,
step_ratio_up=0.4,
)
# runtime settings
total_epochs = 20
================================================
FILE: configs/_base_/schedules/cyclic_40e.py
================================================
# The schedule is usually used by models trained on KITTI dataset
# The learning rate set in the cyclic schedule is the initial learning rate
# rather than the max learning rate. Since the target_ratio is (10, 1e-4),
# the learning rate will change from 0.0018 to 0.018, than go to 0.0018*1e-4
lr = 0.0018
# The optimizer follows the setting in SECOND.Pytorch, but here we use
# the offcial AdamW optimizer implemented by PyTorch.
optimizer = dict(type='AdamW', lr=lr, betas=(0.95, 0.99), weight_decay=0.01)
optimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2))
# We use cyclic learning rate and momentum schedule following SECOND.Pytorch
# https://github.com/traveller59/second.pytorch/blob/3aba19c9688274f75ebb5e576f65cfe54773c021/torchplus/train/learning_schedules_fastai.py#L69 # noqa
# We implement them in mmcv, for more details, please refer to
# https://github.com/open-mmlab/mmcv/blob/f48241a65aebfe07db122e9db320c31b685dc674/mmcv/runner/hooks/lr_updater.py#L327 # noqa
# https://github.com/open-mmlab/mmcv/blob/f48241a65aebfe07db122e9db320c31b685dc674/mmcv/runner/hooks/momentum_updater.py#L130 # noqa
lr_config = dict(
policy='cyclic',
target_ratio=(10, 1e-4),
cyclic_times=1,
step_ratio_up=0.4,
)
momentum_config = dict(
policy='cyclic',
target_ratio=(0.85 / 0.95, 1),
cyclic_times=1,
step_ratio_up=0.4,
)
# Although the total_epochs is 40, this schedule is usually used we
# RepeatDataset with repeat ratio N, thus the actual total epoch
# number could be Nx40
total_epochs = 40
================================================
FILE: configs/_base_/schedules/mmdet_schedule_1x.py
================================================
# optimizer
optimizer = dict(type='SGD', lr=0.02, momentum=0.9, weight_decay=0.0001)
optimizer_config = dict(grad_clip=None)
# learning policy
lr_config = dict(
policy='step',
warmup='linear',
warmup_iters=500,
warmup_ratio=0.001,
step=[8, 11])
total_epochs = 12
================================================
FILE: configs/_base_/schedules/schedule_2x.py
================================================
# optimizer
# This schedule is mainly used by models on nuScenes dataset
optimizer = dict(type='AdamW', lr=0.001, weight_decay=0.01)
# max_norm=10 is better for SECOND
optimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))
lr_config = dict(
policy='step',
warmup='linear',
warmup_iters=1000,
warmup_ratio=1.0 / 1000,
step=[20, 23])
momentum_config = None
# runtime settings
total_epochs = 24
================================================
FILE: configs/_base_/schedules/schedule_3x.py
================================================
# optimizer
# This schedule is mainly used by models on indoor dataset,
# e.g., VoteNet on SUNRGBD and ScanNet
lr = 0.008 # max learning rate
optimizer = dict(type='AdamW', lr=lr, weight_decay=0.01)
optimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2))
lr_config = dict(policy='step', warmup=None, step=[24, 32])
# runtime settings
total_epochs = 36
================================================
FILE: configs/benchmark/hv_PartA2_secfpn_4x8_cyclic_80e_pcdet_kitti-3d-3class.py
================================================
# model settings
voxel_size = [0.05, 0.05, 0.1]
point_cloud_range = [0, -40, -3, 70.4, 40, 1] # velodyne coordinates, x, y, z
model = dict(
type='PartA2',
voxel_layer=dict(
max_num_points=5, # max_points_per_voxel
point_cloud_range=point_cloud_range,
voxel_size=voxel_size,
max_voxels=(16000, 40000) # (training, testing) max_coxels
),
voxel_encoder=dict(type='HardSimpleVFE'),
middle_encoder=dict(
type='SparseUNet',
in_channels=4,
sparse_shape=[41, 1600, 1408],
order=('conv', 'norm', 'act')),
backbone=dict(
type='SECOND',
in_channels=256,
layer_nums=[5, 5],
layer_strides=[1, 2],
out_channels=[128, 256]),
neck=dict(
type='SECONDFPN',
in_channels=[128, 256],
upsample_strides=[1, 2],
out_channels=[256, 256]),
rpn_head=dict(
type='PartA2RPNHead',
num_classes=3,
in_channels=512,
feat_channels=512,
use_direction_classifier=True,
anchor_generator=dict(
type='Anchor3DRangeGenerator',
ranges=[[0, -40.0, -0.6, 70.4, 40.0, -0.6],
[0, -40.0, -0.6, 70.4, 40.0, -0.6],
[0, -40.0, -1.78, 70.4, 40.0, -1.78]],
sizes=[[0.6, 0.8, 1.73], [0.6, 1.76, 1.73], [1.6, 3.9, 1.56]],
rotations=[0, 1.57],
reshape_out=False),
diff_rad_by_sin=True,
assigner_per_size=True,
assign_per_class=True,
bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),
loss_cls=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),
loss_dir=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),
roi_head=dict(
type='PartAggregationROIHead',
num_classes=3,
semantic_head=dict(
type='PointwiseSemanticHead',
in_channels=16,
extra_width=0.2,
seg_score_thr=0.3,
num_classes=3,
loss_seg=dict(
type='FocalLoss',
use_sigmoid=True,
reduction='sum',
gamma=2.0,
alpha=0.25,
loss_weight=1.0),
loss_part=dict(
type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0)),
seg_roi_extractor=dict(
type='Single3DRoIAwareExtractor',
roi_layer=dict(
type='RoIAwarePool3d',
out_size=14,
max_pts_per_voxel=128,
mode='max')),
part_roi_extractor=dict(
type='Single3DRoIAwareExtractor',
roi_layer=dict(
type='RoIAwarePool3d',
out_size=14,
max_pts_per_voxel=128,
mode='avg')),
bbox_head=dict(
type='PartA2BboxHead',
num_classes=3,
seg_in_channels=16,
part_in_channels=4,
seg_conv_channels=[64, 64],
part_conv_channels=[64, 64],
merge_conv_channels=[128, 128],
down_conv_channels=[128, 256],
bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),
shared_fc_channels=[256, 512, 512, 512],
cls_channels=[256, 256],
reg_channels=[256, 256],
dropout_ratio=0.1,
roi_feat_size=14,
with_corner_loss=True,
loss_bbox=dict(
type='SmoothL1Loss',
beta=1.0 / 9.0,
reduction='sum',
loss_weight=1.0),
loss_cls=dict(
type='CrossEntropyLoss',
use_sigmoid=True,
reduction='sum',
loss_weight=1.0))),
# model training and testing settings
train_cfg=dict(
rpn=dict(
assigner=[
dict( # for Pedestrian
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.5,
neg_iou_thr=0.35,
min_pos_iou=0.35,
ignore_iof_thr=-1),
dict( # for Cyclist
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.5,
neg_iou_thr=0.35,
min_pos_iou=0.35,
ignore_iof_thr=-1),
dict( # for Car
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.6,
neg_iou_thr=0.45,
min_pos_iou=0.45,
ignore_iof_thr=-1)
],
allowed_border=0,
pos_weight=-1,
debug=False),
rpn_proposal=dict(
nms_pre=9000,
nms_post=512,
max_num=512,
nms_thr=0.8,
score_thr=0,
use_rotate_nms=False),
rcnn=dict(
assigner=[
dict( # for Pedestrian
type='MaxIoUAssigner',
iou_calculator=dict(
type='BboxOverlaps3D', coordinate='lidar'),
pos_iou_thr=0.55,
neg_iou_thr=0.55,
min_pos_iou=0.55,
ignore_iof_thr=-1),
dict( # for Cyclist
type='MaxIoUAssigner',
iou_calculator=dict(
type='BboxOverlaps3D', coordinate='lidar'),
pos_iou_thr=0.55,
neg_iou_thr=0.55,
min_pos_iou=0.55,
ignore_iof_thr=-1),
dict( # for Car
type='MaxIoUAssigner',
iou_calculator=dict(
type='BboxOverlaps3D', coordinate='lidar'),
pos_iou_thr=0.55,
neg_iou_thr=0.55,
min_pos_iou=0.55,
ignore_iof_thr=-1)
],
sampler=dict(
type='IoUNegPiecewiseSampler',
num=128,
pos_fraction=0.55,
neg_piece_fractions=[0.8, 0.2],
neg_iou_piece_thrs=[0.55, 0.1],
neg_pos_ub=-1,
add_gt_as_proposals=False,
return_iou=True),
cls_pos_thr=0.75,
cls_neg_thr=0.25)),
test_cfg=dict(
rpn=dict(
nms_pre=1024,
nms_post=100,
max_num=100,
nms_thr=0.7,
score_thr=0,
use_rotate_nms=True),
rcnn=dict(
use_rotate_nms=True,
use_raw_score=True,
nms_thr=0.01,
score_thr=0.3)))
# dataset settings
dataset_type = 'KittiDataset'
data_root = 'data/kitti/'
class_names = ['Pedestrian', 'Cyclist', 'Car']
input_modality = dict(use_lidar=True, use_camera=False)
db_sampler = dict(
data_root=data_root,
info_path=data_root + 'kitti_dbinfos_train.pkl',
rate=1.0,
prepare=dict(
filter_by_difficulty=[-1],
filter_by_min_points=dict(Car=5, Pedestrian=5, Cyclist=5)),
classes=class_names,
sample_groups=dict(Car=20, Pedestrian=15, Cyclist=15))
train_pipeline = [
dict(type='LoadPointsFromFile', coord_type='LIDAR', load_dim=4, use_dim=4),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),
dict(type='ObjectSample', db_sampler=db_sampler),
dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.78539816, 0.78539816],
scale_ratio_range=[0.95, 1.05]),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(type='LoadPointsFromFile', coord_type='LIDAR', load_dim=4, use_dim=4),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=4,
workers_per_gpu=4,
train=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_train.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=train_pipeline,
modality=input_modality,
classes=class_names,
test_mode=False),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True))
# optimizer
lr = 0.001 # max learning rate
optimizer = dict(type='AdamW', lr=lr, betas=(0.95, 0.99), weight_decay=0.01)
optimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2))
lr_config = dict(
policy='cyclic',
target_ratio=(10, 1e-4),
cyclic_times=1,
step_ratio_up=0.4)
momentum_config = dict(
policy='cyclic',
target_ratio=(0.85 / 0.95, 1),
cyclic_times=1,
step_ratio_up=0.4)
checkpoint_config = dict(interval=1)
evaluation = dict(interval=1)
# yapf:disable
log_config = dict(
interval=50,
hooks=[
dict(type='TextLoggerHook'),
dict(type='TensorboardLoggerHook')
])
# yapf:enable
# runtime settings
total_epochs = 80
dist_params = dict(backend='nccl', port=29506)
log_level = 'INFO'
find_unused_parameters = True
work_dir = './work_dirs/parta2_secfpn_80e'
load_from = None
resume_from = None
workflow = [('train', 1)]
================================================
FILE: configs/benchmark/hv_pointpillars_secfpn_3x8_100e_det3d_kitti-3d-car.py
================================================
# model settings
voxel_size = [0.16, 0.16, 4]
point_cloud_range = [0, -39.68, -3, 69.12, 39.68, 1]
model = dict(
type='VoxelNet',
voxel_layer=dict(
max_num_points=64,
point_cloud_range=point_cloud_range,
voxel_size=voxel_size,
max_voxels=(12000, 20000)),
voxel_encoder=dict(
type='PillarFeatureNet',
in_channels=4,
feat_channels=[64],
with_distance=False,
voxel_size=voxel_size,
point_cloud_range=point_cloud_range),
middle_encoder=dict(
type='PointPillarsScatter', in_channels=64, output_shape=[496, 432]),
backbone=dict(
type='SECOND',
in_channels=64,
layer_nums=[3, 5, 5],
layer_strides=[2, 2, 2],
out_channels=[64, 128, 256]),
neck=dict(
type='SECONDFPN',
in_channels=[64, 128, 256],
upsample_strides=[1, 2, 4],
out_channels=[128, 128, 128]),
bbox_head=dict(
type='Anchor3DHead',
num_classes=1,
in_channels=384,
feat_channels=384,
use_direction_classifier=True,
anchor_generator=dict(
type='Anchor3DRangeGenerator',
ranges=[[0, -39.68, -1.78, 69.12, 39.68, -1.78]],
sizes=[[1.6, 3.9, 1.56]],
rotations=[0, 1.57],
reshape_out=True),
diff_rad_by_sin=True,
bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),
loss_cls=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),
loss_dir=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),
# model training and testing settings
train_cfg=dict(
assigner=dict(
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.6,
neg_iou_thr=0.45,
min_pos_iou=0.45,
ignore_iof_thr=-1),
allowed_border=0,
pos_weight=-1,
debug=False),
test_cfg=dict(
use_rotate_nms=True,
nms_across_levels=False,
nms_thr=0.01,
score_thr=0.1,
min_bbox_size=0,
nms_pre=100,
max_num=50))
# dataset settings
dataset_type = 'KittiDataset'
data_root = 'data/kitti/'
class_names = ['Car']
input_modality = dict(use_lidar=True, use_camera=False)
db_sampler = dict(
data_root=data_root,
info_path=data_root + 'kitti_dbinfos_train.pkl',
rate=1.0,
prepare=dict(filter_by_difficulty=[-1], filter_by_min_points=dict(Car=5)),
sample_groups=dict(Car=15),
classes=class_names)
train_pipeline = [
dict(type='LoadPointsFromFile', coord_type='LIDAR', load_dim=4, use_dim=4),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),
dict(type='ObjectSample', db_sampler=db_sampler),
dict(
type='ObjectNoise',
num_try=100,
loc_noise_std=[0.25, 0.25, 0.25],
global_rot_range=[0.0, 0.0],
rot_uniform_noise=[-0.15707963267, 0.15707963267]),
dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
dict(
type='GlobalRotScale',
rot_uniform_noise=[-0.78539816, 0.78539816],
scaling_uniform_noise=[0.95, 1.05]),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(type='LoadPointsFromFile', coord_type='LIDAR', load_dim=4, use_dim=4),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
]
data = dict(
samples_per_gpu=3,
workers_per_gpu=3,
train=dict(
type='RepeatDataset',
times=2,
dataset=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_train.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=train_pipeline,
modality=input_modality,
classes=class_names,
test_mode=False)),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True))
# optimizer
lr = 0.001 # max learning rate
optimizer = dict(
type='AdamW',
lr=lr,
betas=(0.95, 0.99), # the momentum is change during training
weight_decay=0.01)
optimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))
# learning policy
lr_config = dict(
policy='cyclic',
target_ratio=(10, 1e-4),
cyclic_times=1,
step_ratio_up=0.4)
momentum_config = dict(
policy='cyclic',
target_ratio=(0.85 / 0.95, 1),
cyclic_times=1,
step_ratio_up=0.4)
checkpoint_config = dict(interval=1)
evaluation = dict(interval=1)
# yapf:disable
log_config = dict(
interval=50,
hooks=[
dict(type='TextLoggerHook'),
dict(type='TensorboardLoggerHook')
])
# yapf:enable
# runtime settings
total_epochs = 50
dist_params = dict(backend='nccl')
log_level = 'INFO'
work_dir = './work_dirs/pp_secfpn_100e'
load_from = None
resume_from = None
workflow = [('train', 50)]
================================================
FILE: configs/benchmark/hv_pointpillars_secfpn_4x8_80e_pcdet_kitti-3d-3class.py
================================================
# model settings
point_cloud_range = [0, -39.68, -3, 69.12, 39.68, 1]
voxel_size = [0.16, 0.16, 4]
model = dict(
type='VoxelNet',
voxel_layer=dict(
max_num_points=32, # max_points_per_voxel
point_cloud_range=point_cloud_range,
voxel_size=voxel_size,
max_voxels=(16000, 40000) # (training, testing) max_coxels
),
voxel_encoder=dict(
type='PillarFeatureNet',
in_channels=4,
feat_channels=[64],
with_distance=False,
voxel_size=voxel_size,
point_cloud_range=point_cloud_range,
),
middle_encoder=dict(
type='PointPillarsScatter',
in_channels=64,
output_shape=[496, 432],
),
backbone=dict(
type='SECOND',
in_channels=64,
layer_nums=[3, 5, 5],
layer_strides=[2, 2, 2],
out_channels=[64, 128, 256],
),
neck=dict(
type='SECONDFPN',
in_channels=[64, 128, 256],
upsample_strides=[1, 2, 4],
out_channels=[128, 128, 128],
),
bbox_head=dict(
type='Anchor3DHead',
num_classes=3,
in_channels=384,
feat_channels=384,
use_direction_classifier=True,
anchor_generator=dict(
type='Anchor3DRangeGenerator',
ranges=[
[0, -40.0, -0.6, 70.4, 40.0, -0.6],
[0, -40.0, -0.6, 70.4, 40.0, -0.6],
[0, -40.0, -1.78, 70.4, 40.0, -1.78],
],
sizes=[[0.6, 0.8, 1.73], [0.6, 1.76, 1.73], [1.6, 3.9, 1.56]],
rotations=[0, 1.57],
reshape_out=False),
diff_rad_by_sin=True,
bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),
loss_cls=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),
loss_dir=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2),
),
# model training and testing settings
train_cfg=dict(
assigner=[
dict( # for Pedestrian
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.5,
neg_iou_thr=0.35,
min_pos_iou=0.35,
ignore_iof_thr=-1),
dict( # for Cyclist
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.5,
neg_iou_thr=0.35,
min_pos_iou=0.35,
ignore_iof_thr=-1),
dict( # for Car
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.6,
neg_iou_thr=0.45,
min_pos_iou=0.45,
ignore_iof_thr=-1),
],
allowed_border=0,
pos_weight=-1,
debug=False),
test_cfg=dict(
use_rotate_nms=True,
nms_across_levels=False,
nms_thr=0.01,
score_thr=0.1,
min_bbox_size=0,
nms_pre=100,
max_num=50))
# dataset settings
dataset_type = 'KittiDataset'
data_root = 'data/kitti/'
class_names = ['Pedestrian', 'Cyclist', 'Car']
input_modality = dict(use_lidar=True, use_camera=False)
db_sampler = dict(
data_root=data_root,
info_path=data_root + 'kitti_dbinfos_train.pkl',
rate=1.0,
prepare=dict(
filter_by_difficulty=[-1],
filter_by_min_points=dict(
Car=5,
Pedestrian=5,
Cyclist=5,
)),
classes=class_names,
sample_groups=dict(
Car=15,
Pedestrian=15,
Cyclist=15,
))
train_pipeline = [
dict(type='LoadPointsFromFile', coord_type='LIDAR', load_dim=4, use_dim=4),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),
dict(type='ObjectSample', db_sampler=db_sampler),
dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.78539816, 0.78539816],
scale_ratio_range=[0.95, 1.05]),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d']),
]
test_pipeline = [
dict(type='LoadPointsFromFile', coord_type='LIDAR', load_dim=4, use_dim=4),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=4,
workers_per_gpu=4,
train=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_train.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=train_pipeline,
modality=input_modality,
classes=class_names,
test_mode=False),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True))
# optimizer
lr = 0.0003 # max learning rate
optimizer = dict(
type='AdamW',
lr=lr,
betas=(0.95, 0.99), # the momentum is change during training
weight_decay=0.01)
optimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2))
# learning policy
lr_config = dict(
policy='cyclic',
target_ratio=(10, 1e-4),
cyclic_times=1,
step_ratio_up=0.4)
momentum_config = dict(
policy='cyclic',
target_ratio=(0.85 / 0.95, 1),
cyclic_times=1,
step_ratio_up=0.4)
checkpoint_config = dict(interval=1)
evaluation = dict(interval=2)
# yapf:disable
log_config = dict(
interval=50,
hooks=[
dict(type='TextLoggerHook'),
dict(type='TensorboardLoggerHook')
])
# yapf:enable
# runtime settings
total_epochs = 80
dist_params = dict(backend='nccl')
log_level = 'INFO'
work_dir = './work_dirs/pp_secfpn_80e'
load_from = None
resume_from = None
workflow = [('train', 1)]
================================================
FILE: configs/benchmark/hv_second_secfpn_4x8_80e_pcdet_kitti-3d-3class.py
================================================
# model settings
voxel_size = [0.05, 0.05, 0.1]
point_cloud_range = [0, -40, -3, 70.4, 40, 1]
model = dict(
type='VoxelNet',
voxel_layer=dict(
max_num_points=5,
point_cloud_range=point_cloud_range,
voxel_size=voxel_size,
max_voxels=(16000, 40000)),
voxel_encoder=dict(type='HardSimpleVFE'),
middle_encoder=dict(
type='SparseEncoder',
in_channels=4,
sparse_shape=[41, 1600, 1408],
order=('conv', 'norm', 'act')),
backbone=dict(
type='SECOND',
in_channels=256,
layer_nums=[5, 5],
layer_strides=[1, 2],
out_channels=[128, 256]),
neck=dict(
type='SECONDFPN',
in_channels=[128, 256],
upsample_strides=[1, 2],
out_channels=[256, 256]),
bbox_head=dict(
type='Anchor3DHead',
num_classes=3,
in_channels=512,
feat_channels=512,
use_direction_classifier=True,
anchor_generator=dict(
type='Anchor3DRangeGenerator',
ranges=[
[0, -40.0, -0.6, 70.4, 40.0, -0.6],
[0, -40.0, -0.6, 70.4, 40.0, -0.6],
[0, -40.0, -1.78, 70.4, 40.0, -1.78],
],
sizes=[[0.6, 0.8, 1.73], [0.6, 1.76, 1.73], [1.6, 3.9, 1.56]],
rotations=[0, 1.57],
reshape_out=False),
diff_rad_by_sin=True,
bbox_coder=dict(type='DeltaXYZWLHRBBoxCoder'),
loss_cls=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=1.0),
loss_bbox=dict(type='SmoothL1Loss', beta=1.0 / 9.0, loss_weight=2.0),
loss_dir=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=0.2)),
# model training and testing settings
train_cfg=dict(
assigner=[
dict( # for Pedestrian
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.5,
neg_iou_thr=0.35,
min_pos_iou=0.35,
ignore_iof_thr=-1),
dict( # for Cyclist
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.5,
neg_iou_thr=0.35,
min_pos_iou=0.35,
ignore_iof_thr=-1),
dict( # for Car
type='MaxIoUAssigner',
iou_calculator=dict(type='BboxOverlapsNearest3D'),
pos_iou_thr=0.6,
neg_iou_thr=0.45,
min_pos_iou=0.45,
ignore_iof_thr=-1),
],
allowed_border=0,
pos_weight=-1,
debug=False),
test_cfg=dict(
use_rotate_nms=True,
nms_across_levels=False,
nms_thr=0.01,
score_thr=0.1,
min_bbox_size=0,
nms_pre=100,
max_num=50))
# dataset settings
dataset_type = 'KittiDataset'
data_root = 'data/kitti/'
class_names = ['Pedestrian', 'Cyclist', 'Car']
input_modality = dict(use_lidar=False, use_camera=False)
db_sampler = dict(
data_root=data_root,
info_path=data_root + 'kitti_dbinfos_train.pkl',
rate=1.0,
prepare=dict(
filter_by_difficulty=[-1],
filter_by_min_points=dict(
Car=5,
Pedestrian=5,
Cyclist=5,
)),
classes=class_names,
sample_groups=dict(
Car=20,
Pedestrian=15,
Cyclist=15,
))
file_client_args = dict(backend='disk')
# file_client_args = dict(
# backend='petrel', path_mapping=dict(data='s3://kitti_data/'))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4,
file_client_args=file_client_args),
dict(
type='LoadAnnotations3D',
with_bbox_3d=True,
with_label_3d=True,
file_client_args=file_client_args),
dict(type='ObjectSample', db_sampler=db_sampler),
dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.78539816, 0.78539816],
scale_ratio_range=[0.95, 1.05]),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4,
file_client_args=file_client_args),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
samples_per_gpu=4,
workers_per_gpu=4,
train=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_train.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=train_pipeline,
modality=input_modality,
classes=class_names,
test_mode=False),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val.pkl',
split='training',
pts_prefix='velodyne_reduced',
pipeline=test_pipeline,
modality=input_modality,
classes=class_names,
test_mode=True))
# optimizer
lr = 0.0003 # max learning rate
optimizer = dict(type='AdamW', lr=lr, betas=(0.95, 0.99), weight_decay=0.01)
optimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2))
lr_config = dict(
policy='cyclic',
target_ratio=(10, 1e-4),
cyclic_times=1,
step_ratio_up=0.4)
momentum_config = dict(
policy='cyclic',
target_ratio=(0.85 / 0.95, 1),
cyclic_times=1,
step_ratio_up=0.4)
checkpoint_config = dict(interval=1)
evaluation = dict(interval=2)
# yapf:disable
log_config = dict(
interval=50,
hooks=[
dict(type='TextLoggerHook'),
dict(type='TensorboardLoggerHook')
])
# yapf:enable
# runtime settings
total_epochs = 80
dist_params = dict(backend='nccl')
log_level = 'INFO'
work_dir = './work_dirs/sec_secfpn_80e'
load_from = None
resume_from = None
workflow = [('train', 1)]
================================================
FILE: configs/centerpoint/README.md
================================================
# Center-based 3D Object Detection and Tracking
## Introduction
[ALGORITHM]
We implement CenterPoint and provide the result and checkpoints on nuScenes dataset.
We follow the below style to name config files. Contributors are advised to follow the same style.
`{xxx}` is required field and `[yyy]` is optional.
`{model}`: model type like `centerpoint`.
`{model setting}`: voxel size and voxel type like `01voxel`, `02pillar`.
`{backbone}`: backbone type like `second`.
`{neck}`: neck type like `secfpn`.
`[dcn]`: Whether to use deformable convolution.
`[circle]`: Whether to use circular nms.
`[batch_per_gpu x gpu]`: GPUs and samples per GPU, 4x8 is used by default.
`{schedule}`: training schedule, options are 1x, 2x, 20e, etc. 1x and 2x means 12 epochs and 24 epochs respectively. 20e is adopted in cascade models, which denotes 20 epochs. For 1x/2x, initial learning rate decays by a factor of 10 at the 8/16th and 11/22th epochs. For 20e, initial learning rate decays by a factor of 10 at the 16th and 19th epochs.
`{dataset}`: dataset like nus-3d, kitti-3d, lyft-3d, scannet-3d, sunrgbd-3d. We also indicate the number of classes we are using if there exist multiple settings, e.g., kitti-3d-3class and kitti-3d-car means training on KITTI dataset with 3 classes and single class, respectively.
```
@article{yin2021center,
title={Center-based 3D Object Detection and Tracking},
author={Yin, Tianwei and Zhou, Xingyi and Kr{\"a}henb{\"u}hl, Philipp},
journal={CVPR},
year={2021},
}
```
## Usage
### Test time augmentation
We have supported double-flip and scale augmentation during test time. To use test time augmentation, users need to modify the
`test_pipeline` and `test_cfg` in the config.
For example, we change `centerpoint_0075voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus.py` to the following.
```python
_base_ = './centerpoint_0075voxel_second_secfpn_circlenms' \
'_4x8_cyclic_20e_nus.py'
model = dict(
test_cfg=dict(
pts=dict(
use_rotate_nms=True,
max_num=83)))
point_cloud_range = [-54, -54, -5.0, 54, 54, 3.0]
file_client_args = dict(backend='disk')
class_names = [
'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',
'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=9,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args,
pad_empty_sweeps=True,
remove_close=True),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=[0.95, 1.0, 1.05],
flip=True,
pcd_horizontal_flip=True,
pcd_vertical_flip=True,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D', sync_2d=False),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
val=dict(pipeline=test_pipeline), test=dict(pipeline=test_pipeline))
```
## Results
### CenterPoint
|Backbone| Voxel type (voxel size) |Dcn|Circular nms| Mem (GB) | Inf time (fps) | mAP |NDS| Download |
| :---------: |:-----: |:-----: | :------: | :------------: | :----: |:----: | :------: |:------: |
|[SECFPN](./centerpoint_01voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus.py)|voxel (0.1)|✗|✓|4.9| |56.19|64.43|[model](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/centerpoint/centerpoint_01voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus/centerpoint_01voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus_20201001_135205-5db91e00.pth) | [log](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/centerpoint/centerpoint_01voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus/centerpoint_01voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus_20201001_135205.log.json)|
|above w/o circle nms|voxel (0.1)|✗|✗| | |56.56|64.46||
|[SECFPN](./centerpoint_01voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py)|voxel (0.1)|✓|✓|5.2| |56.34|64.81|[model](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/centerpoint/centerpoint_01voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus/centerpoint_01voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus_20201004_075317-26d8176c.pth) | [log](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/centerpoint/centerpoint_01voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus/centerpoint_01voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus_20201004_075317.log.json)|
|above w/o circle nms|voxel (0.1)|✓|✗| | |56.60|64.90||
|[SECFPN](./centerpoint_0075voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus.py)|voxel (0.075)|✗|✓|7.8| |57.34|65.23|[model](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/centerpoint/centerpoint_0075voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus/centerpoint_0075voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus_20200925_230905-358fbe3b.pth) | [log](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/centerpoint/centerpoint_0075voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus/centerpoint_0075voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus_20200925_230905.log.json)|
|above w/o circle nms|voxel (0.075)|✗|✗| | |57.63|65.39| |
|[SECFPN](./centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py)|voxel (0.075)|✓|✓|8.5| |57.27|65.58|[model](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/centerpoint/centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus/centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus_20200930_201619-67c8496f.pth) | [log](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/centerpoint/centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus/centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus_20200930_201619.log.json)|
|above w/o circle nms|voxel (0.075)|✓|✗| | |57.43|65.63||
|above w/ double flip|voxel (0.075)|✓|✗| | |59.73|67.39||
|above w/ scale tta|voxel (0.075)|✓|✗| | |60.43|67.65||
|above w/ circle nms w/o scale tta|voxel (0.075)|✓|✗| | |59.52|67.24||
|[SECFPN](./centerpoint_02pillar_second_secfpn_circlenms_4x8_cyclic_20e_nus.py)|pillar (0.2)|✗|✓|4.4| |49.07|59.66|[model](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/centerpoint/centerpoint_01voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus/centerpoint_02pillar_second_secfpn_circlenms_4x8_cyclic_20e_nus_20201004_170716-a134a233.pth) | [log](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/centerpoint/centerpoint_01voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus/centerpoint_02pillar_second_secfpn_circlenms_4x8_cyclic_20e_nus_20201004_170716.log.json)|
|above w/o circle nms|pillar (0.2)|✗|✗| | |49.12|59.66||
|[SECFPN](./centerpoint_02pillar_second_secfpn_dcn_4x8_cyclic_20e_nus.py)|pillar (0.2)|✓|✗| 4.6| |48.8 |59.67 |[model](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/centerpoint/centerpoint_02pillar_second_secfpn_dcn_4x8_cyclic_20e_nus/centerpoint_02pillar_second_secfpn_dcn_4x8_cyclic_20e_nus_20200930_103722-3bb135f2.pth) | [log](https://download.openmmlab.com/mmdetection3d/v0.1.0_models/centerpoint/centerpoint_02pillar_second_secfpn_dcn_4x8_cyclic_20e_nus/centerpoint_02pillar_second_secfpn_dcn_4x8_cyclic_20e_nus_20200930_103722.log.json)|
|above w/ circle nms|pillar (0.2)|✓|✓| | |48.79|59.65||
================================================
FILE: configs/centerpoint/centerpoint_0075voxel_second_secfpn_4x8_cyclic_20e_nus.py
================================================
_base_ = ['./centerpoint_01voxel_second_secfpn_4x8_cyclic_20e_nus.py']
# If point cloud range is changed, the models should also change their point
# cloud range accordingly
voxel_size = [0.075, 0.075, 0.2]
point_cloud_range = [-54, -54, -5.0, 54, 54, 3.0]
# For nuScenes we usually do 10-class detection
class_names = [
'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',
'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'
]
model = dict(
pts_voxel_layer=dict(
voxel_size=voxel_size, point_cloud_range=point_cloud_range),
pts_middle_encoder=dict(sparse_shape=[41, 1440, 1440]),
pts_bbox_head=dict(
bbox_coder=dict(
voxel_size=voxel_size[:2], pc_range=point_cloud_range[:2])),
train_cfg=dict(
pts=dict(
grid_size=[1440, 1440, 40],
voxel_size=voxel_size,
point_cloud_range=point_cloud_range)),
test_cfg=dict(
pts=dict(voxel_size=voxel_size[:2], pc_range=point_cloud_range[:2])))
dataset_type = 'NuScenesDataset'
data_root = 'data/nuscenes/'
file_client_args = dict(backend='disk')
db_sampler = dict(
data_root=data_root,
info_path=data_root + 'nuscenes_dbinfos_train.pkl',
rate=1.0,
prepare=dict(
filter_by_difficulty=[-1],
filter_by_min_points=dict(
car=5,
truck=5,
bus=5,
trailer=5,
construction_vehicle=5,
traffic_cone=5,
barrier=5,
motorcycle=5,
bicycle=5,
pedestrian=5)),
classes=class_names,
sample_groups=dict(
car=2,
truck=3,
construction_vehicle=7,
bus=4,
trailer=6,
barrier=2,
motorcycle=6,
bicycle=6,
pedestrian=2,
traffic_cone=2),
points_loader=dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=9,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args,
pad_empty_sweeps=True,
remove_close=True),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),
dict(type='ObjectSample', db_sampler=db_sampler),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.3925, 0.3925],
scale_ratio_range=[0.95, 1.05],
translation_std=[0, 0, 0]),
dict(
type='RandomFlip3D',
sync_2d=False,
flip_ratio_bev_horizontal=0.5,
flip_ratio_bev_vertical=0.5),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=9,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args,
pad_empty_sweeps=True,
remove_close=True),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
train=dict(dataset=dict(pipeline=train_pipeline)),
val=dict(pipeline=test_pipeline),
test=dict(pipeline=test_pipeline))
================================================
FILE: configs/centerpoint/centerpoint_0075voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus.py
================================================
_base_ = ['./centerpoint_0075voxel_second_secfpn_4x8_cyclic_20e_nus.py']
model = dict(test_cfg=dict(pts=dict(nms_type='circle')))
================================================
FILE: configs/centerpoint/centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_20e_nus.py
================================================
_base_ = ['./centerpoint_0075voxel_second_secfpn_4x8_cyclic_20e_nus.py']
model = dict(
pts_bbox_head=dict(
separate_head=dict(
type='DCNSeparateHead',
dcn_config=dict(
type='DCN',
in_channels=64,
out_channels=64,
kernel_size=3,
padding=1,
groups=4),
init_bias=-2.19,
final_kernel=3)))
================================================
FILE: configs/centerpoint/centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_flip-tta_20e_nus.py
================================================
_base_ = './centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_20e_nus.py'
point_cloud_range = [-54, -54, -5.0, 54, 54, 3.0]
file_client_args = dict(backend='disk')
class_names = [
'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',
'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=9,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args,
pad_empty_sweeps=True,
remove_close=True),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
# Add double-flip augmentation
flip=True,
pcd_horizontal_flip=True,
pcd_vertical_flip=True,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D', sync_2d=False),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
val=dict(pipeline=test_pipeline), test=dict(pipeline=test_pipeline))
================================================
FILE: configs/centerpoint/centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_tta_20e_nus.py
================================================
_base_ = './centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_20e_nus.py'
test_cfg = dict(pts=dict(use_rotate_nms=True, max_num=500))
point_cloud_range = [-54, -54, -5.0, 54, 54, 3.0]
file_client_args = dict(backend='disk')
class_names = [
'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',
'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=9,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args,
pad_empty_sweeps=True,
remove_close=True),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=[0.95, 1.0, 1.05],
# Add double-flip augmentation
flip=True,
pcd_horizontal_flip=True,
pcd_vertical_flip=True,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D', sync_2d=False),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
val=dict(pipeline=test_pipeline), test=dict(pipeline=test_pipeline))
================================================
FILE: configs/centerpoint/centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py
================================================
_base_ = ['./centerpoint_0075voxel_second_secfpn_4x8_cyclic_20e_nus.py']
model = dict(
pts_bbox_head=dict(
separate_head=dict(
type='DCNSeparateHead',
dcn_config=dict(
type='DCN',
in_channels=64,
out_channels=64,
kernel_size=3,
padding=1,
groups=4),
init_bias=-2.19,
final_kernel=3)),
test_cfg=dict(pts=dict(nms_type='circle')))
================================================
FILE: configs/centerpoint/centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_flip-tta_20e_nus.py
================================================
_base_ = './centerpoint_0075voxel_second_secfpn_dcn_' \
'circlenms_4x8_cyclic_20e_nus.py'
point_cloud_range = [-54, -54, -5.0, 54, 54, 3.0]
file_client_args = dict(backend='disk')
class_names = [
'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',
'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=9,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args,
pad_empty_sweeps=True,
remove_close=True),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
# Add double-flip augmentation
flip=True,
pcd_horizontal_flip=True,
pcd_vertical_flip=True,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D', sync_2d=False),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
val=dict(pipeline=test_pipeline), test=dict(pipeline=test_pipeline))
================================================
FILE: configs/centerpoint/centerpoint_01voxel_second_secfpn_4x8_cyclic_20e_nus.py
================================================
_base_ = [
'../_base_/datasets/nus-3d.py',
'../_base_/models/centerpoint_01voxel_second_secfpn_nus.py',
'../_base_/schedules/cyclic_20e.py', '../_base_/default_runtime.py'
]
# If point cloud range is changed, the models should also change their point
# cloud range accordingly
point_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]
# For nuScenes we usually do 10-class detection
class_names = [
'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',
'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'
]
model = dict(
pts_voxel_layer=dict(point_cloud_range=point_cloud_range),
pts_bbox_head=dict(bbox_coder=dict(pc_range=point_cloud_range[:2])),
# model training and testing settings
train_cfg=dict(pts=dict(point_cloud_range=point_cloud_range)),
test_cfg=dict(pts=dict(pc_range=point_cloud_range[:2])))
dataset_type = 'NuScenesDataset'
data_root = 'data/nuscenes/'
file_client_args = dict(backend='disk')
db_sampler = dict(
data_root=data_root,
info_path=data_root + 'nuscenes_dbinfos_train.pkl',
rate=1.0,
prepare=dict(
filter_by_difficulty=[-1],
filter_by_min_points=dict(
car=5,
truck=5,
bus=5,
trailer=5,
construction_vehicle=5,
traffic_cone=5,
barrier=5,
motorcycle=5,
bicycle=5,
pedestrian=5)),
classes=class_names,
sample_groups=dict(
car=2,
truck=3,
construction_vehicle=7,
bus=4,
trailer=6,
barrier=2,
motorcycle=6,
bicycle=6,
pedestrian=2,
traffic_cone=2),
points_loader=dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=9,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args,
pad_empty_sweeps=True,
remove_close=True),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),
dict(type='ObjectSample', db_sampler=db_sampler),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.3925, 0.3925],
scale_ratio_range=[0.95, 1.05],
translation_std=[0, 0, 0]),
dict(
type='RandomFlip3D',
sync_2d=False,
flip_ratio_bev_horizontal=0.5,
flip_ratio_bev_vertical=0.5),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=9,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args,
pad_empty_sweeps=True,
remove_close=True),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
train=dict(
type='CBGSDataset',
dataset=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'nuscenes_infos_train.pkl',
pipeline=train_pipeline,
classes=class_names,
test_mode=False,
use_valid_flag=True,
# we use box_type_3d='LiDAR' in kitti and nuscenes dataset
# and box_type_3d='Depth' in sunrgbd and scannet dataset.
box_type_3d='LiDAR')),
val=dict(pipeline=test_pipeline, classes=class_names),
test=dict(pipeline=test_pipeline, classes=class_names))
evaluation = dict(interval=20)
================================================
FILE: configs/centerpoint/centerpoint_01voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus.py
================================================
_base_ = ['./centerpoint_01voxel_second_secfpn_4x8_cyclic_20e_nus.py']
model = dict(test_cfg=dict(pts=dict(nms_type='circle')))
================================================
FILE: configs/centerpoint/centerpoint_01voxel_second_secfpn_dcn_4x8_cyclic_20e_nus.py
================================================
_base_ = ['./centerpoint_01voxel_second_secfpn_4x8_cyclic_20e_nus.py']
model = dict(
pts_bbox_head=dict(
separate_head=dict(
type='DCNSeparateHead',
dcn_config=dict(
type='DCN',
in_channels=64,
out_channels=64,
kernel_size=3,
padding=1,
groups=4),
init_bias=-2.19,
final_kernel=3)))
================================================
FILE: configs/centerpoint/centerpoint_01voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py
================================================
_base_ = ['./centerpoint_01voxel_second_secfpn_4x8_cyclic_20e_nus.py']
model = dict(
pts_bbox_head=dict(
separate_head=dict(
type='DCNSeparateHead',
dcn_config=dict(
type='DCN',
in_channels=64,
out_channels=64,
kernel_size=3,
padding=1,
groups=4),
init_bias=-2.19,
final_kernel=3)),
test_cfg=dict(pts=dict(nms_type='circle')))
================================================
FILE: configs/centerpoint/centerpoint_02pillar_second_secfpn_4x8_cyclic_20e_nus.py
================================================
_base_ = [
'../_base_/datasets/nus-3d.py',
'../_base_/models/centerpoint_02pillar_second_secfpn_nus.py',
'../_base_/schedules/cyclic_20e.py', '../_base_/default_runtime.py'
]
# If point cloud range is changed, the models should also change their point
# cloud range accordingly
point_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]
# For nuScenes we usually do 10-class detection
class_names = [
'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',
'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'
]
model = dict(
pts_voxel_layer=dict(point_cloud_range=point_cloud_range),
pts_voxel_encoder=dict(point_cloud_range=point_cloud_range),
pts_bbox_head=dict(bbox_coder=dict(pc_range=point_cloud_range[:2])),
# model training and testing settings
train_cfg=dict(pts=dict(point_cloud_range=point_cloud_range)),
test_cfg=dict(pts=dict(pc_range=point_cloud_range[:2])))
dataset_type = 'NuScenesDataset'
data_root = 'data/nuscenes/'
file_client_args = dict(backend='disk')
db_sampler = dict(
data_root=data_root,
info_path=data_root + 'nuscenes_dbinfos_train.pkl',
rate=1.0,
prepare=dict(
filter_by_difficulty=[-1],
filter_by_min_points=dict(
car=5,
truck=5,
bus=5,
trailer=5,
construction_vehicle=5,
traffic_cone=5,
barrier=5,
motorcycle=5,
bicycle=5,
pedestrian=5)),
classes=class_names,
sample_groups=dict(
car=2,
truck=3,
construction_vehicle=7,
bus=4,
trailer=6,
barrier=2,
motorcycle=6,
bicycle=6,
pedestrian=2,
traffic_cone=2),
points_loader=dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=9,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args,
pad_empty_sweeps=True,
remove_close=True),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),
dict(type='ObjectSample', db_sampler=db_sampler),
dict(
type='GlobalRotScaleTrans',
rot_range=[-0.3925, 0.3925],
scale_ratio_range=[0.95, 1.05],
translation_std=[0, 0, 0]),
dict(
type='RandomFlip3D',
sync_2d=False,
flip_ratio_bev_horizontal=0.5,
flip_ratio_bev_vertical=0.5),
dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
dict(type='PointShuffle'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'gt_bboxes_3d', 'gt_labels_3d'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=9,
use_dim=[0, 1, 2, 3, 4],
file_client_args=file_client_args,
pad_empty_sweeps=True,
remove_close=True),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='GlobalRotScaleTrans',
rot_range=[0, 0],
scale_ratio_range=[1., 1.],
translation_std=[0, 0, 0]),
dict(type='RandomFlip3D'),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
data = dict(
train=dict(
type='CBGSDataset',
dataset=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'nuscenes_infos_train.pkl',
pipeline=train_pipeline,
classes=class_names,
gitextract_232uyltz/ ├── .gitignore ├── LICENSE ├── MANIFEST.in ├── README.md ├── README_zh-CN.md ├── configs/ │ ├── 3dssd/ │ │ ├── 3dssd_kitti-3d-car.py │ │ └── README.md │ ├── _base_/ │ │ ├── datasets/ │ │ │ ├── coco_instance.py │ │ │ ├── kitti-3d-3class.py │ │ │ ├── kitti-3d-car.py │ │ │ ├── lyft-3d.py │ │ │ ├── nuim_instance.py │ │ │ ├── nus-3d.py │ │ │ ├── range100_lyft-3d.py │ │ │ ├── scannet-3d-18class.py │ │ │ ├── sunrgbd-3d-10class.py │ │ │ ├── waymoD5-3d-3class.py │ │ │ └── waymoD5-3d-car.py │ │ ├── default_runtime.py │ │ ├── models/ │ │ │ ├── 3dssd.py │ │ │ ├── cascade_mask_rcnn_r50_fpn.py │ │ │ ├── centerpoint_01voxel_second_secfpn_nus.py │ │ │ ├── centerpoint_02pillar_second_secfpn_nus.py │ │ │ ├── h3dnet.py │ │ │ ├── hv_pointpillars_fpn_lyft.py │ │ │ ├── hv_pointpillars_fpn_nus.py │ │ │ ├── hv_pointpillars_fpn_range100_lyft.py │ │ │ ├── hv_pointpillars_secfpn_kitti.py │ │ │ ├── hv_pointpillars_secfpn_waymo.py │ │ │ ├── hv_second_secfpn_kitti.py │ │ │ ├── hv_second_secfpn_waymo.py │ │ │ ├── imvotenet_image.py │ │ │ ├── mask_rcnn_r50_fpn.py │ │ │ └── votenet.py │ │ └── schedules/ │ │ ├── cyclic_20e.py │ │ ├── cyclic_40e.py │ │ ├── mmdet_schedule_1x.py │ │ ├── schedule_2x.py │ │ └── schedule_3x.py │ ├── benchmark/ │ │ ├── hv_PartA2_secfpn_4x8_cyclic_80e_pcdet_kitti-3d-3class.py │ │ ├── hv_pointpillars_secfpn_3x8_100e_det3d_kitti-3d-car.py │ │ ├── hv_pointpillars_secfpn_4x8_80e_pcdet_kitti-3d-3class.py │ │ └── hv_second_secfpn_4x8_80e_pcdet_kitti-3d-3class.py │ ├── centerpoint/ │ │ ├── README.md │ │ ├── centerpoint_0075voxel_second_secfpn_4x8_cyclic_20e_nus.py │ │ ├── centerpoint_0075voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus.py │ │ ├── centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_20e_nus.py │ │ ├── centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_flip-tta_20e_nus.py │ │ ├── centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_tta_20e_nus.py │ │ ├── centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py │ │ ├── centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_flip-tta_20e_nus.py │ │ ├── centerpoint_01voxel_second_secfpn_4x8_cyclic_20e_nus.py │ │ ├── centerpoint_01voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus.py │ │ ├── centerpoint_01voxel_second_secfpn_dcn_4x8_cyclic_20e_nus.py │ │ ├── centerpoint_01voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py │ │ ├── centerpoint_02pillar_second_secfpn_4x8_cyclic_20e_nus.py │ │ ├── centerpoint_02pillar_second_secfpn_circlenms_4x8_cyclic_20e_nus.py │ │ ├── centerpoint_02pillar_second_secfpn_dcn_4x8_cyclic_20e_nus.py │ │ └── centerpoint_02pillar_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py │ ├── dynamic_voxelization/ │ │ ├── README.md │ │ ├── dv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py │ │ ├── dv_second_secfpn_2x8_cosine_80e_kitti-3d-3class.py │ │ └── dv_second_secfpn_6x8_80e_kitti-3d-car.py │ ├── fp16/ │ │ ├── README.md │ │ ├── hv_pointpillars_fpn_sbn-all_fp16_2x8_2x_nus-3d.py │ │ ├── hv_pointpillars_regnet-400mf_fpn_sbn-all_fp16_2x8_2x_nus-3d.py │ │ ├── hv_pointpillars_secfpn_sbn-all_fp16_2x8_2x_nus-3d.py │ │ ├── hv_second_secfpn_fp16_6x8_80e_kitti-3d-3class.py │ │ └── hv_second_secfpn_fp16_6x8_80e_kitti-3d-car.py │ ├── free_anchor/ │ │ ├── README.md │ │ ├── hv_pointpillars_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py │ │ ├── hv_pointpillars_regnet-1.6gf_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py │ │ ├── hv_pointpillars_regnet-1.6gf_fpn_sbn-all_free-anchor_strong-aug_4x8_3x_nus-3d.py │ │ ├── hv_pointpillars_regnet-3.2gf_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py │ │ ├── hv_pointpillars_regnet-3.2gf_fpn_sbn-all_free-anchor_strong-aug_4x8_3x_nus-3d.py │ │ └── hv_pointpillars_regnet-400mf_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py │ ├── h3dnet/ │ │ ├── README.md │ │ └── h3dnet_3x8_scannet-3d-18class.py │ ├── imvotenet/ │ │ ├── README.md │ │ ├── imvotenet_faster_rcnn_r50_fpn_2x4_sunrgbd-3d-10class.py │ │ └── imvotenet_stage2_16x8_sunrgbd-3d-10class.py │ ├── mvxnet/ │ │ ├── README.md │ │ └── dv_mvx-fpn_second_secfpn_adamw_2x8_80e_kitti-3d-3class.py │ ├── nuimages/ │ │ ├── README.md │ │ ├── cascade_mask_rcnn_r101_fpn_1x_nuim.py │ │ ├── cascade_mask_rcnn_r50_fpn_1x_nuim.py │ │ ├── cascade_mask_rcnn_r50_fpn_coco-20e_1x_nuim.py │ │ ├── cascade_mask_rcnn_r50_fpn_coco-20e_20e_nuim.py │ │ ├── cascade_mask_rcnn_x101_32x4d_fpn_1x_nuim.py │ │ ├── htc_r50_fpn_1x_nuim.py │ │ ├── htc_r50_fpn_coco-20e_1x_nuim.py │ │ ├── htc_r50_fpn_coco-20e_20e_nuim.py │ │ ├── htc_without_semantic_r50_fpn_1x_nuim.py │ │ ├── htc_x101_64x4d_fpn_dconv_c3-c5_coco-20e_16x1_20e_nuim.py │ │ ├── mask_rcnn_r101_fpn_1x_nuim.py │ │ ├── mask_rcnn_r50_caffe_fpn_1x_nuim.py │ │ ├── mask_rcnn_r50_caffe_fpn_coco-3x_1x_nuim.py │ │ ├── mask_rcnn_r50_caffe_fpn_coco-3x_20e_nuim.py │ │ ├── mask_rcnn_r50_fpn_1x_nuim.py │ │ ├── mask_rcnn_r50_fpn_coco-2x_1x_nuim.py │ │ ├── mask_rcnn_r50_fpn_coco-2x_1x_nus-2d.py │ │ ├── mask_rcnn_swinT_coco-2x_1x_nuim.py │ │ └── mask_rcnn_x101_32x4d_fpn_1x_nuim.py │ ├── nuscenes.md │ ├── parta2/ │ │ ├── README.md │ │ ├── hv_PartA2_secfpn_2x8_cyclic_80e_kitti-3d-3class.py │ │ └── hv_PartA2_secfpn_2x8_cyclic_80e_kitti-3d-car.py │ ├── pointpillars/ │ │ ├── README.md │ │ ├── hv_pointpillars_fpn_sbn-all_2x8_2x_lyft-3d.py │ │ ├── hv_pointpillars_fpn_sbn-all_4x8_2x_nus-3d.py │ │ ├── hv_pointpillars_fpn_sbn-all_range100_2x8_2x_lyft-3d.py │ │ ├── hv_pointpillars_secfpn_6x8_160e_kitti-3d-3class.py │ │ ├── hv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py │ │ ├── hv_pointpillars_secfpn_sbn-all_2x8_2x_lyft-3d.py │ │ ├── hv_pointpillars_secfpn_sbn-all_4x8_2x_nus-3d.py │ │ ├── hv_pointpillars_secfpn_sbn-all_range100_2x8_2x_lyft-3d.py │ │ ├── hv_pointpillars_secfpn_sbn_2x16_2x_waymo-3d-3class.py │ │ ├── hv_pointpillars_secfpn_sbn_2x16_2x_waymo-3d-car.py │ │ ├── hv_pointpillars_secfpn_sbn_2x16_2x_waymoD5-3d-3class.py │ │ └── hv_pointpillars_secfpn_sbn_2x16_2x_waymoD5-3d-car.py │ ├── regnet/ │ │ ├── README.md │ │ ├── hv_pointpillars_regnet-1.6gf_fpn_sbn-all_4x8_2x_nus-3d.py │ │ ├── hv_pointpillars_regnet-400mf_fpn_sbn-all_2x8_2x_lyft-3d.py │ │ ├── hv_pointpillars_regnet-400mf_fpn_sbn-all_4x8_2x_nus-3d.py │ │ ├── hv_pointpillars_regnet-400mf_fpn_sbn-all_range100_2x8_2x_lyft-3d.py │ │ ├── hv_pointpillars_regnet-400mf_secfpn_sbn-all_2x8_2x_lyft-3d.py │ │ ├── hv_pointpillars_regnet-400mf_secfpn_sbn-all_4x8_2x_nus-3d.py │ │ └── hv_pointpillars_regnet-400mf_secfpn_sbn-all_range100_2x8_2x_lyft-3d.py │ ├── second/ │ │ ├── README.md │ │ ├── hv_second_secfpn_6x8_80e_kitti-3d-3class.py │ │ ├── hv_second_secfpn_6x8_80e_kitti-3d-car.py │ │ └── hv_second_secfpn_sbn_2x16_2x_waymoD5-3d-3class.py │ ├── sparsefusion_nusc_voxel_LC_SwinT.py │ ├── sparsefusion_nusc_voxel_LC_r50.py │ ├── ssn/ │ │ ├── README.md │ │ ├── hv_ssn_regnet-400mf_secfpn_sbn-all_1x16_2x_lyft-3d.py │ │ ├── hv_ssn_regnet-400mf_secfpn_sbn-all_2x16_2x_nus-3d.py │ │ ├── hv_ssn_secfpn_sbn-all_2x16_2x_lyft-3d.py │ │ └── hv_ssn_secfpn_sbn-all_2x16_2x_nus-3d.py │ ├── transfusion_nusc_pillar_L.py │ ├── transfusion_nusc_pillar_LC.py │ ├── transfusion_nusc_voxel_L.py │ ├── transfusion_nusc_voxel_LC.py │ ├── transfusion_waymo_voxel_L.py │ ├── transfusion_waymo_voxel_LC.py │ ├── votenet/ │ │ ├── README.md │ │ ├── votenet_16x8_sunrgbd-3d-10class.py │ │ ├── votenet_8x8_scannet-3d-18class.py │ │ └── votenet_iouloss_8x8_scannet-3d-18class.py │ └── waymo.md ├── demo/ │ └── pcd_demo.py ├── docker/ │ └── Dockerfile ├── mmdet3d/ │ ├── __init__.py │ ├── apis/ │ │ ├── __init__.py │ │ ├── inference.py │ │ └── test.py │ ├── core/ │ │ ├── __init__.py │ │ ├── anchor/ │ │ │ ├── __init__.py │ │ │ └── anchor_3d_generator.py │ │ ├── bbox/ │ │ │ ├── __init__.py │ │ │ ├── assigners/ │ │ │ │ ├── __init__.py │ │ │ │ └── hungarian_assigner.py │ │ │ ├── box_np_ops.py │ │ │ ├── coders/ │ │ │ │ ├── __init__.py │ │ │ │ ├── anchor_free_bbox_coder.py │ │ │ │ ├── camera_bbox_coder.py │ │ │ │ ├── centerpoint_bbox_coders.py │ │ │ │ ├── delta_xyzwhlr_bbox_coder.py │ │ │ │ ├── partial_bin_based_bbox_coder.py │ │ │ │ └── transfusion_bbox_coder.py │ │ │ ├── iou_calculators/ │ │ │ │ ├── __init__.py │ │ │ │ └── iou3d_calculator.py │ │ │ ├── samplers/ │ │ │ │ ├── __init__.py │ │ │ │ └── iou_neg_piecewise_sampler.py │ │ │ ├── structures/ │ │ │ │ ├── __init__.py │ │ │ │ ├── base_box3d.py │ │ │ │ ├── box_3d_mode.py │ │ │ │ ├── cam_box3d.py │ │ │ │ ├── coord_3d_mode.py │ │ │ │ ├── depth_box3d.py │ │ │ │ ├── lidar_box3d.py │ │ │ │ └── utils.py │ │ │ └── transforms.py │ │ ├── evaluation/ │ │ │ ├── __init__.py │ │ │ ├── indoor_eval.py │ │ │ ├── kitti_utils/ │ │ │ │ ├── __init__.py │ │ │ │ ├── eval.py │ │ │ │ └── rotate_iou.py │ │ │ ├── lyft_eval.py │ │ │ ├── seg_eval.py │ │ │ └── waymo_utils/ │ │ │ └── prediction_kitti_to_waymo.py │ │ ├── points/ │ │ │ ├── __init__.py │ │ │ ├── base_points.py │ │ │ ├── cam_points.py │ │ │ ├── depth_points.py │ │ │ └── lidar_points.py │ │ ├── post_processing/ │ │ │ ├── __init__.py │ │ │ ├── box3d_nms.py │ │ │ └── merge_augs.py │ │ ├── utils/ │ │ │ ├── __init__.py │ │ │ └── gaussian.py │ │ ├── visualizer/ │ │ │ ├── __init__.py │ │ │ ├── open3d_vis.py │ │ │ └── show_result.py │ │ └── voxel/ │ │ ├── __init__.py │ │ ├── builder.py │ │ └── voxel_generator.py │ ├── datasets/ │ │ ├── __init__.py │ │ ├── builder.py │ │ ├── custom_3d.py │ │ ├── dataset_wrappers.py │ │ ├── kitti2d_dataset.py │ │ ├── kitti_dataset.py │ │ ├── lyft_dataset.py │ │ ├── nuscenes_dataset.py │ │ ├── nuscenes_dataset_viewInfo.py │ │ ├── pipelines/ │ │ │ ├── __init__.py │ │ │ ├── data_augment_utils.py │ │ │ ├── dbsampler.py │ │ │ ├── formating.py │ │ │ ├── loading.py │ │ │ ├── test_time_aug.py │ │ │ ├── transforms_2d.py │ │ │ └── transforms_3d.py │ │ ├── registry.py │ │ ├── scannet_dataset.py │ │ ├── semantickitti_dataset.py │ │ ├── sunrgbd_dataset.py │ │ └── waymo_dataset.py │ ├── models/ │ │ ├── __init__.py │ │ ├── backbones/ │ │ │ ├── DLA.py │ │ │ ├── __init__.py │ │ │ ├── base_pointnet.py │ │ │ ├── multi_backbone.py │ │ │ ├── nostem_regnet.py │ │ │ ├── pointnet2_sa_msg.py │ │ │ ├── pointnet2_sa_ssg.py │ │ │ ├── second.py │ │ │ └── swin.py │ │ ├── builder.py │ │ ├── dense_heads/ │ │ │ ├── __init__.py │ │ │ ├── anchor3d_head.py │ │ │ ├── base_conv_bbox_head.py │ │ │ ├── centerpoint_head.py │ │ │ ├── free_anchor3d_head.py │ │ │ ├── parta2_rpn_head.py │ │ │ ├── shape_aware_head.py │ │ │ ├── sparsefusion_head_deform.py │ │ │ ├── ssd_3d_head.py │ │ │ ├── train_mixins.py │ │ │ ├── transfusion_head.py │ │ │ └── vote_head.py │ │ ├── detectors/ │ │ │ ├── __init__.py │ │ │ ├── base.py │ │ │ ├── centerpoint.py │ │ │ ├── dynamic_voxelnet.py │ │ │ ├── h3dnet.py │ │ │ ├── imvotenet.py │ │ │ ├── mvx_faster_rcnn.py │ │ │ ├── mvx_two_stage.py │ │ │ ├── parta2.py │ │ │ ├── single_stage.py │ │ │ ├── sparsefusion.py │ │ │ ├── ssd3dnet.py │ │ │ ├── transfusion.py │ │ │ ├── two_stage.py │ │ │ ├── votenet.py │ │ │ └── voxelnet.py │ │ ├── fusion_layers/ │ │ │ ├── __init__.py │ │ │ ├── coord_transform.py │ │ │ ├── point_fusion.py │ │ │ └── vote_fusion.py │ │ ├── losses/ │ │ │ ├── __init__.py │ │ │ ├── axis_aligned_iou_loss.py │ │ │ ├── chamfer_distance.py │ │ │ └── uncertainty_loss.py │ │ ├── middle_encoders/ │ │ │ ├── __init__.py │ │ │ ├── pillar_scatter.py │ │ │ ├── sparse_encoder.py │ │ │ └── sparse_unet.py │ │ ├── model_utils/ │ │ │ ├── __init__.py │ │ │ └── vote_module.py │ │ ├── necks/ │ │ │ ├── __init__.py │ │ │ └── second_fpn.py │ │ ├── registry.py │ │ ├── roi_heads/ │ │ │ ├── __init__.py │ │ │ ├── base_3droi_head.py │ │ │ ├── bbox_heads/ │ │ │ │ ├── __init__.py │ │ │ │ ├── h3d_bbox_head.py │ │ │ │ └── parta2_bbox_head.py │ │ │ ├── h3d_roi_head.py │ │ │ ├── mask_heads/ │ │ │ │ ├── __init__.py │ │ │ │ ├── pointwise_semantic_head.py │ │ │ │ └── primitive_head.py │ │ │ ├── part_aggregation_roi_head.py │ │ │ └── roi_extractors/ │ │ │ ├── __init__.py │ │ │ └── single_roiaware_extractor.py │ │ ├── utils/ │ │ │ ├── __init__.py │ │ │ ├── clip_sigmoid.py │ │ │ ├── deformable_decoder.py │ │ │ ├── depth_encoder.py │ │ │ ├── drop.py │ │ │ ├── ffn.py │ │ │ ├── inverse_sigmoid.py │ │ │ ├── mlp.py │ │ │ ├── network_modules.py │ │ │ ├── ops/ │ │ │ │ ├── functions/ │ │ │ │ │ ├── __init__.py │ │ │ │ │ └── ms_deform_attn_func.py │ │ │ │ ├── make.sh │ │ │ │ ├── modules/ │ │ │ │ │ ├── __init__.py │ │ │ │ │ └── ms_deform_attn.py │ │ │ │ ├── setup.py │ │ │ │ ├── src/ │ │ │ │ │ ├── cpu/ │ │ │ │ │ │ ├── ms_deform_attn_cpu.cpp │ │ │ │ │ │ └── ms_deform_attn_cpu.h │ │ │ │ │ ├── cuda/ │ │ │ │ │ │ ├── ms_deform_attn_cuda.cu │ │ │ │ │ │ ├── ms_deform_attn_cuda.h │ │ │ │ │ │ └── ms_deform_im2col_cuda.cuh │ │ │ │ │ ├── ms_deform_attn.h │ │ │ │ │ └── vision.cpp │ │ │ │ └── test.py │ │ │ ├── projection.py │ │ │ ├── sparsefusion_models.py │ │ │ ├── transformer.py │ │ │ └── transformerdecoder.py │ │ └── voxel_encoders/ │ │ ├── __init__.py │ │ ├── pillar_encoder.py │ │ ├── utils.py │ │ └── voxel_encoder.py │ ├── ops/ │ │ ├── __init__.py │ │ ├── ball_query/ │ │ │ ├── __init__.py │ │ │ ├── ball_query.py │ │ │ └── src/ │ │ │ ├── ball_query.cpp │ │ │ └── ball_query_cuda.cu │ │ ├── furthest_point_sample/ │ │ │ ├── __init__.py │ │ │ ├── furthest_point_sample.py │ │ │ ├── points_sampler.py │ │ │ ├── src/ │ │ │ │ ├── furthest_point_sample.cpp │ │ │ │ └── furthest_point_sample_cuda.cu │ │ │ └── utils.py │ │ ├── gather_points/ │ │ │ ├── __init__.py │ │ │ ├── gather_points.py │ │ │ └── src/ │ │ │ ├── gather_points.cpp │ │ │ └── gather_points_cuda.cu │ │ ├── group_points/ │ │ │ ├── __init__.py │ │ │ ├── group_points.py │ │ │ └── src/ │ │ │ ├── group_points.cpp │ │ │ └── group_points_cuda.cu │ │ ├── interpolate/ │ │ │ ├── __init__.py │ │ │ ├── src/ │ │ │ │ ├── interpolate.cpp │ │ │ │ ├── three_interpolate_cuda.cu │ │ │ │ └── three_nn_cuda.cu │ │ │ ├── three_interpolate.py │ │ │ └── three_nn.py │ │ ├── iou3d/ │ │ │ ├── __init__.py │ │ │ ├── iou3d_utils.py │ │ │ └── src/ │ │ │ ├── iou3d.cpp │ │ │ └── iou3d_kernel.cu │ │ ├── knn/ │ │ │ ├── __init__.py │ │ │ ├── knn.py │ │ │ └── src/ │ │ │ ├── knn.cpp │ │ │ └── knn_cuda.cu │ │ ├── norm.py │ │ ├── pointnet_modules/ │ │ │ ├── __init__.py │ │ │ ├── builder.py │ │ │ ├── point_fp_module.py │ │ │ ├── point_sa_module.py │ │ │ └── registry.py │ │ ├── roiaware_pool3d/ │ │ │ ├── __init__.py │ │ │ ├── points_in_boxes.py │ │ │ ├── roiaware_pool3d.py │ │ │ └── src/ │ │ │ ├── points_in_boxes_cpu.cpp │ │ │ ├── points_in_boxes_cuda.cu │ │ │ ├── roiaware_pool3d.cpp │ │ │ └── roiaware_pool3d_kernel.cu │ │ ├── sparse_block.py │ │ ├── spconv/ │ │ │ ├── __init__.py │ │ │ ├── conv.py │ │ │ ├── functional.py │ │ │ ├── include/ │ │ │ │ ├── paramsgrid.h │ │ │ │ ├── prettyprint.h │ │ │ │ ├── pybind11_utils.h │ │ │ │ ├── spconv/ │ │ │ │ │ ├── fused_spconv_ops.h │ │ │ │ │ ├── geometry.h │ │ │ │ │ ├── indice.cu.h │ │ │ │ │ ├── indice.h │ │ │ │ │ ├── maxpool.h │ │ │ │ │ ├── mp_helper.h │ │ │ │ │ ├── point2voxel.h │ │ │ │ │ ├── pool_ops.h │ │ │ │ │ ├── reordering.cu.h │ │ │ │ │ ├── reordering.h │ │ │ │ │ └── spconv_ops.h │ │ │ │ ├── tensorview/ │ │ │ │ │ ├── helper_kernel.cu.h │ │ │ │ │ ├── helper_launch.h │ │ │ │ │ └── tensorview.h │ │ │ │ ├── torch_utils.h │ │ │ │ └── utility/ │ │ │ │ └── timer.h │ │ │ ├── modules.py │ │ │ ├── ops.py │ │ │ ├── overwrite_spconv/ │ │ │ │ └── write_spconv2.py │ │ │ ├── pool.py │ │ │ ├── src/ │ │ │ │ ├── all.cc │ │ │ │ ├── indice.cc │ │ │ │ ├── indice_cuda.cu │ │ │ │ ├── maxpool.cc │ │ │ │ ├── maxpool_cuda.cu │ │ │ │ ├── reordering.cc │ │ │ │ └── reordering_cuda.cu │ │ │ ├── structure.py │ │ │ └── test_utils.py │ │ └── voxel/ │ │ ├── __init__.py │ │ ├── scatter_points.py │ │ ├── src/ │ │ │ ├── scatter_points_cpu.cpp │ │ │ ├── scatter_points_cuda.cu │ │ │ ├── voxelization.cpp │ │ │ ├── voxelization.h │ │ │ ├── voxelization_cpu.cpp │ │ │ └── voxelization_cuda.cu │ │ └── voxelize.py │ ├── utils/ │ │ ├── __init__.py │ │ └── collect_env.py │ └── version.py ├── requirements/ │ ├── build.txt │ ├── docs.txt │ ├── optional.txt │ ├── readthedocs.txt │ ├── runtime.txt │ └── tests.txt ├── requirements.txt ├── setup.cfg ├── setup.py ├── tests/ │ ├── test_data/ │ │ ├── test_datasets/ │ │ │ ├── test_dataset_wrappers.py │ │ │ ├── test_kitti_dataset.py │ │ │ ├── test_lyft_dataset.py │ │ │ ├── test_nuscene_dataset.py │ │ │ ├── test_scannet_dataset.py │ │ │ ├── test_semantickitti_dataset.py │ │ │ └── test_sunrgbd_dataset.py │ │ └── test_pipelines/ │ │ ├── test_augmentations/ │ │ │ ├── test_data_augment_utils.py │ │ │ ├── test_test_augment_utils.py │ │ │ └── test_transforms_3d.py │ │ ├── test_indoor_pipeline.py │ │ ├── test_indoor_sample.py │ │ ├── test_loadings/ │ │ │ ├── test_load_points_from_multi_sweeps.py │ │ │ └── test_loading.py │ │ └── test_outdoor_pipeline.py │ ├── test_metrics/ │ │ ├── test_indoor_eval.py │ │ ├── test_kitti_eval.py │ │ ├── test_losses.py │ │ └── test_seg_eval.py │ ├── test_models/ │ │ ├── test_backbones.py │ │ ├── test_common_modules/ │ │ │ ├── test_middle_encoders.py │ │ │ ├── test_pointnet_modules.py │ │ │ ├── test_pointnet_ops.py │ │ │ ├── test_roiaware_pool3d.py │ │ │ ├── test_sparse_unet.py │ │ │ └── test_vote_module.py │ │ ├── test_detectors.py │ │ ├── test_forward.py │ │ ├── test_fusion/ │ │ │ ├── test_fusion_coord_trans.py │ │ │ ├── test_point_fusion.py │ │ │ └── test_vote_fusion.py │ │ ├── test_heads/ │ │ │ ├── test_heads.py │ │ │ ├── test_parta2_bbox_head.py │ │ │ ├── test_roi_extractors.py │ │ │ └── test_semantic_heads.py │ │ ├── test_necks/ │ │ │ ├── test_fpn.py │ │ │ └── test_necks.py │ │ └── test_voxel_encoder/ │ │ ├── test_dynamic_scatter.py │ │ ├── test_voxel_encoders.py │ │ ├── test_voxel_generator.py │ │ └── test_voxelize.py │ ├── test_runtime/ │ │ ├── test_apis.py │ │ └── test_config.py │ ├── test_samples/ │ │ └── parta2_roihead_inputs.npz │ └── test_utils/ │ ├── test_anchors.py │ ├── test_assigners.py │ ├── test_bbox_coders.py │ ├── test_box3d.py │ ├── test_box_np_ops.py │ ├── test_coord_3d_mode.py │ ├── test_merge_augs.py │ ├── test_nms.py │ ├── test_points.py │ ├── test_samplers.py │ └── test_utils.py ├── tools/ │ ├── analysis_tools/ │ │ ├── analyze_logs.py │ │ ├── benchmark.py │ │ └── get_flops.py │ ├── combine_view_info.py │ ├── create_data.py │ ├── create_data.sh │ ├── data_converter/ │ │ ├── __init__.py │ │ ├── create_gt_database.py │ │ ├── indoor_converter.py │ │ ├── kitti_converter.py │ │ ├── kitti_data_utils.py │ │ ├── lyft_converter.py │ │ ├── nuimage_converter.py │ │ ├── nuscenes_converter.py │ │ ├── scannet_data_utils.py │ │ ├── sunrgbd_data_utils.py │ │ └── waymo_converter.py │ ├── dist_test.sh │ ├── dist_train.sh │ ├── misc/ │ │ ├── fuse_conv_bn.py │ │ ├── print_config.py │ │ └── visualize_results.py │ ├── model_converters/ │ │ ├── convert_votenet_checkpoints.py │ │ ├── publish_model.py │ │ └── regnet2mmdet.py │ ├── slurm_test.sh │ ├── slurm_train.sh │ ├── test.py │ └── train.py └── train.sh
SYMBOL INDEX (1948 symbols across 277 files)
FILE: demo/pcd_demo.py
function main (line 6) | def main():
FILE: mmdet3d/__init__.py
function digit_version (line 7) | def digit_version(version_str):
FILE: mmdet3d/apis/inference.py
function convert_SyncBN (line 14) | def convert_SyncBN(config):
function init_detector (line 30) | def init_detector(config, checkpoint=None, device='cuda:0'):
function inference_detector (line 64) | def inference_detector(model, pcd):
function show_result_meshlab (line 109) | def show_result_meshlab(data, result, out_dir):
FILE: mmdet3d/apis/test.py
function single_gpu_test (line 5) | def single_gpu_test(model, data_loader, show=False, out_dir=None):
FILE: mmdet3d/core/anchor/anchor_3d_generator.py
class Anchor3DRangeGenerator (line 8) | class Anchor3DRangeGenerator(object):
method __init__ (line 32) | def __init__(self,
method __repr__ (line 60) | def __repr__(self):
method num_base_anchors (line 71) | def num_base_anchors(self):
method num_levels (line 78) | def num_levels(self):
method grid_anchors (line 82) | def grid_anchors(self, featmap_sizes, device='cuda'):
method single_level_grid_anchors (line 107) | def single_level_grid_anchors(self, featmap_size, scale, device='cuda'):
method anchors_single_range (line 147) | def anchors_single_range(self,
class AlignedAnchor3DRangeGenerator (line 213) | class AlignedAnchor3DRangeGenerator(Anchor3DRangeGenerator):
method __init__ (line 239) | def __init__(self, align_corner=False, **kwargs):
method anchors_single_range (line 243) | def anchors_single_range(self,
class AlignedAnchor3DRangeGeneratorPerCls (line 329) | class AlignedAnchor3DRangeGeneratorPerCls(AlignedAnchor3DRangeGenerator):
method __init__ (line 340) | def __init__(self, **kwargs):
method grid_anchors (line 345) | def grid_anchors(self, featmap_sizes, device='cuda'):
method multi_cls_grid_anchors (line 366) | def multi_cls_grid_anchors(self, featmap_sizes, scale, device='cuda'):
FILE: mmdet3d/core/bbox/assigners/hungarian_assigner.py
class BBox3DL1Cost (line 17) | class BBox3DL1Cost(object):
method __init__ (line 18) | def __init__(self, weight):
method __call__ (line 21) | def __call__(self, bboxes, gt_bboxes, train_cfg=None):
class BBoxBEVL1Cost (line 27) | class BBoxBEVL1Cost(object):
method __init__ (line 28) | def __init__(self, weight):
method __call__ (line 31) | def __call__(self, bboxes, gt_bboxes, train_cfg):
class IoU3DCost (line 42) | class IoU3DCost(object):
method __init__ (line 43) | def __init__(self, weight):
method __call__ (line 46) | def __call__(self, iou):
class HeuristicAssigner3D (line 52) | class HeuristicAssigner3D(BaseAssigner):
method __init__ (line 53) | def __init__(self,
method assign (line 60) | def assign(self, bboxes, gt_bboxes, gt_bboxes_ignore=None, gt_labels=N...
class HungarianAssigner3D (line 95) | class HungarianAssigner3D(BaseAssigner):
method __init__ (line 96) | def __init__(self,
method assign (line 107) | def assign(self, bboxes, gt_bboxes, gt_labels, cls_pred, train_cfg):
class HungarianAssignerView2D (line 161) | class HungarianAssignerView2D(HungarianAssigner):
method __init__ (line 162) | def __init__(self,
method assign (line 169) | def assign(self,
class HungarianAssignerViewProj2D (line 273) | class HungarianAssignerViewProj2D(HungarianAssigner):
method __init__ (line 274) | def __init__(self,
method assign (line 281) | def assign(self,
class ViewCost (line 398) | class ViewCost:
method __init__ (line 399) | def __init__(self, weight=1000):
method __call__ (line 402) | def __call__(self, view_pred, gt_views):
class HungarianAssignerCameraBox (line 409) | class HungarianAssignerCameraBox(BaseAssigner):
method __init__ (line 410) | def __init__(self,
method assign (line 422) | def assign(self, bboxes, gt_bboxes, gt_labels, cls_pred, view, train_c...
FILE: mmdet3d/core/bbox/box_np_ops.py
function camera_to_lidar (line 8) | def camera_to_lidar(points, r_rect, velo2cam):
function box_camera_to_lidar (line 28) | def box_camera_to_lidar(data, r_rect, velo2cam):
function corners_nd (line 48) | def corners_nd(dims, origin=0.5):
function rotation_2d (line 81) | def rotation_2d(points, angles):
function center_to_corner_box2d (line 98) | def center_to_corner_box2d(centers, dims, angles=None, origin=0.5):
function depth_to_points (line 122) | def depth_to_points(depth, trunc_pixel):
function depth_to_lidar_points (line 146) | def depth_to_lidar_points(depth, trunc_pixel, P2, r_rect, velo2cam):
function rotation_3d_in_axis (line 170) | def rotation_3d_in_axis(points, angles, axis=0):
function center_to_corner_box3d (line 201) | def center_to_corner_box3d(centers,
function box2d_to_corner_jit (line 231) | def box2d_to_corner_jit(boxes):
function corner_to_standup_nd_jit (line 262) | def corner_to_standup_nd_jit(boxes_corner):
function corner_to_surfaces_3d_jit (line 283) | def corner_to_surfaces_3d_jit(corners):
function rotation_points_single_angle (line 306) | def rotation_points_single_angle(points, angle, axis=0):
function points_cam2img (line 338) | def points_cam2img(points_3d, proj_mat, with_depth=False):
function box3d_to_bbox (line 374) | def box3d_to_bbox(box3d, P2):
function corner_to_surfaces_3d (line 394) | def corner_to_surfaces_3d(corners):
function points_in_rbbox (line 416) | def points_in_rbbox(points, rbbox, z_axis=2, origin=(0.5, 0.5, 0)):
function minmax_to_corner_2d (line 437) | def minmax_to_corner_2d(minmax_box):
function limit_period (line 452) | def limit_period(val, offset=0.5, period=np.pi):
function create_anchors_3d_range (line 468) | def create_anchors_3d_range(feature_size,
function center_to_minmax_2d (line 516) | def center_to_minmax_2d(centers, dims, origin=0.5):
function rbbox2d_to_near_bbox (line 534) | def rbbox2d_to_near_bbox(rbboxes):
function iou_jit (line 554) | def iou_jit(boxes, query_boxes, mode='iou', eps=0.0):
function projection_matrix_to_CRT_kitti (line 592) | def projection_matrix_to_CRT_kitti(proj):
function remove_outside_points (line 616) | def remove_outside_points(points, rect, Trv2c, P2, image_shape):
function get_frustum (line 644) | def get_frustum(bbox_image, C, near_clip=0.001, far_clip=100):
function surface_equ_3d (line 675) | def surface_equ_3d(polygon_surfaces):
function _points_in_convex_polygon_3d_jit (line 700) | def _points_in_convex_polygon_3d_jit(points, polygon_surfaces, normal_ve...
function points_in_convex_polygon_3d_jit (line 737) | def points_in_convex_polygon_3d_jit(points,
function points_in_convex_polygon_jit (line 767) | def points_in_convex_polygon_jit(points, polygon, clockwise=True):
function boxes3d_to_corners3d_lidar (line 811) | def boxes3d_to_corners3d_lidar(boxes3d, bottom_center=True):
FILE: mmdet3d/core/bbox/coders/anchor_free_bbox_coder.py
class AnchorFreeBBoxCoder (line 9) | class AnchorFreeBBoxCoder(PartialBinBasedBBoxCoder):
method __init__ (line 17) | def __init__(self, num_dir_bins, with_rot=True):
method encode (line 23) | def encode(self, gt_bboxes_3d, gt_labels_3d):
method decode (line 53) | def decode(self, bbox_out):
method split_pred (line 87) | def split_pred(self, cls_preds, reg_preds, base_xyz):
FILE: mmdet3d/core/bbox/coders/camera_bbox_coder.py
class CameraBBoxCoder (line 8) | class CameraBBoxCoder(BaseBBoxCoder):
method __init__ (line 9) | def __init__(self, code_size=8):
method encode (line 12) | def encode(self, dst_boxes):
method decode (line 28) | def decode(self, cls, rot, dim, center, vel):
method decode_yaw (line 78) | def decode_yaw(bbox, centers2d, cam2img):
FILE: mmdet3d/core/bbox/coders/centerpoint_bbox_coders.py
class CenterPointBBoxCoder (line 8) | class CenterPointBBoxCoder(BaseBBoxCoder):
method __init__ (line 23) | def __init__(self,
method _gather_feat (line 40) | def _gather_feat(self, feats, inds, feat_masks=None):
method _topk (line 61) | def _topk(self, scores, K=80):
method _transpose_and_gather_feat (line 96) | def _transpose_and_gather_feat(self, feat, ind):
method encode (line 112) | def encode(self):
method decode (line 115) | def decode(self,
FILE: mmdet3d/core/bbox/coders/delta_xyzwhlr_bbox_coder.py
class DeltaXYZWLHRBBoxCoder (line 8) | class DeltaXYZWLHRBBoxCoder(BaseBBoxCoder):
method __init__ (line 15) | def __init__(self, code_size=7):
method encode (line 20) | def encode(src_boxes, dst_boxes):
method decode (line 57) | def decode(anchors, deltas):
FILE: mmdet3d/core/bbox/coders/partial_bin_based_bbox_coder.py
class PartialBinBasedBBoxCoder (line 9) | class PartialBinBasedBBoxCoder(BaseBBoxCoder):
method __init__ (line 19) | def __init__(self, num_dir_bins, num_sizes, mean_sizes, with_rot=True):
method encode (line 27) | def encode(self, gt_bboxes_3d, gt_labels_3d):
method decode (line 58) | def decode(self, bbox_out, suffix=''):
method decode_corners (line 101) | def decode_corners(self, center, size_res, size_class):
method split_pred (line 139) | def split_pred(self, cls_preds, reg_preds, base_xyz):
method angle2class (line 203) | def angle2class(self, angle):
method class2angle (line 224) | def class2angle(self, angle_cls, angle_res, limit_period=True):
FILE: mmdet3d/core/bbox/coders/transfusion_bbox_coder.py
class TransFusionBBoxCoder (line 8) | class TransFusionBBoxCoder(BaseBBoxCoder):
method __init__ (line 9) | def __init__(self,
method encode (line 24) | def encode(self, dst_boxes):
method decode (line 39) | def decode(self, heatmap, rot, dim, center, height, vel, filter=False):
FILE: mmdet3d/core/bbox/iou_calculators/iou3d_calculator.py
class BboxOverlapsNearest3D (line 9) | class BboxOverlapsNearest3D(object):
method __init__ (line 20) | def __init__(self, coordinate='lidar'):
method __call__ (line 24) | def __call__(self, bboxes1, bboxes2, mode='iou', is_aligned=False):
method __repr__ (line 47) | def __repr__(self):
class BboxOverlaps3D (line 55) | class BboxOverlaps3D(object):
method __init__ (line 63) | def __init__(self, coordinate):
method __call__ (line 67) | def __call__(self, bboxes1, bboxes2, mode='iou'):
method __repr__ (line 87) | def __repr__(self):
function bbox_overlaps_nearest_3d (line 94) | def bbox_overlaps_nearest_3d(bboxes1,
function bbox_overlaps_3d (line 141) | def bbox_overlaps_3d(bboxes1, bboxes2, mode='iou', coordinate='camera'):
class AxisAlignedBboxOverlaps3D (line 171) | class AxisAlignedBboxOverlaps3D(object):
method __call__ (line 174) | def __call__(self, bboxes1, bboxes2, mode='iou', is_aligned=False):
method __repr__ (line 195) | def __repr__(self):
function axis_aligned_bbox_overlaps_3d (line 201) | def axis_aligned_bbox_overlaps_3d(bboxes1,
FILE: mmdet3d/core/bbox/samplers/iou_neg_piecewise_sampler.py
class IoUNegPiecewiseSampler (line 8) | class IoUNegPiecewiseSampler(RandomSampler):
method __init__ (line 28) | def __init__(self,
method _sample_pos (line 46) | def _sample_pos(self, assign_result, num_expected, **kwargs):
method _sample_neg (line 56) | def _sample_neg(self, assign_result, num_expected, **kwargs):
method sample (line 98) | def sample(self,
FILE: mmdet3d/core/bbox/structures/base_box3d.py
class BaseInstance3DBoxes (line 9) | class BaseInstance3DBoxes(object):
method __init__ (line 36) | def __init__(self, tensor, box_dim=7, with_yaw=True, origin=(0.5, 0.5,...
method volume (line 68) | def volume(self):
method dims (line 73) | def dims(self):
method yaw (line 78) | def yaw(self):
method height (line 83) | def height(self):
method top_height (line 88) | def top_height(self):
method bottom_height (line 93) | def bottom_height(self):
method center (line 98) | def center(self):
method bottom_center (line 117) | def bottom_center(self):
method gravity_center (line 122) | def gravity_center(self):
method corners (line 127) | def corners(self):
method rotate (line 132) | def rotate(self, angles, axis=0):
method flip (line 142) | def flip(self, bev_direction='horizontal'):
method translate (line 146) | def translate(self, trans_vector):
method in_range_3d (line 156) | def in_range_3d(self, box_range):
method in_range_bev (line 181) | def in_range_bev(self, box_range):
method convert_to (line 195) | def convert_to(self, dst, rt_mat=None):
method scale (line 212) | def scale(self, scale_factor):
method limit_yaw (line 221) | def limit_yaw(self, offset=0.5, period=np.pi):
method nonempty (line 230) | def nonempty(self, threshold: float = 0.0):
method __getitem__ (line 251) | def __getitem__(self, item):
method __len__ (line 280) | def __len__(self):
method __repr__ (line 284) | def __repr__(self):
method cat (line 289) | def cat(cls, boxes_list):
method to (line 311) | def to(self, device):
method clone (line 327) | def clone(self):
method device (line 339) | def device(self):
method __iter__ (line 343) | def __iter__(self):
method height_overlaps (line 352) | def height_overlaps(cls, boxes1, boxes2, mode='iou'):
method overlaps (line 384) | def overlaps(cls, boxes1, boxes2, mode='iou'):
method new_box (line 440) | def new_box(self, data):
FILE: mmdet3d/core/bbox/structures/box_3d_mode.py
class Box3DMode (line 12) | class Box3DMode(IntEnum):
method convert (line 63) | def convert(box, src, dst, rt_mat=None):
FILE: mmdet3d/core/bbox/structures/cam_box3d.py
class CameraInstance3DBoxes (line 9) | class CameraInstance3DBoxes(BaseInstance3DBoxes):
method __init__ (line 38) | def __init__(self,
method height (line 74) | def height(self):
method top_height (line 79) | def top_height(self):
method bottom_height (line 85) | def bottom_height(self):
method gravity_center (line 90) | def gravity_center(self):
method corners (line 99) | def corners(self):
method bev (line 142) | def bev(self):
method nearest_bev (line 148) | def nearest_bev(self):
method rotate (line 168) | def rotate(self, angle, points=None):
method flip (line 204) | def flip(self, bev_direction='horizontal', points=None):
method in_range_bev (line 238) | def in_range_bev(self, box_range):
method height_overlaps (line 261) | def height_overlaps(cls, boxes1, boxes2, mode='iou'):
method convert_to (line 291) | def convert_to(self, dst, rt_mat=None):
FILE: mmdet3d/core/bbox/structures/coord_3d_mode.py
class Coord3DMode (line 14) | class Coord3DMode(IntEnum):
method convert (line 66) | def convert(input, src, dst, rt_mat=None):
method convert_box (line 76) | def convert_box(box, src, dst, rt_mat=None):
method convert_point (line 181) | def convert_point(point, src, dst, rt_mat=None):
FILE: mmdet3d/core/bbox/structures/depth_box3d.py
class DepthInstance3DBoxes (line 10) | class DepthInstance3DBoxes(BaseInstance3DBoxes):
method gravity_center (line 37) | def gravity_center(self):
method corners (line 46) | def corners(self):
method bev (line 87) | def bev(self):
method nearest_bev (line 93) | def nearest_bev(self):
method rotate (line 113) | def rotate(self, angle, points=None):
method flip (line 159) | def flip(self, bev_direction='horizontal', points=None):
method in_range_bev (line 193) | def in_range_bev(self, box_range):
method convert_to (line 215) | def convert_to(self, dst, rt_mat=None):
method points_in_boxes (line 234) | def points_in_boxes(self, points):
method enlarged_box (line 262) | def enlarged_box(self, extra_width):
method get_surface_line_center (line 277) | def get_surface_line_center(self):
FILE: mmdet3d/core/bbox/structures/lidar_box3d.py
class LiDARInstance3DBoxes (line 10) | class LiDARInstance3DBoxes(BaseInstance3DBoxes):
method gravity_center (line 37) | def gravity_center(self):
method corners (line 46) | def corners(self):
method bev (line 87) | def bev(self):
method nearest_bev (line 93) | def nearest_bev(self):
method rotate (line 113) | def rotate(self, angle, points=None):
method flip (line 153) | def flip(self, bev_direction='horizontal', points=None):
method in_range_bev (line 187) | def in_range_bev(self, box_range):
method convert_to (line 208) | def convert_to(self, dst, rt_mat=None):
method enlarged_box (line 227) | def enlarged_box(self, extra_width):
method points_in_boxes (line 242) | def points_in_boxes(self, points):
FILE: mmdet3d/core/bbox/structures/utils.py
function limit_period (line 5) | def limit_period(val, offset=0.5, period=np.pi):
function rotation_3d_in_axis (line 21) | def rotation_3d_in_axis(points, angles, axis=0):
function xywhr2xyxyr (line 64) | def xywhr2xyxyr(boxes_xywhr):
function get_box_type (line 85) | def get_box_type(box_type):
function points_cam2img (line 114) | def points_cam2img(points_3d, proj_mat):
FILE: mmdet3d/core/bbox/transforms.py
function bbox3d_mapping_back (line 4) | def bbox3d_mapping_back(bboxes, scale_factor, flip_horizontal, flip_vert...
function bbox3d2roi (line 26) | def bbox3d2roi(bbox_list):
function bbox3d2result (line 49) | def bbox3d2result(bboxes, scores, labels):
FILE: mmdet3d/core/evaluation/indoor_eval.py
function average_precision (line 7) | def average_precision(recalls, precisions, mode='area'):
function eval_det_cls (line 55) | def eval_det_cls(pred, gt, iou_thr=None):
function eval_map_recall (line 163) | def eval_map_recall(pred, gt, ovthresh=None):
function indoor_eval (line 203) | def indoor_eval(gt_annos,
FILE: mmdet3d/core/evaluation/kitti_utils/eval.py
function get_thresholds (line 8) | def get_thresholds(scores: np.ndarray, num_gt, num_sample_pts=41):
function clean_data (line 28) | def clean_data(gt_anno, dt_anno, current_class, difficulty):
function image_box_overlap (line 84) | def image_box_overlap(boxes, query_boxes, criterion=-1):
function bev_box_overlap (line 115) | def bev_box_overlap(boxes, qboxes, criterion=-1):
function d3_box_overlap_kernel (line 122) | def d3_box_overlap_kernel(boxes, qboxes, rinc, criterion=-1):
function d3_box_overlap (line 153) | def d3_box_overlap(boxes, qboxes, criterion=-1):
function compute_statistics_jit (line 162) | def compute_statistics_jit(overlaps,
function get_split_parts (line 282) | def get_split_parts(num, num_part):
function fused_compute_statistics (line 292) | def fused_compute_statistics(overlaps,
function calculate_iou_partly (line 341) | def calculate_iou_partly(gt_annos, dt_annos, metric, num_parts=50):
function _prepare_data (line 419) | def _prepare_data(gt_annos, dt_annos, current_class, difficulty):
function eval_class (line 450) | def eval_class(gt_annos,
function get_mAP (line 571) | def get_mAP(prec):
function print_str (line 578) | def print_str(value, *arg, sstream=None):
function do_eval (line 587) | def do_eval(gt_annos,
function do_coco_style_eval (line 624) | def do_coco_style_eval(gt_annos, dt_annos, current_classes, overlap_ranges,
function kitti_eval (line 643) | def kitti_eval(gt_annos,
function kitti_eval_coco_style (line 776) | def kitti_eval_coco_style(gt_annos, dt_annos, current_classes):
FILE: mmdet3d/core/evaluation/kitti_utils/rotate_iou.py
function div_up (line 13) | def div_up(m, n):
function trangle_area (line 18) | def trangle_area(a, b, c):
function area (line 24) | def area(int_pts, num_of_inter):
function sort_vertex_in_convex_polygon (line 34) | def sort_vertex_in_convex_polygon(int_pts, num_of_inter):
function line_segment_intersection (line 77) | def line_segment_intersection(pts1, pts2, i, j, temp_pts):
function line_segment_intersection_v1 (line 123) | def line_segment_intersection_v1(pts1, pts2, i, j, temp_pts):
function point_in_quadrilateral (line 162) | def point_in_quadrilateral(pt_x, pt_y, corners):
function quadrilateral_intersection (line 181) | def quadrilateral_intersection(pts1, pts2, int_pts):
function rbbox_to_corners (line 205) | def rbbox_to_corners(corners, rbbox):
function inter (line 231) | def inter(rbbox1, rbbox2):
function devRotateIoUEval (line 257) | def devRotateIoUEval(rbox1, rbox2, criterion=-1):
function rotate_iou_kernel_eval (line 287) | def rotate_iou_kernel_eval(N,
function rotate_iou_gpu_eval (line 340) | def rotate_iou_gpu_eval(boxes, query_boxes, criterion=-1, device_id=0):
FILE: mmdet3d/core/evaluation/lyft_eval.py
function load_lyft_gts (line 13) | def load_lyft_gts(lyft, data_root, eval_split, logger=None):
function load_lyft_predictions (line 72) | def load_lyft_predictions(res_path):
function lyft_eval (line 89) | def lyft_eval(lyft, data_root, res_path, eval_set, output_dir, logger=No...
function get_classwise_aps (line 141) | def get_classwise_aps(gt, predictions, class_names, iou_thresholds):
function get_single_class_aps (line 198) | def get_single_class_aps(gt, predictions, iou_thresholds):
FILE: mmdet3d/core/evaluation/seg_eval.py
function fast_hist (line 6) | def fast_hist(preds, labels, num_classes):
function per_class_iou (line 27) | def per_class_iou(hist):
function get_acc (line 41) | def get_acc(hist):
function get_acc_cls (line 55) | def get_acc_cls(hist):
function seg_eval (line 69) | def seg_eval(gt_labels, seg_preds, label2cat, logger=None):
FILE: mmdet3d/core/evaluation/waymo_utils/prediction_kitti_to_waymo.py
class KITTI2Waymo (line 21) | class KITTI2Waymo(object):
method __init__ (line 39) | def __init__(self,
method get_file_names (line 77) | def get_file_names(self):
method create_folder (line 83) | def create_folder(self):
method parse_objects (line 87) | def parse_objects(self, kitti_result, T_k2w, context_name,
method convert_one (line 169) | def convert_one(self, file_idx):
method convert (line 209) | def convert(self):
method __len__ (line 223) | def __len__(self):
method transform (line 227) | def transform(self, T, x, y, z):
method combine (line 243) | def combine(self, pathnames):
FILE: mmdet3d/core/points/__init__.py
function get_points_type (line 9) | def get_points_type(points_type):
FILE: mmdet3d/core/points/base_points.py
class BasePoints (line 6) | class BasePoints(object):
method __init__ (line 25) | def __init__(self, tensor, points_dim=3, attribute_dims=None):
method coord (line 45) | def coord(self):
method height (line 50) | def height(self):
method color (line 59) | def color(self):
method shape (line 68) | def shape(self):
method shuffle (line 72) | def shuffle(self):
method rotate (line 77) | def rotate(self, rotation, axis=None):
method flip (line 118) | def flip(self, bev_direction='horizontal'):
method translate (line 122) | def translate(self, trans_vector):
method in_range_3d (line 143) | def in_range_3d(self, point_range):
method in_range_bev (line 168) | def in_range_bev(self, point_range):
method convert_to (line 182) | def convert_to(self, dst, rt_mat=None):
method scale (line 199) | def scale(self, scale_factor):
method __getitem__ (line 207) | def __getitem__(self, item):
method __len__ (line 273) | def __len__(self):
method __repr__ (line 277) | def __repr__(self):
method cat (line 282) | def cat(cls, points_list):
method to (line 304) | def to(self, device):
method clone (line 320) | def clone(self):
method device (line 334) | def device(self):
method __iter__ (line 338) | def __iter__(self):
method new_point (line 346) | def new_point(self, data):
FILE: mmdet3d/core/points/cam_points.py
class CameraPoints (line 4) | class CameraPoints(BasePoints):
method __init__ (line 23) | def __init__(self, tensor, points_dim=3, attribute_dims=None):
method flip (line 28) | def flip(self, bev_direction='horizontal'):
method in_range_bev (line 35) | def in_range_bev(self, point_range):
method convert_to (line 52) | def convert_to(self, dst, rt_mat=None):
FILE: mmdet3d/core/points/depth_points.py
class DepthPoints (line 4) | class DepthPoints(BasePoints):
method __init__ (line 23) | def __init__(self, tensor, points_dim=3, attribute_dims=None):
method flip (line 28) | def flip(self, bev_direction='horizontal'):
method in_range_bev (line 35) | def in_range_bev(self, point_range):
method convert_to (line 52) | def convert_to(self, dst, rt_mat=None):
FILE: mmdet3d/core/points/lidar_points.py
class LiDARPoints (line 4) | class LiDARPoints(BasePoints):
method __init__ (line 23) | def __init__(self, tensor, points_dim=3, attribute_dims=None):
method flip (line 28) | def flip(self, bev_direction='horizontal'):
method in_range_bev (line 35) | def in_range_bev(self, point_range):
method convert_to (line 52) | def convert_to(self, dst, rt_mat=None):
FILE: mmdet3d/core/post_processing/box3d_nms.py
function box3d_multiclass_nms (line 8) | def box3d_multiclass_nms(mlvl_bboxes,
function aligned_3d_nms (line 91) | def aligned_3d_nms(boxes, scores, classes, thresh):
function circle_nms (line 142) | def circle_nms(dets, thresh, socre_thre=0, post_max_size=83):
FILE: mmdet3d/core/post_processing/merge_augs.py
function merge_aug_bboxes_3d (line 7) | def merge_aug_bboxes_3d(aug_results, img_metas, test_cfg):
FILE: mmdet3d/core/utils/gaussian.py
function gaussian_2d (line 5) | def gaussian_2d(shape, sigma=1):
function draw_heatmap_gaussian (line 25) | def draw_heatmap_gaussian(heatmap, center, radius, k=1):
function gaussian_radius (line 57) | def gaussian_radius(det_size, min_overlap=0.5):
FILE: mmdet3d/core/visualizer/open3d_vis.py
function _draw_points (line 14) | def _draw_points(points,
function _draw_bboxes (line 56) | def _draw_bboxes(bbox3d,
function show_pts_boxes (line 119) | def show_pts_boxes(points,
function _draw_bboxes_ind (line 181) | def _draw_bboxes_ind(bbox3d,
function show_pts_index_boxes (line 251) | def show_pts_index_boxes(points,
function project_pts_on_img (line 317) | def project_pts_on_img(points,
function project_bbox3d_on_img (line 368) | def project_bbox3d_on_img(bboxes3d,
class Visualizer (line 410) | class Visualizer(object):
method __init__ (line 437) | def __init__(self,
method add_bboxes (line 477) | def add_bboxes(self, bbox3d, bbox_color=None, points_in_box_color=None):
method show (line 497) | def show(self, save_path=None):
FILE: mmdet3d/core/visualizer/show_result.py
function _write_ply (line 7) | def _write_ply(points, out_filename):
function _write_oriented_bbox (line 29) | def _write_oriented_bbox(scene_bbox, out_filename):
function show_result (line 71) | def show_result(points, gt_bboxes, pred_bboxes, out_dir, filename, show=...
FILE: mmdet3d/core/voxel/builder.py
function build_voxel_generator (line 6) | def build_voxel_generator(cfg, **kwargs):
FILE: mmdet3d/core/voxel/voxel_generator.py
class VoxelGenerator (line 5) | class VoxelGenerator(object):
method __init__ (line 16) | def __init__(self,
method generate (line 35) | def generate(self, points):
method voxel_size (line 42) | def voxel_size(self):
method max_num_points_per_voxel (line 47) | def max_num_points_per_voxel(self):
method point_cloud_range (line 52) | def point_cloud_range(self):
method grid_size (line 57) | def grid_size(self):
method __repr__ (line 61) | def __repr__(self):
function points_to_voxel (line 75) | def points_to_voxel(points,
function _points_to_voxel_reverse_kernel (line 137) | def _points_to_voxel_reverse_kernel(points,
function _points_to_voxel_kernel (line 211) | def _points_to_voxel_kernel(points,
FILE: mmdet3d/datasets/builder.py
function build_dataset (line 16) | def build_dataset(cfg, default_args=None):
FILE: mmdet3d/datasets/custom_3d.py
class Custom3DDataset (line 13) | class Custom3DDataset(Dataset):
method __init__ (line 42) | def __init__(self,
method load_annotations (line 70) | def load_annotations(self, ann_file):
method get_data_info (line 81) | def get_data_info(self, index):
method pre_pipeline (line 112) | def pre_pipeline(self, results):
method prepare_train_data (line 138) | def prepare_train_data(self, index):
method prepare_test_data (line 158) | def prepare_test_data(self, index):
method get_classes (line 173) | def get_classes(cls, classes=None):
method format_results (line 199) | def format_results(self,
method evaluate (line 223) | def evaluate(self,
method __len__ (line 269) | def __len__(self):
method _rand_another (line 277) | def _rand_another(self, idx):
method __getitem__ (line 286) | def __getitem__(self, idx):
method _set_group_flag (line 301) | def _set_group_flag(self):
FILE: mmdet3d/datasets/dataset_wrappers.py
class CBGSDataset (line 7) | class CBGSDataset(object):
method __init__ (line 18) | def __init__(self, dataset):
method _get_sample_indices (line 29) | def _get_sample_indices(self):
method __getitem__ (line 60) | def __getitem__(self, idx):
method __len__ (line 69) | def __len__(self):
FILE: mmdet3d/datasets/kitti2d_dataset.py
class Kitti2DDataset (line 8) | class Kitti2DDataset(CustomDataset):
method load_annotations (line 79) | def load_annotations(self, ann_file):
method _filter_imgs (line 95) | def _filter_imgs(self, min_size=32):
method get_ann_info (line 103) | def get_ann_info(self, index):
method prepare_train_img (line 135) | def prepare_train_img(self, idx):
method prepare_test_img (line 156) | def prepare_test_img(self, idx):
method drop_arrays_by_name (line 174) | def drop_arrays_by_name(self, gt_names, used_classes):
method keep_arrays_by_name (line 188) | def keep_arrays_by_name(self, gt_names, used_classes):
method reformat_bbox (line 202) | def reformat_bbox(self, outputs, out=None):
method evaluate (line 219) | def evaluate(self, result_files, eval_types=None):
FILE: mmdet3d/datasets/kitti_dataset.py
class KittiDataset (line 18) | class KittiDataset(Custom3DDataset):
method __init__ (line 53) | def __init__(self,
method _get_pts_filename (line 81) | def _get_pts_filename(self, idx):
method get_data_info (line 94) | def get_data_info(self, index):
method get_ann_info (line 137) | def get_ann_info(self, index):
method drop_arrays_by_name (line 194) | def drop_arrays_by_name(self, gt_names, used_classes):
method keep_arrays_by_name (line 208) | def keep_arrays_by_name(self, gt_names, used_classes):
method remove_dontcare (line 222) | def remove_dontcare(self, ann_info):
method format_results (line 241) | def format_results(self,
method evaluate (line 296) | def evaluate(self,
method bbox2result_kitti (line 360) | def bbox2result_kitti(self,
method bbox2result_kitti2d (line 475) | def bbox2result_kitti2d(self,
method convert_valid_bboxes (line 587) | def convert_valid_bboxes(self, box_dict, info):
method show (line 673) | def show(self, results, out_dir, show=True):
FILE: mmdet3d/datasets/lyft_dataset.py
class LyftDataset (line 18) | class LyftDataset(Custom3DDataset):
method __init__ (line 76) | def __init__(self,
method load_annotations (line 106) | def load_annotations(self, ann_file):
method get_data_info (line 122) | def get_data_info(self, index):
method get_ann_info (line 181) | def get_ann_info(self, index):
method _format_bbox (line 223) | def _format_bbox(self, results, jsonfile_prefix=None):
method _evaluate_single (line 266) | def _evaluate_single(self,
method format_results (line 307) | def format_results(self, results, jsonfile_prefix=None, csv_savepath=N...
method evaluate (line 351) | def evaluate(self,
method show (line 401) | def show(self, results, out_dir):
method json2csv (line 426) | def json2csv(self, json_path, csv_savepath):
function output_to_lyft_box (line 463) | def output_to_lyft_box(detection):
function lidar_lyft_box_to_global (line 496) | def lidar_lyft_box_to_global(info, boxes):
FILE: mmdet3d/datasets/nuscenes_dataset.py
class NuScenesDataset (line 15) | class NuScenesDataset(Custom3DDataset):
method __init__ (line 104) | def __init__(self,
method get_cat_ids (line 145) | def get_cat_ids(self, idx):
method load_annotations (line 169) | def load_annotations(self, ann_file):
method get_data_info (line 185) | def get_data_info(self, index):
method get_ann_info (line 256) | def get_ann_info(self, index):
method _format_bbox (line 305) | def _format_bbox(self, results, jsonfile_prefix=None):
method _evaluate_single (line 374) | def _evaluate_single(self,
method format_results (line 427) | def format_results(self, results, jsonfile_prefix=None):
method evaluate (line 465) | def evaluate(self,
method show (line 509) | def show(self, results, out_dir):
function output_to_nusc_box (line 535) | def output_to_nusc_box(detection):
function lidar_nusc_box_to_global (line 578) | def lidar_nusc_box_to_global(info,
FILE: mmdet3d/datasets/nuscenes_dataset_viewInfo.py
class NuScenesDataset_ViewInfo (line 15) | class NuScenesDataset_ViewInfo(NuScenesDataset):
method get_ann_info (line 20) | def get_ann_info(self, index):
method get_data_info (line 132) | def get_data_info(self, index):
FILE: mmdet3d/datasets/pipelines/data_augment_utils.py
function _rotation_box2d_jit_ (line 12) | def _rotation_box2d_jit_(corners, angle, rot_mat_T):
function box_collision_test (line 30) | def box_collision_test(boxes, qboxes, clockwise=True):
function noise_per_box (line 127) | def noise_per_box(boxes, valid_mask, loc_noises, rot_noises):
function noise_per_box_v2_ (line 168) | def noise_per_box_v2_(boxes, valid_mask, loc_noises, rot_noises,
function _select_transform (line 234) | def _select_transform(transform, indices):
function _rotation_matrix_3d_ (line 253) | def _rotation_matrix_3d_(rot_mat_T, angle, axis):
function points_transform_ (line 282) | def points_transform_(points, centers, point_masks, loc_transform,
function box3d_transform_ (line 312) | def box3d_transform_(boxes, loc_transform, rot_transform, valid_mask):
function noise_per_object_v3_ (line 328) | def noise_per_object_v3_(gt_boxes,
FILE: mmdet3d/datasets/pipelines/dbsampler.py
class BatchSampler (line 12) | class BatchSampler:
method __init__ (line 23) | def __init__(self,
method _sample (line 41) | def _sample(self, num):
method _reset (line 58) | def _reset(self):
method sample (line 66) | def sample(self, num):
class DataBaseSampler (line 80) | class DataBaseSampler(object):
method __init__ (line 94) | def __init__(self,
method filter_by_difficulty (line 150) | def filter_by_difficulty(db_infos, removed_difficulty):
method filter_by_min_points (line 169) | def filter_by_min_points(db_infos, min_gt_points_dict):
method sample_all (line 190) | def sample_all(self, gt_bboxes, gt_labels, img=None):
method sample_class_v2 (line 279) | def sample_class_v2(self, name, num, gt_bboxes):
FILE: mmdet3d/datasets/pipelines/formating.py
class DefaultFormatBundle (line 13) | class DefaultFormatBundle(object):
method __init__ (line 30) | def __init__(self, ):
method __call__ (line 33) | def __call__(self, results):
method __repr__ (line 95) | def __repr__(self):
class Collect3D (line 100) | class Collect3D(object):
method __init__ (line 150) | def __init__(self,
method __call__ (line 163) | def __call__(self, results):
method __repr__ (line 186) | def __repr__(self):
class DefaultFormatBundle3D (line 193) | class DefaultFormatBundle3D(DefaultFormatBundle):
method __init__ (line 208) | def __init__(self, class_names, with_gt=True, with_label=True):
method __call__ (line 214) | def __call__(self, results):
method __repr__ (line 274) | def __repr__(self):
FILE: mmdet3d/datasets/pipelines/loading.py
class MyResize (line 13) | class MyResize(object):
method __init__ (line 53) | def __init__(self,
method random_select (line 86) | def random_select(img_scales):
method random_sample (line 104) | def random_sample(img_scales):
method random_sample_ratio (line 131) | def random_sample_ratio(img_scale, ratio_range):
method _random_scale (line 157) | def _random_scale(self, results):
method _resize_img (line 190) | def _resize_img(self, results):
method _resize_bboxes (line 227) | def _resize_bboxes(self, results):
method _resize_centers (line 237) | def _resize_centers(self, results):
method _resize_masks (line 245) | def _resize_masks(self, results):
method _resize_seg (line 255) | def _resize_seg(self, results):
method _resize_camera (line 272) | def _resize_camera(self, results):
method __call__ (line 284) | def __call__(self, results):
method __repr__ (line 327) | def __repr__(self):
class MyNormalize (line 338) | class MyNormalize(object):
method __init__ (line 350) | def __init__(self, mean, std, to_rgb=True):
method __call__ (line 355) | def __call__(self, results):
method __repr__ (line 373) | def __repr__(self):
class MyPad (line 380) | class MyPad(object):
method __init__ (line 393) | def __init__(self, size=None, size_divisor=None, pad_val=0):
method _pad_img (line 401) | def _pad_img(self, results):
method _pad_masks (line 416) | def _pad_masks(self, results):
method _pad_seg (line 422) | def _pad_seg(self, results):
method __call__ (line 429) | def __call__(self, results):
method __repr__ (line 443) | def __repr__(self):
class LoadMultiViewImageFromFiles (line 452) | class LoadMultiViewImageFromFiles(object):
method __init__ (line 463) | def __init__(self, to_float32=False, img_scale=None, color_type='uncha...
method pad (line 468) | def pad(self, img):
method __call__ (line 474) | def __call__(self, results):
method __repr__ (line 518) | def __repr__(self):
class LoadPointsFromMultiSweeps (line 525) | class LoadPointsFromMultiSweeps(object):
method __init__ (line 546) | def __init__(self,
method _load_points (line 563) | def _load_points(self, pts_filename):
method _remove_close (line 585) | def _remove_close(self, points, radius=1.0):
method __call__ (line 607) | def __call__(self, results):
method __repr__ (line 657) | def __repr__(self):
class PointSegClassMapping (line 663) | class PointSegClassMapping(object):
method __init__ (line 673) | def __init__(self, valid_cat_ids):
method __call__ (line 676) | def __call__(self, results):
method __repr__ (line 702) | def __repr__(self):
class NormalizePointsColor (line 710) | class NormalizePointsColor(object):
method __init__ (line 717) | def __init__(self, color_mean):
method __call__ (line 720) | def __call__(self, results):
method __repr__ (line 739) | def __repr__(self):
class LoadPointsFromFile (line 747) | class LoadPointsFromFile(object):
method __init__ (line 769) | def __init__(self,
method _load_points (line 788) | def _load_points(self, pts_filename):
method __call__ (line 811) | def __call__(self, results):
method __repr__ (line 842) | def __repr__(self):
class LoadAnnotations3D (line 853) | class LoadAnnotations3D(LoadAnnotations):
method __init__ (line 885) | def __init__(self,
method _load_bboxes_3d (line 910) | def _load_bboxes_3d(self, results):
method _load_labels_3d (line 923) | def _load_labels_3d(self, results):
method _load_masks_3d (line 935) | def _load_masks_3d(self, results):
method _load_semantic_seg_3d (line 960) | def _load_semantic_seg_3d(self, results):
method __call__ (line 987) | def __call__(self, results):
method __repr__ (line 1011) | def __repr__(self):
class MyLoadAnnotations3D (line 1028) | class MyLoadAnnotations3D(LoadAnnotations3D):
method __init__ (line 1029) | def __init__(self, with_bbox_3d=True, with_label_3d=True, with_mask_3d...
method __call__ (line 1048) | def __call__(self, results):
method _load_centers_2d (line 1070) | def _load_centers_2d(self, results):
method _load_cam_box (line 1084) | def _load_cam_box(self, results):
method _load_visible (line 1098) | def _load_visible(self, results):
class SparseDepth (line 1105) | class SparseDepth(object):
method __init__ (line 1109) | def __init__(self, scale_factors, depth_mean=14.41, depth_var=156.89, ...
method __call__ (line 1115) | def __call__(self, results):
FILE: mmdet3d/datasets/pipelines/test_time_aug.py
class MultiScaleFlipAug3D (line 10) | class MultiScaleFlipAug3D(object):
method __init__ (line 32) | def __init__(self,
method __call__ (line 69) | def __call__(self, results):
method __repr__ (line 118) | def __repr__(self):
FILE: mmdet3d/datasets/pipelines/transforms_2d.py
class OurRandomAffine (line 15) | class OurRandomAffine:
method __init__ (line 52) | def __init__(self,
method _transform_bbox (line 76) | def _transform_bbox(self, results, warp_mats, flips, width, height):
method _transform_camera (line 170) | def _transform_camera(self, results, warp_mats, flips, width):
method __call__ (line 196) | def __call__(self, results):
method __repr__ (line 278) | def __repr__(self):
method _get_scaling_matrix (line 288) | def _get_scaling_matrix(scale_ratio):
method _get_translation_matrix (line 295) | def _get_translation_matrix(x, y):
method _get_flip_matrix (line 301) | def _get_flip_matrix(flip, width):
class PhotoMetricDistortionMultiViewImage (line 314) | class PhotoMetricDistortionMultiViewImage:
method __init__ (line 333) | def __init__(self,
method __call__ (line 345) | def __call__(self, results):
method __repr__ (line 413) | def __repr__(self):
FILE: mmdet3d/datasets/pipelines/transforms_3d.py
class RandomFlip3D (line 14) | class RandomFlip3D(RandomFlip):
method __init__ (line 32) | def __init__(self,
method random_flip_data_3d (line 50) | def random_flip_data_3d(self, input_dict, direction='horizontal'):
method __call__ (line 71) | def __call__(self, input_dict):
method __repr__ (line 110) | def __repr__(self):
class OurRandomFlip3D (line 119) | class OurRandomFlip3D(object):
method __init__ (line 137) | def __init__(self,
method random_flip_data_3d (line 156) | def random_flip_data_3d(self, input_dict, direction='horizontal'):
method __call__ (line 194) | def __call__(self, input_dict):
method __repr__ (line 233) | def __repr__(self):
class ObjectSample (line 243) | class ObjectSample(object):
method __init__ (line 253) | def __init__(self, db_sampler, sample_2d=False):
method remove_points_in_boxes (line 261) | def remove_points_in_boxes(points, boxes):
method __call__ (line 275) | def __call__(self, input_dict):
method __repr__ (line 333) | def __repr__(self):
class ObjectNoise (line 347) | class ObjectNoise(object):
method __init__ (line 362) | def __init__(self,
method __call__ (line 372) | def __call__(self, input_dict):
method __repr__ (line 401) | def __repr__(self):
class GlobalRotScaleTrans (line 412) | class GlobalRotScaleTrans(object):
method __init__ (line 429) | def __init__(self,
method _trans_bbox_points (line 439) | def _trans_bbox_points(self, input_dict):
method _rot_bbox_points (line 465) | def _rot_bbox_points(self, input_dict):
method _scale_bbox_points (line 489) | def _scale_bbox_points(self, input_dict):
method _random_scale (line 510) | def _random_scale(self, input_dict):
method __call__ (line 524) | def __call__(self, input_dict):
method __repr__ (line 550) | def __repr__(self):
class OurGlobalRotScaleTrans (line 560) | class OurGlobalRotScaleTrans(object):
method __init__ (line 577) | def __init__(self,
method _trans_bbox_points (line 587) | def _trans_bbox_points(self, input_dict):
method _rot_bbox_points (line 622) | def _rot_bbox_points(self, input_dict):
method _scale_bbox_points (line 653) | def _scale_bbox_points(self, input_dict):
method _random_scale (line 688) | def _random_scale(self, input_dict):
method _random_rotation (line 702) | def _random_rotation(self, input_dict):
method __call__ (line 709) | def __call__(self, input_dict):
method __repr__ (line 737) | def __repr__(self):
class PointShuffle (line 748) | class PointShuffle(object):
method __call__ (line 751) | def __call__(self, input_dict):
method __repr__ (line 764) | def __repr__(self):
class ObjectRangeFilter (line 769) | class ObjectRangeFilter(object):
method __init__ (line 776) | def __init__(self, point_cloud_range):
method __call__ (line 780) | def __call__(self, input_dict):
method __repr__ (line 807) | def __repr__(self):
class OurObjectRangeFilter (line 816) | class OurObjectRangeFilter(object):
method __init__ (line 823) | def __init__(self, point_cloud_range):
method __call__ (line 827) | def __call__(self, input_dict):
method __repr__ (line 872) | def __repr__(self):
class PointsRangeFilter (line 880) | class PointsRangeFilter(object):
method __init__ (line 887) | def __init__(self, point_cloud_range):
method __call__ (line 890) | def __call__(self, input_dict):
method __repr__ (line 906) | def __repr__(self):
class ObjectNameFilter (line 914) | class ObjectNameFilter(object):
method __init__ (line 921) | def __init__(self, classes):
method __call__ (line 925) | def __call__(self, input_dict):
method __repr__ (line 964) | def __repr__(self):
class IndoorPointSample (line 972) | class IndoorPointSample(object):
method __init__ (line 982) | def __init__(self, num_points):
method points_random_sampling (line 985) | def points_random_sampling(self,
method __call__ (line 1016) | def __call__(self, results):
method __repr__ (line 1042) | def __repr__(self):
class BackgroundPointsFilter (line 1050) | class BackgroundPointsFilter(object):
method __init__ (line 1057) | def __init__(self, bbox_enlarge_range):
method __call__ (line 1068) | def __call__(self, input_dict):
method __repr__ (line 1105) | def __repr__(self):
class VoxelBasedPointSampler (line 1114) | class VoxelBasedPointSampler(object):
method __init__ (line 1126) | def __init__(self, cur_sweep_cfg, prev_sweep_cfg=None, time_dim=3):
method _sample_points (line 1139) | def _sample_points(self, points, sampler, point_dim):
method __call__ (line 1165) | def __call__(self, results):
method __repr__ (line 1233) | def __repr__(self):
FILE: mmdet3d/datasets/scannet_dataset.py
class ScanNetDataset (line 11) | class ScanNetDataset(Custom3DDataset):
method __init__ (line 46) | def __init__(self,
method get_ann_info (line 65) | def get_ann_info(self, index):
method show (line 109) | def show(self, results, out_dir, show=True):
FILE: mmdet3d/datasets/semantickitti_dataset.py
class SemanticKITTIDataset (line 8) | class SemanticKITTIDataset(Custom3DDataset):
method __init__ (line 43) | def __init__(self,
method get_ann_info (line 62) | def get_ann_info(self, index):
FILE: mmdet3d/datasets/sunrgbd_dataset.py
class SUNRGBDDataset (line 13) | class SUNRGBDDataset(Custom3DDataset):
method __init__ (line 46) | def __init__(self,
method get_data_info (line 68) | def get_data_info(self, index):
method get_ann_info (line 112) | def get_ann_info(self, index):
method show (line 154) | def show(self, results, out_dir, show=True):
method evaluate (line 176) | def evaluate(self,
FILE: mmdet3d/datasets/waymo_dataset.py
class WaymoDataset (line 15) | class WaymoDataset(KittiDataset):
method __init__ (line 54) | def __init__(self,
method _get_pts_filename (line 88) | def _get_pts_filename(self, idx):
method get_data_info (line 93) | def get_data_info(self, index):
method format_results (line 165) | def format_results(self,
method evaluate (line 247) | def evaluate(self,
method bbox2result_kitti (line 384) | def bbox2result_kitti(self,
method convert_valid_bboxes (line 499) | def convert_valid_bboxes(self, box_dict, info):
FILE: mmdet3d/models/backbones/DLA.py
function get_model_url (line 24) | def get_model_url(data='imagenet', name='dla34', hash='ba72cf86'):
function conv3x3 (line 28) | def conv3x3(in_planes, out_planes, stride=1):
class BasicBlock (line 34) | class BasicBlock(nn.Module):
method __init__ (line 35) | def __init__(self, inplanes, planes, stride=1, dilation=1):
method forward (line 48) | def forward(self, x, residual=None):
class Bottleneck (line 65) | class Bottleneck(nn.Module):
method __init__ (line 68) | def __init__(self, inplanes, planes, stride=1, dilation=1):
method forward (line 85) | def forward(self, x, residual=None):
class BottleneckX (line 106) | class BottleneckX(nn.Module):
method __init__ (line 110) | def __init__(self, inplanes, planes, stride=1, dilation=1):
method forward (line 129) | def forward(self, x, residual=None):
class Root (line 150) | class Root(nn.Module):
method __init__ (line 151) | def __init__(self, in_channels, out_channels, kernel_size, residual):
method forward (line 160) | def forward(self, *x):
class Tree (line 171) | class Tree(nn.Module):
method __init__ (line 172) | def __init__(self, levels, block, in_channels, out_channels, stride=1,
method forward (line 211) | def forward(self, x, residual=None, children=None):
class DLA (line 227) | class DLA(nn.Module):
method __init__ (line 228) | def __init__(self, levels, channels, num_classes=1000,
method _make_level (line 272) | def _make_level(self, block, inplanes, planes, blocks, stride=1):
method _make_conv_level (line 289) | def _make_conv_level(self, inplanes, planes, convs, stride=1, dilation...
method forward (line 301) | def forward(self, x, pre_img=None, pre_hm=None):
method load_pretrained_model (line 314) | def load_pretrained_model(self, data='imagenet', name='dla34', hash='b...
function dla34 (line 329) | def dla34(pretrained=True, **kwargs): # DLA-34
function dla102 (line 341) | def dla102(pretrained=None, **kwargs): # DLA-102
function dla46_c (line 351) | def dla46_c(pretrained=None, **kwargs): # DLA-46-C
function dla46x_c (line 362) | def dla46x_c(pretrained=None, **kwargs): # DLA-X-46-C
function dla60x_c (line 373) | def dla60x_c(pretrained=None, **kwargs): # DLA-X-60-C
function dla60 (line 384) | def dla60(pretrained=None, **kwargs): # DLA-60
function dla60x (line 395) | def dla60x(pretrained=None, **kwargs): # DLA-X-60
function dla102x (line 406) | def dla102x(pretrained=None, **kwargs): # DLA-X-102
function dla102x2 (line 416) | def dla102x2(pretrained=None, **kwargs): # DLA-X-102 64
function dla169 (line 426) | def dla169(pretrained=None, **kwargs): # DLA-169
class Identity (line 436) | class Identity(nn.Module):
method __init__ (line 438) | def __init__(self):
method forward (line 441) | def forward(self, x):
function fill_fc_weights (line 445) | def fill_fc_weights(layers):
function fill_up_weights (line 452) | def fill_up_weights(up):
class Conv (line 464) | class Conv(nn.Module):
method __init__ (line 465) | def __init__(self, chi, cho):
method forward (line 472) | def forward(self, x):
class GlobalConv (line 476) | class GlobalConv(nn.Module):
method __init__ (line 477) | def __init__(self, chi, cho, k=7, d=1):
method forward (line 498) | def forward(self, x):
class DeformConv (line 504) | class DeformConv(nn.Module):
method __init__ (line 505) | def __init__(self, chi, cho):
method forward (line 513) | def forward(self, x):
class IDAUp (line 519) | class IDAUp(nn.Module):
method __init__ (line 520) | def __init__(self, o, channels, up_f, node_type=(DeformConv, DeformCon...
method forward (line 537) | def forward(self, layers, startp, endp):
class DLAUp (line 546) | class DLAUp(nn.Module):
method __init__ (line 547) | def __init__(self, startp, channels, scales, in_channels=None,
method forward (line 565) | def forward(self, layers):
class Interpolate (line 574) | class Interpolate(nn.Module):
method __init__ (line 575) | def __init__(self, scale, mode):
method forward (line 580) | def forward(self, x):
class BaseModel (line 592) | class BaseModel(nn.Module):
method __init__ (line 593) | def __init__(self, heads, head_convs, num_stacks, last_channel, opt=No...
method img2feats (line 645) | def img2feats(self, x):
method imgpre2feats (line 648) | def imgpre2feats(self, x, pre_img=None, pre_hm=None):
method forward (line 651) | def forward(self, x, pre_img=None, pre_hm=None):
class DLASeg (line 674) | class DLASeg(BaseModel):
method __init__ (line 675) | def __init__(self, num_layers, heads, head_convs):
method init_weights (line 699) | def init_weights(self, pretrained=None):
method img2feats (line 706) | def img2feats(self, x):
method imgpre2feats (line 717) | def imgpre2feats(self, x, pre_img=None, pre_hm=None):
class Opt (line 729) | class Opt:
FILE: mmdet3d/models/backbones/base_pointnet.py
class BasePointNet (line 6) | class BasePointNet(nn.Module, metaclass=ABCMeta):
method __init__ (line 9) | def __init__(self):
method init_weights (line 13) | def init_weights(self, pretrained=None):
method _split_point_feats (line 23) | def _split_point_feats(points):
FILE: mmdet3d/models/backbones/multi_backbone.py
class MultiBackbone (line 11) | class MultiBackbone(nn.Module):
method __init__ (line 26) | def __init__(self,
method init_weights (line 80) | def init_weights(self, pretrained=None):
method forward (line 90) | def forward(self, points):
FILE: mmdet3d/models/backbones/nostem_regnet.py
class NoStemRegNet (line 6) | class NoStemRegNet(RegNet):
method __init__ (line 60) | def __init__(self, arch, **kwargs):
method _make_stem_layer (line 63) | def _make_stem_layer(self, in_channels, base_channels):
method forward (line 68) | def forward(self, x):
FILE: mmdet3d/models/backbones/pointnet2_sa_msg.py
class PointNet2SAMSG (line 12) | class PointNet2SAMSG(BasePointNet):
method __init__ (line 40) | def __init__(self,
method forward (line 116) | def forward(self, points):
FILE: mmdet3d/models/backbones/pointnet2_sa_ssg.py
class PointNet2SASSG (line 11) | class PointNet2SASSG(BasePointNet):
method __init__ (line 33) | def __init__(self,
method forward (line 88) | def forward(self, points):
FILE: mmdet3d/models/backbones/second.py
class SECOND (line 9) | class SECOND(nn.Module):
method __init__ (line 21) | def __init__(self,
method init_weights (line 64) | def init_weights(self, pretrained=None):
method forward (line 73) | def forward(self, x):
FILE: mmdet3d/models/backbones/swin.py
function _no_grad_trunc_normal_ (line 23) | def _no_grad_trunc_normal_(tensor: Tensor, mean: float, std: float, a: f...
function trunc_normal_ (line 63) | def trunc_normal_(tensor: Tensor,
function trunc_normal_init (line 85) | def trunc_normal_init(module: nn.Module,
class AdaptivePadding (line 97) | class AdaptivePadding(nn.Module):
method __init__ (line 127) | def __init__(self, kernel_size=1, stride=1, dilation=1, padding='corne...
method get_pad_shape (line 143) | def get_pad_shape(self, input_shape):
method forward (line 155) | def forward(self, x):
class PatchEmbed (line 168) | class PatchEmbed(BaseModule):
method __init__ (line 194) | def __init__(
method forward (line 268) | def forward(self, x):
class PatchMerging (line 289) | class PatchMerging(BaseModule):
method __init__ (line 318) | def __init__(self,
method forward (line 367) | def forward(self, x, input_size):
function swin_converter (line 412) | def swin_converter(ckpt):
class WindowMSA (line 467) | class WindowMSA(BaseModule):
method __init__ (line 486) | def __init__(self,
method init_weights (line 523) | def init_weights(self):
method forward (line 526) | def forward(self, x, mask=None):
method double_step_seq (line 567) | def double_step_seq(step1, len1, step2, len2):
class ShiftWindowMSA (line 573) | class ShiftWindowMSA(BaseModule):
method __init__ (line 596) | def __init__(self,
method forward (line 625) | def forward(self, query, hw_shape):
method window_reverse (line 701) | def window_reverse(self, windows, H, W):
method window_partition (line 717) | def window_partition(self, x):
class SwinBlock (line 733) | class SwinBlock(BaseModule):
method __init__ (line 758) | def __init__(self,
method forward (line 803) | def forward(self, x, hw_shape):
class SwinBlockSequence (line 826) | class SwinBlockSequence(BaseModule):
method __init__ (line 855) | def __init__(self,
method forward (line 900) | def forward(self, x, hw_shape):
class SwinTransformer (line 912) | class SwinTransformer(BaseModule):
method __init__ (line 969) | def __init__(self,
method train (line 1087) | def train(self, mode=True):
method _freeze_stages (line 1092) | def _freeze_stages(self):
method init_weights (line 1114) | def init_weights(self, pretrained=None):
method forward (line 1191) | def forward(self, x):
FILE: mmdet3d/models/builder.py
function build_backbone (line 8) | def build_backbone(cfg):
function build_neck (line 13) | def build_neck(cfg):
function build_roi_extractor (line 18) | def build_roi_extractor(cfg):
function build_shared_head (line 23) | def build_shared_head(cfg):
function build_head (line 28) | def build_head(cfg):
function build_loss (line 33) | def build_loss(cfg):
function build_detector (line 38) | def build_detector(cfg, train_cfg=None, test_cfg=None):
function build_voxel_encoder (line 51) | def build_voxel_encoder(cfg):
function build_middle_encoder (line 56) | def build_middle_encoder(cfg):
function build_fusion_layer (line 61) | def build_fusion_layer(cfg):
FILE: mmdet3d/models/dense_heads/anchor3d_head.py
class Anchor3DHead (line 17) | class Anchor3DHead(nn.Module, AnchorTrainMixin):
method __init__ (line 43) | def __init__(self,
method _init_assigner_sampler (line 106) | def _init_assigner_sampler(self):
method _init_layers (line 122) | def _init_layers(self):
method init_weights (line 132) | def init_weights(self):
method forward_single (line 138) | def forward_single(self, x):
method forward (line 155) | def forward(self, feats):
method get_anchors (line 168) | def get_anchors(self, featmap_sizes, input_metas, device='cuda'):
method loss_single (line 188) | def loss_single(self, cls_score, bbox_pred, dir_cls_preds, labels,
method add_sin_difference (line 275) | def add_sin_difference(boxes1, boxes2):
method loss (line 299) | def loss(self,
method get_bboxes (line 370) | def get_bboxes(self,
method get_bboxes_single (line 421) | def get_bboxes_single(self,
FILE: mmdet3d/models/dense_heads/base_conv_bbox_head.py
class BaseConvBboxHead (line 9) | class BaseConvBboxHead(nn.Module):
method __init__ (line 20) | def __init__(self,
method _add_conv_branch (line 81) | def _add_conv_branch(self, in_channels, conv_channels):
method init_weights (line 101) | def init_weights(self):
method forward (line 105) | def forward(self, feats):
FILE: mmdet3d/models/dense_heads/centerpoint_head.py
class SeparateHead (line 18) | class SeparateHead(nn.Module):
method __init__ (line 36) | def __init__(self,
method init_weights (line 81) | def init_weights(self):
method forward (line 91) | def forward(self, x):
class DCNSeparateHead (line 122) | class DCNSeparateHead(nn.Module):
method __init__ (line 146) | def __init__(self,
method init_weights (line 196) | def init_weights(self):
method forward (line 201) | def forward(self, x):
class CenterHead (line 235) | class CenterHead(nn.Module):
method __init__ (line 266) | def __init__(self,
method init_weights (line 319) | def init_weights(self):
method forward_single (line 324) | def forward_single(self, x):
method forward (line 343) | def forward(self, feats):
method _gather_feat (line 355) | def _gather_feat(self, feat, ind, mask=None):
method get_targets (line 380) | def get_targets(self, gt_bboxes_3d, gt_labels_3d):
method get_targets_single (line 417) | def get_targets_single(self, gt_bboxes_3d, gt_labels_3d):
method loss (line 556) | def loss(self, gt_bboxes_3d, gt_labels_3d, preds_dicts, **kwargs):
method get_bboxes (line 605) | def get_bboxes(self, preds_dicts, img_metas, img=None, rescale=False):
method get_task_detections (line 699) | def get_task_detections(self, num_class_with_bg, batch_cls_preds,
FILE: mmdet3d/models/dense_heads/free_anchor3d_head.py
class FreeAnchor3DHead (line 12) | class FreeAnchor3DHead(Anchor3DHead):
method __init__ (line 30) | def __init__(self,
method loss (line 43) | def loss(self,
method positive_bag_loss (line 244) | def positive_bag_loss(self, matched_cls_prob, matched_box_prob):
method negative_bag_loss (line 266) | def negative_bag_loss(self, cls_prob, box_prob):
FILE: mmdet3d/models/dense_heads/parta2_rpn_head.py
class PartA2RPNHead (line 14) | class PartA2RPNHead(Anchor3DHead):
method __init__ (line 51) | def __init__(self,
method loss (line 86) | def loss(self,
method get_bboxes_single (line 126) | def get_bboxes_single(self,
method class_agnostic_nms (line 222) | def class_agnostic_nms(self, mlvl_bboxes, mlvl_bboxes_for_nms,
FILE: mmdet3d/models/dense_heads/shape_aware_head.py
class BaseShapeHead (line 14) | class BaseShapeHead(nn.Module):
method __init__ (line 41) | def __init__(self,
method init_weights (line 88) | def init_weights(self):
method forward (line 97) | def forward(self, x):
class ShapeAwareHead (line 141) | class ShapeAwareHead(Anchor3DHead):
method __init__ (line 152) | def __init__(self, tasks, assign_per_class=True, **kwargs):
method _init_layers (line 157) | def _init_layers(self):
method init_weights (line 178) | def init_weights(self):
method forward_single (line 183) | def forward_single(self, x):
method loss_single (line 216) | def loss_single(self, cls_score, bbox_pred, dir_cls_preds, labels,
method loss (line 278) | def loss(self,
method get_bboxes (line 345) | def get_bboxes(self,
method get_bboxes_single (line 397) | def get_bboxes_single(self,
FILE: mmdet3d/models/dense_heads/sparsefusion_head_deform.py
class SparseFusionHead2D_Deform (line 30) | class SparseFusionHead2D_Deform(nn.Module):
method __init__ (line 31) | def __init__(self,
method create_2D_grid (line 260) | def create_2D_grid(self, x_size, y_size):
method init_bn_momentum (line 269) | def init_bn_momentum(self):
method init_weights (line 274) | def init_weights(self):
method _init_assigner_sampler (line 292) | def _init_assigner_sampler(self):
method forward_single (line 314) | def forward_single(self, inputs, img_inputs, img_metas, sparse_depth):
method forward (line 473) | def forward(self, feats, img_feats, img_metas, sparse_depth=None):
method construct_input_padding_mask (line 496) | def construct_input_padding_mask(self, img_feats, img_metas):
method construction_view_projection_matrix (line 529) | def construction_view_projection_matrix(self, proj_matrix, img_query_v...
method construct_projection_matrix (line 538) | def construct_projection_matrix(self, img_metas, device):
method build_heatmap_LN (line 555) | def build_heatmap_LN(self, hidden_channel, bias, num_classes, layer_nu...
method build_heatmap (line 575) | def build_heatmap(self, hidden_channel, bias, num_classes, layer_num=2...
method generate_heatmap_deform (line 598) | def generate_heatmap_deform(self, lidar_feat, img_feat, voxel_height, ...
method generate_heatmap (line 762) | def generate_heatmap(self, lidar_feat, min_voxel_height, max_voxel_hei...
method generate_heatmap_img (line 797) | def generate_heatmap_img(self, img_feats, batch_size):
method get_targets (line 837) | def get_targets(self, gt_bboxes_3d, gt_labels_3d, gt_bboxes, gt_labels...
method get_targets_single_2d (line 916) | def get_targets_single_2d(self, gt_bboxes, gt_labels, gt_centers_2d, g...
method get_targets_single (line 1129) | def get_targets_single(self, gt_bboxes_3d, gt_labels_3d, gt_visible, p...
method get_targets_single_view (line 1293) | def get_targets_single_view(self, gt_bboxes_3d, gt_labels_3d, gt_visib...
method loss (line 1411) | def loss(self, gt_bboxes_3d, gt_labels_3d, gt_bboxes, gt_labels, gt_pt...
method get_bboxes (line 1615) | def get_bboxes(self, preds_dicts, img_metas, img=None, rescale=False, ...
method get_layer_num_proposal (line 1737) | def get_layer_num_proposal(self, idx_layer):
FILE: mmdet3d/models/dense_heads/ssd_3d_head.py
class SSD3DHead (line 16) | class SSD3DHead(VoteHead):
method __init__ (line 42) | def __init__(self,
method _get_cls_out_channels (line 83) | def _get_cls_out_channels(self):
method _get_reg_out_channels (line 88) | def _get_reg_out_channels(self):
method _extract_input (line 95) | def _extract_input(self, feat_dict):
method loss (line 113) | def loss(self,
method get_targets (line 219) | def get_targets(self,
method get_targets_single (line 307) | def get_targets_single(self,
method get_bboxes (line 439) | def get_bboxes(self, points, bbox_preds, input_metas, rescale=False):
method multiclass_nms_single (line 471) | def multiclass_nms_single(self, obj_scores, sem_scores, bbox, points,
method _assign_targets_by_points_inside (line 545) | def _assign_targets_by_points_inside(self, bboxes_3d, points):
FILE: mmdet3d/models/dense_heads/train_mixins.py
class AnchorTrainMixin (line 8) | class AnchorTrainMixin(object):
method anchor_target_3d (line 11) | def anchor_target_3d(self,
method anchor_target_3d_single (line 101) | def anchor_target_3d_single(self,
method anchor_target_single_assigner (line 237) | def anchor_target_single_assigner(self,
function get_direction_target (line 317) | def get_direction_target(anchors,
FILE: mmdet3d/models/dense_heads/transfusion_head.py
class PositionEmbeddingLearned (line 25) | class PositionEmbeddingLearned(nn.Module):
method __init__ (line 30) | def __init__(self, input_channel, num_pos_feats=288):
method forward (line 38) | def forward(self, xyz):
class TransformerDecoderLayer (line 44) | class TransformerDecoderLayer(nn.Module):
method __init__ (line 45) | def __init__(self, d_model, nhead, dim_feedforward=2048, dropout=0.1, ...
method with_pos_embed (line 79) | def with_pos_embed(self, tensor, pos_embed):
method forward (line 82) | def forward(self, query, key, query_pos, key_pos, attn_mask=None):
class MultiheadAttention (line 125) | class MultiheadAttention(nn.Module):
method __init__ (line 149) | def __init__(self, embed_dim, num_heads, dropout=0., bias=True, add_bi...
method _reset_parameters (line 185) | def _reset_parameters(self):
method forward (line 201) | def forward(self, query, key, value, key_padding_mask=None, need_weigh...
function multi_head_attention_forward (line 255) | def multi_head_attention_forward(query, # type: Tensor
class FFN (line 516) | class FFN(nn.Module):
method __init__ (line 517) | def __init__(self,
method init_weights (line 562) | def init_weights(self):
method forward (line 572) | def forward(self, x):
class TransFusionHead (line 603) | class TransFusionHead(nn.Module):
method __init__ (line 604) | def __init__(self,
method create_2D_grid (line 768) | def create_2D_grid(self, x_size, y_size):
method init_weights (line 777) | def init_weights(self):
method init_bn_momentum (line 786) | def init_bn_momentum(self):
method _init_assigner_sampler (line 791) | def _init_assigner_sampler(self):
method forward_single (line 807) | def forward_single(self, inputs, img_inputs, img_metas):
method forward (line 1043) | def forward(self, feats, img_feats, img_metas):
method get_targets (line 1059) | def get_targets(self, gt_bboxes_3d, gt_labels_3d, preds_dict):
method get_targets_single (line 1100) | def get_targets_single(self, gt_bboxes_3d, gt_labels_3d, preds_dict, b...
method loss (line 1229) | def loss(self, gt_bboxes_3d, gt_labels_3d, preds_dicts, **kwargs):
method get_bboxes (line 1296) | def get_bboxes(self, preds_dicts, img_metas, img=None, rescale=False, ...
FILE: mmdet3d/models/dense_heads/vote_head.py
class VoteHead (line 18) | class VoteHead(nn.Module):
method __init__ (line 42) | def __init__(self,
method init_weights (line 95) | def init_weights(self):
method _get_cls_out_channels (line 99) | def _get_cls_out_channels(self):
method _get_reg_out_channels (line 104) | def _get_reg_out_channels(self):
method _extract_input (line 111) | def _extract_input(self, feat_dict):
method forward (line 138) | def forward(self, feat_dict, sample_mod):
method loss (line 225) | def loss(self,
method get_targets (line 353) | def get_targets(self,
method get_targets_single (line 442) | def get_targets_single(self,
method get_bboxes (line 566) | def get_bboxes(self,
method multiclass_nms_single (line 608) | def multiclass_nms_single(self, obj_scores, sem_scores, bbox, points,
FILE: mmdet3d/models/detectors/base.py
class Base3DDetector (line 11) | class Base3DDetector(BaseDetector):
method forward_test (line 14) | def forward_test(self, points, img_metas, img=None, **kwargs):
method forward (line 46) | def forward(self, return_loss=True, **kwargs):
method show_results (line 62) | def show_results(self, data, result, out_dir):
FILE: mmdet3d/models/detectors/centerpoint.py
class CenterPoint (line 9) | class CenterPoint(MVXTwoStageDetector):
method __init__ (line 12) | def __init__(self,
method extract_pts_feat (line 34) | def extract_pts_feat(self, pts, img_feats, img_metas):
method forward_pts_train (line 48) | def forward_pts_train(self,
method simple_test_pts (line 74) | def simple_test_pts(self, x, img_metas, rescale=False):
method aug_test_pts (line 85) | def aug_test_pts(self, feats, img_metas, rescale=False):
method aug_test (line 186) | def aug_test(self, points, img_metas, imgs=None, rescale=False):
FILE: mmdet3d/models/detectors/dynamic_voxelnet.py
class DynamicVoxelNet (line 10) | class DynamicVoxelNet(VoxelNet):
method __init__ (line 14) | def __init__(self,
method extract_feat (line 36) | def extract_feat(self, points, img_metas):
method voxelize (line 49) | def voxelize(self, points):
FILE: mmdet3d/models/detectors/h3dnet.py
class H3DNet (line 9) | class H3DNet(TwoStage3DDetector):
method __init__ (line 15) | def __init__(self,
method forward_train (line 32) | def forward_train(self,
method simple_test (line 98) | def simple_test(self, points, img_metas, imgs=None, rescale=False):
method aug_test (line 130) | def aug_test(self, points, img_metas, imgs=None, rescale=False):
method extract_feats (line 168) | def extract_feats(self, points, img_metas):
FILE: mmdet3d/models/detectors/imvotenet.py
function sample_valid_seeds (line 12) | def sample_valid_seeds(mask, num_sampled_seed=1024):
class ImVoteNet (line 53) | class ImVoteNet(Base3DDetector):
method __init__ (line 56) | def __init__(self,
method init_weights (line 137) | def init_weights(self, pretrained=None):
method freeze_img_branch_params (line 173) | def freeze_img_branch_params(self):
method _load_from_state_dict (line 191) | def _load_from_state_dict(self, state_dict, prefix, local_metadata, st...
method train (line 205) | def train(self, mode=True):
method with_img_bbox (line 221) | def with_img_bbox(self):
method with_img_bbox_head (line 228) | def with_img_bbox_head(self):
method with_img_backbone (line 234) | def with_img_backbone(self):
method with_img_neck (line 239) | def with_img_neck(self):
method with_img_rpn (line 244) | def with_img_rpn(self):
method with_img_roi_head (line 249) | def with_img_roi_head(self):
method with_pts_bbox (line 254) | def with_pts_bbox(self):
method with_pts_backbone (line 260) | def with_pts_backbone(self):
method with_pts_neck (line 265) | def with_pts_neck(self):
method extract_feat (line 269) | def extract_feat(self, imgs):
method extract_img_feat (line 273) | def extract_img_feat(self, img):
method extract_img_feats (line 280) | def extract_img_feats(self, imgs):
method extract_pts_feat (line 294) | def extract_pts_feat(self, pts):
method extract_pts_feats (line 306) | def extract_pts_feats(self, pts):
method extract_bboxes_2d (line 312) | def extract_bboxes_2d(self,
method forward_train (line 370) | def forward_train(self,
method forward_test (line 525) | def forward_test(self,
method simple_test_img_only (line 610) | def simple_test_img_only(self,
method simple_test (line 649) | def simple_test(self,
method aug_test_img_only (line 718) | def aug_test_img_only(self, img, img_metas, rescale=False):
method aug_test (line 752) | def aug_test(self,
FILE: mmdet3d/models/detectors/mvx_faster_rcnn.py
class MVXFasterRCNN (line 10) | class MVXFasterRCNN(MVXTwoStageDetector):
method __init__ (line 13) | def __init__(self, **kwargs):
class DynamicMVXFasterRCNN (line 18) | class DynamicMVXFasterRCNN(MVXTwoStageDetector):
method __init__ (line 21) | def __init__(self, **kwargs):
method voxelize (line 26) | def voxelize(self, points):
method extract_pts_feat (line 48) | def extract_pts_feat(self, points, img_feats, img_metas):
FILE: mmdet3d/models/detectors/mvx_two_stage.py
class MVXTwoStageDetector (line 20) | class MVXTwoStageDetector(Base3DDetector):
method __init__ (line 23) | def __init__(self,
method init_weights (line 80) | def init_weights(self, pretrained=None):
method with_pts_roi_head (line 121) | def with_pts_roi_head(self):
method with_img_shared_head (line 127) | def with_img_shared_head(self):
method with_pts_bbox (line 133) | def with_pts_bbox(self):
method with_img_bbox (line 139) | def with_img_bbox(self):
method with_img_backbone (line 145) | def with_img_backbone(self):
method with_pts_backbone (line 150) | def with_pts_backbone(self):
method with_fusion (line 155) | def with_fusion(self):
method with_img_neck (line 161) | def with_img_neck(self):
method with_pts_neck (line 166) | def with_pts_neck(self):
method with_img_rpn (line 171) | def with_img_rpn(self):
method with_img_roi_head (line 176) | def with_img_roi_head(self):
method with_voxel_encoder (line 181) | def with_voxel_encoder(self):
method with_middle_encoder (line 187) | def with_middle_encoder(self):
method extract_img_feat (line 192) | def extract_img_feat(self, img, img_metas):
method extract_pts_feat (line 213) | def extract_pts_feat(self, pts, img_feats, img_metas):
method extract_feat (line 227) | def extract_feat(self, points, img, img_metas):
method voxelize (line 236) | def voxelize(self, points):
method forward_train (line 261) | def forward_train(self,
method forward_pts_train (line 315) | def forward_pts_train(self,
method forward_img_train (line 342) | def forward_img_train(self,
method simple_test_img (line 396) | def simple_test_img(self, x, img_metas, proposals=None, rescale=False):
method simple_test_rpn (line 407) | def simple_test_rpn(self, x, img_metas, rpn_test_cfg):
method simple_test_pts (line 414) | def simple_test_pts(self, x, x_img, img_metas, rescale=False):
method simple_test (line 425) | def simple_test(self, points, img_metas, img=None, rescale=False):
method aug_test (line 443) | def aug_test(self, points, img_metas, imgs=None, rescale=False):
method extract_feats (line 453) | def extract_feats(self, points, img_metas, imgs=None):
method aug_test_pts (line 461) | def aug_test_pts(self, feats, img_metas, rescale=False):
method show_results (line 480) | def show_results(self, data, result, out_dir):
FILE: mmdet3d/models/detectors/parta2.py
class PartA2 (line 11) | class PartA2(TwoStage3DDetector):
method __init__ (line 17) | def __init__(self,
method extract_feat (line 41) | def extract_feat(self, points, img_metas):
method voxelize (line 57) | def voxelize(self, points):
method forward_train (line 87) | def forward_train(self,
method simple_test (line 136) | def simple_test(self, points, img_metas, proposals=None, rescale=False):
FILE: mmdet3d/models/detectors/single_stage.py
class SingleStage3DDetector (line 8) | class SingleStage3DDetector(Base3DDetector):
method __init__ (line 25) | def __init__(self,
method init_weights (line 43) | def init_weights(self, pretrained=None):
method extract_feat (line 55) | def extract_feat(self, points, img_metas=None):
method extract_feats (line 66) | def extract_feats(self, points, img_metas):
FILE: mmdet3d/models/detectors/sparsefusion.py
class SparseFusionDetector (line 21) | class SparseFusionDetector(MVXTwoStageDetector):
method __init__ (line 24) | def __init__(self, **kwargs):
method init_weights (line 32) | def init_weights(self, pretrained=None):
method extract_img_feat (line 51) | def extract_img_feat(self, img, img_metas):
method extract_voxel_heights (line 73) | def extract_voxel_heights(self, voxels, coors):
method extract_pts_feat (line 114) | def extract_pts_feat(self, pts, img_feats, img_metas):
method voxelize (line 135) | def voxelize(self, points):
method forward_train (line 163) | def forward_train(self,
method forward_pts_train (line 223) | def forward_pts_train(self,
method simple_test_pts (line 259) | def simple_test_pts(self, x, x_img, img_metas, rescale=False, sparse_d...
method simple_test (line 273) | def simple_test(self, points, img_metas, img=None, sparse_depth=None, ...
method forward_test (line 292) | def forward_test(self, points, img_metas, img=None, sparse_depth=None,...
FILE: mmdet3d/models/detectors/ssd3dnet.py
class SSD3DNet (line 6) | class SSD3DNet(VoteNet):
method __init__ (line 12) | def __init__(self,
FILE: mmdet3d/models/detectors/transfusion.py
class TransFusionDetector (line 20) | class TransFusionDetector(MVXTwoStageDetector):
method __init__ (line 23) | def __init__(self, **kwargs):
method init_weights (line 29) | def init_weights(self, pretrained=None):
method extract_img_feat (line 41) | def extract_img_feat(self, img, img_metas):
method extract_pts_feat (line 62) | def extract_pts_feat(self, pts, img_feats, img_metas):
method voxelize (line 80) | def voxelize(self, points):
method forward_train (line 105) | def forward_train(self,
method forward_pts_train (line 159) | def forward_pts_train(self,
method simple_test_pts (line 186) | def simple_test_pts(self, x, x_img, img_metas, rescale=False):
method simple_test (line 197) | def simple_test(self, points, img_metas, img=None, rescale=False):
FILE: mmdet3d/models/detectors/two_stage.py
class TwoStage3DDetector (line 6) | class TwoStage3DDetector(Base3DDetector, TwoStageDetector):
method __init__ (line 14) | def __init__(self, **kwargs):
FILE: mmdet3d/models/detectors/votenet.py
class VoteNet (line 9) | class VoteNet(SingleStage3DDetector):
method __init__ (line 12) | def __init__(self,
method forward_train (line 25) | def forward_train(self,
method simple_test (line 60) | def simple_test(self, points, img_metas, imgs=None, rescale=False):
method aug_test (line 83) | def aug_test(self, points, img_metas, imgs=None, rescale=False):
FILE: mmdet3d/models/detectors/voxelnet.py
class VoxelNet (line 13) | class VoxelNet(SingleStage3DDetector):
method __init__ (line 16) | def __init__(self,
method extract_feat (line 38) | def extract_feat(self, points, img_metas):
method voxelize (line 51) | def voxelize(self, points):
method forward_train (line 68) | def forward_train(self,
method simple_test (line 96) | def simple_test(self, points, img_metas, imgs=None, rescale=False):
method aug_test (line 108) | def aug_test(self, points, img_metas, imgs=None, rescale=False):
FILE: mmdet3d/models/fusion_layers/coord_transform.py
function apply_3d_transformation (line 7) | def apply_3d_transformation(pcd, coords_type, img_meta, reverse=False):
function extract_2d_info (line 93) | def extract_2d_info(img_meta, tensor):
function bbox_2d_transform (line 121) | def bbox_2d_transform(img_meta, bbox_2d, ori2new):
function coord_2d_transform (line 175) | def coord_2d_transform(img_meta, coord_2d, ori2new):
FILE: mmdet3d/models/fusion_layers/point_fusion.py
function point_sample (line 10) | def point_sample(
class PointFusion (line 99) | class PointFusion(nn.Module):
method __init__ (line 132) | def __init__(self,
method init_weights (line 206) | def init_weights(self):
method forward (line 212) | def forward(self, img_feats, pts, pts_feats, img_metas):
method obtain_mlvl_feats (line 239) | def obtain_mlvl_feats(self, img_feats, pts, img_metas):
method sample_single (line 272) | def sample_single(self, img_feats, pts, img_meta):
FILE: mmdet3d/models/fusion_layers/vote_fusion.py
class VoteFusion (line 12) | class VoteFusion(nn.Module):
method __init__ (line 20) | def __init__(self, num_classes=10, max_imvote_per_pixel=3):
method forward (line 25) | def forward(self, imgs, bboxes_2d_rescaled, seeds_3d_depth, img_metas,
FILE: mmdet3d/models/losses/axis_aligned_iou_loss.py
function axis_aligned_iou_loss (line 10) | def axis_aligned_iou_loss(pred, target):
class AxisAlignedIoULoss (line 29) | class AxisAlignedIoULoss(nn.Module):
method __init__ (line 38) | def __init__(self, reduction='mean', loss_weight=1.0):
method forward (line 44) | def forward(self,
FILE: mmdet3d/models/losses/chamfer_distance.py
function chamfer_distance (line 8) | def chamfer_distance(src,
class ChamferDistance (line 75) | class ChamferDistance(nn.Module):
method __init__ (line 87) | def __init__(self,
method forward (line 101) | def forward(self,
FILE: mmdet3d/models/losses/uncertainty_loss.py
function laplacian_aleatoric_uncertainty_loss (line 8) | def laplacian_aleatoric_uncertainty_loss(pred, target):
class LaplaceL1Loss (line 27) | class LaplaceL1Loss(nn.Module):
method __init__ (line 35) | def __init__(self, reduction='mean', loss_weight=1.0):
method forward (line 40) | def forward(self,
FILE: mmdet3d/models/middle_encoders/pillar_scatter.py
class PointPillarsScatter (line 9) | class PointPillarsScatter(nn.Module):
method __init__ (line 19) | def __init__(self, in_channels, output_shape):
method forward (line 28) | def forward(self, voxel_features, coors, batch_size=None):
method forward_single (line 37) | def forward_single(self, voxel_features, coors):
method forward_batch (line 61) | def forward_batch(self, voxel_features, coors, batch_size):
FILE: mmdet3d/models/middle_encoders/sparse_encoder.py
class SparseEncoder (line 10) | class SparseEncoder(nn.Module):
method __init__ (line 31) | def __init__(self,
method forward (line 96) | def forward(self, voxel_features, coors, batch_size):
method make_encoder_layers (line 129) | def make_encoder_layers(self,
FILE: mmdet3d/models/middle_encoders/sparse_unet.py
class SparseUNet (line 11) | class SparseUNet(nn.Module):
method __init__ (line 30) | def __init__(self,
method forward (line 97) | def forward(self, voxel_features, coors, batch_size):
method decoder_layer_forward (line 149) | def decoder_layer_forward(self, x_lateral, x_bottom, lateral_layer,
method reduce_channel (line 172) | def reduce_channel(x, out_channels):
method make_encoder_layers (line 191) | def make_encoder_layers(self, make_block, norm_cfg, in_channels):
method make_decoder_layers (line 237) | def make_decoder_layers(self, make_block, norm_cfg, in_channels):
FILE: mmdet3d/models/model_utils/vote_module.py
class VoteModule (line 9) | class VoteModule(nn.Module):
method __init__ (line 34) | def __init__(self,
method forward (line 85) | def forward(self, seed_points, seed_feats):
method get_loss (line 149) | def get_loss(self, seed_points, vote_points, seed_indices,
FILE: mmdet3d/models/necks/second_fpn.py
class SECONDFPN (line 12) | class SECONDFPN(nn.Module):
method __init__ (line 26) | def __init__(self,
method init_weights (line 67) | def init_weights(self):
method forward (line 76) | def forward(self, x):
FILE: mmdet3d/models/roi_heads/base_3droi_head.py
class Base3DRoIHead (line 5) | class Base3DRoIHead(nn.Module, metaclass=ABCMeta):
method __init__ (line 8) | def __init__(self,
method with_bbox (line 27) | def with_bbox(self):
method with_mask (line 32) | def with_mask(self):
method init_weights (line 37) | def init_weights(self, pretrained):
method init_bbox_head (line 42) | def init_bbox_head(self):
method init_mask_head (line 47) | def init_mask_head(self):
method init_assigner_sampler (line 52) | def init_assigner_sampler(self):
method forward_train (line 57) | def forward_train(self,
method simple_test (line 83) | def simple_test(self,
method aug_test (line 93) | def aug_test(self, x, proposal_list, img_metas, rescale=False, **kwargs):
FILE: mmdet3d/models/roi_heads/bbox_heads/h3d_bbox_head.py
class H3DBboxHead (line 16) | class H3DBboxHead(nn.Module):
method __init__ (line 56) | def __init__(self,
method init_weights (line 201) | def init_weights(self, pretrained=None):
method forward (line 210) | def forward(self, feats_dict, sample_mod):
method loss (line 318) | def loss(self,
method get_bboxes (line 446) | def get_bboxes(self,
method multiclass_nms_single (line 492) | def multiclass_nms_single(self, obj_scores, sem_scores, bbox, points,
method get_proposal_stage_loss (line 552) | def get_proposal_stage_loss(self,
method get_targets (line 661) | def get_targets(self,
method get_targets_single (line 761) | def get_targets_single(self,
FILE: mmdet3d/models/roi_heads/bbox_heads/parta2_bbox_head.py
class PartA2BboxHead (line 17) | class PartA2BboxHead(nn.Module):
method __init__ (line 47) | def __init__(self,
method init_weights (line 225) | def init_weights(self):
method forward (line 233) | def forward(self, seg_feats, part_feats):
method loss (line 283) | def loss(self, cls_score, bbox_pred, rois, labels, bbox_targets,
method get_targets (line 356) | def get_targets(self, sampling_results, rcnn_train_cfg, concat=True):
method _get_target_single (line 396) | def _get_target_single(self, pos_bboxes, pos_gt_bboxes, ious, cfg):
method get_corner_loss_lidar (line 462) | def get_corner_loss_lidar(self, pred_bbox3d, gt_bbox3d, delta=1):
method get_bboxes (line 497) | def get_bboxes(self,
method multi_class_nms (line 556) | def multi_class_nms(self,
FILE: mmdet3d/models/roi_heads/h3d_roi_head.py
class H3DRoIHead (line 8) | class H3DRoIHead(Base3DRoIHead):
method __init__ (line 18) | def __init__(self,
method init_weights (line 31) | def init_weights(self, pretrained):
method init_mask_head (line 36) | def init_mask_head(self):
method init_bbox_head (line 41) | def init_bbox_head(self, bbox_head):
method init_assigner_sampler (line 47) | def init_assigner_sampler(self):
method forward_train (line 51) | def forward_train(self,
method simple_test (line 119) | def simple_test(self, feats_dict, img_metas, points, rescale=False):
FILE: mmdet3d/models/roi_heads/mask_heads/pointwise_semantic_head.py
class PointwiseSemanticHead (line 12) | class PointwiseSemanticHead(nn.Module):
method __init__ (line 26) | def __init__(self,
method forward (line 52) | def forward(self, x):
method get_targets_single (line 78) | def get_targets_single(self, voxel_centers, gt_bboxes_3d, gt_labels_3d):
method get_targets (line 127) | def get_targets(self, voxels_dict, gt_bboxes_3d, gt_labels_3d):
method loss (line 159) | def loss(self, semantic_results, semantic_targets):
FILE: mmdet3d/models/roi_heads/mask_heads/primitive_head.py
class PrimitiveHead (line 14) | class PrimitiveHead(nn.Module):
method __init__ (line 39) | def __init__(self,
method init_weights (line 113) | def init_weights(self):
method forward (line 117) | def forward(self, feats_dict, sample_mod):
method loss (line 188) | def loss(self,
method get_targets (line 259) | def get_targets(self,
method get_targets_single (line 327) | def get_targets_single(self,
method primitive_decode_scores (line 603) | def primitive_decode_scores(self, predictions, aggregated_points):
method check_horizon (line 631) | def check_horizon(self, points):
method check_dist (line 644) | def check_dist(self, plane_equ, points):
method point2line_dist (line 657) | def point2line_dist(self, points, pts_a, pts_b):
method match_point2line (line 676) | def match_point2line(self, points, corners, with_yaw, mode='bottom'):
method match_point2plane (line 717) | def match_point2plane(self, plane, points):
method compute_primitive_loss (line 735) | def compute_primitive_loss(self, primitive_center, primitive_semantic,
method get_primitive_center (line 784) | def get_primitive_center(self, pred_flag, center):
method _assign_primitive_line_targets (line 803) | def _assign_primitive_line_targets(self,
method _assign_primitive_surface_targets (line 868) | def _assign_primitive_surface_targets(self,
method _get_plane_fomulation (line 952) | def _get_plane_fomulation(self, vector1, vector2, point):
FILE: mmdet3d/models/roi_heads/part_aggregation_roi_head.py
class PartAggregationROIHead (line 12) | class PartAggregationROIHead(Base3DRoIHead):
method __init__ (line 25) | def __init__(self,
method init_weights (line 46) | def init_weights(self, pretrained):
method init_mask_head (line 51) | def init_mask_head(self):
method init_bbox_head (line 56) | def init_bbox_head(self, bbox_head):
method init_assigner_sampler (line 60) | def init_assigner_sampler(self):
method with_semantic (line 74) | def with_semantic(self):
method forward_train (line 79) | def forward_train(self, feats_dict, voxels_dict, img_metas, proposal_l...
method simple_test (line 121) | def simple_test(self, feats_dict, voxels_dict, img_metas, proposal_list,
method _bbox_forward_train (line 164) | def _bbox_forward_train(self, seg_feats, part_feats, voxels_dict,
method _bbox_forward (line 191) | def _bbox_forward(self, seg_feats, part_feats, voxels_dict, rois):
method _assign_and_sample (line 222) | def _assign_and_sample(self, proposal_list, gt_bboxes_3d, gt_labels_3d):
method _semantic_forward_train (line 296) | def _semantic_forward_train(self, x, voxels_dict, gt_bboxes_3d,
FILE: mmdet3d/models/roi_heads/roi_extractors/single_roiaware_extractor.py
class Single3DRoIAwareExtractor (line 9) | class Single3DRoIAwareExtractor(nn.Module):
method __init__ (line 18) | def __init__(self, roi_layer=None):
method build_roi_layers (line 22) | def build_roi_layers(self, layer_cfg):
method forward (line 31) | def forward(self, feats, coordinate, batch_inds, rois):
FILE: mmdet3d/models/utils/clip_sigmoid.py
function clip_sigmoid (line 4) | def clip_sigmoid(x, eps=1e-4):
FILE: mmdet3d/models/utils/deformable_decoder.py
class DeformableTransformerDecoderLayer (line 20) | class DeformableTransformerDecoderLayer(nn.Module):
method __init__ (line 21) | def __init__(self, d_model, nhead, level_num=4, dim_feedforward=2048, ...
method with_pos_embed (line 56) | def with_pos_embed(self, tensor, pos_embed):
method forward (line 59) | def forward(self, query, key, query_pos, key_pos, reference_points, le...
FILE: mmdet3d/models/utils/depth_encoder.py
class DepthEncoderResNet (line 9) | class DepthEncoderResNet(nn.Module):
method __init__ (line 10) | def __init__(self, input_channel, input_channel_img, hidden_channel, d...
method _make_layer (line 37) | def _make_layer(self, block, planes, blocks, stride=1):
method forward (line 54) | def forward(self, sparse_depth, img_inputs):
FILE: mmdet3d/models/utils/drop.py
function drop_path (line 11) | def drop_path(x: torch.Tensor,
class DropPath (line 32) | class DropPath(nn.Module):
method __init__ (line 43) | def __init__(self, drop_prob: float = 0.1):
method forward (line 47) | def forward(self, x: torch.Tensor) -> torch.Tensor:
class Dropout (line 52) | class Dropout(nn.Dropout):
method __init__ (line 63) | def __init__(self, drop_prob: float = 0.5, inplace: bool = False):
function build_dropout (line 67) | def build_dropout(cfg: Dict, default_args: Optional[Dict] = None) -> Any:
FILE: mmdet3d/models/utils/ffn.py
class FFN (line 13) | class FFN(nn.Module):
method __init__ (line 14) | def __init__(self,
method init_weights (line 75) | def init_weights(self):
method forward (line 85) | def forward(self, x):
class FFNLN (line 115) | class FFNLN(nn.Module):
method __init__ (line 116) | def __init__(self,
method init_weights (line 167) | def init_weights(self):
method forward (line 177) | def forward(self, x):
class FFNReg (line 208) | class FFNReg(nn.Module):
method __init__ (line 209) | def __init__(self,
method init_weights (line 248) | def init_weights(self):
method forward (line 258) | def forward(self, x):
FILE: mmdet3d/models/utils/inverse_sigmoid.py
function inverse_sigmoid (line 3) | def inverse_sigmoid(x, eps=1e-5):
FILE: mmdet3d/models/utils/mlp.py
class MLP (line 5) | class MLP(nn.Module):
method __init__ (line 23) | def __init__(self,
method forward (line 47) | def forward(self, img_features):
FILE: mmdet3d/models/utils/network_modules.py
function denormalize_pos (line 7) | def denormalize_pos(normal_pos, x_max, y_max, sigmoid=True):
function normalize_pos (line 16) | def normalize_pos(pos, x_max, y_max):
class LayerNorm (line 22) | class LayerNorm(nn.Module):
method __init__ (line 29) | def __init__(self, normalized_shape, eps=1e-6, data_format="channels_l...
method forward (line 39) | def forward(self, x):
class ConvLN (line 49) | class ConvLN(nn.Module):
method __init__ (line 50) | def __init__(self, input_channel, hidden_channel, kernel_size=3, stri...
method forward (line 64) | def forward(self, x):
class SE_Block (line 69) | class SE_Block(nn.Module):
method __init__ (line 70) | def __init__(self, c):
method forward (line 77) | def forward(self, x):
FILE: mmdet3d/models/utils/ops/functions/ms_deform_attn_func.py
class MSDeformAttnFunction (line 21) | class MSDeformAttnFunction(Function):
method forward (line 23) | def forward(ctx, value, value_spatial_shapes, value_level_start_index,...
method backward (line 32) | def backward(ctx, grad_output):
function ms_deform_attn_core_pytorch (line 41) | def ms_deform_attn_core_pytorch(value, value_spatial_shapes, sampling_lo...
FILE: mmdet3d/models/utils/ops/modules/ms_deform_attn.py
function _is_power_of_2 (line 24) | def _is_power_of_2(n):
class MSDeformAttn (line 30) | class MSDeformAttn(nn.Module):
method __init__ (line 31) | def __init__(self, d_model=256, n_levels=4, n_heads=8, n_points=4):
method _reset_parameters (line 62) | def _reset_parameters(self):
method forward (line 78) | def forward(self, query, reference_points, input_flatten, input_spatia...
FILE: mmdet3d/models/utils/ops/setup.py
function get_extensions (line 23) | def get_extensions():
FILE: mmdet3d/models/utils/ops/src/cpu/ms_deform_attn_cpu.cpp
function ms_deform_attn_cpu_forward (line 17) | at::Tensor
function ms_deform_attn_cpu_backward (line 29) | std::vector<at::Tensor>
FILE: mmdet3d/models/utils/ops/src/ms_deform_attn.h
function im2col_step (line 27) | int im2col_step)
FILE: mmdet3d/models/utils/ops/src/vision.cpp
function PYBIND11_MODULE (line 13) | PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
FILE: mmdet3d/models/utils/ops/test.py
function check_forward_equal_with_pytorch_double (line 32) | def check_forward_equal_with_pytorch_double():
function check_forward_equal_with_pytorch_float (line 48) | def check_forward_equal_with_pytorch_float():
function check_gradient_numerical (line 63) | def check_gradient_numerical(channels=4, grad_value=True, grad_sampling_...
FILE: mmdet3d/models/utils/projection.py
class PointProjection (line 5) | class PointProjection(nn.Module):
method __init__ (line 6) | def __init__(self, pos_channel, hidden_channel):
method forward (line 20) | def forward(self, query_feat, query_pos):
class ImageProjection (line 26) | class ImageProjection(nn.Module):
method __init__ (line 27) | def __init__(self, pos_channel, hidden_channel):
method forward (line 41) | def forward(self, query_feat, query_pos):
class ProjectionL2Norm (line 48) | class ProjectionL2Norm(nn.Module):
method __init__ (line 49) | def __init__(self, hidden_channel):
method forward (line 54) | def forward(self, query_feat):
class ProjectionLayerNorm (line 60) | class ProjectionLayerNorm(nn.Module):
method __init__ (line 61) | def __init__(self, hidden_channel, norm=True, input_channel=None):
method forward (line 71) | def forward(self, query_feat):
class Projection_wPos (line 79) | class Projection_wPos(nn.Module):
method __init__ (line 80) | def __init__(self, hidden_channel, pos_embed):
method forward (line 86) | def forward(self, query_feat, query_pos):
FILE: mmdet3d/models/utils/sparsefusion_models.py
class PointTransformer2D_3D (line 14) | class PointTransformer2D_3D(nn.Module):
method __init__ (line 15) | def __init__(self, hidden_channel, num_heads, num_decoder_layers, pred...
method forward (line 33) | def forward(self, pts_query_feat, pts_query_pos, lidar_feat_flatten, b...
class CameraSE (line 54) | class CameraSE(nn.Module):
method __init__ (line 55) | def __init__(self, cam_dim, hidden_channel):
method forward (line 68) | def forward(self, feat, cam_info):
class ImageTransformer_Cam_3D_MS (line 74) | class ImageTransformer_Cam_3D_MS(nn.Module):
method __init__ (line 75) | def __init__(self, num_views, hidden_channel, num_heads, num_decoder_l...
method forward (line 101) | def forward(self, img_query_feat, normal_img_query_pos, img_query_view...
method transform_bbox (line 227) | def transform_bbox(self, ret_dict, camera_info, width, img_metas):
class ViewTransformer (line 260) | class ViewTransformer(nn.Module):
method __init__ (line 261) | def __init__(self, hidden_channel, num_heads, prediction_heads, ffn_ch...
method forward (line 284) | def forward(self, img_query_feat, img_query_pos_bev, normal_img_query_...
class FusionTransformer2D_3D_Self (line 335) | class FusionTransformer2D_3D_Self(nn.Module):
method __init__ (line 336) | def __init__(self, hidden_channel, num_heads, num_decoder_layers, pred...
method forward (line 359) | def forward(self, pts_query_feat, pts_query_pos, img_query_feat, img_q...
class ImageTransformer2D_3D_MS (line 394) | class ImageTransformer2D_3D_MS(nn.Module):
method __init__ (line 395) | def __init__(self, num_views, hidden_channel, num_heads, num_decoder_l...
method forward (line 416) | def forward(self, img_query_feat, normal_img_query_pos, img_query_view...
method camera2lidar (line 482) | def camera2lidar(self, camera_coords, lidar2img, img_meta, batch_size):
FILE: mmdet3d/models/utils/transformer.py
function _ntuple (line 23) | def _ntuple(n):
class GELU (line 33) | class GELU(nn.Module):
method forward (line 50) | def forward(self, input: torch.Tensor) -> torch.Tensor:
class ModuleList (line 59) | class ModuleList(BaseModule, nn.ModuleList):
method __init__ (line 66) | def __init__(self,
class Sequential (line 72) | class Sequential(BaseModule, nn.Sequential):
method __init__ (line 78) | def __init__(self, *args, init_cfg: Optional[dict] = None):
function build_positional_encoding (line 82) | def build_positional_encoding(cfg, default_args=None):
function build_attention (line 87) | def build_attention(cfg, default_args=None):
function build_feedforward_network (line 92) | def build_feedforward_network(cfg, default_args=None):
function build_transformer_layer (line 97) | def build_transformer_layer(cfg, default_args=None):
function build_transformer_layer_sequence (line 102) | def build_transformer_layer_sequence(cfg, default_args=None):
class AdaptivePadding (line 107) | class AdaptivePadding(nn.Module):
method __init__ (line 142) | def __init__(self, kernel_size=1, stride=1, dilation=1, padding='corne...
method get_pad_shape (line 155) | def get_pad_shape(self, input_shape):
method forward (line 176) | def forward(self, x):
class PatchEmbed (line 197) | class PatchEmbed(BaseModule):
method __init__ (line 225) | def __init__(self,
method forward (line 297) | def forward(self, x):
class PatchMerging (line 321) | class PatchMerging(BaseModule):
method __init__ (line 353) | def __init__(self,
method forward (line 402) | def forward(self, x, input_size):
class MultiheadAttention (line 451) | class MultiheadAttention(BaseModule):
method __init__ (line 473) | def __init__(self,
method forward (line 505) | def forward(self,
class FFN (line 599) | class FFN(BaseModule):
method __init__ (line 627) | def __init__(self,
method forward (line 662) | def forward(self, x, identity=None):
class BaseTransformerLayer (line 676) | class BaseTransformerLayer(BaseModule):
method __init__ (line 712) | def __init__(self,
method forward (line 805) | def forward(self,
class TransformerLayerSequence (line 907) | class TransformerLayerSequence(BaseModule):
method __init__ (line 926) | def __init__(self, transformerlayers=None, num_layers=None, init_cfg=N...
method forward (line 942) | def forward(self,
FILE: mmdet3d/models/utils/transformerdecoder.py
class PositionEmbeddingLearnedLN (line 25) | class PositionEmbeddingLearnedLN(nn.Module):
method __init__ (line 30) | def __init__(self, input_channel, num_pos_feats=288):
method forward (line 39) | def forward(self, xyz):
class PositionEmbeddingLearned (line 44) | class PositionEmbeddingLearned(nn.Module):
method __init__ (line 49) | def __init__(self, input_channel, num_pos_feats=288):
method forward (line 57) | def forward(self, xyz):
class PositionEmbeddingLearnedwoNorm (line 62) | class PositionEmbeddingLearnedwoNorm(nn.Module):
method __init__ (line 67) | def __init__(self, input_channel, num_pos_feats=288):
method forward (line 75) | def forward(self, xyz):
class PositionEmbeddingLearnedMulti (line 80) | class PositionEmbeddingLearnedMulti(nn.Module):
method __init__ (line 85) | def __init__(self, input_channel, num_pos_feats=288, pos_num=2):
method forward (line 97) | def forward(self, xyzs):
class PositionEmbeddingLearnedMultiInput (line 110) | class PositionEmbeddingLearnedMultiInput(nn.Module):
method __init__ (line 111) | def __init__(self, input_channels, num_pos_feats=288):
method forward (line 119) | def forward(self, xyzs):
class TransformerDecoderLayer (line 130) | class TransformerDecoderLayer(nn.Module):
method __init__ (line 131) | def __init__(self, d_model, nhead, dim_feedforward=2048, dropout=0.1, ...
method with_pos_embed (line 166) | def with_pos_embed(self, tensor, pos_embed):
method forward (line 169) | def forward(self, query, key, query_pos, key_pos, attn_mask=None, need...
class MultiheadAttention (line 215) | class MultiheadAttention(nn.Module):
method __init__ (line 239) | def __init__(self, embed_dim, num_heads, dropout=0., bias=True, add_bi...
method _reset_parameters (line 275) | def _reset_parameters(self):
method forward (line 291) | def forward(self, query, key, value, key_padding_mask=None, need_weigh...
function multi_head_attention_forward (line 345) | def multi_head_attention_forward(query, # type: Tensor
FILE: mmdet3d/models/voxel_encoders/pillar_encoder.py
class PillarFeatureNet (line 12) | class PillarFeatureNet(nn.Module):
method __init__ (line 39) | def __init__(self,
method forward (line 91) | def forward(self, features, num_points, coors):
class DynamicPillarFeatureNet (line 154) | class DynamicPillarFeatureNet(PillarFeatureNet):
method __init__ (line 181) | def __init__(self,
method map_voxel_center_to_point (line 223) | def map_voxel_center_to_point(self, pts_coors, voxel_mean, voxel_coors):
method forward (line 263) | def forward(self, features, coors):
FILE: mmdet3d/models/voxel_encoders/utils.py
function get_paddings_indicator (line 8) | def get_paddings_indicator(actual_num, max_num, axis=0):
class VFELayer (line 31) | class VFELayer(nn.Module):
method __init__ (line 48) | def __init__(self,
method forward (line 64) | def forward(self, inputs):
class PFNLayer (line 106) | class PFNLayer(nn.Module):
method __init__ (line 122) | def __init__(self,
method forward (line 144) | def forward(self, inputs, num_voxels=None, aligned_distance=None):
FILE: mmdet3d/models/voxel_encoders/voxel_encoder.py
class HardSimpleVFE (line 13) | class HardSimpleVFE(nn.Module):
method __init__ (line 22) | def __init__(self, num_features=4):
method forward (line 28) | def forward(self, features, num_points, coors):
class DynamicSimpleVFE (line 48) | class DynamicSimpleVFE(nn.Module):
method __init__ (line 59) | def __init__(self,
method forward (line 68) | def forward(self, features, coors):
class DynamicVFE (line 87) | class DynamicVFE(nn.Module):
method __init__ (line 116) | def __init__(self,
method map_voxel_center_to_point (line 176) | def map_voxel_center_to_point(self, pts_coors, voxel_mean, voxel_coors):
method forward (line 219) | def forward(self,
class HardVFE (line 287) | class HardVFE(nn.Module):
method __init__ (line 315) | def __init__(self,
method forward (line 384) | def forward(self,
method fusion_with_mask (line 452) | def fusion_with_mask(self, features, mask, voxel_feats, coors, img_feats,
FILE: mmdet3d/ops/ball_query/ball_query.py
class BallQuery (line 7) | class BallQuery(Function):
method forward (line 14) | def forward(ctx, min_radius: float, max_radius: float, sample_num: int,
method backward (line 43) | def backward(ctx, a=None):
FILE: mmdet3d/ops/ball_query/src/ball_query.cpp
function ball_query_wrapper (line 30) | int ball_query_wrapper(int b, int n, int m, float min_radius, float max_...
function PYBIND11_MODULE (line 45) | PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
FILE: mmdet3d/ops/furthest_point_sample/furthest_point_sample.py
class FurthestPointSampling (line 7) | class FurthestPointSampling(Function):
method forward (line 15) | def forward(ctx, points_xyz: torch.Tensor,
method backward (line 38) | def backward(xyz, a=None):
class FurthestPointSamplingWithDist (line 42) | class FurthestPointSamplingWithDist(Function):
method forward (line 50) | def forward(ctx, points_dist: torch.Tensor,
method backward (line 73) | def backward(xyz, a=None):
FILE: mmdet3d/ops/furthest_point_sample/points_sampler.py
function get_sampler_type (line 11) | def get_sampler_type(sampler_type):
class Points_Sampler (line 34) | class Points_Sampler(nn.Module):
method __init__ (line 48) | def __init__(self,
method forward (line 66) | def forward(self, points_xyz, features):
class DFPS_Sampler (line 102) | class DFPS_Sampler(nn.Module):
method __init__ (line 108) | def __init__(self):
method forward (line 111) | def forward(self, points, features, npoint):
class FFPS_Sampler (line 117) | class FFPS_Sampler(nn.Module):
method __init__ (line 123) | def __init__(self):
method forward (line 126) | def forward(self, points, features, npoint):
class FS_Sampler (line 135) | class FS_Sampler(nn.Module):
method __init__ (line 141) | def __init__(self):
method forward (line 144) | def forward(self, points, features, npoint):
FILE: mmdet3d/ops/furthest_point_sample/src/furthest_point_sample.cpp
function furthest_point_sampling_wrapper (line 32) | int furthest_point_sampling_wrapper(int b, int n, int m,
function furthest_point_sampling_with_dist_wrapper (line 45) | int furthest_point_sampling_with_dist_wrapper(int b, int n, int m,
function PYBIND11_MODULE (line 59) | PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
FILE: mmdet3d/ops/furthest_point_sample/utils.py
function calc_square_dist (line 4) | def calc_square_dist(point_feat_a, point_feat_b, norm=True):
FILE: mmdet3d/ops/gather_points/gather_points.py
class GatherPoints (line 7) | class GatherPoints(Function):
method forward (line 14) | def forward(ctx, features: torch.Tensor,
method backward (line 40) | def backward(ctx, grad_out):
FILE: mmdet3d/ops/gather_points/src/gather_points.cpp
function gather_points_wrapper (line 28) | int gather_points_wrapper(int b, int c, int n, int npoints,
function gather_points_grad_wrapper (line 40) | int gather_points_grad_wrapper(int b, int c, int n, int npoints,
function PYBIND11_MODULE (line 54) | PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
FILE: mmdet3d/ops/group_points/group_points.py
class QueryAndGroup (line 10) | class QueryAndGroup(nn.Module):
method __init__ (line 32) | def __init__(self,
method forward (line 53) | def forward(self, points_xyz, center_xyz, features=None):
class GroupAll (line 112) | class GroupAll(nn.Module):
method __init__ (line 121) | def __init__(self, use_xyz: bool = True):
method forward (line 125) | def forward(self,
class GroupingOperation (line 153) | class GroupingOperation(Function):
method forward (line 160) | def forward(ctx, features: torch.Tensor,
method backward (line 186) | def backward(ctx,
FILE: mmdet3d/ops/group_points/src/group_points.cpp
function group_points_grad_wrapper (line 31) | int group_points_grad_wrapper(int b, int c, int n, int npoints, int nsam...
function group_points_wrapper (line 45) | int group_points_wrapper(int b, int c, int n, int npoints, int nsample,
function PYBIND11_MODULE (line 59) | PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
FILE: mmdet3d/ops/interpolate/src/interpolate.cpp
function three_nn_wrapper (line 46) | void three_nn_wrapper(int b, int n, int m, at::Tensor unknown_tensor,
function three_interpolate_wrapper (line 58) | void three_interpolate_wrapper(int b, int c, int m, int n,
function three_interpolate_grad_wrapper (line 72) | void three_interpolate_grad_wrapper(int b, int c, int n, int m,
function PYBIND11_MODULE (line 87) | PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
FILE: mmdet3d/ops/interpolate/three_interpolate.py
class ThreeInterpolate (line 8) | class ThreeInterpolate(Function):
method forward (line 11) | def forward(ctx, features: torch.Tensor, indices: torch.Tensor,
method backward (line 39) | def backward(
FILE: mmdet3d/ops/interpolate/three_nn.py
class ThreeNN (line 8) | class ThreeNN(Function):
method forward (line 11) | def forward(ctx, target: torch.Tensor,
method backward (line 41) | def backward(ctx, a=None, b=None):
FILE: mmdet3d/ops/iou3d/iou3d_utils.py
function boxes_iou_bev (line 6) | def boxes_iou_bev(boxes_a, boxes_b):
function nms_gpu (line 25) | def nms_gpu(boxes, scores, thresh, pre_maxsize=None, post_max_size=None):
function nms_normal_gpu (line 53) | def nms_normal_gpu(boxes, scores, thresh):
FILE: mmdet3d/ops/iou3d/src/iou3d.cpp
function gpuAssert (line 29) | inline void gpuAssert(cudaError_t code, const char *file, int line,
function boxes_overlap_bev_gpu (line 50) | int boxes_overlap_bev_gpu(at::Tensor boxes_a, at::Tensor boxes_b,
function boxes_iou_bev_gpu (line 73) | int boxes_iou_bev_gpu(at::Tensor boxes_a, at::Tensor boxes_b,
function nms_gpu (line 95) | int nms_gpu(at::Tensor boxes, at::Tensor keep,
function nms_normal_gpu (line 149) | int nms_normal_gpu(at::Tensor boxes, at::Tensor keep,
function PYBIND11_MODULE (line 203) | PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
FILE: mmdet3d/ops/knn/knn.py
class KNN (line 7) | class KNN(Function):
method forward (line 14) | def forward(ctx,
method backward (line 65) | def backward(ctx, a=None):
FILE: mmdet3d/ops/knn/src/knn.cpp
function knn_wrapper (line 26) | void knn_wrapper(
function PYBIND11_MODULE (line 60) | PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
FILE: mmdet3d/ops/norm.py
class AllReduce (line 9) | class AllReduce(Function):
method forward (line 12) | def forward(ctx, input):
method backward (line 22) | def backward(ctx, grad_output):
class NaiveSyncBatchNorm1d (line 28) | class NaiveSyncBatchNorm1d(nn.BatchNorm1d):
method __init__ (line 46) | def __init__(self, *args, **kwargs):
method forward (line 54) | def forward(self, input):
class NaiveSyncBatchNorm2d (line 82) | class NaiveSyncBatchNorm2d(nn.BatchNorm2d):
method __init__ (line 100) | def __init__(self, *args, **kwargs):
method forward (line 108) | def forward(self, input):
FILE: mmdet3d/ops/pointnet_modules/builder.py
function build_sa_module (line 4) | def build_sa_module(cfg, *args, **kwargs):
FILE: mmdet3d/ops/pointnet_modules/point_fp_module.py
class PointFPModule (line 10) | class PointFPModule(nn.Module):
method __init__ (line 21) | def __init__(self,
method forward (line 39) | def forward(self, target: torch.Tensor, source: torch.Tensor,
FILE: mmdet3d/ops/pointnet_modules/point_sa_module.py
class PointSAModuleMSG (line 12) | class PointSAModuleMSG(nn.Module):
method __init__ (line 44) | def __init__(self,
method forward (line 121) | def forward(
class PointSAModule (line 183) | class PointSAModule(PointSAModuleMSG):
method __init__ (line 209) | def __init__(self,
FILE: mmdet3d/ops/roiaware_pool3d/points_in_boxes.py
function points_in_boxes_gpu (line 6) | def points_in_boxes_gpu(points, boxes):
function points_in_boxes_cpu (line 53) | def points_in_boxes_cpu(points, boxes):
function points_in_boxes_batch (line 85) | def points_in_boxes_batch(points, boxes):
FILE: mmdet3d/ops/roiaware_pool3d/roiaware_pool3d.py
class RoIAwarePool3d (line 9) | class RoIAwarePool3d(nn.Module):
method __init__ (line 11) | def __init__(self, out_size, max_pts_per_voxel=128, mode='max'):
method forward (line 26) | def forward(self, rois, pts, pts_feature):
class RoIAwarePool3dFunction (line 44) | class RoIAwarePool3dFunction(Function):
method forward (line 47) | def forward(ctx, rois, pts, pts_feature, out_size, max_pts_per_voxel,
method backward (line 91) | def backward(ctx, grad_out):
FILE: mmdet3d/ops/roiaware_pool3d/src/points_in_boxes_cpu.cpp
function lidar_to_local_coords_cpu (line 16) | inline void lidar_to_local_coords_cpu(float shift_x, float shift_y, floa...
function check_pt_in_box3d_cpu (line 25) | inline int check_pt_in_box3d_cpu(const float *pt, const float *box3d,
function points_in_boxes_cpu (line 42) | int points_in_boxes_cpu(at::Tensor boxes_tensor, at::Tensor pts_tensor,
FILE: mmdet3d/ops/roiaware_pool3d/src/roiaware_pool3d.cpp
function roiaware_pool3d_gpu (line 49) | int roiaware_pool3d_gpu(at::Tensor rois, at::Tensor pts, at::Tensor pts_...
function roiaware_pool3d_gpu_backward (line 92) | int roiaware_pool3d_gpu_backward(at::Tensor pts_idx_of_voxels,
function PYBIND11_MODULE (line 126) | PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
FILE: mmdet3d/ops/sparse_block.py
function replace_feature (line 7) | def replace_feature(out, new_features):
class SparseBottleneck (line 15) | class SparseBottleneck(Bottleneck, spconv.SparseModule):
method __init__ (line 33) | def __init__(self,
method forward (line 51) | def forward(self, x):
class SparseBasicBlock (line 81) | class SparseBasicBlock(BasicBlock, spconv.SparseModule):
method __init__ (line 99) | def __init__(self,
method forward (line 116) | def forward(self, x):
function make_sparse_convmodule (line 142) | def make_sparse_convmodule(in_channels,
FILE: mmdet3d/ops/spconv/conv.py
function _calculate_fan_in_and_fan_out_hwio (line 27) | def _calculate_fan_in_and_fan_out_hwio(tensor):
class SparseConvolution (line 48) | class SparseConvolution(SparseModule):
method __init__ (line 50) | def __init__(self,
method reset_parameters (line 106) | def reset_parameters(self):
method forward (line 113) | def forward(self, input):
class SparseConv2d (line 208) | class SparseConv2d(SparseConvolution):
method __init__ (line 210) | def __init__(self,
class SparseConv3d (line 234) | class SparseConv3d(SparseConvolution):
method __init__ (line 236) | def __init__(self,
class SparseConv4d (line 260) | class SparseConv4d(SparseConvolution):
method __init__ (line 262) | def __init__(self,
class SparseConvTranspose2d (line 286) | class SparseConvTranspose2d(SparseConvolution):
method __init__ (line 288) | def __init__(self,
class SparseConvTranspose3d (line 313) | class SparseConvTranspose3d(SparseConvolution):
method __init__ (line 315) | def __init__(self,
class SparseInverseConv2d (line 340) | class SparseInverseConv2d(SparseConvolution):
method __init__ (line 342) | def __init__(self,
class SparseInverseConv3d (line 359) | class SparseInverseConv3d(SparseConvolution):
method __init__ (line 361) | def __init__(self,
class SubMConv2d (line 378) | class SubMConv2d(SparseConvolution):
method __init__ (line 380) | def __init__(self,
class SubMConv3d (line 405) | class SubMConv3d(SparseConvolution):
method __init__ (line 407) | def __init__(self,
class SubMConv4d (line 432) | class SubMConv4d(SparseConvolution):
method __init__ (line 434) | def __init__(self,
FILE: mmdet3d/ops/spconv/functional.py
class SparseConvFunction (line 20) | class SparseConvFunction(Function):
method forward (line 23) | def forward(ctx, features, filters, indice_pairs, indice_pair_num,
method backward (line 30) | def backward(ctx, grad_output):
class SparseInverseConvFunction (line 39) | class SparseInverseConvFunction(Function):
method forward (line 42) | def forward(ctx, features, filters, indice_pairs, indice_pair_num,
method backward (line 49) | def backward(ctx, grad_output):
class SubMConvFunction (line 58) | class SubMConvFunction(Function):
method forward (line 61) | def forward(ctx, features, filters, indice_pairs, indice_pair_num,
method backward (line 68) | def backward(ctx, grad_output):
class SparseMaxPoolFunction (line 77) | class SparseMaxPoolFunction(Function):
method forward (line 80) | def forward(ctx, features, indice_pairs, indice_pair_num,
method backward (line 88) | def backward(ctx, grad_output):
FILE: mmdet3d/ops/spconv/include/paramsgrid.h
function namespace (line 20) | namespace detail {
FILE: mmdet3d/ops/spconv/include/prettyprint.h
function namespace (line 25) | namespace pretty_print {
type custom_delims_base (line 385) | struct custom_delims_base {
type T (line 429) | typedef const T *const_iterator;
type T (line 430) | typedef T value_type;
type typename (line 447) | typedef typename T::const_local_iterator const_iterator;
type typename (line 448) | typedef typename T::size_type size_type;
function namespace (line 480) | namespace std {
FILE: mmdet3d/ops/spconv/include/spconv/fused_spconv_ops.h
function namespace (line 25) | namespace spconv {
FILE: mmdet3d/ops/spconv/include/spconv/geometry.h
function namespace (line 23) | namespace spconv {
FILE: mmdet3d/ops/spconv/include/spconv/indice.cu.h
function namespace (line 21) | namespace spconv {
function assignGridAndIndiceOutKernel (line 113) | void assignGridAndIndiceOutKernel(
function prepareSubMGridKernel (line 148) | void prepareSubMGridKernel(
function resetGridKernel (line 206) | void resetGridKernel(const Index *indicePairUnique,
FILE: mmdet3d/ops/spconv/include/spconv/indice.h
function namespace (line 19) | namespace spconv {
FILE: mmdet3d/ops/spconv/include/spconv/maxpool.h
function namespace (line 19) | namespace spconv {
FILE: mmdet3d/ops/spconv/include/spconv/mp_helper.h
function namespace (line 6) | namespace spconv {
FILE: mmdet3d/ops/spconv/include/spconv/point2voxel.h
function namespace (line 28) | namespace spconv {
FILE: mmdet3d/ops/spconv/include/spconv/pool_ops.h
function namespace (line 24) | namespace spconv {
FILE: mmdet3d/ops/spconv/include/spconv/reordering.cu.h
function namespace (line 20) | namespace spconv {
function gatherVecKernel (line 49) | void gatherVecKernel(T *buffer, const T *features,
function scatterAddGenericKernel (line 100) | void scatterAddGenericKernel(T *outFeatures, const T *buffer,
FILE: mmdet3d/ops/spconv/include/spconv/reordering.h
function namespace (line 19) | namespace spconv {
FILE: mmdet3d/ops/spconv/include/spconv/spconv_ops.h
function indicePairUnique (line 70) | auto indicePairUnique = torch::full(
FILE: mmdet3d/ops/spconv/include/tensorview/helper_kernel.cu.h
function namespace (line 3) | namespace tv {
FILE: mmdet3d/ops/spconv/include/tensorview/helper_launch.h
function namespace (line 4) | namespace tv
FILE: mmdet3d/ops/spconv/include/tensorview/tensorview.h
function namespace (line 28) | namespace tv {
type GPU (line 104) | struct GPU {
type CPU (line 109) | struct CPU {}
type size_type (line 188) | typedef size_t size_type;
function class (line 190) | class iterator {
function rowArrayIdx (line 401) | unsigned rowArrayIdx(std::vector<int> &shape,
function rowArrayIdx (line 417) | TV_HOST_DEVICE_INLINE unsigned rowArrayIdx(std::vector<int> &shape,
function rowArrayIdx (line 429) | unsigned rowArrayIdx(const Shape &shape,
function rowArrayIdx (line 442) | TV_HOST_DEVICE_INLINE unsigned rowArrayIdx(const Shape &shape,
function rowArrayIdx (line 454) | unsigned rowArrayIdx(const Index *indexes,
function Index (line 467) | Index rowArrayIdxInv(Index index, Index *output,
function TV_HOST_DEVICE_INLINE (line 481) | TV_HOST_DEVICE_INLINE static unsigned run(const Shape &shape,
type ArrayIndexRowMajor (line 489) | struct ArrayIndexRowMajor
function TV_HOST_DEVICE_INLINE (line 490) | TV_HOST_DEVICE_INLINE static unsigned run(const Shape &shape,
function namespace (line 496) | namespace detail {
function TV_HOST_DEVICE_INLINE (line 527) | TV_HOST_DEVICE_INLINE TensorView() {}
function explicit (line 528) | explicit TV_HOST_DEVICE_INLINE TensorView(T *ptr, Shape shape)
function TV_HOST_DEVICE_INLINE (line 534) | TV_HOST_DEVICE_INLINE TensorView(T *ptr, Integers... shapes)
function TV_HOST_DEVICE_INLINE (line 589) | TV_HOST_DEVICE_INLINE T &operator()() {
function TV_HOST_DEVICE_INLINE (line 828) | TV_HOST_DEVICE_INLINE T &operator[](int idx) {
function TV_HOST_DEVICE_INLINE (line 866) | TV_HOST_DEVICE_INLINE T *data() { return mPtr; }
function TV_HOST_DEVICE_INLINE (line 867) | TV_HOST_DEVICE_INLINE const T *data() const { return mPtr; }
function TV_HOST_DEVICE_INLINE (line 869) | TV_HOST_DEVICE_INLINE int dim(int idx) const { return mShape[idx]; }
function Shape (line 873) | Shape shapes{int(newShapes)...};
function Shape (line 885) | Shape shapes{int(newShapes)...};
function Shape (line 916) | Shape new_shape{to_slice(slices)[0]...};
function Slice (line 1053) | Slice to_slice(T1 s) const {
function TV_HOST_DEVICE_INLINE (line 1057) | TV_HOST_DEVICE_INLINE Slice to_slice(Slice s) const { return Slice(s); }
function namespace (line 1075) | namespace detail {
function printTensorView (line 1105) | void printTensorView(const TensorView<T> tensor,
function printTensorView (line 1152) | void printTensorView(const T *ptr, Shape shape) {
function printTensorView (line 1158) | void printTensorView(const T *ptr, Shape shape,
FILE: mmdet3d/ops/spconv/include/torch_utils.h
function namespace (line 21) | namespace tv {
FILE: mmdet3d/ops/spconv/modules.py
function is_spconv_module (line 22) | def is_spconv_module(module):
function is_sparse_conv (line 27) | def is_sparse_conv(module):
function _mean_update (line 32) | def _mean_update(vals, m_vals, t):
class SparseModule (line 46) | class SparseModule(nn.Module):
class SparseSequential (line 52) | class SparseSequential(SparseModule):
method __init__ (line 85) | def __init__(self, *args, **kwargs):
method __getitem__ (line 101) | def __getitem__(self, idx):
method __len__ (line 111) | def __len__(self):
method sparity_dict (line 115) | def sparity_dict(self):
method add (line 118) | def add(self, module, name=None):
method forward (line 125) | def forward(self, input):
method fused (line 139) | def fused(self):
class ToDense (line 190) | class ToDense(SparseModule):
method forward (line 193) | def forward(self, x: SparseConvTensor):
class RemoveGrid (line 197) | class RemoveGrid(SparseModule):
method forward (line 200) | def forward(self, x: SparseConvTensor):
FILE: mmdet3d/ops/spconv/ops.py
function get_conv_output_size (line 20) | def get_conv_output_size(input_size, kernel_size, stride, padding, dilat...
function get_deconv_output_size (line 33) | def get_deconv_output_size(input_size, kernel_size, stride, padding, dil...
function get_indice_pairs (line 46) | def get_indice_pairs(indices,
function indice_conv (line 108) | def indice_conv(features,
function fused_indice_conv (line 129) | def fused_indice_conv(features, filters, bias, indice_pairs, indice_pair...
function indice_conv_backward (line 142) | def indice_conv_backward(features,
function indice_maxpool (line 161) | def indice_maxpool(features, indice_pairs, indice_pair_num, num_activate...
function indice_maxpool_backward (line 174) | def indice_maxpool_backward(features, out_features, out_bp, indice_pairs,
FILE: mmdet3d/ops/spconv/overwrite_spconv/write_spconv2.py
function register_spconv2 (line 8) | def register_spconv2():
function _save_to_state_dict (line 42) | def _save_to_state_dict(self, destination, prefix, keep_vars):
function _load_from_state_dict (line 61) | def _load_from_state_dict(self, state_dict, prefix, local_metadata, strict,
FILE: mmdet3d/ops/spconv/pool.py
class SparseMaxPool (line 21) | class SparseMaxPool(SparseModule):
method __init__ (line 23) | def __init__(self,
method forward (line 47) | def forward(self, input):
class SparseMaxPool2d (line 74) | class SparseMaxPool2d(SparseMaxPool):
method __init__ (line 76) | def __init__(self, kernel_size, stride=1, padding=0, dilation=1):
class SparseMaxPool3d (line 81) | class SparseMaxPool3d(SparseMaxPool):
method __init__ (line 83) | def __init__(self, kernel_size, stride=1, padding=0, dilation=1):
FILE: mmdet3d/ops/spconv/src/all.cc
function PYBIND11_MODULE (line 21) | PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
FILE: mmdet3d/ops/spconv/src/indice.cc
type spconv (line 20) | namespace spconv {
type functor (line 22) | namespace functor {
type CreateConvIndicePairFunctor<tv::CPU, Index, IndexGrid, NDim> (line 24) | struct CreateConvIndicePairFunctor<tv::CPU, Index, IndexGrid, NDim> {
method Index (line 25) | Index operator()(const tv::CPU& d, tv::TensorView<const Index> ind...
type CreateSubMIndicePairFunctor<tv::CPU, Index, IndexGrid, NDim> (line 49) | struct CreateSubMIndicePairFunctor<tv::CPU, Index, IndexGrid, NDim> {
method Index (line 50) | Index operator()(const tv::CPU& d, tv::TensorView<const Index> ind...
FILE: mmdet3d/ops/spconv/src/maxpool.cc
type spconv (line 18) | namespace spconv {
type functor (line 20) | namespace functor {
type SparseMaxPoolForwardFunctor<tv::CPU, T, Index> (line 22) | struct SparseMaxPoolForwardFunctor<tv::CPU, T, Index> {
type SparseMaxPoolBackwardFunctor<tv::CPU, T, Index> (line 43) | struct SparseMaxPoolBackwardFunctor<tv::CPU, T, Index> {
FILE: mmdet3d/ops/spconv/src/reordering.cc
type spconv (line 18) | namespace spconv {
type functor (line 19) | namespace functor {
type SparseGatherFunctor<tv::CPU, T, Index> (line 21) | struct SparseGatherFunctor<tv::CPU, T, Index> {
type SparseScatterAddFunctor<tv::CPU, T, Index> (line 35) | struct SparseScatterAddFunctor<tv::CPU, T, Index> {
FILE: mmdet3d/ops/spconv/structure.py
function scatter_nd (line 5) | def scatter_nd(indices, updates, shape):
class SparseConvTensor (line 21) | class SparseConvTensor(object):
method __init__ (line 23) | def __init__(self,
method spatial_size (line 45) | def spatial_size(self):
method find_indice_pair (line 48) | def find_indice_pair(self, key):
method dense (line 55) | def dense(self, channels_first=True):
method sparity (line 67) | def sparity(self):
FILE: mmdet3d/ops/spconv/test_utils.py
class TestCase (line 18) | class TestCase(unittest.TestCase):
method _GetNdArray (line 20) | def _GetNdArray(self, a):
method assertAllEqual (line 25) | def assertAllEqual(self, a, b):
method assertAllClose (line 56) | def assertAllClose(self, a, b, rtol=1e-6, atol=1e-6):
method _assertArrayLikeAllClose (line 90) | def _assertArrayLikeAllClose(self, a, b, rtol=1e-6, atol=1e-6, msg=None):
function params_grid (line 123) | def params_grid(*params):
function generate_sparse_data (line 144) | def generate_sparse_data(shape,
FILE: mmdet3d/ops/voxel/scatter_points.py
class _dynamic_scatter (line 9) | class _dynamic_scatter(Function):
method forward (line 12) | def forward(ctx, feats, coors, reduce_type='max'):
method backward (line 37) | def backward(ctx, grad_voxel_feats, grad_voxel_coors=None):
class DynamicScatter (line 53) | class DynamicScatter(nn.Module):
method __init__ (line 55) | def __init__(self, voxel_size, point_cloud_range, average_points: bool):
method forward_single (line 74) | def forward_single(self, points, coors):
method forward (line 78) | def forward(self, points, coors):
method __repr__ (line 101) | def __repr__(self):
FILE: mmdet3d/ops/voxel/src/scatter_points_cpu.cpp
function determin_max_points_kernel (line 8) | void determin_max_points_kernel(
function scatter_point_to_voxel_kernel (line 39) | void scatter_point_to_voxel_kernel(
type voxelization (line 61) | namespace voxelization {
function dynamic_point_to_voxel_cpu (line 63) | std::vector<at::Tensor> dynamic_point_to_voxel_cpu(
FILE: mmdet3d/ops/voxel/src/voxelization.cpp
type voxelization (line 4) | namespace voxelization {
function PYBIND11_MODULE (line 6) | PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
FILE: mmdet3d/ops/voxel/src/voxelization.h
type reduce_t (line 4) | typedef enum { SUM = 0, MEAN = 1, MAX = 2 } reduce_t;
function namespace (line 6) | namespace voxelization {
function reduce_t (line 85) | inline reduce_t convert_reduce_type(const std::string &reduce_type) {
function std (line 96) | inline std::vector<torch::Tensor> dynamic_point_to_voxel_forward(const t...
function dynamic_point_to_voxel_backward (line 110) | inline void dynamic_point_to_voxel_backward(torch::Tensor &grad_feats,
FILE: mmdet3d/ops/voxel/src/voxelization_cpu.cpp
function dynamic_voxelize_kernel (line 8) | void dynamic_voxelize_kernel(const torch::TensorAccessor<T, 2> points,
function hard_voxelize_kernel (line 44) | void hard_voxelize_kernel(const torch::TensorAccessor<T, 2> points,
type voxelization (line 103) | namespace voxelization {
function hard_voxelize_cpu (line 105) | int hard_voxelize_cpu(const at::Tensor& points, at::Tensor& voxels,
function dynamic_voxelize_cpu (line 144) | void dynamic_voxelize_cpu(const at::Tensor& points, at::Tensor& coors,
FILE: mmdet3d/ops/voxel/voxelize.py
class _Voxelization (line 10) | class _Voxelization(Function):
method forward (line 13) | def forward(ctx,
class Voxelization (line 64) | class Voxelization(nn.Module):
method __init__ (line 66) | def __init__(self,
method forward (line 102) | def forward(self, input):
method __repr__ (line 115) | def __repr__(self):
FILE: mmdet3d/utils/collect_env.py
function collect_env (line 8) | def collect_env():
FILE: mmdet3d/version.py
function parse_version_info (line 7) | def parse_version_info(version_str):
FILE: setup.py
function readme (line 9) | def readme():
function get_version (line 18) | def get_version():
function make_cuda_ext (line 30) | def make_cuda_ext(name,
function parse_requirements (line 62) | def parse_requirements(fname='requirements.txt', with_version=True):
FILE: tests/test_data/test_datasets/test_dataset_wrappers.py
function test_getitem (line 7) | def test_getitem():
FILE: tests/test_data/test_datasets/test_kitti_dataset.py
function _generate_kitti_dataset_config (line 11) | def _generate_kitti_dataset_config():
function test_getitem (line 50) | def test_getitem():
function test_evaluate (line 116) | def test_evaluate():
function test_show (line 138) | def test_show():
function test_format_results (line 169) | def test_format_results():
function test_bbox2result_kitti (line 207) | def test_bbox2result_kitti():
function test_bbox2result_kitti2d (line 252) | def test_bbox2result_kitti2d():
FILE: tests/test_data/test_datasets/test_lyft_dataset.py
function test_getitem (line 8) | def test_getitem():
function test_evaluate (line 109) | def test_evaluate():
FILE: tests/test_data/test_datasets/test_nuscene_dataset.py
function test_getitem (line 6) | def test_getitem():
FILE: tests/test_data/test_datasets/test_scannet_dataset.py
function test_getitem (line 8) | def test_getitem():
function test_evaluate (line 115) | def test_evaluate():
function test_show (line 168) | def test_show():
FILE: tests/test_data/test_datasets/test_semantickitti_dataset.py
function test_getitem (line 6) | def test_getitem():
FILE: tests/test_data/test_datasets/test_sunrgbd_dataset.py
function test_getitem (line 8) | def test_getitem():
function test_evaluate (line 99) | def test_evaluate():
function test_show (line 126) | def test_show():
FILE: tests/test_data/test_pipelines/test_augmentations/test_data_augment_utils.py
function test_noise_per_object_v3_ (line 8) | def test_noise_per_object_v3_():
function test_points_transform (line 30) | def test_points_transform():
FILE: tests/test_data/test_pipelines/test_augmentations/test_test_augment_utils.py
function test_multi_scale_flip_aug_3D (line 8) | def test_multi_scale_flip_aug_3D():
FILE: tests/test_data/test_pipelines/test_augmentations/test_transforms_3d.py
function test_remove_points_in_boxes (line 13) | def test_remove_points_in_boxes():
function test_object_sample (line 41) | def test_object_sample():
function test_object_noise (line 106) | def test_object_noise():
function test_random_flip_3d (line 142) | def test_random_flip_3d():
function test_background_points_filter (line 199) | def test_background_points_filter():
function test_voxel_based_point_filter (line 242) | def test_voxel_based_point_filter():
FILE: tests/test_data/test_pipelines/test_indoor_pipeline.py
function test_scannet_pipeline (line 10) | def test_scannet_pipeline():
function test_sunrgbd_pipeline (line 107) | def test_sunrgbd_pipeline():
FILE: tests/test_data/test_pipelines/test_indoor_sample.py
function test_indoor_sample (line 7) | def test_indoor_sample():
FILE: tests/test_data/test_pipelines/test_loadings/test_load_points_from_multi_sweeps.py
function test_load_points_from_multi_sweeps (line 7) | def test_load_points_from_multi_sweeps():
FILE: tests/test_data/test_pipelines/test_loadings/test_loading.py
function test_load_points_from_indoor_file (line 12) | def test_load_points_from_indoor_file():
function test_load_points_from_outdoor_file (line 44) | def test_load_points_from_outdoor_file():
function test_load_annotations3D (line 69) | def test_load_annotations3D():
function test_load_points_from_multi_sweeps (line 120) | def test_load_points_from_multi_sweeps():
FILE: tests/test_data/test_pipelines/test_outdoor_pipeline.py
function test_outdoor_aug_pipeline (line 8) | def test_outdoor_aug_pipeline():
function test_outdoor_velocity_aug_pipeline (line 128) | def test_outdoor_velocity_aug_pipeline():
FILE: tests/test_metrics/test_indoor_eval.py
function test_indoor_eval (line 8) | def test_indoor_eval():
function test_indoor_eval_less_classes (line 133) | def test_indoor_eval_less_classes():
function test_average_precision (line 183) | def test_average_precision():
FILE: tests/test_metrics/test_kitti_eval.py
function test_do_eval (line 9) | def test_do_eval():
function test_kitti_eval (line 112) | def test_kitti_eval():
function test_eval_class (line 189) | def test_eval_class():
FILE: tests/test_metrics/test_losses.py
function test_chamfer_disrance (line 5) | def test_chamfer_disrance():
FILE: tests/test_metrics/test_seg_eval.py
function test_indoor_eval (line 8) | def test_indoor_eval():
FILE: tests/test_models/test_backbones.py
function test_pointnet2_sa_ssg (line 8) | def test_pointnet2_sa_ssg():
function test_multi_backbone (line 45) | def test_multi_backbone():
function test_pointnet2_sa_msg (line 156) | def test_pointnet2_sa_msg():
FILE: tests/test_models/test_common_modules/test_middle_encoders.py
function test_sparse_encoder (line 7) | def test_sparse_encoder():
FILE: tests/test_models/test_common_modules/test_pointnet_modules.py
function test_pointnet_sa_module_msg (line 6) | def test_pointnet_sa_module_msg():
function test_pointnet_sa_module (line 137) | def test_pointnet_sa_module():
function test_pointnet_fp_module (line 169) | def test_pointnet_fp_module():
FILE: tests/test_models/test_common_modules/test_pointnet_ops.py
function test_fps (line 9) | def test_fps():
function test_ball_query (line 26) | def test_ball_query():
function test_knn (line 76) | def test_knn():
function test_grouping_points (line 126) | def test_grouping_points():
function test_gather_points (line 198) | def test_gather_points():
function test_three_interpolate (line 240) | def test_three_interpolate():
function test_three_nn (line 310) | def test_three_nn():
function test_fps_with_dist (line 377) | def test_fps_with_dist():
FILE: tests/test_models/test_common_modules/test_roiaware_pool3d.py
function test_RoIAwarePool3d (line 9) | def test_RoIAwarePool3d():
function test_points_in_boxes_gpu (line 43) | def test_points_in_boxes_gpu():
function test_points_in_boxes_cpu (line 75) | def test_points_in_boxes_cpu():
function test_points_in_boxes_batch (line 97) | def test_points_in_boxes_batch():
FILE: tests/test_models/test_common_modules/test_sparse_unet.py
function test_SparseUNet (line 7) | def test_SparseUNet():
function test_SparseBasicBlock (line 52) | def test_SparseBasicBlock():
function test_make_sparse_convmodule (line 85) | def test_make_sparse_convmodule():
FILE: tests/test_models/test_common_modules/test_vote_module.py
function test_vote_module (line 4) | def test_vote_module():
FILE: tests/test_models/test_detectors.py
function _setup_seed (line 12) | def _setup_seed(seed):
function _get_config_directory (line 20) | def _get_config_directory():
function _get_config_module (line 35) | def _get_config_module(fname):
function _get_model_cfg (line 44) | def _get_model_cfg(fname):
function _get_detector_cfg (line 56) | def _get_detector_cfg(fname):
function test_get_dynamic_voxelnet (line 73) | def test_get_dynamic_voxelnet():
function test_voxel_net (line 87) | def test_voxel_net():
function test_3dssd (line 124) | def test_3dssd():
function test_vote_net (line 165) | def test_vote_net():
function test_parta2 (line 208) | def test_parta2():
function test_centerpoint (line 250) | def test_centerpoint():
FILE: tests/test_models/test_forward.py
function _get_config_directory (line 13) | def _get_config_directory():
function _get_config_module (line 28) | def _get_config_module(fname):
function _get_detector_cfg (line 37) | def _get_detector_cfg(fname):
function _test_two_stage_forward (line 48) | def _test_two_stage_forward(cfg_file):
function _test_single_stage_forward (line 106) | def _test_single_stage_forward(cfg_file):
function _demo_mm_inputs (line 142) | def _demo_mm_inputs(input_shape=(1, 3, 300, 300),
FILE: tests/test_models/test_fusion/test_fusion_coord_trans.py
function test_coords_transformation (line 12) | def test_coords_transformation():
FILE: tests/test_models/test_fusion/test_point_fusion.py
function test_sample_single (line 12) | def test_sample_single():
FILE: tests/test_models/test_fusion/test_vote_fusion.py
function test_vote_fusion (line 12) | def test_vote_fusion():
FILE: tests/test_models/test_heads/test_heads.py
function _setup_seed (line 14) | def _setup_seed(seed):
function _get_config_directory (line 22) | def _get_config_directory():
function _get_config_module (line 37) | def _get_config_module(fname):
function _get_head_cfg (line 46) | def _get_head_cfg(fname):
function _get_rpn_head_cfg (line 64) | def _get_rpn_head_cfg(fname):
function _get_roi_head_cfg (line 82) | def _get_roi_head_cfg(fname):
function _get_pts_bbox_head_cfg (line 100) | def _get_pts_bbox_head_cfg(fname):
function _get_vote_head_cfg (line 118) | def _get_vote_head_cfg(fname):
function _get_parta2_bbox_head_cfg (line 136) | def _get_parta2_bbox_head_cfg(fname):
function test_anchor3d_head_loss (line 149) | def test_anchor3d_head_loss():
function test_anchor3d_head_getboxes (line 201) | def test_anchor3d_head_getboxes():
function test_parta2_rpnhead_getboxes (line 232) | def test_parta2_rpnhead_getboxes():
function test_vote_head (line 265) | def test_vote_head():
function test_parta2_bbox_head (line 360) | def test_parta2_bbox_head():
function test_part_aggregation_ROI_head (line 372) | def test_part_aggregation_ROI_head():
function test_free_anchor_3D_head (line 446) | def test_free_anchor_3D_head():
function test_primitive_head (line 478) | def test_primitive_head():
function test_h3d_head (line 591) | def test_h3d_head():
function test_center_head (line 693) | def test_center_head():
function test_dcn_center_head (line 768) | def test_dcn_center_head():
function test_ssd3d_head (line 888) | def test_ssd3d_head():
function test_shape_aware_head_loss (line 950) | def test_shape_aware_head_loss():
function test_shape_aware_head_getboxes (line 1014) | def test_shape_aware_head_getboxes():
FILE: tests/test_models/test_heads/test_parta2_bbox_head.py
function test_loss (line 13) | def test_loss():
function test_get_targets (line 85) | def test_get_targets():
function test_get_bboxes (line 254) | def test_get_bboxes():
function test_multi_class_nms (line 359) | def test_multi_class_nms():
function test_make_sparse_convmodule (line 437) | def test_make_sparse_convmodule():
FILE: tests/test_models/test_heads/test_roi_extractors.py
function test_single_roiaware_extractor (line 7) | def test_single_roiaware_extractor():
FILE: tests/test_models/test_heads/test_semantic_heads.py
function test_PointwiseSemanticHead (line 7) | def test_PointwiseSemanticHead():
FILE: tests/test_models/test_necks/test_fpn.py
function test_secfpn (line 4) | def test_secfpn():
FILE: tests/test_models/test_necks/test_necks.py
function test_centerpoint_fpn (line 6) | def test_centerpoint_fpn():
FILE: tests/test_models/test_voxel_encoder/test_dynamic_scatter.py
function test_dynamic_scatter (line 8) | def test_dynamic_scatter():
FILE: tests/test_models/test_voxel_encoder/test_voxel_encoders.py
function test_pillar_feature_net (line 6) | def test_pillar_feature_net():
function test_hard_simple_VFE (line 26) | def test_hard_simple_VFE():
FILE: tests/test_models/test_voxel_encoder/test_voxel_generator.py
function test_voxel_generator (line 6) | def test_voxel_generator():
FILE: tests/test_models/test_voxel_encoder/test_voxelize.py
function _get_voxel_points_indices (line 10) | def _get_voxel_points_indices(points, coors, voxel):
function test_voxelization (line 15) | def test_voxelization():
FILE: tests/test_runtime/test_apis.py
function _get_config_directory (line 17) | def _get_config_directory():
function _get_config_module (line 32) | def _get_config_module(fname):
function test_convert_SyncBN (line 41) | def test_convert_SyncBN():
function test_show_result_meshlab (line 51) | def test_show_result_meshlab():
function test_inference_detector (line 83) | def test_inference_detector():
function test_single_gpu_test (line 98) | def test_single_gpu_test():
FILE: tests/test_runtime/test_config.py
function _get_config_directory (line 4) | def _get_config_directory():
function test_config_build_detector (line 19) | def test_config_build_detector():
function test_config_build_pipeline (line 73) | def test_config_build_pipeline():
function _check_roi_head (line 101) | def _check_roi_head(config, head):
function _check_roi_extractor (line 129) | def _check_roi_extractor(config, roi_extractor, prev_roi_extractor=None):
function _check_mask_head (line 156) | def _check_mask_head(mask_cfg, mask_head):
function _check_bbox_head (line 174) | def _check_bbox_head(bbox_cfg, bbox_head):
function check_parta2_roi_head (line 198) | def check_parta2_roi_head(config, head):
function _check_parta2_roi_extractor (line 217) | def _check_parta2_roi_extractor(config, roi_extractor):
function _check_parta2_bbox_head (line 224) | def _check_parta2_bbox_head(bbox_cfg, bbox_head):
function check_h3d_roi_head (line 239) | def check_h3d_roi_head(config, head):
function _check_primitive_extractor (line 261) | def _check_primitive_extractor(config, primitive_extractor):
function _check_h3d_bbox_head (line 267) | def _check_h3d_bbox_head(bbox_cfg, bbox_head):
FILE: tests/test_utils/test_anchors.py
function test_anchor_3d_range_generator (line 12) | def test_anchor_3d_range_generator():
function test_aligned_anchor_generator (line 45) | def test_aligned_anchor_generator():
function test_aligned_anchor_generator_per_cls (line 186) | def test_aligned_anchor_generator_per_cls():
FILE: tests/test_utils/test_assigners.py
function test_max_iou_assigner (line 12) | def test_max_iou_assigner():
function test_max_iou_assigner_with_ignore (line 36) | def test_max_iou_assigner_with_ignore():
function test_max_iou_assigner_with_empty_gt (line 63) | def test_max_iou_assigner_with_empty_gt():
function test_max_iou_assigner_with_empty_boxes (line 82) | def test_max_iou_assigner_with_empty_boxes():
function test_max_iou_assigner_with_empty_boxes_and_ignore (line 106) | def test_max_iou_assigner_with_empty_boxes_and_ignore():
function test_max_iou_assigner_with_empty_boxes_and_gt (line 140) | def test_max_iou_assigner_with_empty_boxes_and_gt():
FILE: tests/test_utils/test_bbox_coders.py
function test_partial_bin_based_box_coder (line 7) | def test_partial_bin_based_box_coder():
function test_anchor_free_box_coder (line 221) | def test_anchor_free_box_coder():
function test_centerpoint_bbox_coder (line 328) | def test_centerpoint_bbox_coder():
FILE: tests/test_utils/test_box3d.py
function test_bbox3d_mapping_back (line 16) | def test_bbox3d_mapping_back():
function test_bbox3d2roi (line 43) | def test_bbox3d2roi():
function test_base_boxes3d (line 60) | def test_base_boxes3d():
function test_lidar_boxes3d (line 93) | def test_lidar_boxes3d():
function test_boxes_conversion (line 471) | def test_boxes_conversion():
function test_camera_boxes3d (line 616) | def test_camera_boxes3d():
function test_boxes3d_overlaps (line 897) | def test_boxes3d_overlaps():
function test_depth_boxes3d (line 964) | def test_depth_boxes3d():
function test_rotation_3d_in_axis (line 1197) | def test_rotation_3d_in_axis():
function test_limit_period (line 1215) | def test_limit_period():
function test_xywhr2xyxyr (line 1224) | def test_xywhr2xyxyr():
class test_get_box_type (line 1234) | class test_get_box_type(unittest.TestCase):
method test_get_box_type (line 1236) | def test_get_box_type(self):
method test_bad_box_type (line 1249) | def test_bad_box_type(self):
function test_points_cam2img (line 1253) | def test_points_cam2img():
FILE: tests/test_utils/test_box_np_ops.py
function test_camera_to_lidar (line 4) | def test_camera_to_lidar():
function test_box_camera_to_lidar (line 20) | def test_box_camera_to_lidar():
function test_corners_nd (line 37) | def test_corners_nd():
function test_center_to_corner_box2d (line 46) | def test_center_to_corner_box2d():
function test_rotation_2d (line 58) | def test_rotation_2d():
FILE: tests/test_utils/test_coord_3d_mode.py
function test_points_conversion (line 9) | def test_points_conversion():
function test_boxes_conversion (line 231) | def test_boxes_conversion():
FILE: tests/test_utils/test_merge_augs.py
function test_merge_aug_bboxes_3d (line 9) | def test_merge_aug_bboxes_3d():
FILE: tests/test_utils/test_nms.py
function test_aligned_3d_nms (line 5) | def test_aligned_3d_nms():
function test_circle_nms (line 61) | def test_circle_nms():
FILE: tests/test_utils/test_points.py
function test_base_points (line 8) | def test_base_points():
function test_cam_points (line 232) | def test_cam_points():
function test_lidar_points (line 506) | def test_lidar_points():
function test_depth_points (line 780) | def test_depth_points():
FILE: tests/test_utils/test_samplers.py
function test_iou_piecewise_sampler (line 8) | def test_iou_piecewise_sampler():
FILE: tests/test_utils/test_utils.py
function test_gaussian (line 6) | def test_gaussian():
FILE: tools/analysis_tools/analyze_logs.py
function cal_train_time (line 9) | def cal_train_time(log_dicts, args):
function plot_curve (line 32) | def plot_curve(log_dicts, args):
function add_plot_parser (line 92) | def add_plot_parser(subparsers):
function add_time_parser (line 122) | def add_time_parser(subparsers):
function parse_args (line 138) | def parse_args():
function load_json_logs (line 148) | def load_json_logs(json_logs):
function main (line 168) | def main():
FILE: tools/analysis_tools/benchmark.py
function parse_args (line 14) | def parse_args():
function main (line 30) | def main():
FILE: tools/analysis_tools/get_flops.py
function parse_args (line 15) | def parse_args():
function main (line 44) | def main():
FILE: tools/combine_view_info.py
function project_to_image (line 13) | def project_to_image(points, cam_int, cam_ext, img_h, img_w):
function combine_data (line 34) | def combine_data(data_root, info_file, coco_file, output_file):
FILE: tools/create_data.py
function kitti_data_prep (line 11) | def kitti_data_prep(root_path, info_prefix, version, out_dir):
function nuscenes_data_prep (line 35) | def nuscenes_data_prep(root_path,
function lyft_data_prep (line 70) | def lyft_data_prep(root_path,
function scannet_data_prep (line 110) | def scannet_data_prep(root_path, info_prefix, out_dir, workers):
function sunrgbd_data_prep (line 123) | def sunrgbd_data_prep(root_path, info_prefix, out_dir, workers):
function waymo_data_prep (line 136) | def waymo_data_prep(root_path,
FILE: tools/data_converter/create_gt_database.py
function _poly2mask (line 15) | def _poly2mask(mask_ann, img_h, img_w):
function _parse_coco_ann_info (line 31) | def _parse_coco_ann_info(ann_info):
function crop_image_patch_v2 (line 68) | def crop_image_patch_v2(pos_proposals, pos_assigned_gt_inds, gt_masks):
function crop_image_patch (line 88) | def crop_image_patch(pos_proposals, gt_masks, pos_assigned_gt_inds, org_...
function create_groundtruth_database (line 108) | def create_groundtruth_database(dataset_class_name,
FILE: tools/data_converter/indoor_converter.py
function create_indoor_info_file (line 8) | def create_indoor_info_file(data_path,
FILE: tools/data_converter/kitti_converter.py
function convert_to_kitti_info_version2 (line 9) | def convert_to_kitti_info_version2(info):
function _read_imageset_file (line 34) | def _read_imageset_file(path):
function _calculate_num_points_in_gt (line 40) | def _calculate_num_points_in_gt(data_path,
function create_kitti_info_file (line 81) | def create_kitti_info_file(data_path,
function create_waymo_info_file (line 144) | def create_waymo_info_file(data_path,
function _create_reduced_point_cloud (line 224) | def _create_reduced_point_cloud(data_path,
function create_reduced_point_cloud (line 283) | def create_reduced_point_cloud(data_path,
FILE: tools/data_converter/kitti_data_utils.py
function get_image_index_str (line 9) | def get_image_index_str(img_idx, use_prefix_id=False):
function get_kitti_info_path (line 16) | def get_kitti_info_path(idx,
function get_image_path (line 39) | def get_image_path(idx,
function get_label_path (line 50) | def get_label_path(idx,
function get_velodyne_path (line 61) | def get_velodyne_path(idx,
function get_calib_path (line 71) | def get_calib_path(idx,
function get_pose_path (line 81) | def get_pose_path(idx,
function get_label_anno (line 91) | def get_label_anno(label_path):
function _extend_matrix (line 135) | def _extend_matrix(mat):
function get_kitti_image_info (line 140) | def get_kitti_image_info(path,
function get_waymo_image_info (line 264) | def get_waymo_image_info(path,
function kitti_anno_to_label_file (line 443) | def kitti_anno_to_label_file(annos, folder):
function add_difficulty_to_annos (line 466) | def add_difficulty_to_annos(info):
function kitti_result_line (line 511) | def kitti_result_line(result_dict, precision=4):
FILE: tools/data_converter/lyft_converter.py
function create_lyft_infos (line 16) | def create_lyft_infos(root_path,
function _fill_trainval_infos (line 91) | def _fill_trainval_infos(lyft,
function export_2d_annotation (line 212) | def export_2d_annotation(root_path, info_path, version):
FILE: tools/data_converter/nuimage_converter.py
function parse_args (line 31) | def parse_args():
function get_img_annos (line 62) | def get_img_annos(nuim, img_info, cat2id, out_dir, data_root, seg_root):
function export_nuim_to_coco (line 149) | def export_nuim_to_coco(nuim, data_root, out_dir, extra_tag, version, np...
function main (line 214) | def main():
FILE: tools/data_converter/nuscenes_converter.py
function create_nuscenes_infos (line 19) | def create_nuscenes_infos(root_path,
function get_available_scenes (line 96) | def get_available_scenes(nusc):
function _fill_trainval_infos (line 137) | def _fill_trainval_infos(nusc,
function obtain_sensor2top (line 266) | def obtain_sensor2top(nusc,
function export_2d_annotation (line 327) | def export_2d_annotation(root_path, info_path, version):
function get_2d_boxes (line 378) | def get_2d_boxes(nusc, sample_data_token: str,
function post_process_coords (line 464) | def post_process_coords(
function generate_record (line 497) | def generate_record(ann_rec: dict, x1: float, y1: float, x2: float, y2: ...
FILE: tools/data_converter/scannet_data_utils.py
class ScanNetData (line 7) | class ScanNetData(object):
method __init__ (line 17) | def __init__(self, root_path, split='train'):
method __len__ (line 41) | def __len__(self):
method get_box_label (line 44) | def get_box_label(self, idx):
method get_infos (line 50) | def get_infos(self, num_workers=4, has_label=True, sample_id_list=None):
FILE: tools/data_converter/sunrgbd_data_utils.py
function random_sampling (line 8) | def random_sampling(points, num_points, replace=None, return_choices=Fal...
class SUNRGBDInstance (line 32) | class SUNRGBDInstance(object):
method __init__ (line 34) | def __init__(self, line):
class SUNRGBDData (line 58) | class SUNRGBDData(object):
method __init__ (line 69) | def __init__(self, root_path, split='train', use_v1=False):
method __len__ (line 94) | def __len__(self):
method get_image (line 97) | def get_image(self, idx):
method get_image_shape (line 101) | def get_image_shape(self, idx):
method get_depth (line 105) | def get_depth(self, idx):
method get_calibration (line 110) | def get_calibration(self, idx):
method get_label_objects (line 119) | def get_label_objects(self, idx):
method get_infos (line 125) | def get_infos(self, num_workers=4, has_label=True, sample_id_list=None):
FILE: tools/data_converter/waymo_converter.py
class Waymo2KITTI (line 22) | class Waymo2KITTI(object):
method __init__ (line 37) | def __init__(self,
method convert (line 91) | def convert(self):
method convert_one (line 98) | def convert_one(self, file_idx):
method __len__ (line 124) | def __len__(self):
method save_image (line 128) | def save_image(self, frame, file_idx, frame_idx):
method save_calib (line 143) | def save_calib(self, frame, file_idx, frame_idx):
method save_lidar (line 199) | def save_lidar(self, frame, file_idx, frame_idx):
method save_label (line 249) | def save_label(self, frame, file_idx, frame_idx):
method save_pose (line 349) | def save_pose(self, frame, file_idx, frame_idx):
method create_folder (line 368) | def create_folder(self):
method convert_range_image_to_point_cloud (line 388) | def convert_range_image_to_point_cloud(self,
method cart_to_homo (line 496) | def cart_to_homo(self, mat):
FILE: tools/misc/fuse_conv_bn.py
function fuse_conv_bn (line 9) | def fuse_conv_bn(conv, bn):
function fuse_module (line 25) | def fuse_module(m):
function parse_args (line 46) | def parse_args():
function main (line 56) | def main():
FILE: tools/misc/print_config.py
function parse_args (line 5) | def parse_args():
function main (line 15) | def main():
FILE: tools/misc/visualize_results.py
function parse_args (line 8) | def parse_args():
function main (line 20) | def main():
FILE: tools/model_converters/convert_votenet_checkpoints.py
function parse_args (line 10) | def parse_args():
function parse_config (line 19) | def parse_config(config_strings):
function main (line 69) | def main():
FILE: tools/model_converters/publish_model.py
function parse_args (line 6) | def parse_args():
function process_checkpoint (line 15) | def process_checkpoint(in_file, out_file):
function main (line 28) | def main():
FILE: tools/model_converters/regnet2mmdet.py
function convert_stem (line 6) | def convert_stem(model_key, model_weight, state_dict, converted_names):
function convert_head (line 14) | def convert_head(model_key, model_weight, state_dict, converted_names):
function convert_reslayer (line 21) | def convert_reslayer(model_key, model_weight, state_dict, converted_names):
function convert (line 53) | def convert(src, dst):
function main (line 79) | def main():
FILE: tools/test.py
function parse_args (line 19) | def parse_args():
function main (line 101) | def main():
FILE: tools/train.py
function parse_args (line 22) | def parse_args():
function main (line 91) | def main():
Condensed preview — 516 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (3,426K chars).
[
{
"path": ".gitignore",
"chars": 1544,
"preview": "# Byte-compiled / optimized / DLL files\r\n__pycache__/\r\n*.py[cod]\r\n*$py.class\r\n*.ipynb\r\n\r\n# C extensions\r\n*.so\r\n\r\n# Distr"
},
{
"path": "LICENSE",
"chars": 11400,
"preview": "Copyright 2018-2019 Open-MMLab. All rights reserved.\n\n Apache License\n "
},
{
"path": "MANIFEST.in",
"chars": 147,
"preview": "include requirements/*.txt\ninclude mmdet3d/ops/**/*.cpp mmdet3d/ops/**/*.cu\ninclude mmdet3d/ops/**/*.h mmdet3d/ops/**/*."
},
{
"path": "README.md",
"chars": 6116,
"preview": "# [ICCV 2023] SparseFusion: Fusing Multi-Modal Sparse Representations for Multi-Sensor 3D Object Detection\n\n# yapf:disable push\n# By default we use textlogger hook and tensorboard\n# For more "
},
{
"path": "configs/_base_/models/3dssd.py",
"chars": 3448,
"preview": "model = dict(\n type='SSD3DNet',\n backbone=dict(\n type='PointNet2SAMSG',\n in_channels=4,\n num_"
},
{
"path": "configs/_base_/models/cascade_mask_rcnn_r50_fpn.py",
"chars": 6976,
"preview": "# model settings\nmodel = dict(\n type='CascadeRCNN',\n pretrained='torchvision://resnet50',\n backbone=dict(\n "
},
{
"path": "configs/_base_/models/centerpoint_01voxel_second_secfpn_nus.py",
"chars": 3275,
"preview": "voxel_size = [0.1, 0.1, 0.2]\nmodel = dict(\n type='CenterPoint',\n pts_voxel_layer=dict(\n max_num_points=10, "
},
{
"path": "configs/_base_/models/centerpoint_02pillar_second_secfpn_nus.py",
"chars": 3183,
"preview": "voxel_size = [0.2, 0.2, 8]\nmodel = dict(\n type='CenterPoint',\n pts_voxel_layer=dict(\n max_num_points=20, vo"
},
{
"path": "configs/_base_/models/h3dnet.py",
"chars": 10970,
"preview": "primitive_z_cfg = dict(\n type='PrimitiveHead',\n num_dims=2,\n num_classes=18,\n primitive_mode='z',\n upper_"
},
{
"path": "configs/_base_/models/hv_pointpillars_fpn_lyft.py",
"chars": 963,
"preview": "_base_ = './hv_pointpillars_fpn_nus.py'\n\n# model settings (based on nuScenes model settings)\n# Voxel size for voxel enco"
},
{
"path": "configs/_base_/models/hv_pointpillars_fpn_nus.py",
"chars": 3314,
"preview": "# model settings\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n"
},
{
"path": "configs/_base_/models/hv_pointpillars_fpn_range100_lyft.py",
"chars": 975,
"preview": "_base_ = './hv_pointpillars_fpn_nus.py'\n\n# model settings (based on nuScenes model settings)\n# Voxel size for voxel enco"
},
{
"path": "configs/_base_/models/hv_pointpillars_secfpn_kitti.py",
"chars": 3072,
"preview": "voxel_size = [0.16, 0.16, 4]\nmodel = dict(\n type='VoxelNet',\n voxel_layer=dict(\n max_num_points=32,\n "
},
{
"path": "configs/_base_/models/hv_pointpillars_secfpn_waymo.py",
"chars": 3987,
"preview": "# model settings\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n"
},
{
"path": "configs/_base_/models/hv_second_secfpn_kitti.py",
"chars": 2884,
"preview": "model = dict(\n type='VoxelNet',\n voxel_layer=dict(\n max_num_points=5,\n point_cloud_range=[0, -40, -3"
},
{
"path": "configs/_base_/models/hv_second_secfpn_waymo.py",
"chars": 3503,
"preview": "# model settings\n# Voxel size for voxel encoder\n# Usually voxel size is changed consistently with the point cloud range\n"
},
{
"path": "configs/_base_/models/imvotenet_image.py",
"chars": 3499,
"preview": "model = dict(\n type='ImVoteNet',\n img_backbone=dict(\n type='ResNet',\n depth=50,\n num_stages=4"
},
{
"path": "configs/_base_/models/mask_rcnn_r50_fpn.py",
"chars": 4080,
"preview": "# model settings\nmodel = dict(\n type='MaskRCNN',\n pretrained='torchvision://resnet50',\n backbone=dict(\n "
},
{
"path": "configs/_base_/models/votenet.py",
"chars": 2576,
"preview": "model = dict(\n type='VoteNet',\n backbone=dict(\n type='PointNet2SASSG',\n in_channels=4,\n num_p"
},
{
"path": "configs/_base_/schedules/cyclic_20e.py",
"chars": 761,
"preview": "# For nuScenes dataset, we usually evaluate the model at the end of training.\n# Since the models are trained by 24 epoch"
},
{
"path": "configs/_base_/schedules/cyclic_40e.py",
"chars": 1540,
"preview": "# The schedule is usually used by models trained on KITTI dataset\n\n# The learning rate set in the cyclic schedule is the"
},
{
"path": "configs/_base_/schedules/mmdet_schedule_1x.py",
"chars": 283,
"preview": "# optimizer\noptimizer = dict(type='SGD', lr=0.02, momentum=0.9, weight_decay=0.0001)\noptimizer_config = dict(grad_clip=N"
},
{
"path": "configs/_base_/schedules/schedule_2x.py",
"chars": 423,
"preview": "# optimizer\n# This schedule is mainly used by models on nuScenes dataset\noptimizer = dict(type='AdamW', lr=0.001, weight"
},
{
"path": "configs/_base_/schedules/schedule_3x.py",
"chars": 363,
"preview": "# optimizer\n# This schedule is mainly used by models on indoor dataset,\n# e.g., VoteNet on SUNRGBD and ScanNet\nlr = 0.00"
},
{
"path": "configs/benchmark/hv_PartA2_secfpn_4x8_cyclic_80e_pcdet_kitti-3d-3class.py",
"chars": 10982,
"preview": "# model settings\nvoxel_size = [0.05, 0.05, 0.1]\npoint_cloud_range = [0, -40, -3, 70.4, 40, 1] # velodyne coordinates, x"
},
{
"path": "configs/benchmark/hv_pointpillars_secfpn_3x8_100e_det3d_kitti-3d-car.py",
"chars": 6009,
"preview": "# model settings\nvoxel_size = [0.16, 0.16, 4]\npoint_cloud_range = [0, -39.68, -3, 69.12, 39.68, 1]\nmodel = dict(\n typ"
},
{
"path": "configs/benchmark/hv_pointpillars_secfpn_4x8_80e_pcdet_kitti-3d-3class.py",
"chars": 7208,
"preview": "# model settings\npoint_cloud_range = [0, -39.68, -3, 69.12, 39.68, 1]\nvoxel_size = [0.16, 0.16, 4]\nmodel = dict(\n typ"
},
{
"path": "configs/benchmark/hv_second_secfpn_4x8_80e_pcdet_kitti-3d-3class.py",
"chars": 7238,
"preview": "# model settings\nvoxel_size = [0.05, 0.05, 0.1]\npoint_cloud_range = [0, -40, -3, 70.4, 40, 1]\n\nmodel = dict(\n type='V"
},
{
"path": "configs/centerpoint/README.md",
"chars": 7827,
"preview": "# Center-based 3D Object Detection and Tracking\n\n## Introduction\n\n[ALGORITHM]\n\nWe implement CenterPoint and provide the "
},
{
"path": "configs/centerpoint/centerpoint_0075voxel_second_secfpn_4x8_cyclic_20e_nus.py",
"chars": 4386,
"preview": "_base_ = ['./centerpoint_01voxel_second_secfpn_4x8_cyclic_20e_nus.py']\n\n# If point cloud range is changed, the models sh"
},
{
"path": "configs/centerpoint/centerpoint_0075voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus.py",
"chars": 131,
"preview": "_base_ = ['./centerpoint_0075voxel_second_secfpn_4x8_cyclic_20e_nus.py']\n\nmodel = dict(test_cfg=dict(pts=dict(nms_type='"
},
{
"path": "configs/centerpoint/centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_20e_nus.py",
"chars": 442,
"preview": "_base_ = ['./centerpoint_0075voxel_second_secfpn_4x8_cyclic_20e_nus.py']\n\nmodel = dict(\n pts_bbox_head=dict(\n "
},
{
"path": "configs/centerpoint/centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_flip-tta_20e_nus.py",
"chars": 1576,
"preview": "_base_ = './centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_20e_nus.py'\n\npoint_cloud_range = [-54, -54, -5.0, 54, 54,"
},
{
"path": "configs/centerpoint/centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_tta_20e_nus.py",
"chars": 1653,
"preview": "_base_ = './centerpoint_0075voxel_second_secfpn_dcn_4x8_cyclic_20e_nus.py'\n\ntest_cfg = dict(pts=dict(use_rotate_nms=True"
},
{
"path": "configs/centerpoint/centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py",
"chars": 490,
"preview": "_base_ = ['./centerpoint_0075voxel_second_secfpn_4x8_cyclic_20e_nus.py']\n\nmodel = dict(\n pts_bbox_head=dict(\n "
},
{
"path": "configs/centerpoint/centerpoint_0075voxel_second_secfpn_dcn_circlenms_4x8_cyclic_flip-tta_20e_nus.py",
"chars": 1600,
"preview": "_base_ = './centerpoint_0075voxel_second_secfpn_dcn_' \\\n 'circlenms_4x8_cyclic_20e_nus.py'\n\npoint_cloud_range = "
},
{
"path": "configs/centerpoint/centerpoint_01voxel_second_secfpn_4x8_cyclic_20e_nus.py",
"chars": 4762,
"preview": "_base_ = [\n '../_base_/datasets/nus-3d.py',\n '../_base_/models/centerpoint_01voxel_second_secfpn_nus.py',\n '../"
},
{
"path": "configs/centerpoint/centerpoint_01voxel_second_secfpn_circlenms_4x8_cyclic_20e_nus.py",
"chars": 129,
"preview": "_base_ = ['./centerpoint_01voxel_second_secfpn_4x8_cyclic_20e_nus.py']\n\nmodel = dict(test_cfg=dict(pts=dict(nms_type='ci"
},
{
"path": "configs/centerpoint/centerpoint_01voxel_second_secfpn_dcn_4x8_cyclic_20e_nus.py",
"chars": 440,
"preview": "_base_ = ['./centerpoint_01voxel_second_secfpn_4x8_cyclic_20e_nus.py']\n\nmodel = dict(\n pts_bbox_head=dict(\n se"
},
{
"path": "configs/centerpoint/centerpoint_01voxel_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py",
"chars": 488,
"preview": "_base_ = ['./centerpoint_01voxel_second_secfpn_4x8_cyclic_20e_nus.py']\n\nmodel = dict(\n pts_bbox_head=dict(\n se"
},
{
"path": "configs/centerpoint/centerpoint_02pillar_second_secfpn_4x8_cyclic_20e_nus.py",
"chars": 4730,
"preview": "_base_ = [\n '../_base_/datasets/nus-3d.py',\n '../_base_/models/centerpoint_02pillar_second_secfpn_nus.py',\n '.."
},
{
"path": "configs/centerpoint/centerpoint_02pillar_second_secfpn_circlenms_4x8_cyclic_20e_nus.py",
"chars": 130,
"preview": "_base_ = ['./centerpoint_02pillar_second_secfpn_4x8_cyclic_20e_nus.py']\n\nmodel = dict(test_cfg=dict(pts=dict(nms_type='c"
},
{
"path": "configs/centerpoint/centerpoint_02pillar_second_secfpn_dcn_4x8_cyclic_20e_nus.py",
"chars": 441,
"preview": "_base_ = ['./centerpoint_02pillar_second_secfpn_4x8_cyclic_20e_nus.py']\n\nmodel = dict(\n pts_bbox_head=dict(\n s"
},
{
"path": "configs/centerpoint/centerpoint_02pillar_second_secfpn_dcn_circlenms_4x8_cyclic_20e_nus.py",
"chars": 489,
"preview": "_base_ = ['./centerpoint_02pillar_second_secfpn_4x8_cyclic_20e_nus.py']\n\nmodel = dict(\n pts_bbox_head=dict(\n s"
},
{
"path": "configs/dynamic_voxelization/README.md",
"chars": 2217,
"preview": "# Dynamic Voxelization\n\n## Introduction\n\n[ALGORITHM]\n\nWe implement Dynamic Voxelization proposed in and provide its res"
},
{
"path": "configs/dynamic_voxelization/dv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py",
"chars": 577,
"preview": "_base_ = '../pointpillars/hv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py'\n\nvoxel_size = [0.16, 0.16, 4]\npoint_cloud_ran"
},
{
"path": "configs/dynamic_voxelization/dv_second_secfpn_2x8_cosine_80e_kitti-3d-3class.py",
"chars": 906,
"preview": "_base_ = '../second/hv_second_secfpn_6x8_80e_kitti-3d-3class.py'\n\npoint_cloud_range = [0, -40, -3, 70.4, 40, 1]\nvoxel_si"
},
{
"path": "configs/dynamic_voxelization/dv_second_secfpn_6x8_80e_kitti-3d-car.py",
"chars": 518,
"preview": "_base_ = '../second/hv_second_secfpn_6x8_80e_kitti-3d-car.py'\n\npoint_cloud_range = [0, -40, -3, 70.4, 40, 1]\nvoxel_size "
},
{
"path": "configs/fp16/README.md",
"chars": 3227,
"preview": "# Mixed Precision Training\n\n## Introduction\n\n[OTHERS]\n\nWe implement mixed precision training and apply it to VoxelNets ("
},
{
"path": "configs/fp16/hv_pointpillars_fpn_sbn-all_fp16_2x8_2x_nus-3d.py",
"chars": 217,
"preview": "_base_ = '../pointpillars/hv_pointpillars_fpn_sbn-all_4x8_2x_nus-3d.py'\ndata = dict(samples_per_gpu=2, workers_per_gpu=2"
},
{
"path": "configs/fp16/hv_pointpillars_regnet-400mf_fpn_sbn-all_fp16_2x8_2x_nus-3d.py",
"chars": 224,
"preview": "_base_ = '../regnet/hv_pointpillars_regnet-400mf_fpn_sbn-all_4x8_2x_nus-3d.py'\ndata = dict(samples_per_gpu=2, workers_pe"
},
{
"path": "configs/fp16/hv_pointpillars_secfpn_sbn-all_fp16_2x8_2x_nus-3d.py",
"chars": 220,
"preview": "_base_ = '../pointpillars/hv_pointpillars_secfpn_sbn-all_4x8_2x_nus-3d.py'\ndata = dict(samples_per_gpu=2, workers_per_gp"
},
{
"path": "configs/fp16/hv_second_secfpn_fp16_6x8_80e_kitti-3d-3class.py",
"chars": 110,
"preview": "_base_ = '../second/hv_second_secfpn_6x8_80e_kitti-3d-3class.py'\n# fp16 settings\nfp16 = dict(loss_scale=512.)\n"
},
{
"path": "configs/fp16/hv_second_secfpn_fp16_6x8_80e_kitti-3d-car.py",
"chars": 107,
"preview": "_base_ = '../second/hv_second_secfpn_6x8_80e_kitti-3d-car.py'\n# fp16 settings\nfp16 = dict(loss_scale=512.)\n"
},
{
"path": "configs/free_anchor/README.md",
"chars": 7713,
"preview": "# FreeAnchor for 3D Object Detection\n\n## Introduction\n\n[ALGORITHM]\n\nWe implement FreeAnchor in 3D detection systems and "
},
{
"path": "configs/free_anchor/hv_pointpillars_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py",
"chars": 1605,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_nus.py',\n '../_base_/datasets/nus-3d.py', '../_base_/schedules/s"
},
{
"path": "configs/free_anchor/hv_pointpillars_regnet-1.6gf_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py",
"chars": 553,
"preview": "_base_ = './hv_pointpillars_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py'\n\nmodel = dict(\n pretrained=dict(pts='open-mmlab"
},
{
"path": "configs/free_anchor/hv_pointpillars_regnet-1.6gf_fpn_sbn-all_free-anchor_strong-aug_4x8_3x_nus-3d.py",
"chars": 2442,
"preview": "_base_ = './hv_pointpillars_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py'\n\nmodel = dict(\n pretrained=dict(pts='open-mmlab"
},
{
"path": "configs/free_anchor/hv_pointpillars_regnet-3.2gf_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py",
"chars": 554,
"preview": "_base_ = './hv_pointpillars_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py'\n\nmodel = dict(\n pretrained=dict(pts='open-mmlab"
},
{
"path": "configs/free_anchor/hv_pointpillars_regnet-3.2gf_fpn_sbn-all_free-anchor_strong-aug_4x8_3x_nus-3d.py",
"chars": 2441,
"preview": "_base_ = './hv_pointpillars_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py'\n\nmodel = dict(\n pretrained=dict(pts='open-mmlab"
},
{
"path": "configs/free_anchor/hv_pointpillars_regnet-400mf_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py",
"chars": 552,
"preview": "_base_ = './hv_pointpillars_fpn_sbn-all_free-anchor_4x8_2x_nus-3d.py'\n\nmodel = dict(\n pretrained=dict(pts='open-mmlab"
},
{
"path": "configs/h3dnet/README.md",
"chars": 1058,
"preview": "# H3DNet: 3D Object Detection Using Hybrid Geometric Primitives\n\n## Introduction\n\n[ALGORITHM]\n\nWe implement H3DNet and p"
},
{
"path": "configs/h3dnet/h3dnet_3x8_scannet-3d-18class.py",
"chars": 3099,
"preview": "_base_ = [\n '../_base_/datasets/scannet-3d-18class.py', '../_base_/models/h3dnet.py',\n '../_base_/schedules/schedu"
},
{
"path": "configs/imvotenet/README.md",
"chars": 1938,
"preview": "# ImVoteNet: Boosting 3D Object Detection in Point Clouds with Image Votes\n\n## Introduction\n\n[ALGORITHM]\n\nWe implement I"
},
{
"path": "configs/imvotenet/imvotenet_faster_rcnn_r50_fpn_2x4_sunrgbd-3d-10class.py",
"chars": 1950,
"preview": "_base_ = [\n '../_base_/datasets/sunrgbd-3d-10class.py', '../_base_/default_runtime.py',\n '../_base_/models/imvoten"
},
{
"path": "configs/imvotenet/imvotenet_stage2_16x8_sunrgbd-3d-10class.py",
"chars": 8719,
"preview": "_base_ = [\n '../_base_/datasets/sunrgbd-3d-10class.py',\n '../_base_/schedules/schedule_3x.py', '../_base_/default_"
},
{
"path": "configs/mvxnet/README.md",
"chars": 1186,
"preview": "# MVX-Net: Multimodal VoxelNet for 3D Object Detection\n\n## Introduction\n\n[ALGORITHM]\n\nWe implement MVX-Net and provide i"
},
{
"path": "configs/mvxnet/dv_mvx-fpn_second_secfpn_adamw_2x8_80e_kitti-3d-3class.py",
"chars": 8529,
"preview": "# model settings\nvoxel_size = [0.05, 0.05, 0.1]\npoint_cloud_range = [0, -40, -3, 70.4, 40, 1]\n\nmodel = dict(\n type='D"
},
{
"path": "configs/nuimages/README.md",
"chars": 10178,
"preview": "# NuImages Results\n\n## Introduction\n\n[DATASET]\n\nWe support and provide some baseline results on [nuImages dataset](https"
},
{
"path": "configs/nuimages/cascade_mask_rcnn_r101_fpn_1x_nuim.py",
"chars": 127,
"preview": "_base_ = './cascade_mask_rcnn_r50_fpn_1x_nuim.py'\nmodel = dict(pretrained='torchvision://resnet101', backbone=dict(depth"
},
{
"path": "configs/nuimages/cascade_mask_rcnn_r50_fpn_1x_nuim.py",
"chars": 2335,
"preview": "_base_ = [\n '../_base_/models/cascade_mask_rcnn_r50_fpn.py',\n '../_base_/datasets/nuim_instance.py',\n '../_base"
},
{
"path": "configs/nuimages/cascade_mask_rcnn_r50_fpn_coco-20e_1x_nuim.py",
"chars": 263,
"preview": "_base_ = './cascade_mask_rcnn_r50_fpn_1x_nuim.py'\n\nload_from = 'http://download.openmmlab.com/mmdetection/v2.0/cascade_r"
},
{
"path": "configs/nuimages/cascade_mask_rcnn_r50_fpn_coco-20e_20e_nuim.py",
"chars": 332,
"preview": "_base_ = './cascade_mask_rcnn_r50_fpn_1x_nuim.py'\n\n# learning policy\nlr_config = dict(step=[16, 19])\ntotal_epochs = 20\n\n"
},
{
"path": "configs/nuimages/cascade_mask_rcnn_x101_32x4d_fpn_1x_nuim.py",
"chars": 376,
"preview": "_base_ = './cascade_mask_rcnn_r50_fpn_1x_nuim.py'\nmodel = dict(\n pretrained='open-mmlab://resnext101_32x4d',\n back"
},
{
"path": "configs/nuimages/htc_r50_fpn_1x_nuim.py",
"chars": 1466,
"preview": "_base_ = './htc_without_semantic_r50_fpn_1x_nuim.py'\nmodel = dict(\n roi_head=dict(\n semantic_roi_extractor=dic"
},
{
"path": "configs/nuimages/htc_r50_fpn_coco-20e_1x_nuim.py",
"chars": 174,
"preview": "_base_ = './htc_r50_fpn_1x_nuim.py'\n\nload_from = 'http://download.openmmlab.com/mmdetection/v2.0/htc/htc_r50_fpn_20e_coc"
},
{
"path": "configs/nuimages/htc_r50_fpn_coco-20e_20e_nuim.py",
"chars": 113,
"preview": "_base_ = './htc_r50_fpn_coco-20e_1x_nuim.py'\n# learning policy\nlr_config = dict(step=[16, 19])\ntotal_epochs = 20\n"
},
{
"path": "configs/nuimages/htc_without_semantic_r50_fpn_1x_nuim.py",
"chars": 7693,
"preview": "_base_ = [\n '../_base_/datasets/nuim_instance.py',\n '../_base_/schedules/mmdet_schedule_1x.py', '../_base_/default"
},
{
"path": "configs/nuimages/htc_x101_64x4d_fpn_dconv_c3-c5_coco-20e_16x1_20e_nuim.py",
"chars": 848,
"preview": "_base_ = './htc_r50_fpn_1x_nuim.py'\nmodel = dict(\n pretrained='open-mmlab://resnext101_64x4d',\n backbone=dict(\n "
},
{
"path": "configs/nuimages/mask_rcnn_r101_fpn_1x_nuim.py",
"chars": 119,
"preview": "_base_ = './mask_rcnn_r50_fpn_1x_nuim.py'\nmodel = dict(pretrained='torchvision://resnet101', backbone=dict(depth=101))\n"
},
{
"path": "configs/nuimages/mask_rcnn_r50_caffe_fpn_1x_nuim.py",
"chars": 1636,
"preview": "_base_ = [\n '../_base_/models/mask_rcnn_r50_fpn.py',\n '../_base_/datasets/nuim_instance.py',\n '../_base_/schedu"
},
{
"path": "configs/nuimages/mask_rcnn_r50_caffe_fpn_coco-3x_1x_nuim.py",
"chars": 1866,
"preview": "_base_ = [\n '../_base_/models/mask_rcnn_r50_fpn.py',\n '../_base_/datasets/nuim_instance.py',\n '../_base_/schedu"
},
{
"path": "configs/nuimages/mask_rcnn_r50_caffe_fpn_coco-3x_20e_nuim.py",
"chars": 1934,
"preview": "_base_ = [\n '../_base_/models/mask_rcnn_r50_fpn.py',\n '../_base_/datasets/nuim_instance.py',\n '../_base_/schedu"
},
{
"path": "configs/nuimages/mask_rcnn_r50_fpn_1x_nuim.py",
"chars": 286,
"preview": "_base_ = [\n '../_base_/models/mask_rcnn_r50_fpn.py',\n '../_base_/datasets/nuim_instance.py',\n '../_base_/schedu"
},
{
"path": "configs/nuimages/mask_rcnn_r50_fpn_coco-2x_1x_nuim.py",
"chars": 478,
"preview": "_base_ = [\n '../_base_/models/mask_rcnn_r50_fpn.py',\n '../_base_/datasets/nuim_instance.py',\n '../_base_/schedu"
},
{
"path": "configs/nuimages/mask_rcnn_r50_fpn_coco-2x_1x_nus-2d.py",
"chars": 1298,
"preview": "_base_ = [\n '../_base_/models/mask_rcnn_r50_fpn.py',\n '../_base_/datasets/nuim_instance.py',\n '../_base_/schedu"
},
{
"path": "configs/nuimages/mask_rcnn_swinT_coco-2x_1x_nuim.py",
"chars": 5168,
"preview": "_base_ = [\r\n '../_base_/datasets/nuim_instance.py', '../_base_/default_runtime.py'\r\n]\r\n\r\nmodel = dict(\r\n type='Mas"
},
{
"path": "configs/nuimages/mask_rcnn_x101_32x4d_fpn_1x_nuim.py",
"chars": 368,
"preview": "_base_ = './mask_rcnn_r50_fpn_1x_nuim.py'\nmodel = dict(\n pretrained='open-mmlab://resnext101_32x4d',\n backbone=dic"
},
{
"path": "configs/nuscenes.md",
"chars": 3570,
"preview": "# MODEL ZOO\n\n## Common settings and notes\n\n- The experiments are run with PyTorch 1.7.0, CUDA 10.1 and CUDNN 7.6\n- The t"
},
{
"path": "configs/parta2/README.md",
"chars": 1737,
"preview": "# From Points to Parts: 3D Object Detection from Point Cloud with Part-aware and Part-aggregation Network\n\n## Introducti"
},
{
"path": "configs/parta2/hv_PartA2_secfpn_2x8_cyclic_80e_kitti-3d-3class.py",
"chars": 10495,
"preview": "_base_ = ['../_base_/schedules/cyclic_40e.py', '../_base_/default_runtime.py']\n\n# model settings\nvoxel_size = [0.05, 0.0"
},
{
"path": "configs/parta2/hv_PartA2_secfpn_2x8_cyclic_80e_kitti-3d-car.py",
"chars": 4737,
"preview": "_base_ = './hv_PartA2_secfpn_2x8_cyclic_80e_kitti-3d-3class.py'\n\nvoxel_size = [0.05, 0.05, 0.1]\npoint_cloud_range = [0, "
},
{
"path": "configs/pointpillars/README.md",
"chars": 6852,
"preview": "# PointPillars: Fast Encoders for Object Detection from Point Clouds\n\n## Introduction\n\n[ALGORITHM]\n\nWe implement PointPi"
},
{
"path": "configs/pointpillars/hv_pointpillars_fpn_sbn-all_2x8_2x_lyft-3d.py",
"chars": 175,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_lyft.py',\n '../_base_/datasets/lyft-3d.py', '../_base_/schedules"
},
{
"path": "configs/pointpillars/hv_pointpillars_fpn_sbn-all_4x8_2x_nus-3d.py",
"chars": 173,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_nus.py',\n '../_base_/datasets/nus-3d.py', '../_base_/schedules/s"
},
{
"path": "configs/pointpillars/hv_pointpillars_fpn_sbn-all_range100_2x8_2x_lyft-3d.py",
"chars": 193,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_range100_lyft.py',\n '../_base_/datasets/range100_lyft-3d.py',\n "
},
{
"path": "configs/pointpillars/hv_pointpillars_secfpn_6x8_160e_kitti-3d-3class.py",
"chars": 3360,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_secfpn_kitti.py',\n '../_base_/datasets/kitti-3d-3class.py',\n '../"
},
{
"path": "configs/pointpillars/hv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py",
"chars": 3199,
"preview": "# model settings\n_base_ = './hv_pointpillars_secfpn_6x8_160e_kitti-3d-3class.py'\n\npoint_cloud_range = [0, -39.68, -3, 69"
},
{
"path": "configs/pointpillars/hv_pointpillars_secfpn_sbn-all_2x8_2x_lyft-3d.py",
"chars": 1756,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_lyft.py',\n '../_base_/datasets/lyft-3d.py',\n '../_base_/sched"
},
{
"path": "configs/pointpillars/hv_pointpillars_secfpn_sbn-all_4x8_2x_nus-3d.py",
"chars": 1754,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_nus.py',\n '../_base_/datasets/nus-3d.py',\n '../_base_/schedul"
},
{
"path": "configs/pointpillars/hv_pointpillars_secfpn_sbn-all_range100_2x8_2x_lyft-3d.py",
"chars": 1805,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_range100_lyft.py',\n '../_base_/datasets/range100_lyft-3d.py',\n "
},
{
"path": "configs/pointpillars/hv_pointpillars_secfpn_sbn_2x16_2x_waymo-3d-3class.py",
"chars": 266,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_secfpn_waymo.py',\n '../_base_/datasets/waymoD5-3d-3class.py',\n '."
},
{
"path": "configs/pointpillars/hv_pointpillars_secfpn_sbn_2x16_2x_waymo-3d-car.py",
"chars": 1171,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_secfpn_waymo.py',\n '../_base_/datasets/waymoD5-3d-car.py',\n '../_"
},
{
"path": "configs/pointpillars/hv_pointpillars_secfpn_sbn_2x16_2x_waymoD5-3d-3class.py",
"chars": 194,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_secfpn_waymo.py',\n '../_base_/datasets/waymoD5-3d-3class.py',\n '."
},
{
"path": "configs/pointpillars/hv_pointpillars_secfpn_sbn_2x16_2x_waymoD5-3d-car.py",
"chars": 1099,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_secfpn_waymo.py',\n '../_base_/datasets/waymoD5-3d-car.py',\n '../_"
},
{
"path": "configs/regnet/README.md",
"chars": 5515,
"preview": "# Designing Network Design Spaces\n\n## Introduction\n\n[BACKBONE]\n\nWe implement RegNetX models in 3D detection systems and "
},
{
"path": "configs/regnet/hv_pointpillars_regnet-1.6gf_fpn_sbn-all_4x8_2x_nus-3d.py",
"chars": 703,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_nus.py',\n '../_base_/datasets/nus-3d.py',\n '../_base_/schedul"
},
{
"path": "configs/regnet/hv_pointpillars_regnet-400mf_fpn_sbn-all_2x8_2x_lyft-3d.py",
"chars": 754,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_lyft.py',\n '../_base_/datasets/lyft-3d.py',\n '../_base_/sched"
},
{
"path": "configs/regnet/hv_pointpillars_regnet-400mf_fpn_sbn-all_4x8_2x_nus-3d.py",
"chars": 752,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_nus.py',\n '../_base_/datasets/nus-3d.py',\n '../_base_/schedul"
},
{
"path": "configs/regnet/hv_pointpillars_regnet-400mf_fpn_sbn-all_range100_2x8_2x_lyft-3d.py",
"chars": 772,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_range100_lyft.py',\n '../_base_/datasets/range100_lyft-3d.py',\n "
},
{
"path": "configs/regnet/hv_pointpillars_regnet-400mf_secfpn_sbn-all_2x8_2x_lyft-3d.py",
"chars": 1677,
"preview": "_base_ = './hv_pointpillars_regnet-400mf_fpn_sbn-all_2x8_2x_lyft-3d.py'\n# model settings\nmodel = dict(\n pts_neck=dict"
},
{
"path": "configs/regnet/hv_pointpillars_regnet-400mf_secfpn_sbn-all_4x8_2x_nus-3d.py",
"chars": 1676,
"preview": "_base_ = './hv_pointpillars_regnet-400mf_fpn_sbn-all_4x8_2x_nus-3d.py'\n# model settings\nmodel = dict(\n pts_neck=dict("
},
{
"path": "configs/regnet/hv_pointpillars_regnet-400mf_secfpn_sbn-all_range100_2x8_2x_lyft-3d.py",
"chars": 1728,
"preview": "_base_ = \\\n './hv_pointpillars_regnet-400mf_fpn_sbn-all_range100_2x8_2x_lyft-3d.py'\n# model settings\nmodel = dict(\n "
},
{
"path": "configs/second/README.md",
"chars": 2554,
"preview": "# Second: Sparsely embedded convolutional detection\n\n## Introduction\n\n[ALGORITHM]\n\nWe implement SECOND and provide the r"
},
{
"path": "configs/second/hv_second_secfpn_6x8_80e_kitti-3d-3class.py",
"chars": 180,
"preview": "_base_ = [\n '../_base_/models/hv_second_secfpn_kitti.py',\n '../_base_/datasets/kitti-3d-3class.py',\n '../_base_"
},
{
"path": "configs/second/hv_second_secfpn_6x8_80e_kitti-3d-car.py",
"chars": 970,
"preview": "_base_ = [\n '../_base_/models/hv_second_secfpn_kitti.py',\n '../_base_/datasets/kitti-3d-car.py', '../_base_/schedu"
},
{
"path": "configs/second/hv_second_secfpn_sbn_2x16_2x_waymoD5-3d-3class.py",
"chars": 3697,
"preview": "_base_ = [\n '../_base_/models/hv_second_secfpn_waymo.py',\n '../_base_/datasets/waymoD5-3d-3class.py',\n '../_bas"
},
{
"path": "configs/sparsefusion_nusc_voxel_LC_SwinT.py",
"chars": 14294,
"preview": "point_cloud_range = [-54.0, -54.0, -5.0, 54.0, 54.0, 3.0]\r\nclass_names = [\r\n 'car', 'truck', 'construction_vehicle', "
},
{
"path": "configs/sparsefusion_nusc_voxel_LC_r50.py",
"chars": 13961,
"preview": "point_cloud_range = [-54.0, -54.0, -5.0, 54.0, 54.0, 3.0]\r\nclass_names = [\r\n 'car', 'truck', 'construction_vehicle', "
},
{
"path": "configs/ssn/README.md",
"chars": 4615,
"preview": "# SSN: Shape Signature Networks for Multi-class Object Detection from Point Clouds\n\n## Introduction\n\n[ALGORITHM]\n\nWe imp"
},
{
"path": "configs/ssn/hv_ssn_regnet-400mf_secfpn_sbn-all_1x16_2x_lyft-3d.py",
"chars": 697,
"preview": "_base_ = './hv_ssn_secfpn_sbn-all_2x16_2x_lyft-3d.py'\n# model settings\nmodel = dict(\n type='MVXFasterRCNN',\n pretr"
},
{
"path": "configs/ssn/hv_ssn_regnet-400mf_secfpn_sbn-all_2x16_2x_nus-3d.py",
"chars": 627,
"preview": "_base_ = './hv_ssn_secfpn_sbn-all_2x16_2x_nus-3d.py'\n# model settings\nmodel = dict(\n type='MVXFasterRCNN',\n pretra"
},
{
"path": "configs/ssn/hv_ssn_secfpn_sbn-all_2x16_2x_lyft-3d.py",
"chars": 8730,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_lyft.py',\n '../_base_/datasets/lyft-3d.py',\n '../_base_/sched"
},
{
"path": "configs/ssn/hv_ssn_secfpn_sbn-all_2x16_2x_nus-3d.py",
"chars": 9769,
"preview": "_base_ = [\n '../_base_/models/hv_pointpillars_fpn_nus.py',\n '../_base_/datasets/nus-3d.py',\n '../_base_/schedul"
},
{
"path": "configs/transfusion_nusc_pillar_L.py",
"chars": 8832,
"preview": "point_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nclass_names = [\n 'car', 'truck', 'construction_vehicle', 'b"
},
{
"path": "configs/transfusion_nusc_pillar_LC.py",
"chars": 9079,
"preview": "point_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]\nclass_names = [\n 'car', 'truck', 'construction_vehicle', 'b"
},
{
"path": "configs/transfusion_nusc_voxel_L.py",
"chars": 8895,
"preview": "point_cloud_range = [-54.0, -54.0, -5.0, 54.0, 54.0, 3.0]\nclass_names = [\n 'car', 'truck', 'construction_vehicle', 'b"
},
{
"path": "configs/transfusion_nusc_voxel_LC.py",
"chars": 9148,
"preview": "point_cloud_range = [-54.0, -54.0, -5.0, 54.0, 54.0, 3.0]\nclass_names = [\n 'car', 'truck', 'construction_vehicle', 'b"
},
{
"path": "configs/transfusion_waymo_voxel_L.py",
"chars": 8163,
"preview": "point_cloud_range = [-75.2, -75.2, -2, 75.2, 75.2, 4]\nclass_names = ['Car', 'Pedestrian', 'Cyclist']\nvoxel_size = [0.1, "
},
{
"path": "configs/transfusion_waymo_voxel_LC.py",
"chars": 8903,
"preview": "point_cloud_range = [-75.2, -75.2, -2, 75.2, 75.2, 4]\nclass_names = ['Car', 'Pedestrian', 'Cyclist']\nvoxel_size = [0.1, "
},
{
"path": "configs/votenet/README.md",
"chars": 3283,
"preview": "# Deep Hough Voting for 3D Object Detection in Point Clouds\n\n## Introduction\n\n[ALGORITHM]\n\nWe implement VoteNet and prov"
},
{
"path": "configs/votenet/votenet_16x8_sunrgbd-3d-10class.py",
"chars": 836,
"preview": "_base_ = [\n '../_base_/datasets/sunrgbd-3d-10class.py', '../_base_/models/votenet.py',\n '../_base_/schedules/sched"
},
{
"path": "configs/votenet/votenet_8x8_scannet-3d-18class.py",
"chars": 1651,
"preview": "_base_ = [\n '../_base_/datasets/scannet-3d-18class.py', '../_base_/models/votenet.py',\n '../_base_/schedules/sched"
},
{
"path": "configs/votenet/votenet_iouloss_8x8_scannet-3d-18class.py",
"chars": 232,
"preview": "_base_ = ['./votenet_8x8_scannet-3d-18class.py']\n\n# model settings, add iou loss\nmodel = dict(\n bbox_head=dict(\n "
},
{
"path": "configs/waymo.md",
"chars": 978,
"preview": "# MODEL ZOO\n\n## Common settings and notes\n\n- The experiments are run with PyTorch 1.7.0, CUDA 10.1 and CUDNN 7.6\n- The t"
},
{
"path": "demo/pcd_demo.py",
"chars": 999,
"preview": "from argparse import ArgumentParser\n\nfrom mmdet3d.apis import inference_detector, init_detector, show_result_meshlab\n\n\nd"
},
{
"path": "docker/Dockerfile",
"chars": 1038,
"preview": "ARG PYTORCH=\"1.6.0\"\nARG CUDA=\"10.1\"\nARG CUDNN=\"7\"\n\nFROM pytorch/pytorch:${PYTORCH}-cuda${CUDA}-cudnn${CUDNN}-devel\n\nENV "
},
{
"path": "mmdet3d/__init__.py",
"chars": 1273,
"preview": "import mmcv\n\nimport mmdet\nfrom .version import __version__, short_version\n\n\ndef digit_version(version_str):\n digit_ve"
},
{
"path": "mmdet3d/apis/__init__.py",
"chars": 275,
"preview": "from .inference import (convert_SyncBN, inference_detector, init_detector,\n show_result_meshlab)\n"
},
{
"path": "mmdet3d/apis/inference.py",
"chars": 4610,
"preview": "import mmcv\nimport torch\nfrom copy import deepcopy\nfrom mmcv.parallel import collate, scatter\nfrom mmcv.runner import lo"
},
{
"path": "mmdet3d/apis/test.py",
"chars": 1134,
"preview": "import mmcv\nimport torch\n\n\ndef single_gpu_test(model, data_loader, show=False, out_dir=None):\n \"\"\"Test model with sin"
},
{
"path": "mmdet3d/core/__init__.py",
"chars": 349,
"preview": "from .anchor import * # noqa: F401, F403\nfrom .bbox import * # noqa: F401, F403\nfrom .evaluation import * # noqa: F40"
},
{
"path": "mmdet3d/core/anchor/__init__.py",
"chars": 393,
"preview": "from mmdet.core.anchor import build_anchor_generator\nfrom .anchor_3d_generator import (AlignedAnchor3DRangeGenerator,\n "
},
{
"path": "mmdet3d/core/anchor/anchor_3d_generator.py",
"chars": 17129,
"preview": "import mmcv\nimport torch\n\nfrom mmdet.core.anchor import ANCHOR_GENERATORS\n\n\n@ANCHOR_GENERATORS.register_module()\nclass A"
},
{
"path": "mmdet3d/core/bbox/__init__.py",
"chars": 1610,
"preview": "from .assigners import AssignResult, BaseAssigner, MaxIoUAssigner\nfrom .coders import DeltaXYZWLHRBBoxCoder\n# from .bbox"
},
{
"path": "mmdet3d/core/bbox/assigners/__init__.py",
"chars": 431,
"preview": "from mmdet.core.bbox import AssignResult, BaseAssigner, MaxIoUAssigner\nfrom .hungarian_assigner import HungarianAssigner"
},
{
"path": "mmdet3d/core/bbox/assigners/hungarian_assigner.py",
"chars": 21697,
"preview": "from mmdet.core.bbox.builder import BBOX_ASSIGNERS\nfrom mmdet.core.bbox.assigners import AssignResult, BaseAssigner\nfrom"
},
{
"path": "mmdet3d/core/bbox/box_np_ops.py",
"chars": 32421,
"preview": "# TODO: clean the functions in this file and move the APIs into box structures\n# in the future\n\nimport numba\nimport nump"
},
{
"path": "mmdet3d/core/bbox/coders/__init__.py",
"chars": 579,
"preview": "from mmdet.core.bbox import build_bbox_coder\nfrom .anchor_free_bbox_coder import AnchorFreeBBoxCoder\nfrom .centerpoint_b"
},
{
"path": "mmdet3d/core/bbox/coders/anchor_free_bbox_coder.py",
"chars": 4319,
"preview": "import numpy as np\nimport torch\n\nfrom mmdet.core.bbox.builder import BBOX_CODERS\nfrom .partial_bin_based_bbox_coder impo"
},
{
"path": "mmdet3d/core/bbox/coders/camera_bbox_coder.py",
"chars": 2909,
"preview": "import torch\r\n\r\nfrom mmdet.core.bbox import BaseBBoxCoder\r\nfrom mmdet.core.bbox.builder import BBOX_CODERS\r\n\r\n\r\n@BBOX_CO"
},
{
"path": "mmdet3d/core/bbox/coders/centerpoint_bbox_coders.py",
"chars": 8543,
"preview": "import torch\n\nfrom mmdet.core.bbox import BaseBBoxCoder\nfrom mmdet.core.bbox.builder import BBOX_CODERS\n\n\n@BBOX_CODERS.r"
},
{
"path": "mmdet3d/core/bbox/coders/delta_xyzwhlr_bbox_coder.py",
"chars": 3074,
"preview": "import torch\n\nfrom mmdet.core.bbox import BaseBBoxCoder\nfrom mmdet.core.bbox.builder import BBOX_CODERS\n\n\n@BBOX_CODERS.r"
},
{
"path": "mmdet3d/core/bbox/coders/partial_bin_based_bbox_coder.py",
"chars": 9098,
"preview": "import numpy as np\nimport torch\n\nfrom mmdet.core.bbox import BaseBBoxCoder\nfrom mmdet.core.bbox.builder import BBOX_CODE"
},
{
"path": "mmdet3d/core/bbox/coders/transfusion_bbox_coder.py",
"chars": 5354,
"preview": "import torch\n\nfrom mmdet.core.bbox import BaseBBoxCoder\nfrom mmdet.core.bbox.builder import BBOX_CODERS\n\n\n@BBOX_CODERS.r"
},
{
"path": "mmdet3d/core/bbox/iou_calculators/__init__.py",
"chars": 444,
"preview": "from .iou3d_calculator import (AxisAlignedBboxOverlaps3D, BboxOverlaps3D,\n BboxOverlapsNea"
},
{
"path": "mmdet3d/core/bbox/iou_calculators/iou3d_calculator.py",
"chars": 12463,
"preview": "import torch\n\nfrom mmdet.core.bbox import bbox_overlaps\nfrom mmdet.core.bbox.iou_calculators.builder import IOU_CALCULAT"
},
{
"path": "mmdet3d/core/bbox/samplers/__init__.py",
"chars": 600,
"preview": "from mmdet.core.bbox.samplers import (BaseSampler, CombinedSampler,\n InstanceBalanc"
},
{
"path": "mmdet3d/core/bbox/samplers/iou_neg_piecewise_sampler.py",
"chars": 6813,
"preview": "import torch\n\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS\nfrom . import RandomSampler, SamplingResult\n\n\n@BBOX_SAMP"
},
{
"path": "mmdet3d/core/bbox/structures/__init__.py",
"chars": 615,
"preview": "from .base_box3d import BaseInstance3DBoxes\nfrom .box_3d_mode import Box3DMode\nfrom .cam_box3d import CameraInstance3DBo"
},
{
"path": "mmdet3d/core/bbox/structures/base_box3d.py",
"chars": 16275,
"preview": "import numpy as np\nimport torch\nfrom abc import abstractmethod\n\nfrom mmdet3d.ops.iou3d import iou3d_cuda\nfrom .utils imp"
},
{
"path": "mmdet3d/core/bbox/structures/box_3d_mode.py",
"chars": 5980,
"preview": "import numpy as np\nimport torch\nfrom enum import IntEnum, unique\n\nfrom .base_box3d import BaseInstance3DBoxes\nfrom .cam_"
},
{
"path": "mmdet3d/core/bbox/structures/cam_box3d.py",
"chars": 12069,
"preview": "import numpy as np\nimport torch\n\nfrom mmdet3d.core.points import BasePoints\nfrom .base_box3d import BaseInstance3DBoxes\n"
},
{
"path": "mmdet3d/core/bbox/structures/coord_3d_mode.py",
"chars": 10972,
"preview": "import numpy as np\nimport torch\nfrom enum import IntEnum, unique\n\nfrom mmdet3d.core.points import (BasePoints, CameraPoi"
},
{
"path": "mmdet3d/core/bbox/structures/depth_box3d.py",
"chars": 12942,
"preview": "import numpy as np\nimport torch\n\nfrom mmdet3d.core.points import BasePoints\nfrom mmdet3d.ops import points_in_boxes_batc"
},
{
"path": "mmdet3d/core/bbox/structures/lidar_box3d.py",
"chars": 9864,
"preview": "import numpy as np\nimport torch\n\nfrom mmdet3d.core.points import BasePoints\nfrom mmdet3d.ops.roiaware_pool3d import poin"
},
{
"path": "mmdet3d/core/bbox/structures/utils.py",
"chars": 4865,
"preview": "import numpy as np\nimport torch\n\n\ndef limit_period(val, offset=0.5, period=np.pi):\n \"\"\"Limit the value into a period "
},
{
"path": "mmdet3d/core/bbox/transforms.py",
"chars": 2081,
"preview": "import torch\n\n\ndef bbox3d_mapping_back(bboxes, scale_factor, flip_horizontal, flip_vertical):\n \"\"\"Map bboxes from tes"
},
{
"path": "mmdet3d/core/evaluation/__init__.py",
"chars": 261,
"preview": "from .indoor_eval import indoor_eval\nfrom .kitti_utils import kitti_eval, kitti_eval_coco_style\nfrom .lyft_eval import l"
},
{
"path": "mmdet3d/core/evaluation/indoor_eval.py",
"chars": 11037,
"preview": "import numpy as np\nimport torch\nfrom mmcv.utils import print_log\nfrom terminaltables import AsciiTable\n\n\ndef average_pre"
},
{
"path": "mmdet3d/core/evaluation/kitti_utils/__init__.py",
"chars": 103,
"preview": "from .eval import kitti_eval, kitti_eval_coco_style\n\n__all__ = ['kitti_eval', 'kitti_eval_coco_style']\n"
},
{
"path": "mmdet3d/core/evaluation/kitti_utils/eval.py",
"chars": 33476,
"preview": "import gc\nimport io as sysio\nimport numba\nimport numpy as np\n\n\n@numba.jit\ndef get_thresholds(scores: np.ndarray, num_gt,"
},
{
"path": "mmdet3d/core/evaluation/kitti_utils/rotate_iou.py",
"chars": 13267,
"preview": "#####################\n# Based on https://github.com/hongzhenwang/RRPN-revise\n# Licensed under The MIT License\n# Author: "
},
{
"path": "mmdet3d/core/evaluation/lyft_eval.py",
"chars": 10305,
"preview": "import mmcv\nimport numpy as np\nfrom lyft_dataset_sdk.eval.detection.mAP_evaluation import (Box3D, get_ap,\n "
},
{
"path": "mmdet3d/core/evaluation/seg_eval.py",
"chars": 3372,
"preview": "import numpy as np\nfrom mmcv.utils import print_log\nfrom terminaltables import AsciiTable\n\n\ndef fast_hist(preds, labels,"
},
{
"path": "mmdet3d/core/evaluation/waymo_utils/prediction_kitti_to_waymo.py",
"chars": 9652,
"preview": "r\"\"\"Adapted from `Waymo to KITTI converter\n <https://github.com/caizhongang/waymo_kitti_converter>`_.\n\"\"\"\n\ntry:\n f"
},
{
"path": "mmdet3d/core/points/__init__.py",
"chars": 873,
"preview": "from .base_points import BasePoints\nfrom .cam_points import CameraPoints\nfrom .depth_points import DepthPoints\nfrom .lid"
},
{
"path": "mmdet3d/core/points/base_points.py",
"chars": 13731,
"preview": "import numpy as np\nimport torch\nfrom abc import abstractmethod\n\n\nclass BasePoints(object):\n \"\"\"Base class for Points."
},
{
"path": "mmdet3d/core/points/cam_points.py",
"chars": 2818,
"preview": "from .base_points import BasePoints\n\n\nclass CameraPoints(BasePoints):\n \"\"\"Points of instances in CAM coordinates.\n\n "
},
{
"path": "mmdet3d/core/points/depth_points.py",
"chars": 2820,
"preview": "from .base_points import BasePoints\n\n\nclass DepthPoints(BasePoints):\n \"\"\"Points of instances in DEPTH coordinates.\n\n "
},
{
"path": "mmdet3d/core/points/lidar_points.py",
"chars": 2820,
"preview": "from .base_points import BasePoints\n\n\nclass LiDARPoints(BasePoints):\n \"\"\"Points of instances in LIDAR coordinates.\n\n "
},
{
"path": "mmdet3d/core/post_processing/__init__.py",
"chars": 531,
"preview": "from mmdet.core.post_processing import (merge_aug_bboxes, merge_aug_masks,\n merge"
},
{
"path": "mmdet3d/core/post_processing/box3d_nms.py",
"chars": 6369,
"preview": "import numba\nimport numpy as np\nimport torch\n\nfrom mmdet3d.ops.iou3d.iou3d_utils import nms_gpu, nms_normal_gpu\n\n\ndef bo"
},
{
"path": "mmdet3d/core/post_processing/merge_augs.py",
"chars": 3447,
"preview": "import torch\n\nfrom mmdet3d.ops.iou3d.iou3d_utils import nms_gpu, nms_normal_gpu\nfrom ..bbox import bbox3d2result, bbox3d"
},
{
"path": "mmdet3d/core/utils/__init__.py",
"chars": 145,
"preview": "from .gaussian import draw_heatmap_gaussian, gaussian_2d, gaussian_radius\n\n__all__ = ['gaussian_2d', 'gaussian_radius', "
}
]
// ... and 316 more files (download for full content)
About this extraction
This page contains the full source code of the yichen928/SparseFusion GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 516 files (3.1 MB), approximately 850.9k tokens, and a symbol index with 1948 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.
Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.