Showing preview only (4,495K chars total). Download the full file or copy to clipboard to get everything.
Repository: NVlabs/BEV-Planner
Branch: main
Commit: 01c28d6db56a
Files: 481
Total size: 4.2 MB
Directory structure:
gitextract_5bm2vozl/
├── .gitignore
├── README.md
├── configs/
│ ├── _base_/
│ │ ├── datasets/
│ │ │ ├── coco_instance.py
│ │ │ ├── kitti-3d-3class.py
│ │ │ ├── kitti-3d-car.py
│ │ │ ├── kitti-mono3d.py
│ │ │ ├── lyft-3d.py
│ │ │ ├── nuim_instance.py
│ │ │ ├── nus-3d.py
│ │ │ ├── nus-mono3d.py
│ │ │ ├── range100_lyft-3d.py
│ │ │ ├── s3dis-3d-5class.py
│ │ │ ├── s3dis_seg-3d-13class.py
│ │ │ ├── scannet-3d-18class.py
│ │ │ ├── scannet_seg-3d-20class.py
│ │ │ ├── sunrgbd-3d-10class.py
│ │ │ ├── waymoD5-3d-3class.py
│ │ │ └── waymoD5-3d-car.py
│ │ ├── default_runtime.py
│ │ ├── init.py
│ │ ├── models/
│ │ │ ├── 3dssd.py
│ │ │ ├── cascade_mask_rcnn_r50_fpn.py
│ │ │ ├── centerpoint_01voxel_second_secfpn_nus.py
│ │ │ ├── centerpoint_02pillar_second_secfpn_nus.py
│ │ │ ├── dgcnn.py
│ │ │ ├── fcaf3d.py
│ │ │ ├── fcos3d.py
│ │ │ ├── groupfree3d.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
│ │ │ ├── paconv_cuda_ssg.py
│ │ │ ├── paconv_ssg.py
│ │ │ ├── parta2.py
│ │ │ ├── pgd.py
│ │ │ ├── point_rcnn.py
│ │ │ ├── pointnet2_msg.py
│ │ │ ├── pointnet2_ssg.py
│ │ │ ├── smoke.py
│ │ │ └── votenet.py
│ │ └── schedules/
│ │ ├── cosine.py
│ │ ├── cyclic_20e.py
│ │ ├── cyclic_40e.py
│ │ ├── mmdet_schedule_1x.py
│ │ ├── schedule_2x.py
│ │ ├── schedule_3x.py
│ │ ├── seg_cosine_100e.py
│ │ ├── seg_cosine_150e.py
│ │ ├── seg_cosine_200e.py
│ │ └── seg_cosine_50e.py
│ └── bev_next/
│ ├── bev_planner.py
│ ├── bev_planner_plus.py
│ ├── bev_planner_plus_plus.py
│ ├── bev_planner_w_map.py
│ ├── det_pretrain_320x800_vov_36ep.py
│ ├── det_pretrain_640x1600_vov_36ep.py
│ └── map_pretrain.py
├── mmdet3d/
│ ├── __init__.py
│ ├── apis/
│ │ ├── __init__.py
│ │ ├── inference.py
│ │ ├── test.py
│ │ └── train.py
│ ├── core/
│ │ ├── __init__.py
│ │ ├── anchor/
│ │ │ ├── __init__.py
│ │ │ └── anchor_3d_generator.py
│ │ ├── bbox/
│ │ │ ├── __init__.py
│ │ │ ├── assigners/
│ │ │ │ └── __init__.py
│ │ │ ├── box_np_ops.py
│ │ │ ├── coders/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── anchor_free_bbox_coder.py
│ │ │ │ ├── centerpoint_bbox_coders.py
│ │ │ │ ├── delta_xyzwhlr_bbox_coder.py
│ │ │ │ ├── fcos3d_bbox_coder.py
│ │ │ │ ├── groupfree3d_bbox_coder.py
│ │ │ │ ├── monoflex_bbox_coder.py
│ │ │ │ ├── partial_bin_based_bbox_coder.py
│ │ │ │ ├── pgd_bbox_coder.py
│ │ │ │ ├── point_xyzwhlr_bbox_coder.py
│ │ │ │ └── smoke_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
│ │ │ │ ├── custom_box.py
│ │ │ │ ├── depth_box3d.py
│ │ │ │ ├── lidar_box3d.py
│ │ │ │ └── utils.py
│ │ │ ├── transforms.py
│ │ │ └── util.py
│ │ ├── evaluation/
│ │ │ ├── __init__.py
│ │ │ ├── indoor_eval.py
│ │ │ ├── instance_seg_eval.py
│ │ │ ├── kitti_utils/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── eval.py
│ │ │ │ └── rotate_iou.py
│ │ │ ├── lyft_eval.py
│ │ │ ├── scannet_utils/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── evaluate_semantic_instance.py
│ │ │ │ └── util_3d.py
│ │ │ ├── seg_eval.py
│ │ │ └── waymo_utils/
│ │ │ ├── __init__.py
│ │ │ └── prediction_kitti_to_waymo.py
│ │ ├── hook/
│ │ │ ├── __init__.py
│ │ │ ├── ema.py
│ │ │ ├── forge_load.py
│ │ │ ├── sequentialsontrol.py
│ │ │ └── utils.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
│ │ │ ├── array_converter.py
│ │ │ └── gaussian.py
│ │ ├── visualizer/
│ │ │ ├── __init__.py
│ │ │ ├── image_vis.py
│ │ │ ├── open3d_vis.py
│ │ │ └── show_result.py
│ │ └── voxel/
│ │ ├── __init__.py
│ │ ├── builder.py
│ │ └── voxel_generator.py
│ ├── datasets/
│ │ ├── __init__.py
│ │ ├── builder.py
│ │ ├── custom_3d.py
│ │ ├── custom_3d_seg.py
│ │ ├── dataset_wrappers.py
│ │ ├── evals/
│ │ │ ├── eval_utils.py
│ │ │ ├── map_api.py
│ │ │ ├── metric_utils.py
│ │ │ └── nuscenes_eval_motion.py
│ │ ├── evaluation/
│ │ │ ├── AP.py
│ │ │ ├── __init__.py
│ │ │ ├── distance.py
│ │ │ ├── raster_eval.py
│ │ │ └── vector_eval.py
│ │ ├── kitti2d_dataset.py
│ │ ├── kitti_dataset.py
│ │ ├── kitti_mono_dataset.py
│ │ ├── lyft_dataset.py
│ │ ├── map_utils/
│ │ │ ├── mean_ap.py
│ │ │ ├── tpfp.py
│ │ │ └── tpfp_chamfer.py
│ │ ├── nuscenes_dataset.py
│ │ ├── nuscenes_eval.py
│ │ ├── nuscenes_mono_dataset.py
│ │ ├── occ_metrics.py
│ │ ├── occupancy_eval.py
│ │ ├── pipelines/
│ │ │ ├── __init__.py
│ │ │ ├── compose.py
│ │ │ ├── data_augment_utils.py
│ │ │ ├── dbsampler.py
│ │ │ ├── formating.py
│ │ │ ├── loading.py
│ │ │ ├── test_time_aug.py
│ │ │ └── transforms_3d.py
│ │ ├── s3dis_dataset.py
│ │ ├── samplers/
│ │ │ ├── __init__.py
│ │ │ ├── d_sampler.py
│ │ │ └── infinite_group_each_sample_in_batch_sampler.py
│ │ ├── scannet_dataset.py
│ │ ├── semantickitti_dataset.py
│ │ ├── sunrgbd_dataset.py
│ │ ├── utils.py
│ │ ├── vector_map.py
│ │ └── waymo_dataset.py
│ ├── models/
│ │ ├── __init__.py
│ │ ├── backbones/
│ │ │ ├── __init__.py
│ │ │ ├── base_pointnet.py
│ │ │ ├── convnext.py
│ │ │ ├── dgcnn.py
│ │ │ ├── dla.py
│ │ │ ├── load.py
│ │ │ ├── mink_resnet.py
│ │ │ ├── multi_backbone.py
│ │ │ ├── nostem_regnet.py
│ │ │ ├── pointnet2_sa_msg.py
│ │ │ ├── pointnet2_sa_ssg.py
│ │ │ ├── resnet.py
│ │ │ ├── second.py
│ │ │ ├── swin.py
│ │ │ ├── vovnet.py
│ │ │ └── vovnet2.py
│ │ ├── builder.py
│ │ ├── decode_heads/
│ │ │ ├── __init__.py
│ │ │ ├── decode_head.py
│ │ │ ├── dgcnn_head.py
│ │ │ ├── paconv_head.py
│ │ │ └── pointnet2_head.py
│ │ ├── dense_heads/
│ │ │ ├── __init__.py
│ │ │ ├── anchor3d_head.py
│ │ │ ├── anchor_free_mono3d_head.py
│ │ │ ├── base_conv_bbox_head.py
│ │ │ ├── base_mono3d_dense_head.py
│ │ │ ├── centerpoint_head.py
│ │ │ ├── centerpoint_head_single_task.py
│ │ │ ├── fcaf3d_head.py
│ │ │ ├── fcos_mono3d_head.py
│ │ │ ├── free_anchor3d_head.py
│ │ │ ├── groupfree3d_head.py
│ │ │ ├── monoflex_head.py
│ │ │ ├── parta2_rpn_head.py
│ │ │ ├── pgd_head.py
│ │ │ ├── point_rpn_head.py
│ │ │ ├── shape_aware_head.py
│ │ │ ├── smoke_mono3d_head.py
│ │ │ ├── ssd_3d_head.py
│ │ │ ├── train_mixins.py
│ │ │ └── vote_head.py
│ │ ├── detectors/
│ │ │ ├── __init__.py
│ │ │ ├── base.py
│ │ │ ├── bevdet.py
│ │ │ ├── centerpoint.py
│ │ │ ├── dynamic_voxelnet.py
│ │ │ ├── fcos_mono3d.py
│ │ │ ├── groupfree3dnet.py
│ │ │ ├── h3dnet.py
│ │ │ ├── imvotenet.py
│ │ │ ├── imvoxelnet.py
│ │ │ ├── mink_single_stage.py
│ │ │ ├── mvx_faster_rcnn.py
│ │ │ ├── mvx_two_stage.py
│ │ │ ├── parta2.py
│ │ │ ├── point_rcnn.py
│ │ │ ├── sassd.py
│ │ │ ├── single_stage.py
│ │ │ ├── single_stage_mono3d.py
│ │ │ ├── smoke_mono3d.py
│ │ │ ├── ssd3dnet.py
│ │ │ ├── two_stage.py
│ │ │ ├── votenet.py
│ │ │ └── voxelnet.py
│ │ ├── fbbev/
│ │ │ ├── __init__.py
│ │ │ ├── detectors/
│ │ │ │ ├── __init__.py
│ │ │ │ └── bev_planner.py
│ │ │ ├── heads/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── occupancy_head.py
│ │ │ │ └── yolox.py
│ │ │ ├── modules/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── depth_net.py
│ │ │ │ ├── fpn3d.py
│ │ │ │ ├── frpn.py
│ │ │ │ ├── occ_loss_utils/
│ │ │ │ │ ├── __init__.py
│ │ │ │ │ ├── focal_loss.py
│ │ │ │ │ ├── lovasz_softmax.py
│ │ │ │ │ ├── nusc_param.py
│ │ │ │ │ └── semkitti.py
│ │ │ │ └── resnet3d.py
│ │ │ ├── motion_head/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── motion_head.py
│ │ │ │ ├── motion_planner_head.py
│ │ │ │ └── traj_loss.py
│ │ │ ├── planner_head/
│ │ │ │ ├── AD_mlp.py
│ │ │ │ ├── __init__.py
│ │ │ │ ├── metric_stp3.py
│ │ │ │ ├── naive_planner.py
│ │ │ │ ├── plan_loss.py
│ │ │ │ └── plan_loss_gt.py
│ │ │ ├── streammapnet/
│ │ │ │ ├── CustomMSDeformableAttention.py
│ │ │ │ ├── __init__.py
│ │ │ │ ├── cost.py
│ │ │ │ ├── fp16_dattn.py
│ │ │ │ ├── hungarian_lines_assigner.py
│ │ │ │ ├── loss.py
│ │ │ │ ├── map_utils.py
│ │ │ │ ├── streammapnet_head.py
│ │ │ │ ├── transformer.py
│ │ │ │ └── utils.py
│ │ │ ├── streampetr/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── hungarian_assigner_2d.py
│ │ │ │ ├── hungarian_assigner_3d.py
│ │ │ │ ├── match_cost.py
│ │ │ │ ├── nms_free_coder.py
│ │ │ │ ├── petr_transformer.py
│ │ │ │ ├── streampetr_utils.py
│ │ │ │ └── streampetr_v2.py
│ │ │ ├── track_head/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── instances.py
│ │ │ │ ├── losses/
│ │ │ │ │ ├── __init__.py
│ │ │ │ │ ├── tracking_loss.py
│ │ │ │ │ ├── tracking_loss_base.py
│ │ │ │ │ ├── tracking_loss_combo.py
│ │ │ │ │ ├── tracking_loss_mem_bank.py
│ │ │ │ │ └── tracking_loss_prediction.py
│ │ │ │ ├── runtime_tracker.py
│ │ │ │ ├── streampetr_utils.py
│ │ │ │ ├── track_nms_free_coder.py
│ │ │ │ ├── trackpetr.py
│ │ │ │ └── utils.py
│ │ │ ├── utils/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── bricks.py
│ │ │ │ ├── draw_bbox.py
│ │ │ │ ├── eval_hook.py
│ │ │ │ ├── grid_mask.py
│ │ │ │ ├── timer_cp.py
│ │ │ │ └── wechat_logger.py
│ │ │ └── view_transformation/
│ │ │ ├── __init__.py
│ │ │ ├── backward_projection/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── backward_projection.py
│ │ │ │ └── bevformer_utils/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── bevformer.py
│ │ │ │ ├── bevformer_encoder.py
│ │ │ │ ├── custom_base_transformer_layer.py
│ │ │ │ ├── multi_scale_deformable_attn_function.py
│ │ │ │ ├── positional_encoding.py
│ │ │ │ └── spatial_cross_attention_depth.py
│ │ │ └── forward_projection/
│ │ │ ├── __init__.py
│ │ │ └── view_transformer.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
│ │ │ ├── multibin_loss.py
│ │ │ ├── paconv_regularization_loss.py
│ │ │ ├── rotated_iou_loss.py
│ │ │ └── uncertain_smooth_l1_loss.py
│ │ ├── middle_encoders/
│ │ │ ├── __init__.py
│ │ │ ├── pillar_scatter.py
│ │ │ ├── sparse_encoder.py
│ │ │ └── sparse_unet.py
│ │ ├── model_utils/
│ │ │ ├── __init__.py
│ │ │ ├── edge_fusion_module.py
│ │ │ ├── transformer.py
│ │ │ └── vote_module.py
│ │ ├── necks/
│ │ │ ├── __init__.py
│ │ │ ├── dla_neck.py
│ │ │ ├── fpn.py
│ │ │ ├── imvoxel_neck.py
│ │ │ ├── lss_fpn.py
│ │ │ ├── pointnet2_fp_neck.py
│ │ │ ├── second_fpn.py
│ │ │ └── view_transformer.py
│ │ ├── roi_heads/
│ │ │ ├── __init__.py
│ │ │ ├── base_3droi_head.py
│ │ │ ├── bbox_heads/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── h3d_bbox_head.py
│ │ │ │ ├── parta2_bbox_head.py
│ │ │ │ └── point_rcnn_bbox_head.py
│ │ │ ├── h3d_roi_head.py
│ │ │ ├── mask_heads/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── pointwise_semantic_head.py
│ │ │ │ └── primitive_head.py
│ │ │ ├── part_aggregation_roi_head.py
│ │ │ ├── point_rcnn_roi_head.py
│ │ │ └── roi_extractors/
│ │ │ ├── __init__.py
│ │ │ ├── single_roiaware_extractor.py
│ │ │ └── single_roipoint_extractor.py
│ │ ├── segmentors/
│ │ │ ├── __init__.py
│ │ │ ├── base.py
│ │ │ └── encoder_decoder.py
│ │ ├── utils/
│ │ │ ├── __init__.py
│ │ │ ├── clip_sigmoid.py
│ │ │ ├── edge_indices.py
│ │ │ ├── gen_keypoints.py
│ │ │ ├── handle_objs.py
│ │ │ └── mlp.py
│ │ └── voxel_encoders/
│ │ ├── __init__.py
│ │ ├── pillar_encoder.py
│ │ ├── utils.py
│ │ └── voxel_encoder.py
│ ├── ops/
│ │ ├── __init__.py
│ │ ├── bev_pool_v2/
│ │ │ ├── __init__.py
│ │ │ ├── bev_pool.py
│ │ │ └── src/
│ │ │ ├── bev_pool.cpp
│ │ │ └── bev_pool_cuda.cu
│ │ ├── dgcnn_modules/
│ │ │ ├── __init__.py
│ │ │ ├── dgcnn_fa_module.py
│ │ │ ├── dgcnn_fp_module.py
│ │ │ └── dgcnn_gf_module.py
│ │ ├── norm.py
│ │ ├── ops_dcnv3/
│ │ │ ├── functions/
│ │ │ │ ├── __init__.py
│ │ │ │ └── dcnv3_func.py
│ │ │ ├── make.sh
│ │ │ ├── modules/
│ │ │ │ ├── __init__.py
│ │ │ │ └── dcnv3.py
│ │ │ ├── setup.py
│ │ │ ├── src/
│ │ │ │ ├── cpu/
│ │ │ │ │ ├── dcnv3_cpu.cpp
│ │ │ │ │ └── dcnv3_cpu.h
│ │ │ │ ├── cuda/
│ │ │ │ │ ├── dcnv3_cuda.cu
│ │ │ │ │ ├── dcnv3_cuda.h
│ │ │ │ │ └── dcnv3_im2col_cuda.cuh
│ │ │ │ ├── dcnv3.h
│ │ │ │ └── vision.cpp
│ │ │ └── test.py
│ │ ├── paconv/
│ │ │ ├── __init__.py
│ │ │ ├── paconv.py
│ │ │ └── utils.py
│ │ ├── pointnet_modules/
│ │ │ ├── __init__.py
│ │ │ ├── builder.py
│ │ │ ├── paconv_sa_module.py
│ │ │ ├── point_fp_module.py
│ │ │ └── point_sa_module.py
│ │ ├── sparse_block.py
│ │ └── spconv/
│ │ ├── __init__.py
│ │ └── overwrite_spconv/
│ │ ├── __init__.py
│ │ └── write_spconv2.py
│ ├── utils/
│ │ ├── __init__.py
│ │ ├── collect_env.py
│ │ ├── compat_cfg.py
│ │ ├── logger.py
│ │ ├── misc.py
│ │ └── setup_env.py
│ └── version.py
├── requirements/
│ ├── build.txt
│ ├── docs.txt
│ ├── mminstall.txt
│ ├── optional.txt
│ ├── readthedocs.txt
│ ├── runtime.txt
│ └── tests.txt
└── tools/
├── analysis_tools/
│ ├── analyze_logs.py
│ ├── benchmark.py
│ ├── benchmark_sequential.py
│ ├── benchmark_trt.py
│ ├── benchmark_view_transformer.py
│ ├── create_video.py
│ ├── generate_mask_based_on_lidar_points.py
│ ├── get_flops.py
│ ├── model_converter.py
│ ├── occupancy_cbgs.py
│ ├── vis.py
│ └── vis_occupancy.py
├── create_data.py
├── create_data.sh
├── create_data_bev_planner.py
├── data_converter/
│ ├── __init__.py
│ ├── create_gt_database.py
│ ├── imgaug_demo.py
│ ├── indoor_converter.py
│ ├── kitti_converter.py
│ ├── kitti_data_utils.py
│ ├── lyft_converter.py
│ ├── lyft_data_fixer.py
│ ├── nuimage_converter.py
│ ├── nuscenes_converter.py
│ ├── nuscenes_prediction_tools.py
│ ├── nuscenes_track_converter.py
│ ├── s3dis_data_utils.py
│ ├── scannet_data_utils.py
│ ├── sunrgbd_data_utils.py
│ └── waymo_converter.py
├── deployment/
│ ├── mmdet3d2torchserve.py
│ ├── mmdet3d_handler.py
│ └── test_torchserver.py
├── dist_test.sh
├── dist_train.sh
├── eval.py
├── misc/
│ ├── browse_dataset.py
│ ├── download.sh
│ ├── fuse_conv_bn.py
│ ├── print_config.py
│ ├── tmp.txt
│ └── visualize_results.py
├── model_converters/
│ ├── convert_h3dnet_checkpoints.py
│ ├── convert_votenet_checkpoints.py
│ ├── publish_model.py
│ └── regnet2mmdet.py
├── slurm_test.sh
├── slurm_train.sh
├── test.py
├── train.py
├── update_data_coords.py
└── update_data_coords.sh
================================================
FILE CONTENTS
================================================
================================================
FILE: .gitignore
================================================
# Byte-compiled / optimized / DLL files
__pycache__/
*.py[cod]
*.vsix
*$py.class
*.ipynb
*.zip
# C extensions
*.so
*.npz
*.npy
# Distribution / packaging
.Python
*.mp4
*.pth
*.jpg
*.jpeg
*.png
*.log
*.json
*.csv
ckpts
work_dirs
nuscenes-mini
nuscenes-mini/
work_dirs/
work_dirs_/
data/
tests/
test/
test2/
val/
ckpts/
build/
develop-eggs/
dist/
downloads/
eggs/
.eggs/
lib/
wandb/
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/
barrier
bicycle
bus
car
construction_vehicle
driveable_surface
manmade
motorcycle
other_flat
others
pedestrian
per
sidewalk
terrain
traffic_cone
trailer
truck
vegetation
# 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/
*~
mmdet3d/.mim
# Pytorch
*.pth
# demo
*.jpg
*.png
data/s3dis/Stanford3dDataset_v1.2_Aligned_Version/
data/scannet/scans/
data/sunrgbd/OFFICIAL_SUNRGBD/
*.obj
*.ply
*.pdf
# Waymo evaluation
mmdet3d/core/evaluation/waymo_utils/compute_detection_metrics_main
================================================
FILE: README.md
================================================
# Is Ego Status All You Need for Open-Loop End-to-End Autonomous Driving?
### [arXiv](http://arxiv.org/abs/2312.03031) | [知乎](https://zhuanlan.zhihu.com/p/669454065)
https://github.com/NVlabs/BEV-Planner/assets/27915819/93afa127-813f-4d36-b4f2-84f6b8d9b905
## INTRODUCTION
End-to-end autonomous driving recently emerged as a promising research direction to target autonomy from a full-stack perspective. Along this line, many of the latest works follow an open-loop evaluation setting on nuScenes to study the planning behavior. In this paper, we delve deeper into the problem by conducting thorough analyses and demystifying more devils in the details. We initially observed that the nuScenes dataset, characterized by relatively simple driving scenarios, leads to an under-utilization of perception information in end-to-end models incorporating ego status, such as the ego vehicle's velocity. These models tend to rely predominantly on the ego vehicle's status for future path planning.
Beyond the limitations of the dataset, we also note that current metrics do not comprehensively assess the planning quality, leading to potentially biased conclusions drawn from existing benchmarks. To address this issue, we introduce a new metric to evaluate whether the predicted trajectories adhere to the road.
We further propose a simple baseline able to achieve competitive results without relying on perception annotations.
Given the current limitations on the benchmark and metrics, we suggest the community reassess relevant prevailing research and be cautious whether the continued pursuit of state-of-the-art would yield convincing and universal conclusions.
## Start
### 1.Setting up Environment
### 2.Preparing Dataset
### 3.Training
### 4.Eval
================================================
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)
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/kitti/':
# 's3://openmmlab/datasets/detection3d/kitti/',
# 'data/kitti/':
# 's3://openmmlab/datasets/detection3d/kitti/'
# }))
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),
points_loader=dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4,
file_client_args=file_client_args),
file_client_args=file_client_args)
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'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4,
file_client_args=file_client_args),
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',
file_client_args=file_client_args)),
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',
file_client_args=file_client_args),
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',
file_client_args=file_client_args))
evaluation = dict(interval=1, pipeline=eval_pipeline)
================================================
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'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4,
file_client_args=file_client_args),
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, pipeline=eval_pipeline)
================================================
FILE: configs/_base_/datasets/kitti-mono3d.py
================================================
dataset_type = 'KittiMonoDataset'
data_root = 'data/kitti/'
class_names = ['Pedestrian', 'Cyclist', 'Car']
input_modality = dict(use_lidar=False, use_camera=True)
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='LoadImageFromFileMono3D'),
dict(
type='LoadAnnotations3D',
with_bbox=True,
with_label=True,
with_attr_label=False,
with_bbox_3d=True,
with_label_3d=True,
with_bbox_depth=True),
dict(type='Resize', img_scale=(1242, 375), keep_ratio=True),
dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
dict(type='Normalize', **img_norm_cfg),
dict(type='Pad', size_divisor=32),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(
type='Collect3D',
keys=[
'img', 'gt_bboxes', 'gt_labels', 'gt_bboxes_3d', 'gt_labels_3d',
'centers2d', 'depths'
]),
]
test_pipeline = [
dict(type='LoadImageFromFileMono3D'),
dict(
type='MultiScaleFlipAug',
img_scale=(1242, 375),
flip=False,
transforms=[
dict(type='RandomFlip3D'),
dict(type='Normalize', **img_norm_cfg),
dict(type='Pad', size_divisor=32),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['img']),
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_pipeline = [
dict(type='LoadImageFromFileMono3D'),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['img'])
]
data = dict(
samples_per_gpu=2,
workers_per_gpu=2,
train=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_train_mono3d.coco.json',
info_file=data_root + 'kitti_infos_train.pkl',
img_prefix=data_root,
classes=class_names,
pipeline=train_pipeline,
modality=input_modality,
test_mode=False,
box_type_3d='Camera'),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val_mono3d.coco.json',
info_file=data_root + 'kitti_infos_val.pkl',
img_prefix=data_root,
classes=class_names,
pipeline=test_pipeline,
modality=input_modality,
test_mode=True,
box_type_3d='Camera'),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'kitti_infos_val_mono3d.coco.json',
info_file=data_root + 'kitti_infos_val.pkl',
img_prefix=data_root,
classes=class_names,
pipeline=test_pipeline,
modality=input_modality,
test_mode=True,
box_type_3d='Camera'))
evaluation = dict(interval=2)
================================================
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'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_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='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, pipeline=eval_pipeline)
================================================
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'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_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='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
]
data = dict(
samples_per_gpu=4,
workers_per_gpu=4,
test_dataloader=dict(runner_type='EpochBasedRunner'),
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, pipeline=eval_pipeline)
================================================
FILE: configs/_base_/datasets/nus-mono3d.py
================================================
dataset_type = 'NuScenesMonoDataset'
data_root = 'data/nuscenes/'
class_names = [
'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',
'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'
]
# Input modality for nuScenes dataset, this is consistent with the submission
# format which requires the information in input_modality.
input_modality = dict(
use_lidar=False,
use_camera=True,
use_radar=False,
use_map=False,
use_external=False)
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='LoadImageFromFileMono3D'),
dict(
type='LoadAnnotations3D',
with_bbox=True,
with_label=True,
with_attr_label=True,
with_bbox_3d=True,
with_label_3d=True,
with_bbox_depth=True),
dict(type='Resize', img_scale=(1600, 900), keep_ratio=True),
dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
dict(type='Normalize', **img_norm_cfg),
dict(type='Pad', size_divisor=32),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(
type='Collect3D',
keys=[
'img', 'gt_bboxes', 'gt_labels', 'attr_labels', 'gt_bboxes_3d',
'gt_labels_3d', 'centers2d', 'depths'
]),
]
test_pipeline = [
dict(type='LoadImageFromFileMono3D'),
dict(
type='MultiScaleFlipAug',
scale_factor=1.0,
flip=False,
transforms=[
dict(type='RandomFlip3D'),
dict(type='Normalize', **img_norm_cfg),
dict(type='Pad', size_divisor=32),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['img']),
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_pipeline = [
dict(type='LoadImageFromFileMono3D'),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['img'])
]
data = dict(
samples_per_gpu=2,
workers_per_gpu=2,
train=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'nuscenes_infos_train_mono3d.coco.json',
img_prefix=data_root,
classes=class_names,
pipeline=train_pipeline,
modality=input_modality,
test_mode=False,
box_type_3d='Camera'),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'nuscenes_infos_val_mono3d.coco.json',
img_prefix=data_root,
classes=class_names,
pipeline=test_pipeline,
modality=input_modality,
test_mode=True,
box_type_3d='Camera'),
test=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'nuscenes_infos_val_mono3d.coco.json',
img_prefix=data_root,
classes=class_names,
pipeline=test_pipeline,
modality=input_modality,
test_mode=True,
box_type_3d='Camera'))
evaluation = dict(interval=2)
================================================
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'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_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='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, pipeline=eval_pipeline)
================================================
FILE: configs/_base_/datasets/s3dis-3d-5class.py
================================================
# dataset settings
dataset_type = 'S3DISDataset'
data_root = './data/s3dis/'
class_names = ('table', 'chair', 'sofa', 'bookcase', 'board')
train_area = [1, 2, 3, 4, 6]
test_area = 5
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=True,
load_dim=6,
use_dim=[0, 1, 2, 3, 4, 5]),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),
dict(type='PointSample', num_points=40000),
dict(
type='RandomFlip3D',
sync_2d=False,
flip_ratio_bev_horizontal=0.5,
flip_ratio_bev_vertical=0.5),
dict(
type='GlobalRotScaleTrans',
# following ScanNet dataset the rotation range is 5 degrees
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'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=True,
load_dim=6,
use_dim=[0, 1, 2, 3, 4, 5]),
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='PointSample', num_points=40000),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=False,
load_dim=6,
use_dim=[0, 1, 2, 3, 4, 5]),
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='ConcatDataset',
datasets=[
dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + f's3dis_infos_Area_{i}.pkl',
pipeline=train_pipeline,
filter_empty_gt=False,
classes=class_names,
box_type_3d='Depth') for i in train_area
],
separate_eval=False)),
val=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + f's3dis_infos_Area_{test_area}.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 + f's3dis_infos_Area_{test_area}.pkl',
pipeline=test_pipeline,
classes=class_names,
test_mode=True,
box_type_3d='Depth'))
evaluation = dict(pipeline=eval_pipeline)
================================================
FILE: configs/_base_/datasets/s3dis_seg-3d-13class.py
================================================
# dataset settings
dataset_type = 'S3DISSegDataset'
data_root = './data/s3dis/'
class_names = ('ceiling', 'floor', 'wall', 'beam', 'column', 'window', 'door',
'table', 'chair', 'sofa', 'bookcase', 'board', 'clutter')
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/s3dis/':
# 's3://openmmlab/datasets/detection3d/s3dis_processed/',
# 'data/s3dis/':
# 's3://openmmlab/datasets/detection3d/s3dis_processed/'
# }))
num_points = 4096
train_area = [1, 2, 3, 4, 6]
test_area = 5
train_pipeline = [
dict(
type='LoadPointsFromFile',
file_client_args=file_client_args,
coord_type='DEPTH',
shift_height=False,
use_color=True,
load_dim=6,
use_dim=[0, 1, 2, 3, 4, 5]),
dict(
type='LoadAnnotations3D',
file_client_args=file_client_args,
with_bbox_3d=False,
with_label_3d=False,
with_mask_3d=False,
with_seg_3d=True),
dict(
type='PointSegClassMapping',
valid_cat_ids=tuple(range(len(class_names))),
max_cat_id=13),
dict(
type='IndoorPatchPointSample',
num_points=num_points,
block_size=1.0,
ignore_index=len(class_names),
use_normalized_coord=True,
enlarge_size=0.2,
min_unique_num=None),
dict(type='NormalizePointsColor', color_mean=None),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
file_client_args=file_client_args,
coord_type='DEPTH',
shift_height=False,
use_color=True,
load_dim=6,
use_dim=[0, 1, 2, 3, 4, 5]),
dict(type='NormalizePointsColor', color_mean=None),
dict(
# a wrapper in order to successfully call test function
# actually we don't perform test-time-aug
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.0,
flip_ratio_bev_vertical=0.0),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
# we need to load gt seg_mask!
eval_pipeline = [
dict(
type='LoadPointsFromFile',
file_client_args=file_client_args,
coord_type='DEPTH',
shift_height=False,
use_color=True,
load_dim=6,
use_dim=[0, 1, 2, 3, 4, 5]),
dict(
type='LoadAnnotations3D',
file_client_args=file_client_args,
with_bbox_3d=False,
with_label_3d=False,
with_mask_3d=False,
with_seg_3d=True),
dict(
type='PointSegClassMapping',
valid_cat_ids=tuple(range(len(class_names))),
max_cat_id=13),
dict(
type='DefaultFormatBundle3D',
with_label=False,
class_names=class_names),
dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])
]
data = dict(
samples_per_gpu=8,
workers_per_gpu=4,
# train on area 1, 2, 3, 4, 6
# test on area 5
train=dict(
type=dataset_type,
data_root=data_root,
ann_files=[
data_root + f's3dis_infos_Area_{i}.pkl' for i in train_area
],
pipeline=train_pipeline,
classes=class_names,
test_mode=False,
ignore_index=len(class_names),
scene_idxs=[
data_root + f'seg_info/Area_{i}_resampled_scene_idxs.npy'
for i in train_area
],
file_client_args=file_client_args),
val=dict(
type=dataset_type,
data_root=data_root,
ann_files=data_root + f's3dis_infos_Area_{test_area}.pkl',
pipeline=test_pipeline,
classes=class_names,
test_mode=True,
ignore_index=len(class_names),
scene_idxs=data_root +
f'seg_info/Area_{test_area}_resampled_scene_idxs.npy',
file_client_args=file_client_args),
test=dict(
type=dataset_type,
data_root=data_root,
ann_files=data_root + f's3dis_infos_Area_{test_area}.pkl',
pipeline=test_pipeline,
classes=class_names,
test_mode=True,
ignore_index=len(class_names),
file_client_args=file_client_args))
evaluation = dict(pipeline=eval_pipeline)
================================================
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')
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/scannet/':
# 's3://openmmlab/datasets/detection3d/scannet_processed/',
# 'data/scannet/':
# 's3://openmmlab/datasets/detection3d/scannet_processed/'
# }))
train_pipeline = [
dict(
type='LoadPointsFromFile',
file_client_args=file_client_args,
coord_type='DEPTH',
shift_height=True,
load_dim=6,
use_dim=[0, 1, 2]),
dict(
type='LoadAnnotations3D',
file_client_args=file_client_args,
with_bbox_3d=True,
with_label_3d=True,
with_mask_3d=True,
with_seg_3d=True),
dict(type='GlobalAlignment', rotation_axis=2),
dict(
type='PointSegClassMapping',
valid_cat_ids=(3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24, 28, 33, 34,
36, 39),
max_cat_id=40),
dict(type='PointSample', 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',
file_client_args=file_client_args,
coord_type='DEPTH',
shift_height=True,
load_dim=6,
use_dim=[0, 1, 2]),
dict(type='GlobalAlignment', rotation_axis=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='PointSample', num_points=40000),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_pipeline = [
dict(
type='LoadPointsFromFile',
file_client_args=file_client_args,
coord_type='DEPTH',
shift_height=False,
load_dim=6,
use_dim=[0, 1, 2]),
dict(type='GlobalAlignment', rotation_axis=2),
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',
file_client_args=file_client_args)),
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',
file_client_args=file_client_args),
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_client_args=file_client_args))
evaluation = dict(pipeline=eval_pipeline)
================================================
FILE: configs/_base_/datasets/scannet_seg-3d-20class.py
================================================
# dataset settings
dataset_type = 'ScanNetSegDataset'
data_root = './data/scannet/'
class_names = ('wall', 'floor', 'cabinet', 'bed', 'chair', 'sofa', 'table',
'door', 'window', 'bookshelf', 'picture', 'counter', 'desk',
'curtain', 'refrigerator', 'showercurtrain', 'toilet', 'sink',
'bathtub', 'otherfurniture')
num_points = 8192
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/scannet/':
# 's3://openmmlab/datasets/detection3d/scannet_processed/',
# 'data/scannet/':
# 's3://openmmlab/datasets/detection3d/scannet_processed/'
# }))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=False,
use_color=True,
load_dim=6,
use_dim=[0, 1, 2, 3, 4, 5],
file_client_args=file_client_args),
dict(
type='LoadAnnotations3D',
with_bbox_3d=False,
with_label_3d=False,
with_mask_3d=False,
with_seg_3d=True,
file_client_args=file_client_args),
dict(
type='PointSegClassMapping',
valid_cat_ids=(1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24, 28,
33, 34, 36, 39),
max_cat_id=40),
dict(
type='IndoorPatchPointSample',
num_points=num_points,
block_size=1.5,
ignore_index=len(class_names),
use_normalized_coord=False,
enlarge_size=0.2,
min_unique_num=None),
dict(type='NormalizePointsColor', color_mean=None),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])
]
test_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=False,
use_color=True,
load_dim=6,
use_dim=[0, 1, 2, 3, 4, 5],
file_client_args=file_client_args),
dict(type='NormalizePointsColor', color_mean=None),
dict(
# a wrapper in order to successfully call test function
# actually we don't perform test-time-aug
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.0,
flip_ratio_bev_vertical=0.0),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
# we need to load gt seg_mask!
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=False,
use_color=True,
load_dim=6,
use_dim=[0, 1, 2, 3, 4, 5],
file_client_args=file_client_args),
dict(
type='LoadAnnotations3D',
with_bbox_3d=False,
with_label_3d=False,
with_mask_3d=False,
with_seg_3d=True,
file_client_args=file_client_args),
dict(
type='PointSegClassMapping',
valid_cat_ids=(1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24, 28,
33, 34, 36, 39),
max_cat_id=40),
dict(
type='DefaultFormatBundle3D',
with_label=False,
class_names=class_names),
dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])
]
data = dict(
samples_per_gpu=8,
workers_per_gpu=4,
train=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'scannet_infos_train.pkl',
pipeline=train_pipeline,
classes=class_names,
test_mode=False,
ignore_index=len(class_names),
scene_idxs=data_root + 'seg_info/train_resampled_scene_idxs.npy',
file_client_args=file_client_args),
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,
ignore_index=len(class_names),
file_client_args=file_client_args),
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,
ignore_index=len(class_names),
file_client_args=file_client_args))
evaluation = dict(pipeline=eval_pipeline)
================================================
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')
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/sunrgbd/':
# 's3://openmmlab/datasets/detection3d/sunrgbd_processed/',
# 'data/sunrgbd/':
# 's3://openmmlab/datasets/detection3d/sunrgbd_processed/'
# }))
train_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=True,
load_dim=6,
use_dim=[0, 1, 2],
file_client_args=file_client_args),
dict(type='LoadAnnotations3D', file_client_args=file_client_args),
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='PointSample', 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],
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',
sync_2d=False,
flip_ratio_bev_horizontal=0.5,
),
dict(type='PointSample', num_points=20000),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=False,
load_dim=6,
use_dim=[0, 1, 2],
file_client_args=file_client_args),
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',
file_client_args=file_client_args)),
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',
file_client_args=file_client_args),
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_client_args=file_client_args))
evaluation = dict(pipeline=eval_pipeline)
================================================
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',
coord_type='LIDAR',
load_dim=6,
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'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=6,
use_dim=5,
file_client_args=file_client_args),
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, pipeline=eval_pipeline)
================================================
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=6,
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'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=6,
use_dim=5,
file_client_args=file_client_args),
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, pipeline=eval_pipeline)
================================================
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)]
# disable opencv multithreading to avoid system being overloaded
opencv_num_threads = 0
# set multi-process start method as `fork` to speed up the training
mp_start_method = 'fork'
================================================
FILE: configs/_base_/init.py
================================================
# Copyright (c) Phigent Robotics. All rights reserved.
_base_ = ['../_base_/datasets/nus-3d.py', '../_base_/default_runtime.py']
# Global
# If point cloud range is changed, the models should also change their point
# cloud range accordingly
point_cloud_range = [-40, -40, -1.0, 40, 40, 5.4]
# For nuScenes we usually do 10-class detection
class_names = [
'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',
'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'
]
data_config = {
'cams': [
'CAM_FRONT_LEFT', 'CAM_FRONT', 'CAM_FRONT_RIGHT', 'CAM_BACK_LEFT',
'CAM_BACK', 'CAM_BACK_RIGHT'
],
'Ncams':
6,
'input_size': (256, 704),
'src_size': (900, 1600),
# Augmentation
'resize': (-0.06, 0.11),
'rot': (-5.4, 5.4),
'flip': True,
'crop_h': (0.0, 0.0),
'resize_test': 0.00,
}
use_checkpoint = True
sync_bn = True
# Model
grid_config = {
'x': [-40, 40, 0.8],
'y': [-40, 40, 0.8],
'z': [-1, 5.4, 0.8],
'depth': [2.0, 42.0, 0.5],
}
depth_categories = 80 #(grid_config['depth'][1]-grid_config['depth'][0])//grid_config['depth'][2]
use_custom_eval_hook=True
bda_aug_conf = dict(
rot_lim=(-22.5, 22.5),
scale_lim=(1., 1.),
flip_dx_ratio=0.5,
flip_dy_ratio=0.5)
num_Z_anchors = 8
voxel_size = [0.1, 0.1, 0.1]
bev_h_ = 100
bev_w_ = 100
_dim_ = 256
_pos_dim_ = _dim_//2
_ffn_dim_ = _dim_ * 2
_num_levels_= 1
numC_Trans=80
empty_idx = 0 # noise 0-->255
num_cls = 18 # 0 free, 1-16 obj
visible_mask = False
img_norm_cfg = None
cascade_ratio = 4
sample_from_voxel = False
sample_from_img = False
occ_size = [200, 200, 16]
voxel_out_indices = (0, 1, 2)
voxel_out_channel = 256
voxel_channels = [64, 64*2, 64*4]
model = dict(
type='NewBEV',
use_depth_supervision=True,
img_backbone=dict(
# pretrained='ckpts/resnet50-0676ba61.pth',
type='ResNet',
depth=50,
num_stages=4,
out_indices=(2, 3),
frozen_stages=-1,
norm_cfg=dict(type='BN', requires_grad=True),
norm_eval=False,
with_cp=use_checkpoint,
style='pytorch'),
img_neck=dict(
type='CustomFPN',
in_channels=[1024, 2048],
out_channels=_dim_,
num_outs=1,
start_level=0,
with_cp=use_checkpoint,
out_ids=[0]),
depth_net=dict(
type='CM_DepthNet',
in_channels=_dim_,
context_channels=numC_Trans,
downsample=16,
grid_config=grid_config,
depth_channels=depth_categories,
with_cp=use_checkpoint,
loss_depth_weight=1.,
use_dcn=False,
),
img_view_transformer=dict(
type='LSSViewTransformerFunction3D',
grid_config=grid_config,
input_size=data_config['input_size'],
# in_channels=256,
# out_channels=numC_Trans,
downsample=16),
frpn=None,
bevformer_encoder=None,
img_bev_encoder_backbone=dict(
type='CustomResNet3D',
depth=18,
with_cp=use_checkpoint,
block_strides=[1, 2, 2],
n_input_channels=numC_Trans,
block_inplanes=voxel_channels,
out_indices=voxel_out_indices,
norm_cfg=dict(type='SyncBN', requires_grad=True),
),
img_bev_encoder_neck=dict(
type='FPN3D',
with_cp=use_checkpoint,
in_channels=voxel_channels,
out_channels=voxel_out_channel,
norm_cfg=dict(type='SyncBN', requires_grad=True),
),
occupancy_head= dict(
type='OccHead',
with_cp=use_checkpoint,
norm_cfg=dict(type='SyncBN', requires_grad=True),
soft_weights=True,
cascade_ratio=cascade_ratio,
sample_from_voxel=sample_from_voxel,
sample_from_img=sample_from_img,
final_occ_size=occ_size,
fine_topk=15000,
empty_idx=empty_idx,
num_level=len(voxel_out_indices),
in_channels=[voxel_out_channel] * len(voxel_out_indices),
out_channel=num_cls,
point_cloud_range=point_cloud_range,
loss_weight_cfg=dict(
loss_voxel_ce_weight=1.0,
loss_voxel_sem_scal_weight=1.0,
loss_voxel_geo_scal_weight=1.0,
loss_voxel_lovasz_weight=1.0,
),
),
pts_bbox_head=None)
# Data
dataset_type = 'NuScenesDataset'
data_root = 'data/nuscenes/'
file_client_args = dict(backend='disk')
occupancy_path = '/mount/data/occupancy_cvpr2023/gts'
dense_lidar_prefix = '/mount/data/nuscenes/'
train_pipeline = [
dict(
type='PrepareImageInputs',
is_train=True,
data_config=data_config),
dict(
type='LoadAnnotationsBEVDepth',
bda_aug_conf=bda_aug_conf,
classes=class_names),
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
dense_lidar_prefix=dense_lidar_prefix,
file_client_args=file_client_args),
dict(type='PointToMultiViewDepth', downsample=1, grid_config=grid_config),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
#
dict(type='LoadBEVMask', point_cloud_range=point_cloud_range, bev_size=(bev_h_, bev_w_)),
dict(type='LoadOccupancy', ignore_nonvisible=True, occupancy_path=occupancy_path),
# dict(type='PadMultiViewImage'),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(
type='Collect3D', keys=['img_inputs', 'gt_bboxes_3d', 'gt_labels_3d', 'gt_bev_mask', 'gt_occupancy', 'gt_depth'
])
]
test_pipeline = [
dict(type='PrepareImageInputs', data_config=data_config),
dict(
type='LoadAnnotationsBEVDepth',
bda_aug_conf=bda_aug_conf,
classes=class_names,
is_train=False),
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
dense_lidar_prefix=dense_lidar_prefix,
file_client_args=file_client_args),
dict(type='LoadBEVMask'),
dict(type='LoadOccupancy', occupancy_path=occupancy_path),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points', 'img_inputs', 'gt_bev_mask', 'gt_occupancy', 'visible_mask'])
])
]
input_modality = dict(
use_lidar=False,
use_camera=True,
use_radar=False,
use_map=False,
use_external=False)
share_data_config = dict(
type=dataset_type,
classes=class_names,
modality=input_modality,
img_info_prototype='bevdet',
occupancy_path=occupancy_path,
)
test_data_config = dict(
pipeline=test_pipeline,
ann_file=data_root + 'bevdetv2-nuscenes_infos_val.pkl')
data = dict(
samples_per_gpu=2,
workers_per_gpu=6,
test_dataloader=dict(runner_type='EpochBasedRunner'),
train=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'bevdetv2-nuscenes_infos_train.pkl',
pipeline=train_pipeline,
classes=class_names,
test_mode=False,
use_valid_flag=True,
modality=input_modality,
img_info_prototype='bevdet',
# 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=test_data_config,
test=test_data_config)
for key in ['val', 'test']:
data[key].update(share_data_config)
# data['train']['dataset'].update(share_data_config)
# Optimizer
optimizer = dict(type='AdamW', lr=1.4e-4, weight_decay=1e-2)
optimizer_config = dict(grad_clip=dict(max_norm=5, norm_type=2))
lr_config = dict(
policy='step',
warmup='linear',
warmup_iters=200,
warmup_ratio=0.001,
step=[1,])
runner = dict(type='EpochBasedRunner', max_epochs=1)
log_config = dict(
interval=50,
hooks=[
dict(type='WechatLoggerHook'),
dict(type='TextLoggerHook'),
# dict(type='TensorboardLoggerHook')
])
custom_hooks = [
dict(
type='MEGVIIEMAHook',
init_updates=10560,
priority='NORMAL',
),
dict(
type='ForgeLoadWorker',
priority='VERY_LOW',
),
]
# load_from = 'ckpt1s/r50_256x705_depth_pretrain.pth'
evaluation = dict(interval=12, pipeline=test_pipeline)
fp16 = dict(loss_scale='dynamic')
# checkpoint_config = dict(interval=5)
# find_unused_parameters=True
# Input shape: (256, 704)
# Flops: 192.3 GFLOPs
# Params: 58.39 M
# find_unused_parameters=True
================================================
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))
================================================
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_pre=2000,
nms_post=2000,
max_per_img=2000,
nms=dict(type='nms', iou_threshold=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_pre=1000,
nms_post=1000,
max_per_img=1000,
nms=dict(type='nms', iou_threshold=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/dgcnn.py
================================================
# model settings
model = dict(
type='EncoderDecoder3D',
backbone=dict(
type='DGCNNBackbone',
in_channels=9, # [xyz, rgb, normal_xyz], modified with dataset
num_samples=(20, 20, 20),
knn_modes=('D-KNN', 'F-KNN', 'F-KNN'),
radius=(None, None, None),
gf_channels=((64, 64), (64, 64), (64, )),
fa_channels=(1024, ),
act_cfg=dict(type='LeakyReLU', negative_slope=0.2)),
decode_head=dict(
type='DGCNNHead',
fp_channels=(1216, 512),
channels=256,
dropout_ratio=0.5,
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
act_cfg=dict(type='LeakyReLU', negative_slope=0.2),
loss_decode=dict(
type='CrossEntropyLoss',
use_sigmoid=False,
class_weight=None, # modified with dataset
loss_weight=1.0)),
# model training and testing settings
train_cfg=dict(),
test_cfg=dict(mode='slide'))
================================================
FILE: configs/_base_/models/fcaf3d.py
================================================
model = dict(
type='MinkSingleStage3DDetector',
voxel_size=.01,
backbone=dict(type='MinkResNet', in_channels=3, depth=34),
head=dict(
type='FCAF3DHead',
in_channels=(64, 128, 256, 512),
out_channels=128,
voxel_size=.01,
pts_prune_threshold=100000,
pts_assign_threshold=27,
pts_center_threshold=18,
n_classes=18,
n_reg_outs=6),
train_cfg=dict(),
test_cfg=dict(nms_pre=1000, iou_thr=.5, score_thr=.01))
================================================
FILE: configs/_base_/models/fcos3d.py
================================================
model = dict(
type='FCOSMono3D',
backbone=dict(
type='ResNet',
depth=101,
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',
init_cfg=dict(
type='Pretrained',
checkpoint='open-mmlab://detectron2/resnet101_caffe')),
neck=dict(
type='FPN',
in_channels=[256, 512, 1024, 2048],
out_channels=256,
start_level=1,
add_extra_convs='on_output',
num_outs=5,
relu_before_extra_convs=True),
bbox_head=dict(
type='FCOSMono3DHead',
num_classes=10,
in_channels=256,
stacked_convs=2,
feat_channels=256,
use_direction_classifier=True,
diff_rad_by_sin=True,
pred_attrs=True,
pred_velo=True,
dir_offset=0.7854, # pi/4
dir_limit_offset=0,
strides=[8, 16, 32, 64, 128],
group_reg_dims=(2, 1, 3, 1, 2), # offset, depth, size, rot, velo
cls_branch=(256, ),
reg_branch=(
(256, ), # offset
(256, ), # depth
(256, ), # size
(256, ), # rot
() # velo
),
dir_branch=(256, ),
attr_branch=(256, ),
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=1.0),
loss_attr=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),
loss_centerness=dict(
type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),
bbox_coder=dict(type='FCOS3DBBoxCoder', code_size=9),
norm_on_bbox=True,
centerness_on_reg=True,
center_sampling=True,
conv_bias=True,
dcn_on_last_conv=True),
train_cfg=dict(
allowed_border=0,
code_weight=[1.0, 1.0, 0.2, 1.0, 1.0, 1.0, 1.0, 0.05, 0.05],
pos_weight=-1,
debug=False),
test_cfg=dict(
use_rotate_nms=True,
nms_across_levels=False,
nms_pre=1000,
nms_thr=0.8,
score_thr=0.05,
min_bbox_size=0,
max_per_img=200))
================================================
FILE: configs/_base_/models/groupfree3d.py
================================================
model = dict(
type='GroupFree3DNet',
backbone=dict(
type='PointNet2SASSG',
in_channels=3,
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, 288)),
norm_cfg=dict(type='BN2d'),
sa_cfg=dict(
type='PointSAModule',
pool_mod='max',
use_xyz=True,
normalize_xyz=True)),
bbox_head=dict(
type='GroupFree3DHead',
in_channels=288,
num_decoder_layers=6,
num_proposal=256,
transformerlayers=dict(
type='BaseTransformerLayer',
attn_cfgs=dict(
type='GroupFree3DMHA',
embed_dims=288,
num_heads=8,
attn_drop=0.1,
dropout_layer=dict(type='Dropout', drop_prob=0.1)),
ffn_cfgs=dict(
embed_dims=288,
feedforward_channels=2048,
ffn_drop=0.1,
act_cfg=dict(type='ReLU', inplace=True)),
operation_order=('self_attn', 'norm', 'cross_attn', 'norm', 'ffn',
'norm')),
pred_layer_cfg=dict(
in_channels=288, shared_conv_channels=(288, 288), bias=True),
sampling_objectness_loss=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=8.0),
objectness_loss=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=1.0),
center_loss=dict(
type='SmoothL1Loss', reduction='sum', loss_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', beta=1.0, reduction='sum', loss_weight=10.0),
semantic_loss=dict(
type='CrossEntropyLoss', reduction='sum', loss_weight=1.0)),
# model training and testing settings
train_cfg=dict(sample_mod='kps'),
test_cfg=dict(
sample_mod='kps',
nms_thr=0.25,
score_thr=0.0,
per_class_proposal=True,
prediction_stages='last'))
================================================
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=[
[2.5981, 0.8660, 1.], # 1.5 / sqrt(3)
[1.7321, 0.5774, 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
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, # max_points_per_voxel
point_cloud_range=[0, -39.68, -3, 69.12, 39.68, 1],
voxel_size=voxel_size,
max_voxels=(16000, 40000) # (training, testing) max_voxels
),
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,
assign_per_class=True,
anchor_generator=dict(
type='AlignedAnchor3DRangeGenerator',
ranges=[
[0, -39.68, -0.6, 69.12, 39.68, -0.6],
[0, -39.68, -0.6, 69.12, 39.68, -0.6],
[0, -39.68, -1.78, 69.12, 39.68, -1.78],
],
sizes=[[0.8, 0.6, 1.73], [1.76, 0.6, 1.73], [3.9, 1.6, 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=[
[4.73, 2.08, 1.77], # car
[1.81, 0.84, 1.77], # cyclist
[0.91, 0.84, 1.74] # pedestrian
],
rotations=[0, 1.57],
reshape_out=False),
diff_rad_by_sin=True,
dir_offset=-0.7854, # -pi / 4
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
================================================
voxel_size = [0.05, 0.05, 0.1]
model = dict(
type='VoxelNet',
voxel_layer=dict(
max_num_points=5,
point_cloud_range=[0, -40, -3, 70.4, 40, 1],
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.8, 0.6, 1.73], [1.76, 0.6, 1.73], [3.9, 1.6, 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=[
[4.73, 2.08, 1.77], # car
[0.91, 0.84, 1.74], # pedestrian
[1.81, 0.84, 1.77] # cyclist
],
rotations=[0, 1.57],
reshape_out=False),
diff_rad_by_sin=True,
dir_offset=-0.7854, # -pi / 4
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_per_img=1000,
nms=dict(type='nms', iou_threshold=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_per_img=1000,
nms=dict(type='nms', iou_threshold=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_per_img=1000,
nms=dict(type='nms', iou_threshold=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_per_img=1000,
nms=dict(type='nms', iou_threshold=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/paconv_cuda_ssg.py
================================================
_base_ = './paconv_ssg.py'
model = dict(
backbone=dict(
sa_cfg=dict(
type='PAConvCUDASAModule',
scorenet_cfg=dict(mlp_channels=[8, 16, 16]))))
================================================
FILE: configs/_base_/models/paconv_ssg.py
================================================
# model settings
model = dict(
type='EncoderDecoder3D',
backbone=dict(
type='PointNet2SASSG',
in_channels=9, # [xyz, rgb, normalized_xyz]
num_points=(1024, 256, 64, 16),
radius=(None, None, None, None), # use kNN instead of ball query
num_samples=(32, 32, 32, 32),
sa_channels=((32, 32, 64), (64, 64, 128), (128, 128, 256), (256, 256,
512)),
fp_channels=(),
norm_cfg=dict(type='BN2d', momentum=0.1),
sa_cfg=dict(
type='PAConvSAModule',
pool_mod='max',
use_xyz=True,
normalize_xyz=False,
paconv_num_kernels=[16, 16, 16],
paconv_kernel_input='w_neighbor',
scorenet_input='w_neighbor_dist',
scorenet_cfg=dict(
mlp_channels=[16, 16, 16],
score_norm='softmax',
temp_factor=1.0,
last_bn=False))),
decode_head=dict(
type='PAConvHead',
# PAConv model's decoder takes skip connections from beckbone
# different from PointNet++, it also concats input features in the last
# level of decoder, leading to `128 + 6` as the channel number
fp_channels=((768, 256, 256), (384, 256, 256), (320, 256, 128),
(128 + 6, 128, 128, 128)),
channels=128,
dropout_ratio=0.5,
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
act_cfg=dict(type='ReLU'),
loss_decode=dict(
type='CrossEntropyLoss',
use_sigmoid=False,
class_weight=None, # should be modified with dataset
loss_weight=1.0)),
# correlation loss to regularize PAConv's kernel weights
loss_regularization=dict(
type='PAConvRegularizationLoss', reduction='sum', loss_weight=10.0),
# model training and testing settings
train_cfg=dict(),
test_cfg=dict(mode='slide'))
================================================
FILE: configs/_base_/models/parta2.py
================================================
# model settings
voxel_size = [0.05, 0.05, 0.1]
point_cloud_range = [0, -40, -3, 70.4, 40, 1]
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_voxels
),
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.8, 0.6, 1.73], [1.76, 0.6, 1.73], [3.9, 1.6, 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.1)))
================================================
FILE: configs/_base_/models/pgd.py
================================================
_base_ = './fcos3d.py'
# model settings
model = dict(
bbox_head=dict(
_delete_=True,
type='PGDHead',
num_classes=10,
in_channels=256,
stacked_convs=2,
feat_channels=256,
use_direction_classifier=True,
diff_rad_by_sin=True,
pred_attrs=True,
pred_velo=True,
pred_bbox2d=True,
pred_keypoints=False,
dir_offset=0.7854, # pi/4
strides=[8, 16, 32, 64, 128],
group_reg_dims=(2, 1, 3, 1, 2), # offset, depth, size, rot, velo
cls_branch=(256, ),
reg_branch=(
(256, ), # offset
(256, ), # depth
(256, ), # size
(256, ), # rot
() # velo
),
dir_branch=(256, ),
attr_branch=(256, ),
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=1.0),
loss_attr=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),
loss_centerness=dict(
type='CrossEntropyLoss', use_sigmoid=True, loss_weight=1.0),
norm_on_bbox=True,
centerness_on_reg=True,
center_sampling=True,
conv_bias=True,
dcn_on_last_conv=True,
use_depth_classifier=True,
depth_branch=(256, ),
depth_range=(0, 50),
depth_unit=10,
division='uniform',
depth_bins=6,
bbox_coder=dict(type='PGDBBoxCoder', code_size=9)),
test_cfg=dict(nms_pre=1000, nms_thr=0.8, score_thr=0.01, max_per_img=200))
================================================
FILE: configs/_base_/models/point_rcnn.py
================================================
model = dict(
type='PointRCNN',
backbone=dict(
type='PointNet2SAMSG',
in_channels=4,
num_points=(4096, 1024, 256, 64),
radii=((0.1, 0.5), (0.5, 1.0), (1.0, 2.0), (2.0, 4.0)),
num_samples=((16, 32), (16, 32), (16, 32), (16, 32)),
sa_channels=(((16, 16, 32), (32, 32, 64)), ((64, 64, 128), (64, 96,
128)),
((128, 196, 256), (128, 196, 256)), ((256, 256, 512),
(256, 384, 512))),
fps_mods=(('D-FPS'), ('D-FPS'), ('D-FPS'), ('D-FPS')),
fps_sample_range_lists=((-1), (-1), (-1), (-1)),
aggregation_channels=(None, None, None, None),
dilated_group=(False, False, False, False),
out_indices=(0, 1, 2, 3),
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)),
neck=dict(
type='PointNetFPNeck',
fp_channels=((1536, 512, 512), (768, 512, 512), (608, 256, 256),
(257, 128, 128))),
rpn_head=dict(
type='PointRPNHead',
num_classes=3,
enlarge_width=0.1,
pred_layer_cfg=dict(
in_channels=128,
cls_linear_channels=(256, 256),
reg_linear_channels=(256, 256)),
cls_loss=dict(
type='FocalLoss',
use_sigmoid=True,
reduction='sum',
gamma=2.0,
alpha=0.25,
loss_weight=1.0),
bbox_loss=dict(
type='SmoothL1Loss',
beta=1.0 / 9.0,
reduction='sum',
loss_weight=1.0),
bbox_coder=dict(
type='PointXYZWHLRBBoxCoder',
code_size=8,
# code_size: (center residual (3), size regression (3),
# torch.cos(yaw) (1), torch.sin(yaw) (1)
use_mean_size=True,
mean_size=[[3.9, 1.6, 1.56], [0.8, 0.6, 1.73], [1.76, 0.6,
1.73]])),
roi_head=dict(
type='PointRCNNRoIHead',
point_roi_extractor=dict(
type='Single3DRoIPointExtractor',
roi_layer=dict(type='RoIPointPool3d', num_sampled_points=512)),
bbox_head=dict(
type='PointRCNNBboxHead',
num_classes=1,
pred_layer_cfg=dict(
in_channels=512,
cls_conv_channels=(256, 256),
reg_conv_channels=(256, 256),
bias=True),
in_channels=5,
# 5 = 3 (xyz) + scores + depth
mlp_channels=[128, 128],
num_points=(128, 32, -1),
radius=(0.2, 0.4, 100),
num_samples=(16, 16, 16),
sa_channels=((128, 128, 128), (128, 128, 256), (256, 256, 512)),
with_corner_loss=True),
depth_normalizer=70.0),
# model training and testing settings
train_cfg=dict(
pos_distance_thr=10.0,
rpn=dict(
nms_cfg=dict(
use_rotate_nms=True, iou_thr=0.8, nms_pre=9000, nms_post=512),
score_thr=None),
rcnn=dict(
assigner=[
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,
match_low_quality=False),
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,
match_low_quality=False),
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,
match_low_quality=False)
],
sampler=dict(
type='IoUNegPiecewiseSampler',
num=128,
pos_fraction=0.5,
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.7,
cls_neg_thr=0.25)),
test_cfg=dict(
rpn=dict(
nms_cfg=dict(
use_rotate_nms=True, iou_thr=0.85, nms_pre=9000, nms_post=512),
score_thr=None),
rcnn=dict(use_rotate_nms=True, nms_thr=0.1, score_thr=0.1)))
================================================
FILE: configs/_base_/models/pointnet2_msg.py
================================================
_base_ = './pointnet2_ssg.py'
# model settings
model = dict(
backbone=dict(
_delete_=True,
type='PointNet2SAMSG',
in_channels=6, # [xyz, rgb], should be modified with dataset
num_points=(1024, 256, 64, 16),
radii=((0.05, 0.1), (0.1, 0.2), (0.2, 0.4), (0.4, 0.8)),
num_samples=((16, 32), (16, 32), (16, 32), (16, 32)),
sa_channels=(((16, 16, 32), (32, 32, 64)), ((64, 64, 128), (64, 96,
128)),
((128, 196, 256), (128, 196, 256)), ((256, 256, 512),
(256, 384, 512))),
aggregation_channels=(None, None, None, None),
fps_mods=(('D-FPS'), ('D-FPS'), ('D-FPS'), ('D-FPS')),
fps_sample_range_lists=((-1), (-1), (-1), (-1)),
dilated_group=(False, False, False, False),
out_indices=(0, 1, 2, 3),
sa_cfg=dict(
type='PointSAModuleMSG',
pool_mod='max',
use_xyz=True,
normalize_xyz=False)),
decode_head=dict(
fp_channels=((1536, 256, 256), (512, 256, 256), (352, 256, 128),
(128, 128, 128, 128))))
================================================
FILE: configs/_base_/models/pointnet2_ssg.py
================================================
# model settings
model = dict(
type='EncoderDecoder3D',
backbone=dict(
type='PointNet2SASSG',
in_channels=6, # [xyz, rgb], should be modified with dataset
num_points=(1024, 256, 64, 16),
radius=(0.1, 0.2, 0.4, 0.8),
num_samples=(32, 32, 32, 32),
sa_channels=((32, 32, 64), (64, 64, 128), (128, 128, 256), (256, 256,
512)),
fp_channels=(),
norm_cfg=dict(type='BN2d'),
sa_cfg=dict(
type='PointSAModule',
pool_mod='max',
use_xyz=True,
normalize_xyz=False)),
decode_head=dict(
type='PointNet2Head',
fp_channels=((768, 256, 256), (384, 256, 256), (320, 256, 128),
(128, 128, 128, 128)),
channels=128,
dropout_ratio=0.5,
conv_cfg=dict(type='Conv1d'),
norm_cfg=dict(type='BN1d'),
act_cfg=dict(type='ReLU'),
loss_decode=dict(
type='CrossEntropyLoss',
use_sigmoid=False,
class_weight=None, # should be modified with dataset
loss_weight=1.0)),
# model training and testing settings
train_cfg=dict(),
test_cfg=dict(mode='slide'))
================================================
FILE: configs/_base_/models/smoke.py
================================================
model = dict(
type='SMOKEMono3D',
backbone=dict(
type='DLANet',
depth=34,
in_channels=3,
norm_cfg=dict(type='GN', num_groups=32),
init_cfg=dict(
type='Pretrained',
checkpoint='http://dl.yf.io/dla/models/imagenet/dla34-ba72cf86.pth'
)),
neck=dict(
type='DLANeck',
in_channels=[16, 32, 64, 128, 256, 512],
start_level=2,
end_level=5,
norm_cfg=dict(type='GN', num_groups=32)),
bbox_head=dict(
type='SMOKEMono3DHead',
num_classes=3,
in_channels=64,
dim_channel=[3, 4, 5],
ori_channel=[6, 7],
stacked_convs=0,
feat_channels=64,
use_direction_classifier=False,
diff_rad_by_sin=False,
pred_attrs=False,
pred_velo=False,
dir_offset=0,
strides=None,
group_reg_dims=(8, ),
cls_branch=(256, ),
reg_branch=((256, ), ),
num_attrs=0,
bbox_code_size=7,
dir_branch=(),
attr_branch=(),
bbox_coder=dict(
type='SMOKECoder',
base_depth=(28.01, 16.32),
base_dims=((0.88, 1.73, 0.67), (1.78, 1.70, 0.58), (3.88, 1.63,
1.53)),
code_size=7),
loss_cls=dict(type='GaussianFocalLoss', loss_weight=1.0),
loss_bbox=dict(type='L1Loss', reduction='sum', loss_weight=1 / 300),
loss_dir=dict(
type='CrossEntropyLoss', use_sigmoid=False, loss_weight=1.0),
loss_attr=None,
conv_bias=True,
dcn_on_last_conv=False),
train_cfg=None,
test_cfg=dict(topK=100, local_maximum_kernel=3, max_per_img=100))
================================================
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/cosine.py
================================================
# This schedule is mainly used by models with dynamic voxelization
# optimizer
lr = 0.003 # max learning rate
optimizer = dict(
type='AdamW',
lr=lr,
betas=(0.95, 0.99), # the momentum is change during training
weight_decay=0.001)
optimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2))
lr_config = dict(
policy='CosineAnnealing',
warmup='linear',
warmup_iters=1000,
warmup_ratio=1.0 / 10,
min_lr_ratio=1e-5)
momentum_config = None
runner = dict(type='EpochBasedRunner', max_epochs=40)
================================================
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
runner = dict(type='EpochBasedRunner', max_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 official 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 max_epochs is 40, this schedule is usually used we
# RepeatDataset with repeat ratio N, thus the actual max epoch
# number could be Nx40
runner = dict(type='EpochBasedRunner', max_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])
runner = dict(type='EpochBasedRunner', max_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
runner = dict(type='EpochBasedRunner', max_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
runner = dict(type='EpochBasedRunner', max_epochs=36)
================================================
FILE: configs/_base_/schedules/seg_cosine_100e.py
================================================
# optimizer
# This schedule is mainly used on S3DIS dataset in segmentation task
optimizer = dict(type='SGD', lr=0.1, momentum=0.9, weight_decay=0.0001)
optimizer_config = dict(grad_clip=None)
lr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=1e-5)
# runtime settings
runner = dict(type='EpochBasedRunner', max_epochs=100)
================================================
FILE: configs/_base_/schedules/seg_cosine_150e.py
================================================
# optimizer
# This schedule is mainly used on S3DIS dataset in segmentation task
optimizer = dict(type='SGD', lr=0.2, weight_decay=0.0001, momentum=0.9)
optimizer_config = dict(grad_clip=None)
lr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=0.002)
momentum_config = None
# runtime settings
runner = dict(type='EpochBasedRunner', max_epochs=150)
================================================
FILE: configs/_base_/schedules/seg_cosine_200e.py
================================================
# optimizer
# This schedule is mainly used on ScanNet dataset in segmentation task
optimizer = dict(type='Adam', lr=0.001, weight_decay=0.01)
optimizer_config = dict(grad_clip=None)
lr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=1e-5)
momentum_config = None
# runtime settings
runner = dict(type='EpochBasedRunner', max_epochs=200)
================================================
FILE: configs/_base_/schedules/seg_cosine_50e.py
================================================
# optimizer
# This schedule is mainly used on S3DIS dataset in segmentation task
optimizer = dict(type='Adam', lr=0.001, weight_decay=0.001)
optimizer_config = dict(grad_clip=None)
lr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=1e-5)
momentum_config = None
# runtime settings
runner = dict(type='EpochBasedRunner', max_epochs=50)
================================================
FILE: configs/bev_next/bev_planner.py
================================================
# Copyright (c) 2023-2024, NVIDIA Corporation & Affiliates. All rights reserved.
#
# This work is made available under the Nvidia Source Code License-NC.
# To view a copy of this license, visit
# TODO: add license here
# we follow the online training settings from solofusion
num_gpus = 8
samples_per_gpu = 4
num_iters_per_epoch = int(28130 // (num_gpus * samples_per_gpu) )
num_epochs = 12
checkpoint_epoch_interval = 1
use_custom_eval_hook=True
# Each nuScenes sequence is ~40 keyframes long. Our training procedure samples
# sequences first, then loads frames from the sampled sequence in order
# starting from the first frame. This reduces training step-to-step diversity,
# lowering performance. To increase diversity, we split each training sequence
# in half to ~20 keyframes, and sample these shorter sequences during training.
# During testing, we do not do this splitting.
train_sequences_split_num = 4
test_sequences_split_num = 1
# By default, 3D detection datasets randomly choose another sample if there is
# no GT object in the current sample. This does not make sense when doing
# sequential sampling of frames, so we disable it.
filter_empty_gt = False
# Long-Term Fusion Parameters
do_history = False
history_cat_num = 4
history_cat_conv_out_channels = 160
_base_ = ['../_base_/datasets/nus-3d.py', '../_base_/default_runtime.py']
# Global
# If point cloud range is changed, the models should also change their point
# cloud range accordingly
# bev configs
roi_size = (102.4, 102.4)
bev_h = 128
bev_w = 128
point_cloud_range = [-roi_size[0]/2, -roi_size[1]/2, -5, roi_size[0]/2, roi_size[1]/2, 3]
# For nuScenes we usually do 10-class detection
class_names = [
'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',
'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'
]
data_config = {
'cams': [
'CAM_FRONT_LEFT', 'CAM_FRONT', 'CAM_FRONT_RIGHT', 'CAM_BACK_LEFT',
'CAM_BACK', 'CAM_BACK_RIGHT'
],
'Ncams':
6,
'input_size': (256, 704),
'src_size': (900, 1600),
# Augmentation
'resize': (0.38, 0.55),
'rot': (0, 0),
'flip': True,
'crop_h': (0.0, 0.0),
'resize_test': 0.00,
}
bda_aug_conf = dict(
rot_lim=(-0, 0),
scale_lim=(1., 1.),
flip_dx_ratio=0.,
flip_dy_ratio=0.)
voxel_size = [0.2, 0.2, 8]
use_checkpoint = False
sync_bn = True
# Model
grid_config = {
'x': [-51.2, 51.2, 0.8],
'y': [-51.2, 51.2, 0.8],
'z': [-5, 3, 8],
'depth': [1.0, 60.0, 0.5],
}
depth_categories = 118 #(grid_config['depth'][1]-grid_config['depth'][0])//grid_config['depth'][2]
numC_Trans=80
_dim_ = 256
### occupancy config
empty_idx = 18 # noise 0-->255
num_cls = 19 # 0 others, 1-16 obj, 17 free
fix_void = num_cls == 19
###
map_classes = ['divider', 'ped_crossing', 'boundary']
map_num_vec = 100
map_fixed_ptsnum_per_gt_line = 20 # now only support fixed_pts > 0
map_fixed_ptsnum_per_pred_line = 20
map_eval_use_same_gt_sample_num_flag = True
map_num_classes = len(map_classes)
embed_dims = 256
num_feat_levels = 1
norm_cfg = dict(type='BN2d')
num_queries = 100
# category configs
cat2id = {
'ped_crossing': 0,
'divider': 1,
'boundary': 2,
}
num_class = max(list(cat2id.values())) + 1
num_points = 20
permute = True
with_ego_as_agent = False
###
model = dict(
type='BEVPlanner',
use_depth_supervision=False,
fix_void=fix_void,
do_history = do_history,
history_cat_num=history_cat_num,
single_bev_num_channels=numC_Trans,
fuse_history_bev=True,
use_grid_mask=True,
align_prev_bev=False,
img_backbone=dict(
type='ResNet',
depth=50,
num_stages=4,
out_indices=(2, 3),
frozen_stages=-1,
norm_cfg=dict(type='BN2d', requires_grad=False),
norm_eval=True,
with_cp=False,
# pretrained='torchvision://resnet50',
init_cfg=dict(
type='Pretrained', checkpoint="ckpts/cascade_mask_rcnn_r50_fpn_coco-20e_20e_nuim_20201009_124951-40963960.pth",
prefix='backbone.'),
style='pytorch'),
img_neck=dict(
type='CustomFPN',
in_channels=[1024, 2048],
out_channels=_dim_,
num_outs=1,
start_level=0,
with_cp=use_checkpoint,
out_ids=[0]),
depth_net=dict(
type='CM_DepthNet', # camera-aware depth net
in_channels=_dim_,
context_channels=numC_Trans,
downsample=16,
grid_config=grid_config,
depth_channels=depth_categories,
with_cp=use_checkpoint,
loss_depth_weight=1.,
aspp_mid_channels=96,
use_dcn=False,
),
forward_projection=dict(
type='LSSViewTransformerFunction',
grid_config=grid_config,
input_size=data_config['input_size'],
downsample=16),
frpn=None,
backward_projection=None,
img_bev_encoder_backbone=dict(
type='CustomResNet',
numC_input=numC_Trans,
num_channels=[numC_Trans * 2, numC_Trans * 4, numC_Trans * 8]),
img_bev_encoder_neck=dict(
type='FPN_LSS',
in_channels=numC_Trans * 8 + numC_Trans * 2,
out_channels=256),
occupancy_head=None,
img_det_2d_head=None,
pts_bbox_head=None,
map_head=None,
motion_head=None,
planner_head=dict(
type='NaivePlannerHead'
),
# model training and testing settings
train_cfg=dict(pts=dict(
grid_size=[512, 512, 1],
voxel_size=voxel_size,
point_cloud_range=point_cloud_range,
out_size_factor=4,
assigner=None),
)
)
# Data
dataset_type = 'NuScenesDataset'
data_root = 'data/nuscenes/'
file_client_args = dict(backend='disk')
occupancy_path = '/mount/data/occupancy_cvpr2023/gts'
normalize_cfg = dict(
mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)
train_pipeline = [
dict(
type='PrepareImageInputs',
is_train=True,
normalize_cfg=normalize_cfg,
data_config=data_config),
dict(
type='LoadAnnotationsBEVDepth',
bda_aug_conf=bda_aug_conf,
with_2d_bbox=True,
classes=class_names),
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadVectorMap2',
data_root = data_root,
point_cloud_range =point_cloud_range,
map_classes = ['divider', 'ped_crossing', 'boundary'],
map_num_vec = 100,
map_fixed_ptsnum_per_line = 20, # now only support fixed_pts > 0,
map_eval_use_same_gt_sample_num_flag = True,
map_num_classes = 3,
),
dict(type='PointToMultiViewDepth', downsample=1, grid_config=grid_config),
dict(type='LoadGTMotion'),
dict(type='LoadGTPlaner'),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
# dict(type='VisualInputsAndGT'),
# dict(type='LoadOccupancy', ignore_nonvisible=True, fix_void=fix_void, occupancy_path=occupancy_path),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(
type='Collect3D', keys=['img_inputs', 'gt_bboxes_3d', 'gt_labels_3d', 'gt_depth', 'gt_bboxes_2d', 'gt_labels_2d', 'centers2d', 'depths2d', 'map_gt_labels_3d', 'map_gt_bboxes_3d'
] + ['gt_agent_fut_traj', 'gt_agent_fut_traj_mask']+
['gt_ego_lcf_feat', 'gt_ego_fut_trajs', 'gt_ego_his_trajs', 'gt_ego_fut_cmd', 'gt_ego_fut_masks']
)
]
test_pipeline = [
dict(
type='CustomDistMultiScaleFlipAug3D',
tta=False,
transforms=[
dict(type='PrepareImageInputs',
# img_corruptions='sun',
data_config=data_config, normalize_cfg=normalize_cfg),
dict(
type='LoadAnnotationsBEVDepth',
bda_aug_conf=bda_aug_conf,
classes=class_names,
with_2d_bbox=True,
is_train=False),
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadVectorMap',
data_root = data_root,
point_cloud_range =point_cloud_range,
map_classes = ['divider', 'ped_crossing', 'boundary'],
map_num_vec = 100,
map_fixed_ptsnum_per_line = 20, # now only support fixed_pts > 0,
map_eval_use_same_gt_sample_num_flag = True,
map_num_classes = 3,
),
dict(type='LoadGTPlaner'),
dict(type='LoadGTMotion', with_ego_as_agent=with_ego_as_agent),
dict(type='LoadFutBoxInfo'),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points', 'img_inputs', 'gt_bboxes_3d', 'gt_labels_3d', 'map_gt_bboxes_3d', 'map_gt_labels_3d']+
['gt_agent_fut_traj', 'gt_agent_fut_traj_mask']+['gt_ego_lcf_feat', 'gt_ego_fut_trajs', 'gt_ego_his_trajs', 'gt_ego_fut_cmd', 'gt_ego_fut_masks']+
['gt_fut_segmentations', 'gt_fut_segmentations_plus', 'fut_boxes_in_cur_ego_list']
)
]
)
]
input_modality = dict(
use_lidar=False,
use_camera=True,
use_radar=False,
use_map=False,
use_external=False)
share_data_config = dict(
type=dataset_type,
classes=class_names,
modality=input_modality,
img_info_prototype='bevdet',
occupancy_path=occupancy_path,
data_root=data_root,
use_sequence_group_flag=True,
)
test_data_config = dict(
pipeline=test_pipeline,
map_ann_file=data_root + 'nuscenes_map_infos_102x102_val.pkl',
map_eval_cfg=dict(
region = (102.4, 102.4) # (H, W)
),
load_fut_bbox_info=True,
sequences_split_num=test_sequences_split_num,
ann_file=data_root + 'bev-next-nuscenes_infos_val.pkl')
data = dict(
samples_per_gpu=samples_per_gpu,
workers_per_gpu=2,
test_dataloader=dict(runner_type='IterBasedRunnerEval'),
train=dict(
type=dataset_type,
ann_file=data_root + 'bev-next-nuscenes_infos_train.pkl',
pipeline=train_pipeline,
test_mode=False,
use_valid_flag=True,
sequences_split_num=train_sequences_split_num,
filter_empty_gt=filter_empty_gt,
# 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=test_data_config,
test=test_data_config)
for key in ['train', 'val', 'test']:
data[key].update(share_data_config)
optimizer = dict(
type='AdamW',
lr=1e-4, # bs 8: 2e-4 || bs 16: 4e-4
paramwise_cfg=dict(
custom_keys={
'img_backbone': dict(lr_mult=0.1),
}),
weight_decay=0.01)
optimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))
lr_config = dict(
policy='CosineAnnealing',
warmup='linear',
warmup_iters=500,
warmup_ratio=1.0 / 3,
min_lr_ratio=1e-3,
)
runner = dict(type='IterBasedRunner', max_iters=num_epochs * num_iters_per_epoch)
checkpoint_config = dict(
interval=checkpoint_epoch_interval * num_iters_per_epoch)
evaluation = dict(
interval=num_epochs * num_iters_per_epoch, pipeline=test_pipeline)
log_config = dict(
interval=50,
hooks=[
dict(type='TextLoggerHook'),
])
custom_hooks = [
dict(
type='MEGVIIEMAHook',
init_updates=10560,
priority='NORMAL',
interval=2*num_iters_per_epoch,
),
dict(
type='SequentialControlHook',
temporal_start_iter=0,
),
# dict(
# type='TimerCP',
# )
]
# load_from = None
# resume_from = None
================================================
FILE: configs/bev_next/bev_planner_plus.py
================================================
# Copyright (c) 2023-2024, NVIDIA Corporation & Affiliates. All rights reserved.
#
# This work is made available under the Nvidia Source Code License-NC.
# To view a copy of this license, visit
# TODO: add license here
# we follow the online training settings from solofusion
num_gpus = 8
samples_per_gpu = 4
num_iters_per_epoch = int(28130 // (num_gpus * samples_per_gpu) )
num_epochs = 12
checkpoint_epoch_interval = 1
use_custom_eval_hook=True
# Each nuScenes sequence is ~40 keyframes long. Our training procedure samples
# sequences first, then loads frames from the sampled sequence in order
# starting from the first frame. This reduces training step-to-step diversity,
# lowering performance. To increase diversity, we split each training sequence
# in half to ~20 keyframes, and sample these shorter sequences during training.
# During testing, we do not do this splitting.
train_sequences_split_num = 4
test_sequences_split_num = 1
# By default, 3D detection datasets randomly choose another sample if there is
# no GT object in the current sample. This does not make sense when doing
# sequential sampling of frames, so we disable it.
filter_empty_gt = False
# Long-Term Fusion Parameters
do_history = False
history_cat_num = 4
history_cat_conv_out_channels = 160
_base_ = ['../_base_/datasets/nus-3d.py', '../_base_/default_runtime.py']
# Global
# If point cloud range is changed, the models should also change their point
# cloud range accordingly
# bev configs
roi_size = (102.4, 102.4)
bev_h = 128
bev_w = 128
point_cloud_range = [-roi_size[0]/2, -roi_size[1]/2, -5, roi_size[0]/2, roi_size[1]/2, 3]
# For nuScenes we usually do 10-class detection
class_names = [
'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',
'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'
]
data_config = {
'cams': [
'CAM_FRONT_LEFT', 'CAM_FRONT', 'CAM_FRONT_RIGHT', 'CAM_BACK_LEFT',
'CAM_BACK', 'CAM_BACK_RIGHT'
],
'Ncams':
6,
'input_size': (256, 704),
'src_size': (900, 1600),
# Augmentation
'resize': (0.38, 0.55),
'rot': (0, 0),
'flip': True,
'crop_h': (0.0, 0.0),
'resize_test': 0.00,
}
bda_aug_conf = dict(
rot_lim=(-0, 0),
scale_lim=(1., 1.),
flip_dx_ratio=0.,
flip_dy_ratio=0.)
voxel_size = [0.2, 0.2, 8]
use_checkpoint = False
sync_bn = True
# Model
grid_config = {
'x': [-51.2, 51.2, 0.8],
'y': [-51.2, 51.2, 0.8],
'z': [-5, 3, 8],
'depth': [1.0, 60.0, 0.5],
}
depth_categories = 118 #(grid_config['depth'][1]-grid_config['depth'][0])//grid_config['depth'][2]
numC_Trans=80
_dim_ = 256
### occupancy config
empty_idx = 18 # noise 0-->255
num_cls = 19 # 0 others, 1-16 obj, 17 free
fix_void = num_cls == 19
###
map_classes = ['divider', 'ped_crossing', 'boundary']
map_num_vec = 100
map_fixed_ptsnum_per_gt_line = 20 # now only support fixed_pts > 0
map_fixed_ptsnum_per_pred_line = 20
map_eval_use_same_gt_sample_num_flag = True
map_num_classes = len(map_classes)
embed_dims = 256
num_feat_levels = 1
norm_cfg = dict(type='BN2d')
num_queries = 100
# category configs
cat2id = {
'ped_crossing': 0,
'divider': 1,
'boundary': 2,
}
num_class = max(list(cat2id.values())) + 1
num_points = 20
permute = True
with_ego_as_agent = False
###
model = dict(
type='BEVPlanner',
use_depth_supervision=False,
fix_void=fix_void,
do_history = do_history,
history_cat_num=history_cat_num,
single_bev_num_channels=numC_Trans,
fuse_history_bev=True,
use_grid_mask=True,
align_prev_bev=False,
with_ego_status=True,
img_backbone=dict(
type='ResNet',
depth=50,
num_stages=4,
out_indices=(2, 3),
frozen_stages=-1,
norm_cfg=dict(type='BN2d', requires_grad=False),
norm_eval=True,
with_cp=False,
# pretrained='torchvision://resnet50',
init_cfg=dict(
type='Pretrained', checkpoint="ckpts/cascade_mask_rcnn_r50_fpn_coco-20e_20e_nuim_20201009_124951-40963960.pth",
prefix='backbone.'),
style='pytorch'),
img_neck=dict(
type='CustomFPN',
in_channels=[1024, 2048],
out_channels=_dim_,
num_outs=1,
start_level=0,
with_cp=use_checkpoint,
out_ids=[0]),
depth_net=dict(
type='CM_DepthNet', # camera-aware depth net
in_channels=_dim_,
context_channels=numC_Trans,
downsample=16,
grid_config=grid_config,
depth_channels=depth_categories,
with_cp=use_checkpoint,
loss_depth_weight=1.,
aspp_mid_channels=96,
use_dcn=False,
),
forward_projection=dict(
type='LSSViewTransformerFunction',
grid_config=grid_config,
input_size=data_config['input_size'],
downsample=16),
frpn=None,
backward_projection=None,
img_bev_encoder_backbone=dict(
type='CustomResNet',
numC_input=numC_Trans,
num_channels=[numC_Trans * 2, numC_Trans * 4, numC_Trans * 8]),
img_bev_encoder_neck=dict(
type='FPN_LSS',
in_channels=numC_Trans * 8 + numC_Trans * 2,
out_channels=256),
occupancy_head=None,
img_det_2d_head=None,
pts_bbox_head=None,
map_head=None,
motion_head=None,
planner_head=dict(
type='NaivePlannerHead'
),
# model training and testing settings
train_cfg=dict(pts=dict(
grid_size=[512, 512, 1],
voxel_size=voxel_size,
point_cloud_range=point_cloud_range,
out_size_factor=4,
assigner=None),
)
)
# Data
dataset_type = 'NuScenesDataset'
data_root = 'data/nuscenes/'
file_client_args = dict(backend='disk')
occupancy_path = '/mount/data/occupancy_cvpr2023/gts'
normalize_cfg = dict(
mean=[123.675, 116.28, 103.53], std=[58.395, 57.12, 57.375], to_rgb=True)
train_pipeline = [
dict(
type='PrepareImageInputs',
is_train=True,
normalize_cfg=normalize_cfg,
data_config=data_config),
dict(
type='LoadAnnotationsBEVDepth',
bda_aug_conf=bda_aug_conf,
with_2d_bbox=True,
classes=class_names),
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadVectorMap2',
data_root = data_root,
point_cloud_range =point_cloud_range,
map_classes = ['divider', 'ped_crossing', 'boundary'],
map_num_vec = 100,
map_fixed_ptsnum_per_line = 20, # now only support fixed_pts > 0,
map_eval_use_same_gt_sample_num_flag = True,
map_num_classes = 3,
),
dict(type='PointToMultiViewDepth', downsample=1, grid_config=grid_config),
dict(type='LoadGTMotion'),
dict(type='LoadGTPlaner'),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
# dict(type='VisualInputsAndGT'),
# dict(type='LoadOccupancy', ignore_nonvisible=True, fix_void=fix_void, occupancy_path=occupancy_path),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(
type='Collect3D', keys=['img_inputs', 'gt_bboxes_3d', 'gt_labels_3d', 'gt_depth', 'gt_bboxes_2d', 'gt_labels_2d', 'centers2d', 'depths2d', 'map_gt_labels_3d', 'map_gt_bboxes_3d'
] + ['gt_agent_fut_traj', 'gt_agent_fut_traj_mask']+['can_bus_info']+
['gt_ego_lcf_feat', 'gt_ego_fut_trajs', 'gt_ego_his_trajs', 'gt_ego_fut_cmd', 'gt_ego_fut_masks']
)
]
test_pipeline = [
dict(
type='CustomDistMultiScaleFlipAug3D',
tta=False,
transforms=[
dict(type='PrepareImageInputs',
# img_corruptions='sun',
data_config=data_config, normalize_cfg=normalize_cfg),
dict(
type='LoadAnnotationsBEVDepth',
bda_aug_conf=bda_aug_conf,
classes=class_names,
with_2d_bbox=True,
is_train=False),
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='LoadVectorMap',
data_root = data_root,
point_cloud_range =point_cloud_range,
map_classes = ['divider', 'ped_crossing', 'boundary'],
map_num_vec = 100,
map_fixed_ptsnum_per_line = 20, # now only support fixed_pts > 0,
map_eval_use_same_gt_sample_num_flag = True,
map_num_classes = 3,
),
dict(type='LoadGTPlaner'),
dict(type='LoadGTMotion', with_ego_as_agent=with_ego_as_agent),
dict(type='LoadFutBoxInfo'),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points', 'img_inputs', 'gt_bboxes_3d', 'gt_labels_3d', 'map_gt_bboxes_3d', 'map_gt_labels_3d']+
['gt_agent_fut_traj', 'gt_agent_fut_traj_mask']+['gt_ego_lcf_feat', 'gt_ego_fut_trajs', 'gt_ego_his_trajs', 'gt_ego_fut_cmd', 'gt_ego_fut_masks']+
['gt_fut_segmentations', 'gt_fut_segmentations_plus', 'fut_boxes_in_cur_ego_list']+ ['can_bus_info']
)
]
)
]
input_modality = dict(
use_lidar=False,
use_camera=True,
use_radar=False,
use_map=False,
use_external=False)
share_data_config = dict(
type=dataset_type,
classes=class_names,
modality=input_modality,
img_info_prototype='bevdet',
occupancy_path=occupancy_path,
data_root=data_root,
use_sequence_group_flag=True,
)
test_data_config = dict(
pipeline=test_pipeline,
map_ann_file=data_root + 'nuscenes_map_infos_102x102_val.pkl',
map_eval_cfg=dict(
region = (102.4, 102.4) # (H, W)
),
load_fut_bbox_info=True,
sequences_split_num=test_sequences_split_num,
ann_file=data_root + 'bev-next-nuscenes_infos_val.pkl')
data = dict(
samples_per_gpu=samples_per_gpu,
workers_per_gpu=2,
test_dataloader=dict(runner_type='IterBasedRunnerEval'),
train=dict(
type=dataset_type,
ann_file=data_root + 'bev-next-nuscenes_infos_train.pkl',
pipeline=train_pipeline,
test_mode=False,
use_valid_flag=True,
sequences_split_num=train_sequences_split_num,
filter_empty_gt=filter_empty_gt,
# 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=test_data_config,
test=test_data_config)
for key in ['train', 'val', 'test']:
data[key].update(share_data_config)
optimizer = dict(
type='AdamW',
lr=1e-4, # bs 8: 2e-4 || bs 16: 4e-4
paramwise_cfg=dict(
custom_keys={
'img_backbone': dict(lr_mult=0.1),
}),
weight_decay=0.01)
optimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))
lr_config = dict(
policy='CosineAnnealing',
warmup='linear',
wa
gitextract_5bm2vozl/
├── .gitignore
├── README.md
├── configs/
│ ├── _base_/
│ │ ├── datasets/
│ │ │ ├── coco_instance.py
│ │ │ ├── kitti-3d-3class.py
│ │ │ ├── kitti-3d-car.py
│ │ │ ├── kitti-mono3d.py
│ │ │ ├── lyft-3d.py
│ │ │ ├── nuim_instance.py
│ │ │ ├── nus-3d.py
│ │ │ ├── nus-mono3d.py
│ │ │ ├── range100_lyft-3d.py
│ │ │ ├── s3dis-3d-5class.py
│ │ │ ├── s3dis_seg-3d-13class.py
│ │ │ ├── scannet-3d-18class.py
│ │ │ ├── scannet_seg-3d-20class.py
│ │ │ ├── sunrgbd-3d-10class.py
│ │ │ ├── waymoD5-3d-3class.py
│ │ │ └── waymoD5-3d-car.py
│ │ ├── default_runtime.py
│ │ ├── init.py
│ │ ├── models/
│ │ │ ├── 3dssd.py
│ │ │ ├── cascade_mask_rcnn_r50_fpn.py
│ │ │ ├── centerpoint_01voxel_second_secfpn_nus.py
│ │ │ ├── centerpoint_02pillar_second_secfpn_nus.py
│ │ │ ├── dgcnn.py
│ │ │ ├── fcaf3d.py
│ │ │ ├── fcos3d.py
│ │ │ ├── groupfree3d.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
│ │ │ ├── paconv_cuda_ssg.py
│ │ │ ├── paconv_ssg.py
│ │ │ ├── parta2.py
│ │ │ ├── pgd.py
│ │ │ ├── point_rcnn.py
│ │ │ ├── pointnet2_msg.py
│ │ │ ├── pointnet2_ssg.py
│ │ │ ├── smoke.py
│ │ │ └── votenet.py
│ │ └── schedules/
│ │ ├── cosine.py
│ │ ├── cyclic_20e.py
│ │ ├── cyclic_40e.py
│ │ ├── mmdet_schedule_1x.py
│ │ ├── schedule_2x.py
│ │ ├── schedule_3x.py
│ │ ├── seg_cosine_100e.py
│ │ ├── seg_cosine_150e.py
│ │ ├── seg_cosine_200e.py
│ │ └── seg_cosine_50e.py
│ └── bev_next/
│ ├── bev_planner.py
│ ├── bev_planner_plus.py
│ ├── bev_planner_plus_plus.py
│ ├── bev_planner_w_map.py
│ ├── det_pretrain_320x800_vov_36ep.py
│ ├── det_pretrain_640x1600_vov_36ep.py
│ └── map_pretrain.py
├── mmdet3d/
│ ├── __init__.py
│ ├── apis/
│ │ ├── __init__.py
│ │ ├── inference.py
│ │ ├── test.py
│ │ └── train.py
│ ├── core/
│ │ ├── __init__.py
│ │ ├── anchor/
│ │ │ ├── __init__.py
│ │ │ └── anchor_3d_generator.py
│ │ ├── bbox/
│ │ │ ├── __init__.py
│ │ │ ├── assigners/
│ │ │ │ └── __init__.py
│ │ │ ├── box_np_ops.py
│ │ │ ├── coders/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── anchor_free_bbox_coder.py
│ │ │ │ ├── centerpoint_bbox_coders.py
│ │ │ │ ├── delta_xyzwhlr_bbox_coder.py
│ │ │ │ ├── fcos3d_bbox_coder.py
│ │ │ │ ├── groupfree3d_bbox_coder.py
│ │ │ │ ├── monoflex_bbox_coder.py
│ │ │ │ ├── partial_bin_based_bbox_coder.py
│ │ │ │ ├── pgd_bbox_coder.py
│ │ │ │ ├── point_xyzwhlr_bbox_coder.py
│ │ │ │ └── smoke_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
│ │ │ │ ├── custom_box.py
│ │ │ │ ├── depth_box3d.py
│ │ │ │ ├── lidar_box3d.py
│ │ │ │ └── utils.py
│ │ │ ├── transforms.py
│ │ │ └── util.py
│ │ ├── evaluation/
│ │ │ ├── __init__.py
│ │ │ ├── indoor_eval.py
│ │ │ ├── instance_seg_eval.py
│ │ │ ├── kitti_utils/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── eval.py
│ │ │ │ └── rotate_iou.py
│ │ │ ├── lyft_eval.py
│ │ │ ├── scannet_utils/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── evaluate_semantic_instance.py
│ │ │ │ └── util_3d.py
│ │ │ ├── seg_eval.py
│ │ │ └── waymo_utils/
│ │ │ ├── __init__.py
│ │ │ └── prediction_kitti_to_waymo.py
│ │ ├── hook/
│ │ │ ├── __init__.py
│ │ │ ├── ema.py
│ │ │ ├── forge_load.py
│ │ │ ├── sequentialsontrol.py
│ │ │ └── utils.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
│ │ │ ├── array_converter.py
│ │ │ └── gaussian.py
│ │ ├── visualizer/
│ │ │ ├── __init__.py
│ │ │ ├── image_vis.py
│ │ │ ├── open3d_vis.py
│ │ │ └── show_result.py
│ │ └── voxel/
│ │ ├── __init__.py
│ │ ├── builder.py
│ │ └── voxel_generator.py
│ ├── datasets/
│ │ ├── __init__.py
│ │ ├── builder.py
│ │ ├── custom_3d.py
│ │ ├── custom_3d_seg.py
│ │ ├── dataset_wrappers.py
│ │ ├── evals/
│ │ │ ├── eval_utils.py
│ │ │ ├── map_api.py
│ │ │ ├── metric_utils.py
│ │ │ └── nuscenes_eval_motion.py
│ │ ├── evaluation/
│ │ │ ├── AP.py
│ │ │ ├── __init__.py
│ │ │ ├── distance.py
│ │ │ ├── raster_eval.py
│ │ │ └── vector_eval.py
│ │ ├── kitti2d_dataset.py
│ │ ├── kitti_dataset.py
│ │ ├── kitti_mono_dataset.py
│ │ ├── lyft_dataset.py
│ │ ├── map_utils/
│ │ │ ├── mean_ap.py
│ │ │ ├── tpfp.py
│ │ │ └── tpfp_chamfer.py
│ │ ├── nuscenes_dataset.py
│ │ ├── nuscenes_eval.py
│ │ ├── nuscenes_mono_dataset.py
│ │ ├── occ_metrics.py
│ │ ├── occupancy_eval.py
│ │ ├── pipelines/
│ │ │ ├── __init__.py
│ │ │ ├── compose.py
│ │ │ ├── data_augment_utils.py
│ │ │ ├── dbsampler.py
│ │ │ ├── formating.py
│ │ │ ├── loading.py
│ │ │ ├── test_time_aug.py
│ │ │ └── transforms_3d.py
│ │ ├── s3dis_dataset.py
│ │ ├── samplers/
│ │ │ ├── __init__.py
│ │ │ ├── d_sampler.py
│ │ │ └── infinite_group_each_sample_in_batch_sampler.py
│ │ ├── scannet_dataset.py
│ │ ├── semantickitti_dataset.py
│ │ ├── sunrgbd_dataset.py
│ │ ├── utils.py
│ │ ├── vector_map.py
│ │ └── waymo_dataset.py
│ ├── models/
│ │ ├── __init__.py
│ │ ├── backbones/
│ │ │ ├── __init__.py
│ │ │ ├── base_pointnet.py
│ │ │ ├── convnext.py
│ │ │ ├── dgcnn.py
│ │ │ ├── dla.py
│ │ │ ├── load.py
│ │ │ ├── mink_resnet.py
│ │ │ ├── multi_backbone.py
│ │ │ ├── nostem_regnet.py
│ │ │ ├── pointnet2_sa_msg.py
│ │ │ ├── pointnet2_sa_ssg.py
│ │ │ ├── resnet.py
│ │ │ ├── second.py
│ │ │ ├── swin.py
│ │ │ ├── vovnet.py
│ │ │ └── vovnet2.py
│ │ ├── builder.py
│ │ ├── decode_heads/
│ │ │ ├── __init__.py
│ │ │ ├── decode_head.py
│ │ │ ├── dgcnn_head.py
│ │ │ ├── paconv_head.py
│ │ │ └── pointnet2_head.py
│ │ ├── dense_heads/
│ │ │ ├── __init__.py
│ │ │ ├── anchor3d_head.py
│ │ │ ├── anchor_free_mono3d_head.py
│ │ │ ├── base_conv_bbox_head.py
│ │ │ ├── base_mono3d_dense_head.py
│ │ │ ├── centerpoint_head.py
│ │ │ ├── centerpoint_head_single_task.py
│ │ │ ├── fcaf3d_head.py
│ │ │ ├── fcos_mono3d_head.py
│ │ │ ├── free_anchor3d_head.py
│ │ │ ├── groupfree3d_head.py
│ │ │ ├── monoflex_head.py
│ │ │ ├── parta2_rpn_head.py
│ │ │ ├── pgd_head.py
│ │ │ ├── point_rpn_head.py
│ │ │ ├── shape_aware_head.py
│ │ │ ├── smoke_mono3d_head.py
│ │ │ ├── ssd_3d_head.py
│ │ │ ├── train_mixins.py
│ │ │ └── vote_head.py
│ │ ├── detectors/
│ │ │ ├── __init__.py
│ │ │ ├── base.py
│ │ │ ├── bevdet.py
│ │ │ ├── centerpoint.py
│ │ │ ├── dynamic_voxelnet.py
│ │ │ ├── fcos_mono3d.py
│ │ │ ├── groupfree3dnet.py
│ │ │ ├── h3dnet.py
│ │ │ ├── imvotenet.py
│ │ │ ├── imvoxelnet.py
│ │ │ ├── mink_single_stage.py
│ │ │ ├── mvx_faster_rcnn.py
│ │ │ ├── mvx_two_stage.py
│ │ │ ├── parta2.py
│ │ │ ├── point_rcnn.py
│ │ │ ├── sassd.py
│ │ │ ├── single_stage.py
│ │ │ ├── single_stage_mono3d.py
│ │ │ ├── smoke_mono3d.py
│ │ │ ├── ssd3dnet.py
│ │ │ ├── two_stage.py
│ │ │ ├── votenet.py
│ │ │ └── voxelnet.py
│ │ ├── fbbev/
│ │ │ ├── __init__.py
│ │ │ ├── detectors/
│ │ │ │ ├── __init__.py
│ │ │ │ └── bev_planner.py
│ │ │ ├── heads/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── occupancy_head.py
│ │ │ │ └── yolox.py
│ │ │ ├── modules/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── depth_net.py
│ │ │ │ ├── fpn3d.py
│ │ │ │ ├── frpn.py
│ │ │ │ ├── occ_loss_utils/
│ │ │ │ │ ├── __init__.py
│ │ │ │ │ ├── focal_loss.py
│ │ │ │ │ ├── lovasz_softmax.py
│ │ │ │ │ ├── nusc_param.py
│ │ │ │ │ └── semkitti.py
│ │ │ │ └── resnet3d.py
│ │ │ ├── motion_head/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── motion_head.py
│ │ │ │ ├── motion_planner_head.py
│ │ │ │ └── traj_loss.py
│ │ │ ├── planner_head/
│ │ │ │ ├── AD_mlp.py
│ │ │ │ ├── __init__.py
│ │ │ │ ├── metric_stp3.py
│ │ │ │ ├── naive_planner.py
│ │ │ │ ├── plan_loss.py
│ │ │ │ └── plan_loss_gt.py
│ │ │ ├── streammapnet/
│ │ │ │ ├── CustomMSDeformableAttention.py
│ │ │ │ ├── __init__.py
│ │ │ │ ├── cost.py
│ │ │ │ ├── fp16_dattn.py
│ │ │ │ ├── hungarian_lines_assigner.py
│ │ │ │ ├── loss.py
│ │ │ │ ├── map_utils.py
│ │ │ │ ├── streammapnet_head.py
│ │ │ │ ├── transformer.py
│ │ │ │ └── utils.py
│ │ │ ├── streampetr/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── hungarian_assigner_2d.py
│ │ │ │ ├── hungarian_assigner_3d.py
│ │ │ │ ├── match_cost.py
│ │ │ │ ├── nms_free_coder.py
│ │ │ │ ├── petr_transformer.py
│ │ │ │ ├── streampetr_utils.py
│ │ │ │ └── streampetr_v2.py
│ │ │ ├── track_head/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── instances.py
│ │ │ │ ├── losses/
│ │ │ │ │ ├── __init__.py
│ │ │ │ │ ├── tracking_loss.py
│ │ │ │ │ ├── tracking_loss_base.py
│ │ │ │ │ ├── tracking_loss_combo.py
│ │ │ │ │ ├── tracking_loss_mem_bank.py
│ │ │ │ │ └── tracking_loss_prediction.py
│ │ │ │ ├── runtime_tracker.py
│ │ │ │ ├── streampetr_utils.py
│ │ │ │ ├── track_nms_free_coder.py
│ │ │ │ ├── trackpetr.py
│ │ │ │ └── utils.py
│ │ │ ├── utils/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── bricks.py
│ │ │ │ ├── draw_bbox.py
│ │ │ │ ├── eval_hook.py
│ │ │ │ ├── grid_mask.py
│ │ │ │ ├── timer_cp.py
│ │ │ │ └── wechat_logger.py
│ │ │ └── view_transformation/
│ │ │ ├── __init__.py
│ │ │ ├── backward_projection/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── backward_projection.py
│ │ │ │ └── bevformer_utils/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── bevformer.py
│ │ │ │ ├── bevformer_encoder.py
│ │ │ │ ├── custom_base_transformer_layer.py
│ │ │ │ ├── multi_scale_deformable_attn_function.py
│ │ │ │ ├── positional_encoding.py
│ │ │ │ └── spatial_cross_attention_depth.py
│ │ │ └── forward_projection/
│ │ │ ├── __init__.py
│ │ │ └── view_transformer.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
│ │ │ ├── multibin_loss.py
│ │ │ ├── paconv_regularization_loss.py
│ │ │ ├── rotated_iou_loss.py
│ │ │ └── uncertain_smooth_l1_loss.py
│ │ ├── middle_encoders/
│ │ │ ├── __init__.py
│ │ │ ├── pillar_scatter.py
│ │ │ ├── sparse_encoder.py
│ │ │ └── sparse_unet.py
│ │ ├── model_utils/
│ │ │ ├── __init__.py
│ │ │ ├── edge_fusion_module.py
│ │ │ ├── transformer.py
│ │ │ └── vote_module.py
│ │ ├── necks/
│ │ │ ├── __init__.py
│ │ │ ├── dla_neck.py
│ │ │ ├── fpn.py
│ │ │ ├── imvoxel_neck.py
│ │ │ ├── lss_fpn.py
│ │ │ ├── pointnet2_fp_neck.py
│ │ │ ├── second_fpn.py
│ │ │ └── view_transformer.py
│ │ ├── roi_heads/
│ │ │ ├── __init__.py
│ │ │ ├── base_3droi_head.py
│ │ │ ├── bbox_heads/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── h3d_bbox_head.py
│ │ │ │ ├── parta2_bbox_head.py
│ │ │ │ └── point_rcnn_bbox_head.py
│ │ │ ├── h3d_roi_head.py
│ │ │ ├── mask_heads/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── pointwise_semantic_head.py
│ │ │ │ └── primitive_head.py
│ │ │ ├── part_aggregation_roi_head.py
│ │ │ ├── point_rcnn_roi_head.py
│ │ │ └── roi_extractors/
│ │ │ ├── __init__.py
│ │ │ ├── single_roiaware_extractor.py
│ │ │ └── single_roipoint_extractor.py
│ │ ├── segmentors/
│ │ │ ├── __init__.py
│ │ │ ├── base.py
│ │ │ └── encoder_decoder.py
│ │ ├── utils/
│ │ │ ├── __init__.py
│ │ │ ├── clip_sigmoid.py
│ │ │ ├── edge_indices.py
│ │ │ ├── gen_keypoints.py
│ │ │ ├── handle_objs.py
│ │ │ └── mlp.py
│ │ └── voxel_encoders/
│ │ ├── __init__.py
│ │ ├── pillar_encoder.py
│ │ ├── utils.py
│ │ └── voxel_encoder.py
│ ├── ops/
│ │ ├── __init__.py
│ │ ├── bev_pool_v2/
│ │ │ ├── __init__.py
│ │ │ ├── bev_pool.py
│ │ │ └── src/
│ │ │ ├── bev_pool.cpp
│ │ │ └── bev_pool_cuda.cu
│ │ ├── dgcnn_modules/
│ │ │ ├── __init__.py
│ │ │ ├── dgcnn_fa_module.py
│ │ │ ├── dgcnn_fp_module.py
│ │ │ └── dgcnn_gf_module.py
│ │ ├── norm.py
│ │ ├── ops_dcnv3/
│ │ │ ├── functions/
│ │ │ │ ├── __init__.py
│ │ │ │ └── dcnv3_func.py
│ │ │ ├── make.sh
│ │ │ ├── modules/
│ │ │ │ ├── __init__.py
│ │ │ │ └── dcnv3.py
│ │ │ ├── setup.py
│ │ │ ├── src/
│ │ │ │ ├── cpu/
│ │ │ │ │ ├── dcnv3_cpu.cpp
│ │ │ │ │ └── dcnv3_cpu.h
│ │ │ │ ├── cuda/
│ │ │ │ │ ├── dcnv3_cuda.cu
│ │ │ │ │ ├── dcnv3_cuda.h
│ │ │ │ │ └── dcnv3_im2col_cuda.cuh
│ │ │ │ ├── dcnv3.h
│ │ │ │ └── vision.cpp
│ │ │ └── test.py
│ │ ├── paconv/
│ │ │ ├── __init__.py
│ │ │ ├── paconv.py
│ │ │ └── utils.py
│ │ ├── pointnet_modules/
│ │ │ ├── __init__.py
│ │ │ ├── builder.py
│ │ │ ├── paconv_sa_module.py
│ │ │ ├── point_fp_module.py
│ │ │ └── point_sa_module.py
│ │ ├── sparse_block.py
│ │ └── spconv/
│ │ ├── __init__.py
│ │ └── overwrite_spconv/
│ │ ├── __init__.py
│ │ └── write_spconv2.py
│ ├── utils/
│ │ ├── __init__.py
│ │ ├── collect_env.py
│ │ ├── compat_cfg.py
│ │ ├── logger.py
│ │ ├── misc.py
│ │ └── setup_env.py
│ └── version.py
├── requirements/
│ ├── build.txt
│ ├── docs.txt
│ ├── mminstall.txt
│ ├── optional.txt
│ ├── readthedocs.txt
│ ├── runtime.txt
│ └── tests.txt
└── tools/
├── analysis_tools/
│ ├── analyze_logs.py
│ ├── benchmark.py
│ ├── benchmark_sequential.py
│ ├── benchmark_trt.py
│ ├── benchmark_view_transformer.py
│ ├── create_video.py
│ ├── generate_mask_based_on_lidar_points.py
│ ├── get_flops.py
│ ├── model_converter.py
│ ├── occupancy_cbgs.py
│ ├── vis.py
│ └── vis_occupancy.py
├── create_data.py
├── create_data.sh
├── create_data_bev_planner.py
├── data_converter/
│ ├── __init__.py
│ ├── create_gt_database.py
│ ├── imgaug_demo.py
│ ├── indoor_converter.py
│ ├── kitti_converter.py
│ ├── kitti_data_utils.py
│ ├── lyft_converter.py
│ ├── lyft_data_fixer.py
│ ├── nuimage_converter.py
│ ├── nuscenes_converter.py
│ ├── nuscenes_prediction_tools.py
│ ├── nuscenes_track_converter.py
│ ├── s3dis_data_utils.py
│ ├── scannet_data_utils.py
│ ├── sunrgbd_data_utils.py
│ └── waymo_converter.py
├── deployment/
│ ├── mmdet3d2torchserve.py
│ ├── mmdet3d_handler.py
│ └── test_torchserver.py
├── dist_test.sh
├── dist_train.sh
├── eval.py
├── misc/
│ ├── browse_dataset.py
│ ├── download.sh
│ ├── fuse_conv_bn.py
│ ├── print_config.py
│ ├── tmp.txt
│ └── visualize_results.py
├── model_converters/
│ ├── convert_h3dnet_checkpoints.py
│ ├── convert_votenet_checkpoints.py
│ ├── publish_model.py
│ └── regnet2mmdet.py
├── slurm_test.sh
├── slurm_train.sh
├── test.py
├── train.py
├── update_data_coords.py
└── update_data_coords.sh
Showing preview only (247K chars total). Download the full file or copy to clipboard to get everything.
SYMBOL INDEX (3065 symbols across 326 files)
FILE: mmdet3d/__init__.py
function digit_version (line 9) | def digit_version(version_str):
FILE: mmdet3d/apis/inference.py
function convert_SyncBN (line 22) | def convert_SyncBN(config):
function init_model (line 38) | def init_model(config, checkpoint=None, device='cuda:0'):
function inference_detector (line 81) | def inference_detector(model, pcd):
function inference_multi_modality_detector (line 155) | def inference_multi_modality_detector(model, pcd, image, ann_file):
function inference_mono_3d_detector (line 230) | def inference_mono_3d_detector(model, image, ann_file):
function inference_segmentor (line 289) | def inference_segmentor(model, pcd):
function show_det_result_meshlab (line 328) | def show_det_result_meshlab(data,
function show_seg_result_meshlab (line 371) | def show_seg_result_meshlab(data,
function show_proj_det_result_meshlab (line 403) | def show_proj_det_result_meshlab(data,
function show_result_meshlab (line 484) | def show_result_meshlab(data,
FILE: mmdet3d/apis/test.py
function single_gpu_test (line 12) | def single_gpu_test(model,
function custom_encode_mask_results (line 117) | def custom_encode_mask_results(mask_results):
function custom_multi_gpu_test (line 137) | def custom_multi_gpu_test(model, data_loader, tmpdir=None, gpu_collect=F...
function collect_results_cpu (line 210) | def collect_results_cpu(result_part, size, tmpdir=None):
function collect_results_gpu (line 259) | def collect_results_gpu(result_part, size):
FILE: mmdet3d/apis/train.py
function init_random_seed (line 29) | def init_random_seed(seed=None, device='cuda'):
function set_random_seed (line 60) | def set_random_seed(seed, deterministic=False):
function train_segmentor (line 79) | def train_segmentor(model,
function train_detector (line 183) | def train_detector(model,
function train_model (line 330) | def train_model(model,
FILE: mmdet3d/core/anchor/anchor_3d_generator.py
class Anchor3DRangeGenerator (line 9) | class Anchor3DRangeGenerator(object):
method __init__ (line 39) | def __init__(self,
method __repr__ (line 67) | def __repr__(self):
method num_base_anchors (line 78) | def num_base_anchors(self):
method num_levels (line 85) | def num_levels(self):
method grid_anchors (line 89) | def grid_anchors(self, featmap_sizes, device='cuda'):
method single_level_grid_anchors (line 115) | def single_level_grid_anchors(self, featmap_size, scale, device='cuda'):
method anchors_single_range (line 155) | def anchors_single_range(self,
class AlignedAnchor3DRangeGenerator (line 225) | class AlignedAnchor3DRangeGenerator(Anchor3DRangeGenerator):
method __init__ (line 251) | def __init__(self, align_corner=False, **kwargs):
method anchors_single_range (line 255) | def anchors_single_range(self,
class AlignedAnchor3DRangeGeneratorPerCls (line 344) | class AlignedAnchor3DRangeGeneratorPerCls(AlignedAnchor3DRangeGenerator):
method __init__ (line 355) | def __init__(self, **kwargs):
method grid_anchors (line 360) | def grid_anchors(self, featmap_sizes, device='cuda'):
method multi_cls_grid_anchors (line 382) | def multi_cls_grid_anchors(self, featmap_sizes, scale, device='cuda'):
FILE: mmdet3d/core/bbox/box_np_ops.py
function camera_to_lidar (line 13) | def camera_to_lidar(points, r_rect, velo2cam):
function box_camera_to_lidar (line 36) | def box_camera_to_lidar(data, r_rect, velo2cam):
function corners_nd (line 62) | def corners_nd(dims, origin=0.5):
function center_to_corner_box2d (line 96) | def center_to_corner_box2d(centers, dims, angles=None, origin=0.5):
function depth_to_points (line 123) | def depth_to_points(depth, trunc_pixel):
function depth_to_lidar_points (line 147) | def depth_to_lidar_points(depth, trunc_pixel, P2, r_rect, velo2cam):
function center_to_corner_box3d (line 171) | def center_to_corner_box3d(centers,
function box2d_to_corner_jit (line 204) | def box2d_to_corner_jit(boxes):
function corner_to_standup_nd_jit (line 235) | def corner_to_standup_nd_jit(boxes_corner):
function corner_to_surfaces_3d_jit (line 256) | def corner_to_surfaces_3d_jit(corners):
function rotation_points_single_angle (line 279) | def rotation_points_single_angle(points, angle, axis=0):
function box3d_to_bbox (line 311) | def box3d_to_bbox(box3d, P2):
function corner_to_surfaces_3d (line 331) | def corner_to_surfaces_3d(corners):
function points_in_rbbox (line 353) | def points_in_rbbox(points, rbbox, z_axis=2, origin=(0.5, 0.5, 0)):
function minmax_to_corner_2d (line 379) | def minmax_to_corner_2d(minmax_box):
function create_anchors_3d_range (line 394) | def create_anchors_3d_range(feature_size,
function center_to_minmax_2d (line 444) | def center_to_minmax_2d(centers, dims, origin=0.5):
function rbbox2d_to_near_bbox (line 463) | def rbbox2d_to_near_bbox(rbboxes):
function iou_jit (line 483) | def iou_jit(boxes, query_boxes, mode='iou', eps=0.0):
function projection_matrix_to_CRT_kitti (line 526) | def projection_matrix_to_CRT_kitti(proj):
function remove_outside_points (line 553) | def remove_outside_points(points, rect, Trv2c, P2, image_shape):
function get_frustum (line 584) | def get_frustum(bbox_image, C, near_clip=0.001, far_clip=100):
function surface_equ_3d (line 617) | def surface_equ_3d(polygon_surfaces):
function _points_in_convex_polygon_3d_jit (line 642) | def _points_in_convex_polygon_3d_jit(points, polygon_surfaces, normal_ve...
function points_in_convex_polygon_3d_jit (line 679) | def points_in_convex_polygon_3d_jit(points,
function points_in_convex_polygon_jit (line 709) | def points_in_convex_polygon_jit(points, polygon, clockwise=False):
function boxes3d_to_corners3d_lidar (line 753) | def boxes3d_to_corners3d_lidar(boxes3d, bottom_center=True):
FILE: mmdet3d/core/bbox/coders/anchor_free_bbox_coder.py
class AnchorFreeBBoxCoder (line 10) | class AnchorFreeBBoxCoder(PartialBinBasedBBoxCoder):
method __init__ (line 18) | def __init__(self, num_dir_bins, with_rot=True):
method encode (line 24) | def encode(self, gt_bboxes_3d, gt_labels_3d):
method decode (line 54) | def decode(self, bbox_out):
method split_pred (line 88) | def split_pred(self, cls_preds, reg_preds, base_xyz):
FILE: mmdet3d/core/bbox/coders/centerpoint_bbox_coders.py
class CenterPointBBoxCoder (line 9) | class CenterPointBBoxCoder(BaseBBoxCoder):
method __init__ (line 24) | def __init__(self,
method _gather_feat (line 41) | def _gather_feat(self, feats, inds, feat_masks=None):
method _topk (line 63) | def _topk(self, scores, K=80):
method _transpose_and_gather_feat (line 98) | def _transpose_and_gather_feat(self, feat, ind):
method encode (line 114) | def encode(self):
method decode (line 117) | def decode(self,
FILE: mmdet3d/core/bbox/coders/delta_xyzwhlr_bbox_coder.py
class DeltaXYZWLHRBBoxCoder (line 9) | class DeltaXYZWLHRBBoxCoder(BaseBBoxCoder):
method __init__ (line 16) | def __init__(self, code_size=7):
method encode (line 21) | def encode(src_boxes, dst_boxes):
method decode (line 58) | def decode(anchors, deltas):
FILE: mmdet3d/core/bbox/coders/fcos3d_bbox_coder.py
class FCOS3DBBoxCoder (line 11) | class FCOS3DBBoxCoder(BaseBBoxCoder):
method __init__ (line 24) | def __init__(self,
method encode (line 35) | def encode(self, gt_bboxes_3d, gt_labels_3d, gt_bboxes, gt_labels):
method decode (line 39) | def decode(self, bbox, scale, stride, training, cls_score=None):
method decode_yaw (line 103) | def decode_yaw(bbox, centers2d, dir_cls, dir_offset, cam2img):
FILE: mmdet3d/core/bbox/coders/groupfree3d_bbox_coder.py
class GroupFree3DBBoxCoder (line 10) | class GroupFree3DBBoxCoder(PartialBinBasedBBoxCoder):
method __init__ (line 23) | def __init__(self,
method encode (line 36) | def encode(self, gt_bboxes_3d, gt_labels_3d):
method decode (line 68) | def decode(self, bbox_out, prefix=''):
method split_pred (line 119) | def split_pred(self, cls_preds, reg_preds, base_xyz, prefix=''):
FILE: mmdet3d/core/bbox/coders/monoflex_bbox_coder.py
class MonoFlexCoder (line 11) | class MonoFlexCoder(BaseBBoxCoder):
method __init__ (line 37) | def __init__(self,
method encode (line 74) | def encode(self, gt_bboxes_3d):
method decode (line 108) | def decode(self, bbox, base_centers2d, labels, downsample_ratio, cam2i...
method decode_direct_depth (line 214) | def decode_direct_depth(self, depth_offsets):
method decode_location (line 241) | def decode_location(self,
method keypoints2depth (line 286) | def keypoints2depth(self,
method decode_dims (line 386) | def decode_dims(self, labels, dims_offset):
method decode_orientation (line 414) | def decode_orientation(self, ori_vector, locations):
method decode_bboxes2d (line 470) | def decode_bboxes2d(self, reg_bboxes2d, base_centers2d):
method combine_depths (line 495) | def combine_depths(self, depth, depth_uncertainty):
FILE: mmdet3d/core/bbox/coders/partial_bin_based_bbox_coder.py
class PartialBinBasedBBoxCoder (line 10) | class PartialBinBasedBBoxCoder(BaseBBoxCoder):
method __init__ (line 20) | def __init__(self, num_dir_bins, num_sizes, mean_sizes, with_rot=True):
method encode (line 28) | def encode(self, gt_bboxes_3d, gt_labels_3d):
method decode (line 59) | def decode(self, bbox_out, suffix=''):
method decode_corners (line 102) | def decode_corners(self, center, size_res, size_class):
method split_pred (line 140) | def split_pred(self, cls_preds, reg_preds, base_xyz):
method angle2class (line 204) | def angle2class(self, angle):
method class2angle (line 225) | def class2angle(self, angle_cls, angle_res, limit_period=True):
FILE: mmdet3d/core/bbox/coders/pgd_bbox_coder.py
class PGDBBoxCoder (line 11) | class PGDBBoxCoder(FCOS3DBBoxCoder):
method encode (line 14) | def encode(self, gt_bboxes_3d, gt_labels_3d, gt_bboxes, gt_labels):
method decode_2d (line 18) | def decode_2d(self,
method decode_prob_depth (line 73) | def decode_prob_depth(self, depth_cls_preds, depth_range, depth_unit,
FILE: mmdet3d/core/bbox/coders/point_xyzwhlr_bbox_coder.py
class PointXYZWHLRBBoxCoder (line 10) | class PointXYZWHLRBBoxCoder(BaseBBoxCoder):
method __init__ (line 21) | def __init__(self, code_size=7, use_mean_size=True, mean_size=None):
method encode (line 31) | def encode(self, gt_bboxes_3d, points, gt_labels_3d=None):
method decode (line 78) | def decode(self, box_encodings, points, pred_labels_3d=None):
FILE: mmdet3d/core/bbox/coders/smoke_bbox_coder.py
class SMOKECoder (line 10) | class SMOKECoder(BaseBBoxCoder):
method __init__ (line 20) | def __init__(self, base_depth, base_dims, code_size):
method encode (line 26) | def encode(self, locations, dimensions, orientations, input_metas):
method decode (line 52) | def decode(self,
method _decode_depth (line 107) | def _decode_depth(self, depth_offsets):
method _decode_location (line 114) | def _decode_location(self, points, centers2d_offsets, depths, cam2imgs,
method _decode_dimension (line 155) | def _decode_dimension(self, labels, dims_offset):
method _decode_orientation (line 171) | def _decode_orientation(self, ori_vector, locations):
FILE: mmdet3d/core/bbox/iou_calculators/iou3d_calculator.py
class BboxOverlapsNearest3D (line 10) | class BboxOverlapsNearest3D(object):
method __init__ (line 21) | def __init__(self, coordinate='lidar'):
method __call__ (line 25) | def __call__(self, bboxes1, bboxes2, mode='iou', is_aligned=False):
method __repr__ (line 50) | def __repr__(self):
class BboxOverlaps3D (line 58) | class BboxOverlaps3D(object):
method __init__ (line 66) | def __init__(self, coordinate):
method __call__ (line 70) | def __call__(self, bboxes1, bboxes2, mode='iou'):
method __repr__ (line 92) | def __repr__(self):
function bbox_overlaps_nearest_3d (line 99) | def bbox_overlaps_nearest_3d(bboxes1,
function bbox_overlaps_3d (line 148) | def bbox_overlaps_3d(bboxes1, bboxes2, mode='iou', coordinate='camera'):
class AxisAlignedBboxOverlaps3D (line 180) | class AxisAlignedBboxOverlaps3D(object):
method __call__ (line 183) | def __call__(self, bboxes1, bboxes2, mode='iou', is_aligned=False):
method __repr__ (line 204) | def __repr__(self):
function axis_aligned_bbox_overlaps_3d (line 210) | def axis_aligned_bbox_overlaps_3d(bboxes1,
FILE: mmdet3d/core/bbox/samplers/iou_neg_piecewise_sampler.py
class IoUNegPiecewiseSampler (line 9) | class IoUNegPiecewiseSampler(RandomSampler):
method __init__ (line 29) | def __init__(self,
method _sample_pos (line 47) | def _sample_pos(self, assign_result, num_expected, **kwargs):
method _sample_neg (line 57) | def _sample_neg(self, assign_result, num_expected, **kwargs):
method sample (line 125) | def sample(self,
FILE: mmdet3d/core/bbox/structures/base_box3d.py
class BaseInstance3DBoxes (line 12) | class BaseInstance3DBoxes(object):
method __init__ (line 39) | def __init__(self, tensor, box_dim=7, with_yaw=True, origin=(0.5, 0.5,...
method volume (line 71) | def volume(self):
method dims (line 76) | def dims(self):
method yaw (line 81) | def yaw(self):
method height (line 86) | def height(self):
method top_height (line 91) | def top_height(self):
method bottom_height (line 97) | def bottom_height(self):
method center (line 103) | def center(self):
method bottom_center (line 122) | def bottom_center(self):
method gravity_center (line 127) | def gravity_center(self):
method corners (line 132) | def corners(self):
method bev (line 138) | def bev(self):
method nearest_bev (line 144) | def nearest_bev(self):
method in_range_bev (line 164) | def in_range_bev(self, box_range):
method rotate (line 186) | def rotate(self, angle, points=None):
method flip (line 200) | def flip(self, bev_direction='horizontal'):
method translate (line 210) | def translate(self, trans_vector):
method in_range_3d (line 220) | def in_range_3d(self, box_range):
method convert_to (line 245) | def convert_to(self, dst, rt_mat=None):
method scale (line 263) | def scale(self, scale_factor):
method limit_yaw (line 272) | def limit_yaw(self, offset=0.5, period=np.pi):
method nonempty (line 281) | def nonempty(self, threshold=0.0):
method __getitem__ (line 303) | def __getitem__(self, item):
method __len__ (line 332) | def __len__(self):
method __repr__ (line 336) | def __repr__(self):
method cat (line 341) | def cat(cls, boxes_list):
method to (line 363) | def to(self, device):
method clone (line 379) | def clone(self):
method device (line 391) | def device(self):
method __iter__ (line 395) | def __iter__(self):
method height_overlaps (line 404) | def height_overlaps(cls, boxes1, boxes2, mode='iou'):
method overlaps (line 436) | def overlaps(cls, boxes1, boxes2, mode='iou'):
method new_box (line 489) | def new_box(self, data):
method points_in_boxes_part (line 508) | def points_in_boxes_part(self, points, boxes_override=None):
method points_in_boxes_all (line 537) | def points_in_boxes_all(self, points, boxes_override=None):
method points_in_boxes (line 568) | def points_in_boxes(self, points, boxes_override=None):
method points_in_boxes_batch (line 574) | def points_in_boxes_batch(self, points, boxes_override=None):
FILE: mmdet3d/core/bbox/structures/box_3d_mode.py
class Box3DMode (line 15) | class Box3DMode(IntEnum):
method convert (line 66) | def convert(box, src, dst, rt_mat=None, with_yaw=True):
FILE: mmdet3d/core/bbox/structures/cam_box3d.py
class CameraInstance3DBoxes (line 10) | class CameraInstance3DBoxes(BaseInstance3DBoxes):
method __init__ (line 40) | def __init__(self,
method height (line 76) | def height(self):
method top_height (line 81) | def top_height(self):
method bottom_height (line 88) | def bottom_height(self):
method local_yaw (line 94) | def local_yaw(self):
method gravity_center (line 108) | def gravity_center(self):
method corners (line 117) | def corners(self):
method bev (line 160) | def bev(self):
method rotate (line 170) | def rotate(self, angle, points=None):
method flip (line 218) | def flip(self, bev_direction='horizontal', points=None):
method height_overlaps (line 253) | def height_overlaps(cls, boxes1, boxes2, mode='iou'):
method convert_to (line 283) | def convert_to(self, dst, rt_mat=None):
method points_in_boxes_part (line 303) | def points_in_boxes_part(self, points, boxes_override=None):
method points_in_boxes_all (line 330) | def points_in_boxes_all(self, points, boxes_override=None):
FILE: mmdet3d/core/bbox/structures/coord_3d_mode.py
class Coord3DMode (line 13) | class Coord3DMode(IntEnum):
method convert (line 65) | def convert(input, src, dst, rt_mat=None, with_yaw=True, is_point=True):
method convert_box (line 109) | def convert_box(box, src, dst, rt_mat=None, with_yaw=True):
method convert_point (line 136) | def convert_point(point, src, dst, rt_mat=None):
FILE: mmdet3d/core/bbox/structures/custom_box.py
class CustomBox (line 23) | class CustomBox(Box):
method __init__ (line 26) | def __init__(self,
method render (line 71) | def render(self,
FILE: mmdet3d/core/bbox/structures/depth_box3d.py
class DepthInstance3DBoxes (line 10) | class DepthInstance3DBoxes(BaseInstance3DBoxes):
method gravity_center (line 43) | def gravity_center(self):
method corners (line 52) | def corners(self):
method rotate (line 93) | def rotate(self, angle, points=None):
method flip (line 153) | def flip(self, bev_direction='horizontal', points=None):
method convert_to (line 188) | def convert_to(self, dst, rt_mat=None):
method enlarged_box (line 208) | def enlarged_box(self, extra_width):
method get_surface_line_center (line 223) | 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 41) | def gravity_center(self):
method corners (line 50) | def corners(self):
method rotate (line 91) | def rotate(self, angle, points=None):
method flip (line 143) | def flip(self, bev_direction='horizontal', points=None):
method convert_to (line 177) | def convert_to(self, dst, rt_mat=None):
method enlarged_box (line 197) | def enlarged_box(self, extra_width):
FILE: mmdet3d/core/bbox/structures/utils.py
function limit_period (line 11) | def limit_period(val, offset=0.5, period=np.pi):
function rotation_3d_in_axis (line 29) | def rotation_3d_in_axis(points,
function xywhr2xyxyr (line 121) | def xywhr2xyxyr(boxes_xywhr):
function get_box_type (line 142) | def get_box_type(box_type):
function points_cam2img (line 176) | def points_cam2img(points_3d, proj_mat, with_depth=False):
function points_img2cam (line 218) | def points_img2cam(points, cam2img):
function mono_cam_box2vis (line 251) | def mono_cam_box2vis(cam_box):
function get_proj_mat_by_coord_type (line 297) | def get_proj_mat_by_coord_type(img_meta, coord_type):
function yaw2local (line 314) | def yaw2local(yaw, loc):
FILE: mmdet3d/core/bbox/transforms.py
function bbox3d_mapping_back (line 5) | def bbox3d_mapping_back(bboxes, scale_factor, flip_horizontal, flip_vert...
function bbox3d2roi (line 27) | def bbox3d2roi(bbox_list):
function bbox3d2result (line 50) | def bbox3d2result(bboxes, scores, labels, attrs=None):
FILE: mmdet3d/core/bbox/util.py
function normalize_bbox (line 3) | def normalize_bbox(bboxes, pc_range):
function denormalize_bbox (line 26) | def denormalize_bbox(normalized_bboxes, pc_range):
FILE: mmdet3d/core/evaluation/indoor_eval.py
function average_precision (line 8) | def average_precision(recalls, precisions, mode='area'):
function eval_det_cls (line 56) | def eval_det_cls(pred, gt, iou_thr=None):
function eval_map_recall (line 164) | def eval_map_recall(pred, gt, ovthresh=None):
function indoor_eval (line 203) | def indoor_eval(gt_annos,
FILE: mmdet3d/core/evaluation/instance_seg_eval.py
function aggregate_predictions (line 9) | def aggregate_predictions(masks, labels, scores, valid_class_ids):
function rename_gt (line 39) | def rename_gt(gt_semantic_masks, gt_instance_masks, valid_class_ids):
function instance_seg_eval (line 70) | def instance_seg_eval(gt_semantic_masks,
FILE: mmdet3d/core/evaluation/kitti_utils/eval.py
function get_thresholds (line 10) | def get_thresholds(scores: np.ndarray, num_gt, num_sample_pts=41):
function clean_data (line 30) | def clean_data(gt_anno, dt_anno, current_class, difficulty):
function image_box_overlap (line 86) | def image_box_overlap(boxes, query_boxes, criterion=-1):
function bev_box_overlap (line 117) | def bev_box_overlap(boxes, qboxes, criterion=-1):
function d3_box_overlap_kernel (line 124) | def d3_box_overlap_kernel(boxes, qboxes, rinc, criterion=-1):
function d3_box_overlap (line 155) | def d3_box_overlap(boxes, qboxes, criterion=-1):
function compute_statistics_jit (line 164) | def compute_statistics_jit(overlaps,
function get_split_parts (line 284) | def get_split_parts(num, num_part):
function fused_compute_statistics (line 294) | def fused_compute_statistics(overlaps,
function calculate_iou_partly (line 343) | def calculate_iou_partly(gt_annos, dt_annos, metric, num_parts=50):
function _prepare_data (line 421) | def _prepare_data(gt_annos, dt_annos, current_class, difficulty):
function eval_class (line 452) | def eval_class(gt_annos,
function get_mAP11 (line 573) | def get_mAP11(prec):
function get_mAP40 (line 580) | def get_mAP40(prec):
function print_str (line 587) | def print_str(value, *arg, sstream=None):
function do_eval (line 596) | def do_eval(gt_annos,
function do_coco_style_eval (line 642) | def do_coco_style_eval(gt_annos, dt_annos, current_classes, overlap_ranges,
function kitti_eval (line 662) | def kitti_eval(gt_annos,
function kitti_eval_coco_style (line 881) | def kitti_eval_coco_style(gt_annos, dt_annos, current_classes):
FILE: mmdet3d/core/evaluation/kitti_utils/rotate_iou.py
function div_up (line 15) | def div_up(m, n):
function trangle_area (line 20) | def trangle_area(a, b, c):
function area (line 26) | def area(int_pts, num_of_inter):
function sort_vertex_in_convex_polygon (line 36) | def sort_vertex_in_convex_polygon(int_pts, num_of_inter):
function line_segment_intersection (line 76) | def line_segment_intersection(pts1, pts2, i, j, temp_pts):
function line_segment_intersection_v1 (line 119) | def line_segment_intersection_v1(pts1, pts2, i, j, temp_pts):
function point_in_quadrilateral (line 158) | def point_in_quadrilateral(pt_x, pt_y, corners):
function quadrilateral_intersection (line 177) | def quadrilateral_intersection(pts1, pts2, int_pts):
function rbbox_to_corners (line 201) | def rbbox_to_corners(corners, rbbox):
function inter (line 227) | def inter(rbbox1, rbbox2):
function devRotateIoUEval (line 253) | def devRotateIoUEval(rbox1, rbox2, criterion=-1):
function rotate_iou_kernel_eval (line 283) | def rotate_iou_kernel_eval(N,
function rotate_iou_gpu_eval (line 337) | 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 15) | def load_lyft_gts(lyft, data_root, eval_split, logger=None):
function load_lyft_predictions (line 74) | def load_lyft_predictions(res_path):
function lyft_eval (line 91) | def lyft_eval(lyft, data_root, res_path, eval_set, output_dir, logger=No...
function get_classwise_aps (line 143) | def get_classwise_aps(gt, predictions, class_names, iou_thresholds):
function get_single_class_aps (line 200) | def get_single_class_aps(gt, predictions, iou_thresholds):
FILE: mmdet3d/core/evaluation/scannet_utils/evaluate_semantic_instance.py
function evaluate_matches (line 10) | def evaluate_matches(matches, class_labels, options):
function compute_averages (line 189) | def compute_averages(aps, options, class_labels):
function assign_instances_for_scan (line 221) | def assign_instances_for_scan(pred_info, gt_ids, options, valid_class_ids,
function scannet_eval (line 297) | def scannet_eval(preds, gts, options, valid_class_ids, class_labels,
function get_options (line 330) | def get_options(options=None):
FILE: mmdet3d/core/evaluation/scannet_utils/util_3d.py
class Instance (line 8) | class Instance:
method __init__ (line 21) | def __init__(self, mesh_vert_instances, instance_id):
method get_label_id (line 30) | def get_label_id(instance_id):
method get_instance_verts (line 34) | def get_instance_verts(mesh_vert_instances, instance_id):
method to_json (line 37) | def to_json(self):
method to_dict (line 41) | def to_dict(self):
method from_json (line 50) | def from_json(self, data):
method __str__ (line 58) | def __str__(self):
function get_instances (line 62) | def get_instances(ids, class_ids, class_labels, id2label):
FILE: mmdet3d/core/evaluation/seg_eval.py
function fast_hist (line 7) | def fast_hist(preds, labels, num_classes):
function per_class_iou (line 28) | def per_class_iou(hist):
function get_acc (line 42) | def get_acc(hist):
function get_acc_cls (line 56) | def get_acc_cls(hist):
function seg_eval (line 70) | def seg_eval(gt_labels, seg_preds, label2cat, ignore_index, logger=None):
FILE: mmdet3d/core/evaluation/waymo_utils/prediction_kitti_to_waymo.py
class KITTI2Waymo (line 23) | class KITTI2Waymo(object):
method __init__ (line 41) | def __init__(self,
method get_file_names (line 79) | def get_file_names(self):
method create_folder (line 85) | def create_folder(self):
method parse_objects (line 89) | def parse_objects(self, kitti_result, T_k2w, context_name,
method convert_one (line 171) | def convert_one(self, file_idx):
method convert (line 211) | def convert(self):
method __len__ (line 225) | def __len__(self):
method transform (line 229) | def transform(self, T, x, y, z):
method combine (line 245) | def combine(self, pathnames):
FILE: mmdet3d/core/hook/ema.py
class ModelEMA (line 17) | class ModelEMA:
method __init__ (line 31) | def __init__(self, model, decay=0.9999, updates=0):
method update (line 48) | def update(self, trainer, model):
class MEGVIIEMAHook (line 63) | class MEGVIIEMAHook(Hook):
method __init__ (line 70) | def __init__(self, init_updates=0, decay=0.9990, resume=None, interval...
method before_run (line 77) | def before_run(self, runner):
method after_train_iter (line 100) | def after_train_iter(self, runner):
method after_train_epoch (line 108) | def after_train_epoch(self, runner):
method after_run (line 111) | def after_run(self, runner):
method save_checkpoint (line 115) | def save_checkpoint(self, runner):
method save_checkpoint_iter (line 128) | def save_checkpoint_iter(self, runner):
FILE: mmdet3d/core/hook/forge_load.py
class Monitor (line 22) | class Monitor(threading.Thread):
method __init__ (line 23) | def __init__(self):
method update (line 30) | def update(self, ):
method run (line 36) | def run(self):
method get_current_load (line 42) | def get_current_load():
class ForgeLoadWorker (line 49) | class ForgeLoadWorker(Hook):
method __init__ (line 51) | def __init__(self, target=50):
method after_run (line 59) | def after_run(self, runner):
method __str__ (line 72) | def __str__(self):
method my_kernel (line 78) | def my_kernel(io_array):
method run_awhile (line 87) | def run_awhile(self, sec=10):
method idle_awhile (line 93) | def idle_awhile(self, sec=5):
method _boost (line 97) | def _boost(self, rate=1.2):
method _slow_down (line 101) | def _slow_down(self, rate=1.5):
method adjust_speed (line 105) | def adjust_speed(self, avg_load):
method main (line 117) | def main(self, target=50):
FILE: mmdet3d/core/hook/sequentialsontrol.py
class SequentialControlHook (line 9) | class SequentialControlHook(Hook):
method __init__ (line 12) | def __init__(self, temporal_start_epoch=1, temporal_start_iter=-1):
method set_temporal_flag (line 17) | def set_temporal_flag(self, runner, flag):
method set_temporal_flag_v2 (line 23) | def set_temporal_flag_v2(self, runner, flag):
method before_run (line 29) | def before_run(self, runner):
method before_train_epoch (line 34) | def before_train_epoch(self, runner):
method after_train_iter (line 38) | def after_train_iter(self, runner):
FILE: mmdet3d/core/hook/utils.py
function is_parallel (line 7) | def is_parallel(model):
FILE: mmdet3d/core/points/__init__.py
function get_points_type (line 10) | def get_points_type(points_type):
FILE: mmdet3d/core/points/base_points.py
class BasePoints (line 11) | class BasePoints(object):
method __init__ (line 30) | def __init__(self, tensor, points_dim=3, attribute_dims=None):
method coord (line 50) | def coord(self):
method coord (line 55) | def coord(self, tensor):
method height (line 66) | def height(self):
method height (line 76) | def height(self, tensor):
method color (line 97) | def color(self):
method color (line 107) | def color(self, tensor):
method shape (line 131) | def shape(self):
method shuffle (line 135) | def shuffle(self):
method rotate (line 145) | def rotate(self, rotation, axis=None):
method flip (line 174) | def flip(self, bev_direction='horizontal'):
method translate (line 182) | def translate(self, trans_vector):
method in_range_3d (line 203) | def in_range_3d(self, point_range):
method bev (line 228) | def bev(self):
method in_range_bev (line 232) | def in_range_bev(self, point_range):
method convert_to (line 250) | def convert_to(self, dst, rt_mat=None):
method scale (line 268) | def scale(self, scale_factor):
method __getitem__ (line 276) | def __getitem__(self, item):
method __len__ (line 348) | def __len__(self):
method __repr__ (line 352) | def __repr__(self):
method cat (line 357) | def cat(cls, points_list):
method to (line 379) | def to(self, device):
method clone (line 395) | def clone(self):
method device (line 409) | def device(self):
method __iter__ (line 413) | def __iter__(self):
method new_point (line 421) | def new_point(self, data):
FILE: mmdet3d/core/points/cam_points.py
class CameraPoints (line 5) | class CameraPoints(BasePoints):
method __init__ (line 24) | def __init__(self, tensor, points_dim=3, attribute_dims=None):
method flip (line 29) | def flip(self, bev_direction='horizontal'):
method bev (line 41) | def bev(self):
method convert_to (line 45) | def convert_to(self, dst, rt_mat=None):
FILE: mmdet3d/core/points/depth_points.py
class DepthPoints (line 5) | class DepthPoints(BasePoints):
method __init__ (line 24) | def __init__(self, tensor, points_dim=3, attribute_dims=None):
method flip (line 29) | def flip(self, bev_direction='horizontal'):
method convert_to (line 40) | def convert_to(self, dst, rt_mat=None):
FILE: mmdet3d/core/points/lidar_points.py
class LiDARPoints (line 5) | class LiDARPoints(BasePoints):
method __init__ (line 24) | def __init__(self, tensor, points_dim=3, attribute_dims=None):
method flip (line 29) | def flip(self, bev_direction='horizontal'):
method convert_to (line 40) | 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 131) | def aligned_3d_nms(boxes, scores, classes, thresh):
function circle_nms (line 182) | def circle_nms(dets, thresh, post_max_size=83):
function nms_bev (line 231) | def nms_bev(boxes, scores, thresh, pre_max_size=None, post_max_size=None,
function nms_normal_bev (line 276) | def nms_normal_bev(boxes, scores, thresh):
FILE: mmdet3d/core/post_processing/merge_augs.py
function merge_aug_bboxes_3d (line 8) | def merge_aug_bboxes_3d(aug_results, img_metas, test_cfg):
FILE: mmdet3d/core/utils/array_converter.py
function array_converter (line 9) | def array_converter(to_torch=True,
class ArrayConverter (line 202) | class ArrayConverter:
method __init__ (line 208) | def __init__(self, template_array=None):
method set_template (line 212) | def set_template(self, array):
method convert (line 253) | def convert(self, input_array, target_type=None, target_array=None):
method recover (line 312) | def recover(self, input_array):
FILE: mmdet3d/core/utils/gaussian.py
function gaussian_2d (line 6) | 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):
function get_ellip_gaussian_2D (line 89) | def get_ellip_gaussian_2D(heatmap, center, radius_x, radius_y, k=1):
function ellip_gaussian2D (line 128) | def ellip_gaussian2D(radius,
FILE: mmdet3d/core/visualizer/image_vis.py
function project_pts_on_img (line 10) | def project_pts_on_img(points,
function plot_rect3d_on_img (line 61) | def plot_rect3d_on_img(img,
function draw_lidar_bbox3d_on_img (line 89) | def draw_lidar_bbox3d_on_img(bboxes3d,
function draw_depth_bbox3d_on_img (line 128) | def draw_depth_bbox3d_on_img(bboxes3d,
function draw_camera_bbox3d_on_img (line 168) | def draw_camera_bbox3d_on_img(bboxes3d,
FILE: mmdet3d/core/visualizer/open3d_vis.py
function _draw_points (line 15) | def _draw_points(points,
function _draw_bboxes (line 60) | def _draw_bboxes(bbox3d,
function show_pts_boxes (line 125) | def show_pts_boxes(points,
function _draw_bboxes_ind (line 191) | def _draw_bboxes_ind(bbox3d,
function show_pts_index_boxes (line 263) | def show_pts_index_boxes(points,
class Visualizer (line 333) | class Visualizer(object):
method __init__ (line 363) | def __init__(self,
method add_bboxes (line 404) | def add_bboxes(self, bbox3d, bbox_color=None, points_in_box_color=None):
method add_seg_mask (line 425) | def add_seg_mask(self, seg_mask_colors):
method show (line 447) | def show(self, save_path=None):
FILE: mmdet3d/core/visualizer/show_result.py
function _write_obj (line 12) | def _write_obj(points, out_filename):
function _write_oriented_bbox (line 34) | def _write_oriented_bbox(scene_bbox, out_filename):
function show_result (line 76) | def show_result(points,
function show_seg_result (line 147) | def show_seg_result(points,
function show_multi_modality_result (line 220) | def show_multi_modality_result(img,
FILE: mmdet3d/core/voxel/builder.py
function build_voxel_generator (line 7) | def build_voxel_generator(cfg, **kwargs):
FILE: mmdet3d/core/voxel/voxel_generator.py
class VoxelGenerator (line 6) | class VoxelGenerator(object):
method __init__ (line 17) | def __init__(self,
method generate (line 36) | def generate(self, points):
method voxel_size (line 43) | def voxel_size(self):
method max_num_points_per_voxel (line 48) | def max_num_points_per_voxel(self):
method point_cloud_range (line 53) | def point_cloud_range(self):
method grid_size (line 58) | def grid_size(self):
method __repr__ (line 62) | def __repr__(self):
function points_to_voxel (line 76) | def points_to_voxel(points,
function _points_to_voxel_reverse_kernel (line 138) | def _points_to_voxel_reverse_kernel(points,
function _points_to_voxel_kernel (line 212) | def _points_to_voxel_kernel(points,
FILE: mmdet3d/datasets/builder.py
function build_dataset (line 33) | def build_dataset(cfg, default_args=None):
function build_dataloader (line 61) | def build_dataloader(dataset,
FILE: mmdet3d/datasets/custom_3d.py
class Custom3DDataset (line 24) | class Custom3DDataset(Dataset):
method __init__ (line 70) | def __init__(self,
method load_annotations (line 112) | def load_annotations(self, ann_file):
method get_data_info (line 124) | def get_data_info(self, index):
method get_ann_info (line 156) | def get_ann_info(self, index):
method pre_pipeline (line 197) | def pre_pipeline(self, results):
method prepare_train_data (line 224) | def prepare_train_data(self, index):
method prepare_test_data (line 245) | def prepare_test_data(self, index):
method get_classes (line 260) | def get_classes(cls, classes=None):
method format_results (line 286) | def format_results(self,
method evaluate (line 310) | def evaluate(self,
method _build_default_pipeline (line 362) | def _build_default_pipeline(self):
method _get_pipeline (line 367) | def _get_pipeline(self, pipeline):
method _extract_data (line 384) | def _extract_data(self, index, pipeline, key, load_annos=False):
method __len__ (line 418) | def __len__(self):
method _rand_another (line 426) | def _rand_another(self, idx):
method __getitem__ (line 435) | def __getitem__(self, idx):
method _set_group_flag (line 450) | def _set_group_flag(self):
FILE: mmdet3d/datasets/custom_3d_seg.py
class Custom3DSegDataset (line 18) | class Custom3DSegDataset(Dataset):
method __init__ (line 56) | def __init__(self,
method load_annotations (line 100) | def load_annotations(self, ann_file):
method get_data_info (line 112) | def get_data_info(self, index):
method pre_pipeline (line 141) | def pre_pipeline(self, results):
method prepare_train_data (line 160) | def prepare_train_data(self, index):
method prepare_test_data (line 176) | def prepare_test_data(self, index):
method get_classes_and_palette (line 190) | def get_classes_and_palette(self, classes=None, palette=None):
method get_scene_idxs (line 265) | def get_scene_idxs(self, scene_idxs):
method format_results (line 286) | def format_results(self,
method evaluate (line 310) | def evaluate(self,
method _rand_another (line 364) | def _rand_another(self, idx):
method _build_default_pipeline (line 373) | def _build_default_pipeline(self):
method _get_pipeline (line 378) | def _get_pipeline(self, pipeline):
method _extract_data (line 395) | def _extract_data(self, index, pipeline, key, load_annos=False):
method __len__ (line 429) | def __len__(self):
method __getitem__ (line 437) | def __getitem__(self, idx):
method _set_group_flag (line 458) | def _set_group_flag(self):
FILE: mmdet3d/datasets/dataset_wrappers.py
class CBGSDataset (line 8) | class CBGSDataset(object):
method __init__ (line 19) | def __init__(self, dataset):
method _get_sample_indices (line 30) | def _get_sample_indices(self):
method __getitem__ (line 64) | def __getitem__(self, idx):
method __len__ (line 73) | def __len__(self):
FILE: mmdet3d/datasets/evals/eval_utils.py
function category_to_motion_name (line 18) | def category_to_motion_name(category_name: str):
function detection_prediction_category_to_motion_name (line 47) | def detection_prediction_category_to_motion_name(category_name: str):
class DetectionMotionMetrics (line 72) | class DetectionMotionMetrics(DetectionMetrics):
method deserialize (line 76) | def deserialize(cls, content: dict):
class DetectionMotionMetricDataList (line 93) | class DetectionMotionMetricDataList(DetectionMetricDataList):
method deserialize (line 96) | def deserialize(cls, content: dict):
class DetectionMotionMetricData (line 103) | class DetectionMotionMetricData(DetectionMetricData):
method __init__ (line 108) | def __init__(self,
method __eq__ (line 151) | def __eq__(self, other):
method max_recall_ind (line 158) | def max_recall_ind(self):
method max_recall (line 171) | def max_recall(self):
method serialize (line 176) | def serialize(self):
method deserialize (line 193) | def deserialize(cls, content: dict):
method no_predictions (line 208) | def no_predictions(cls):
method random_md (line 223) | def random_md(cls):
class DetectionMotionBox (line 238) | class DetectionMotionBox(DetectionBox):
method __init__ (line 239) | def __init__(self,
method __eq__ (line 271) | def __eq__(self, other):
method serialize (line 285) | def serialize(self) -> dict:
method deserialize (line 303) | def deserialize(cls, content: dict):
class DetectionMotionBox_modified (line 319) | class DetectionMotionBox_modified(DetectionMotionBox):
method __init__ (line 320) | def __init__(self, *args, token=None, visibility=None, index=None, **k...
method serialize (line 329) | def serialize(self) -> dict:
method deserialize (line 350) | def deserialize(cls, content: dict):
function load_prediction (line 371) | def load_prediction(result_path: str, max_boxes_per_sample: int, box_cls...
function load_gt (line 406) | def load_gt(nusc: NuScenes, eval_split: str, box_cls, data_infos = None,...
function prediction_metrics (line 537) | def prediction_metrics(gt_box_match, pred_box):
function accumulate (line 558) | def accumulate(gt_boxes: EvalBoxes,
function accumulate_motion (line 729) | def accumulate_motion(gt_boxes: EvalBoxes,
FILE: mmdet3d/datasets/evals/map_api.py
class NuScenesMap (line 42) | class NuScenesMap:
method __init__ (line 63) | def __init__(self,
method _load_layer (line 112) | def _load_layer(self, layer_name: str) -> List[dict]:
method _load_layer_dict (line 120) | def _load_layer_dict(self, layer_name: str) -> Dict[str, Union[dict, l...
method _load_layers (line 128) | def _load_layers(self) -> None:
method _make_token2ind (line 151) | def _make_token2ind(self) -> None:
method _make_shortcuts (line 160) | def _make_shortcuts(self) -> None:
method _get_stop_line_cue (line 190) | def _get_stop_line_cue(self, stop_line_record: dict) -> List[dict]:
method get (line 203) | def get(self, layer_name: str, token: str) -> dict:
method getind (line 214) | def getind(self, layer_name: str, token: str) -> int:
method render_record (line 223) | def render_record(self,
method render_layers (line 244) | def render_layers(self,
method render_map_patch (line 262) | def render_map_patch(self,
method render_map_in_image (line 285) | def render_map_in_image(self,
method get_map_mask_in_image (line 319) | def get_map_mask_in_image(self,
method render_egoposes_on_fancy_map (line 353) | def render_egoposes_on_fancy_map(self,
method render_centerlines (line 381) | def render_centerlines(self,
method render_map_mask (line 394) | def render_map_mask(self,
method get_map_mask (line 415) | def get_map_mask(self,
method get_map_geom (line 430) | def get_map_geom(self,
method get_records_in_patch (line 445) | def get_records_in_patch(self,
method is_record_in_patch (line 460) | def is_record_in_patch(self,
method layers_on_point (line 476) | def layers_on_point(self, x: float, y: float, layer_names: List[str] =...
method record_on_point (line 486) | def record_on_point(self, x: float, y: float, layer_name: str) -> str:
method extract_polygon (line 496) | def extract_polygon(self, polygon_token: str) -> Polygon:
method extract_line (line 504) | def extract_line(self, line_token: str) -> LineString:
method get_bounds (line 512) | def get_bounds(self, layer_name: str, token: str) -> Tuple[float, floa...
method get_records_in_radius (line 521) | def get_records_in_radius(self, x: float, y: float, radius: float,
method discretize_centerlines (line 538) | def discretize_centerlines(self, resolution_meters: float) -> List[np....
method discretize_lanes (line 553) | def discretize_lanes(self, tokens: List[str],
method _get_connected_lanes (line 565) | def _get_connected_lanes(self, lane_token: str, incoming_outgoing: str...
method get_outgoing_lane_ids (line 578) | def get_outgoing_lane_ids(self, lane_token: str) -> List[str]:
method get_incoming_lane_ids (line 587) | def get_incoming_lane_ids(self, lane_token: str) -> List[str]:
method get_arcline_path (line 596) | def get_arcline_path(self, lane_token: str) -> List[ArcLinePath]:
method get_closest_lane (line 611) | def get_closest_lane(self, x: float, y: float, radius: float = 5) -> str:
method render_next_roads (line 638) | def render_next_roads(self,
method get_next_roads (line 654) | def get_next_roads(self, x: float, y: float) -> Dict[str, List[str]]:
class NuScenesMapExplorer (line 707) | class NuScenesMapExplorer:
method __init__ (line 709) | def __init__(self,
method render_centerlines (line 742) | def render_centerlines(self,
method render_map_mask (line 769) | def render_map_mask(self,
method get_map_geom (line 813) | def get_map_geom(self,
method map_geom_to_mask (line 840) | def map_geom_to_mask(self,
method get_map_mask (line 861) | def get_map_mask(self,
method render_record (line 911) | def render_record(self,
method render_layers (line 992) | def render_layers(self,
method render_map_patch (line 1024) | def render_map_patch(self,
method render_map_in_image (line 1081) | def render_map_in_image(self,
method points_transform (line 1239) | def points_transform(points, poserecord, cs_record, cam_intrinsic, im_...
method get_map_mask_in_image (line 1293) | def get_map_mask_in_image(self,
method render_egoposes_on_fancy_map (line 1476) | def render_egoposes_on_fancy_map(self,
method render_next_roads (line 1579) | def render_next_roads(self,
method _clip_points_behind_camera (line 1611) | def _clip_points_behind_camera(points, near_plane: float):
method get_records_in_patch (line 1674) | def get_records_in_patch(self,
method is_record_in_patch (line 1705) | def is_record_in_patch(self,
method layers_on_point (line 1729) | def layers_on_point(self, x: float, y: float, layer_names: List[str] =...
method record_on_point (line 1747) | def record_on_point(self, x: float, y: float, layer_name: str) -> str:
method extract_polygon (line 1780) | def extract_polygon(self, polygon_token: str) -> Polygon:
method extract_line (line 1800) | def extract_line(self, line_token: str) -> LineString:
method get_bounds (line 1812) | def get_bounds(self, layer_name: str, token: str) -> Tuple[float, floa...
method _get_polygon_bounds (line 1826) | def _get_polygon_bounds(self, layer_name: str, token: str) -> Tuple[fl...
method _get_line_bounds (line 1862) | def _get_line_bounds(self, layer_name: str, token: str) -> Tuple[float...
method _is_polygon_record_in_patch (line 1887) | def _is_polygon_record_in_patch(self,
method _is_line_record_in_patch (line 1919) | def _is_line_record_in_patch(self,
method _render_layer (line 1956) | def _render_layer(self, ax: Axes, layer_name: str, alpha: float, token...
method _render_polygon_layer (line 1971) | def _render_polygon_layer(self, ax: Axes, layer_name: str, alpha: floa...
method _render_line_layer (line 2011) | def _render_line_layer(self, ax: Axes, layer_name: str, alpha: float, ...
method _get_layer_geom (line 2045) | def _get_layer_geom(self,
method _layer_geom_to_mask (line 2063) | def _layer_geom_to_mask(self,
method mask_for_polygons (line 2084) | def mask_for_polygons(polygons: MultiPolygon, mask: np.ndarray) -> np....
method mask_for_lines (line 2104) | def mask_for_lines(lines: LineString, mask: np.ndarray) -> np.ndarray:
method _polygon_geom_to_mask (line 2123) | def _polygon_geom_to_mask(self,
method _line_geom_to_mask (line 2177) | def _line_geom_to_mask(self,
method _get_layer_polygon (line 2221) | def _get_layer_polygon(self,
method _get_layer_line (line 2275) | def _get_layer_line(self,
method get_patch_coord (line 2315) | def get_patch_coord(patch_box: Tuple[float, float, float, float],
method _get_figsize (line 2335) | def _get_figsize(self, figsize: Union[None, float, Tuple[float, float]...
FILE: mmdet3d/datasets/evals/metric_utils.py
function min_ade (line 6) | def min_ade(traj: torch.Tensor, traj_gt: torch.Tensor,
function min_fde (line 33) | def min_fde(traj: torch.Tensor, traj_gt: torch.Tensor,
function miss_rate (line 64) | def miss_rate(
function traj_fde (line 96) | def traj_fde(gt_box, pred_box, final_step):
FILE: mmdet3d/datasets/evals/nuscenes_eval_motion.py
function class_tp_curve (line 78) | def class_tp_curve(md_list: DetectionMetricDataList,
function center_in_image (line 152) | def center_in_image(box,
function exist_corners_in_image_but_not_all (line 188) | def exist_corners_in_image_but_not_all(box,
function filter_eval_boxes_by_id (line 220) | def filter_eval_boxes_by_id(nusc: NuScenes,
function filter_eval_boxes_by_visibility (line 252) | def filter_eval_boxes_by_visibility(
function filter_by_sample_token (line 284) | def filter_by_sample_token(
function filter_eval_boxes_by_overlap (line 295) | def filter_eval_boxes_by_overlap(nusc: NuScenes,
class MotionEval (line 379) | class MotionEval(NuScenesEval):
method __init__ (line 384) | def __init__(self,
method update_gt (line 483) | def update_gt(self, type_='vis', visibility='1', index=1):
method evaluate (line 516) | def evaluate(self) -> Tuple[DetectionMotionMetrics,
method evaluate_motion (line 582) | def evaluate_motion(
method evaluate_epa (line 647) | def evaluate_epa(
method main (line 717) | def main(self,
method render (line 801) | def render(self, metrics: DetectionMetrics,
function print_traj_metrics (line 855) | def print_traj_metrics(metrics):
FILE: mmdet3d/datasets/evaluation/AP.py
function average_precision (line 7) | def average_precision(recalls, precisions, mode='area'):
function instance_match (line 52) | def instance_match(pred_lines: NDArray,
FILE: mmdet3d/datasets/evaluation/distance.py
function chamfer_distance (line 5) | def chamfer_distance(line1: NDArray, line2: NDArray) -> float:
function frechet_distance (line 23) | def frechet_distance(line1: NDArray, line2: NDArray) -> float:
function chamfer_distance_batch (line 37) | def chamfer_distance_batch(pred_lines, gt_lines):
FILE: mmdet3d/datasets/evaluation/raster_eval.py
class RasterEvaluate (line 14) | class RasterEvaluate(object):
method __init__ (line 22) | def __init__(self, dataset_cfg: Config, n_workers: int=N_WORKERS):
method gts (line 31) | def gts(self) -> Dict[str, NDArray]:
method evaluate (line 42) | def evaluate(self,
FILE: mmdet3d/datasets/evaluation/vector_eval.py
class VectorEvaluate (line 24) | class VectorEvaluate(object):
method __init__ (line 32) | def __init__(self, dataset_cfg: Config, n_workers: int=N_WORKERS) -> N...
method gts (line 45) | def gts(self) -> Dict[str, Dict[int, List[NDArray]]]:
method interp_fixed_num (line 77) | def interp_fixed_num(self,
method interp_fixed_dist (line 96) | def interp_fixed_dist(self,
method _evaluate_single (line 118) | def _evaluate_single(self,
method evaluate (line 169) | def evaluate(self,
FILE: mmdet3d/datasets/kitti2d_dataset.py
class Kitti2DDataset (line 10) | class Kitti2DDataset(CustomDataset):
method load_annotations (line 81) | def load_annotations(self, ann_file):
method _filter_imgs (line 97) | def _filter_imgs(self, min_size=32):
method get_ann_info (line 105) | def get_ann_info(self, index):
method prepare_train_img (line 137) | def prepare_train_img(self, idx):
method prepare_test_img (line 158) | def prepare_test_img(self, idx):
method drop_arrays_by_name (line 176) | def drop_arrays_by_name(self, gt_names, used_classes):
method keep_arrays_by_name (line 190) | def keep_arrays_by_name(self, gt_names, used_classes):
method reformat_bbox (line 204) | def reformat_bbox(self, outputs, out=None):
method evaluate (line 222) | def evaluate(self, result_files, eval_types=None):
FILE: mmdet3d/datasets/kitti_dataset.py
class KittiDataset (line 21) | class KittiDataset(Custom3DDataset):
method __init__ (line 57) | def __init__(self,
method _get_pts_filename (line 87) | def _get_pts_filename(self, idx):
method get_data_info (line 100) | def get_data_info(self, index):
method get_ann_info (line 143) | def get_ann_info(self, index):
method drop_arrays_by_name (line 223) | def drop_arrays_by_name(self, gt_names, used_classes):
method keep_arrays_by_name (line 237) | def keep_arrays_by_name(self, gt_names, used_classes):
method remove_dontcare (line 251) | def remove_dontcare(self, ann_info):
method format_results (line 270) | def format_results(self,
method evaluate (line 325) | def evaluate(self,
method bbox2result_kitti (line 394) | def bbox2result_kitti(self,
method bbox2result_kitti2d (line 509) | def bbox2result_kitti2d(self,
method convert_valid_bboxes (line 621) | def convert_valid_bboxes(self, box_dict, info):
method _build_default_pipeline (line 703) | def _build_default_pipeline(self):
method show (line 722) | def show(self, results, out_dir, show=True, pipeline=None):
FILE: mmdet3d/datasets/kitti_mono_dataset.py
class KittiMonoDataset (line 17) | class KittiMonoDataset(NuScenesMonoDataset):
method __init__ (line 35) | def __init__(self,
method _parse_ann_info (line 57) | def _parse_ann_info(self, img_info, ann_info):
method format_results (line 147) | def format_results(self,
method evaluate (line 203) | def evaluate(self,
method bbox2result_kitti (line 271) | def bbox2result_kitti(self,
method bbox2result_kitti2d (line 386) | def bbox2result_kitti2d(self,
method convert_valid_bboxes (line 497) | def convert_valid_bboxes(self, box_dict, info):
FILE: mmdet3d/datasets/lyft_dataset.py
class LyftDataset (line 22) | class LyftDataset(Custom3DDataset):
method __init__ (line 80) | def __init__(self,
method load_annotations (line 112) | def load_annotations(self, ann_file):
method get_data_info (line 129) | def get_data_info(self, index):
method get_ann_info (line 188) | def get_ann_info(self, index):
method _format_bbox (line 230) | def _format_bbox(self, results, jsonfile_prefix=None):
method _evaluate_single (line 273) | def _evaluate_single(self,
method format_results (line 315) | def format_results(self, results, jsonfile_prefix=None, csv_savepath=N...
method evaluate (line 366) | def evaluate(self,
method _build_default_pipeline (line 422) | def _build_default_pipeline(self):
method show (line 443) | def show(self, results, out_dir, show=False, pipeline=None):
method json2csv (line 475) | def json2csv(self, json_path, csv_savepath):
function output_to_lyft_box (line 513) | def output_to_lyft_box(detection):
function lidar_lyft_box_to_global (line 546) | def lidar_lyft_box_to_global(info, boxes):
FILE: mmdet3d/datasets/map_utils/mean_ap.py
function average_precision (line 14) | def average_precision(recalls, precisions, mode='area'):
function get_cls_results (line 60) | def get_cls_results(gen_results,
function format_res_gt_by_classes (line 137) | def format_res_gt_by_classes(result_path,
function eval_map (line 220) | def eval_map(gen_results,
function print_map_summary (line 331) | def print_map_summary(mean_ap,
FILE: mmdet3d/datasets/map_utils/tpfp.py
function tpfp_bbox (line 9) | def tpfp_bbox(det_bboxes,
function tpfp_rbbox (line 79) | def tpfp_rbbox(det_bboxes,
function tpfp_det (line 149) | def tpfp_det(det_bboxes,
function tpfp_gen (line 216) | def tpfp_gen(gen_lines,
function custom_tpfp_gen (line 290) | def custom_tpfp_gen(gen_lines,
FILE: mmdet3d/datasets/map_utils/tpfp_chamfer.py
function vec_iou (line 15) | def vec_iou(pred_lines, gt_lines):
function convex_iou (line 52) | def convex_iou(pred_lines, gt_lines, gt_mask):
function rbbox_iou (line 86) | def rbbox_iou(pred_lines, gt_lines, gt_mask):
function polyline_score (line 121) | def polyline_score(pred_lines, gt_lines, linewidth=1., metric='POR'):
function custom_polyline_score (line 217) | def custom_polyline_score(pred_lines, gt_lines, linewidth=1., metric='ch...
FILE: mmdet3d/datasets/nuscenes_dataset.py
class NuScenesDataset (line 45) | class NuScenesDataset(Custom3DDataset):
method __init__ (line 156) | def __init__(self,
method get_cat_ids (line 232) | def get_cat_ids(self, idx):
method load_annotations (line 256) | def load_annotations(self, ann_file):
method _set_sequence_group_flag (line 276) | def _set_sequence_group_flag(self):
method get_data_info (line 311) | def get_data_info(self, index):
method get_fut_bbox_info (line 447) | def get_fut_bbox_info(self, info, index):
method get_adj_info (line 463) | def get_adj_info(self, info, index):
method get_ann_info (line 476) | def get_ann_info(self, index):
method format_map_results (line 526) | def format_map_results(self, results, jsonfile_prefix=None):
method get_map_classes (line 574) | def get_map_classes(cls, map_classes=None):
method _format_map (line 600) | def _format_map(self, results, jsonfile_prefix=None, score_thresh=0.2):
method vectormap_pipeline (line 661) | def vectormap_pipeline(self, location, ego2global_translation, patch_a...
method _format_map_gt (line 700) | def _format_map_gt(self):
method _evaluate_single (line 760) | def _evaluate_single(self,
method format_results (line 819) | def format_results(self, results, jsonfile_prefix=None):
method evaluate (line 909) | def evaluate(self, results,
method evaluate_ego_traj (line 968) | def evaluate_ego_traj(self, results, jsonfile_prefix=None, logger=None):
method smoothness (line 1083) | def smoothness(self, data):
method _format_bbox (line 1161) | def _format_bbox(self, results, jsonfile_prefix=None):
method evaluate_tracking (line 1251) | def evaluate_tracking(self,
method format_tracking_results (line 1307) | def format_tracking_results(self, results, jsonfile_prefix=None):
method _format_tracking_bbox (line 1353) | def _format_tracking_bbox(self, results, jsonfile_prefix=None):
method _evaluate_motion_single (line 1463) | def _evaluate_motion_single(self,
method _evaluate_tracking_single (line 1549) | def _evaluate_tracking_single(self,
method evaluate_occupancy (line 1601) | def evaluate_occupancy(self, occ_results, runner=None, show_dir=None, ...
method evaluate_mask (line 1675) | def evaluate_mask(self, results):
method evaluate_map (line 1686) | def evaluate_map(self,
method world2bev_vis (line 1735) | def world2bev_vis(self, x, y):
method __map_visual__ (line 1738) | def __map_visual__(self, gt_map, pred_map, index=0):
method _evaluate_map_single (line 1764) | def _evaluate_map_single(self,
method evaluate_bbox (line 1848) | def evaluate_bbox(self,
method _build_default_pipeline (line 1898) | def _build_default_pipeline(self):
method show (line 1919) | def show(self, results, out_dir, show=False, pipeline=None):
function output_to_nusc_box (line 1953) | def output_to_nusc_box(detection, with_velocity=True):
class NuscenesOccupancy (line 1999) | class NuscenesOccupancy(NuScenesDataset):
method __init__ (line 2021) | def __init__(self, occupancy_info='data/nuscenes/occupancy_category.js...
method get_cat_ids (line 2046) | def get_cat_ids(self, idx):
function lidar_nusc_box_to_global (line 2069) | def lidar_nusc_box_to_global(info,
function invert_matrix_egopose_numpy (line 2108) | def invert_matrix_egopose_numpy(egopose):
function convert_egopose_to_matrix_numpy (line 2118) | def convert_egopose_to_matrix_numpy(rotation, translation):
function output_to_vecs (line 2126) | def output_to_vecs(detection):
FILE: mmdet3d/datasets/nuscenes_eval.py
function class_tp_curve (line 74) | def class_tp_curve(md_list: DetectionMetricDataList,
class DetectionBox_modified (line 137) | class DetectionBox_modified(DetectionBox):
method __init__ (line 138) | def __init__(self, *args, token=None, visibility=None, index=None, **k...
method serialize (line 147) | def serialize(self) -> dict:
method deserialize (line 167) | def deserialize(cls, content: dict):
function center_in_image (line 187) | def center_in_image(box, intrinsic: np.ndarray, imsize: Tuple[int, int],...
function exist_corners_in_image_but_not_all (line 217) | def exist_corners_in_image_but_not_all(box, intrinsic: np.ndarray, imsiz...
function load_gt (line 244) | def load_gt(nusc: NuScenes, eval_split: str, box_cls, verbose: bool = Fa...
function filter_eval_boxes_by_id (line 362) | def filter_eval_boxes_by_id(nusc: NuScenes,
function filter_eval_boxes_by_visibility (line 394) | def filter_eval_boxes_by_visibility(
function filter_by_sample_token (line 426) | def filter_by_sample_token(ori_eval_boxes, valid_sample_tokens=[], verb...
function filter_eval_boxes_by_overlap (line 434) | def filter_eval_boxes_by_overlap(nusc: NuScenes,
function filter_eval_boxes_by_range (line 509) | def filter_eval_boxes_by_range(nusc: NuScenes,
class NuScenesEval_custom (line 569) | class NuScenesEval_custom(NuScenesEval):
method __init__ (line 574) | def __init__(self,
method update_gt (line 662) | def update_gt(self, type_='vis', visibility='1', index=1):
method evaluate (line 691) | def evaluate(self) -> Tuple[DetectionMetrics, DetectionMetricDataList]:
method render (line 741) | def render(self, metrics: DetectionMetrics, md_list: DetectionMetricDa...
method evaluate_mask (line 767) | def evaluate_mask(self, preds, HDMap, Bbox_mask):
FILE: mmdet3d/datasets/nuscenes_mono_dataset.py
class NuScenesMonoDataset (line 23) | class NuScenesMonoDataset(CocoDataset):
method __init__ (line 78) | def __init__(self,
method pre_pipeline (line 148) | def pre_pipeline(self, results):
method _parse_ann_info (line 177) | def _parse_ann_info(self, img_info, ann_info):
method get_attr_name (line 276) | def get_attr_name(self, attr_idx, label_name):
method _format_bbox (line 323) | def _format_bbox(self, results, jsonfile_prefix=None):
method _evaluate_single (line 430) | def _evaluate_single(self,
method format_results (line 488) | def format_results(self, results, jsonfile_prefix=None, **kwargs):
method evaluate (line 537) | def evaluate(self,
method _extract_data (line 588) | def _extract_data(self, index, pipeline, key, load_annos=False):
method _get_pipeline (line 621) | def _get_pipeline(self, pipeline):
method _build_default_pipeline (line 638) | def _build_default_pipeline(self):
method show (line 650) | def show(self, results, out_dir, show=False, pipeline=None):
function output_to_nusc_box (line 686) | def output_to_nusc_box(detection):
function cam_nusc_box_to_global (line 732) | def cam_nusc_box_to_global(info,
function global_nusc_box_to_cam (line 773) | def global_nusc_box_to_cam(info,
function nusc_box_to_cam_box3d (line 812) | def nusc_box_to_cam_box3d(boxes):
FILE: mmdet3d/datasets/occ_metrics.py
function pcolor (line 20) | def pcolor(string, color, on_color=None, attrs=None):
function getCellCoordinates (line 41) | def getCellCoordinates(points, voxelSize):
function getNumUniqueCells (line 45) | def getNumUniqueCells(cells):
class Metric_mIoU (line 50) | class Metric_mIoU():
method __init__ (line 51) | def __init__(self,
method hist_info (line 80) | def hist_info(self, n_cl, pred, gt):
method per_class_iu (line 107) | def per_class_iu(self, hist):
method compute_mIoU (line 111) | def compute_mIoU(self, pred, label, n_classes):
method add_batch (line 122) | def add_batch(self,semantics_pred,semantics_gt,mask_lidar,mask_camera):
method count_miou (line 166) | def count_miou(self):
class Metric_FScore (line 182) | class Metric_FScore():
method __init__ (line 183) | def __init__(self,
method voxel2points (line 210) | def voxel2points(self, voxel):
method add_batch (line 222) | def add_batch(self,semantics_pred,semantics_gt,mask_lidar,mask_camera ):
method count_fscore (line 277) | def count_fscore(self,):
function parse_args (line 291) | def parse_args():
function eval (line 305) | def eval(args):
FILE: mmdet3d/datasets/occupancy_eval.py
function parse_args (line 7) | def parse_args():
function eval (line 19) | def eval(args):
FILE: mmdet3d/datasets/pipelines/compose.py
class Compose (line 11) | class Compose:
method __init__ (line 22) | def __init__(self, transforms):
method __call__ (line 38) | def __call__(self, data):
method __repr__ (line 54) | def __repr__(self):
FILE: mmdet3d/datasets/pipelines/data_augment_utils.py
function _rotation_box2d_jit_ (line 14) | def _rotation_box2d_jit_(corners, angle, rot_mat_T):
function box_collision_test (line 32) | def box_collision_test(boxes, qboxes, clockwise=True):
function noise_per_box (line 129) | def noise_per_box(boxes, valid_mask, loc_noises, rot_noises):
function noise_per_box_v2_ (line 170) | def noise_per_box_v2_(boxes, valid_mask, loc_noises, rot_noises,
function _select_transform (line 236) | def _select_transform(transform, indices):
function _rotation_matrix_3d_ (line 255) | def _rotation_matrix_3d_(rot_mat_T, angle, axis):
function points_transform_ (line 284) | def points_transform_(points, centers, point_masks, loc_transform,
function box3d_transform_ (line 314) | def box3d_transform_(boxes, loc_transform, rot_transform, valid_mask):
function noise_per_object_v3_ (line 330) | def noise_per_object_v3_(gt_boxes,
FILE: mmdet3d/datasets/pipelines/dbsampler.py
class BatchSampler (line 14) | class BatchSampler:
method __init__ (line 25) | def __init__(self,
method _sample (line 43) | def _sample(self, num):
method _reset (line 60) | def _reset(self):
method sample (line 68) | def sample(self, num):
class DataBaseSampler (line 82) | class DataBaseSampler(object):
method __init__ (line 98) | def __init__(self,
method filter_by_difficulty (line 177) | def filter_by_difficulty(db_infos, removed_difficulty):
method filter_by_min_points (line 198) | def filter_by_min_points(db_infos, min_gt_points_dict):
method sample_all (line 219) | def sample_all(self, gt_bboxes, gt_labels, img=None, ground_plane=None):
method sample_class_v2 (line 317) | def sample_class_v2(self, name, num, gt_bboxes):
FILE: mmdet3d/datasets/pipelines/formating.py
class DefaultFormatBundle (line 12) | class DefaultFormatBundle(object):
method __init__ (line 29) | def __init__(self, ):
method __call__ (line 32) | def __call__(self, results):
method __repr__ (line 103) | def __repr__(self):
class Collect3D (line 108) | class Collect3D(object):
method __init__ (line 156) | def __init__(
method __call__ (line 172) | def __call__(self, results):
method __repr__ (line 196) | def __repr__(self):
class DefaultFormatBundle3D (line 203) | class DefaultFormatBundle3D(DefaultFormatBundle):
method __init__ (line 218) | def __init__(self, class_names, with_gt=True, with_label=True):
method __call__ (line 224) | def __call__(self, results):
method __repr__ (line 290) | def __repr__(self):
FILE: mmdet3d/datasets/pipelines/loading.py
class LoadVectorMap (line 37) | class LoadVectorMap(object):
method __init__ (line 39) | def __init__(self, data_root, point_cloud_range, map_fixed_ptsnum_per_...
method vectormap_pipeline (line 47) | def vectormap_pipeline(self, location, ego2global_translation, patch_a...
method __call__ (line 103) | def __call__(self, results):
class LoadVectorMap2 (line 122) | class LoadVectorMap2(object):
method __init__ (line 124) | def __init__(self, data_root, point_cloud_range, map_fixed_ptsnum_per_...
method vectormap_pipeline (line 133) | def vectormap_pipeline(self, location, ego2global_translation, patch_a...
method __call__ (line 191) | def __call__(self, results):
class LoadGTPlaner (line 210) | class LoadGTPlaner(object):
method __init__ (line 211) | def __init__(self):
method __call__ (line 214) | def __call__(self, results):
class LoadGTMotion (line 236) | class LoadGTMotion(object):
method __init__ (line 237) | def __init__(self, with_ego_as_agent=False):
method __call__ (line 240) | def __call__(self, results):
class LoadFutBoxInfo (line 270) | class LoadFutBoxInfo(object):
method __init__ (line 271) | def __init__(self, add_boundary=True):
method gen_dx_bx (line 300) | def gen_dx_bx(self, xbound, ybound, zbound):
method calculate_birds_eye_view_parameters (line 307) | def calculate_birds_eye_view_parameters(self, x_bounds, y_bounds, z_bo...
method get_label (line 328) | def get_label(
method world2bev_vis (line 340) | def world2bev_vis(self, x, y):
method get_birds_eye_view_label (line 343) | def get_birds_eye_view_label(self, boxes_in_cur_ego_list, labels_in_cu...
method __call__ (line 361) | def __call__(self, results):
class LoadSemanticImageMask (line 423) | class LoadSemanticImageMask(object):
method __init__ (line 424) | def __init__(self, mask_file_path='./data/nus_sem'):
method __call__ (line 427) | def __call__(self, results):
method img_transform_core (line 444) | def img_transform_core(self, img, resize_dims, crop, flip, rotate):
class LoadMultiViewImageFromFiles (line 455) | class LoadMultiViewImageFromFiles(object):
method __init__ (line 467) | def __init__(self, to_float32=False, color_type='unchanged'):
method __call__ (line 471) | def __call__(self, results):
method __repr__ (line 511) | def __repr__(self):
class LoadImageFromFileMono3D (line 520) | class LoadImageFromFileMono3D(object):
method __call__ (line 530) | def __call__(self, results):
class LoadOccupancy (line 544) | class LoadOccupancy(object):
method __init__ (line 553) | def __init__(self, occupancy_path='/mount/dnn_data/occupancy_2023/gts',
method __call__ (line 569) | def __call__(self, results):
class LoadPointsFromMultiSweeps (line 627) | class LoadPointsFromMultiSweeps(object):
method __init__ (line 653) | def __init__(self,
method _load_points (line 678) | def _load_points(self, pts_filename):
method _remove_close (line 700) | def _remove_close(self, points, radius=1.0):
method __call__ (line 722) | def __call__(self, results):
method __repr__ (line 781) | def __repr__(self):
class PointsFromLidartoEgo (line 787) | class PointsFromLidartoEgo(object):
method __init__ (line 789) | def __init__(self, translate2ego=True, ego_cam='CAM_FRONT'):
method __call__ (line 793) | def __call__(self, results):
class PointSegClassMapping (line 826) | class PointSegClassMapping(object):
method __init__ (line 838) | def __init__(self, valid_cat_ids, max_cat_id=40):
method __call__ (line 852) | def __call__(self, results):
method __repr__ (line 872) | def __repr__(self):
class NormalizePointsColor (line 881) | class NormalizePointsColor(object):
method __init__ (line 888) | def __init__(self, color_mean):
method __call__ (line 891) | def __call__(self, results):
method __repr__ (line 914) | def __repr__(self):
class LoadPointsFromFile (line 922) | class LoadPointsFromFile(object):
method __init__ (line 948) | def __init__(self,
method _load_points (line 979) | def _load_points(self, pts_filename):
method __call__ (line 1003) | def __call__(self, results):
method __repr__ (line 1058) | def __repr__(self):
class LoadPointsFromDict (line 1072) | class LoadPointsFromDict(LoadPointsFromFile):
method __call__ (line 1075) | def __call__(self, results):
class LoadAnnotations3D (line 1081) | class LoadAnnotations3D(LoadAnnotations):
method __init__ (line 1117) | def __init__(self,
method _load_bboxes_3d (line 1146) | def _load_bboxes_3d(self, results):
method _load_bboxes_depth (line 1159) | def _load_bboxes_depth(self, results):
method _load_labels_3d (line 1172) | def _load_labels_3d(self, results):
method _load_attr_labels (line 1184) | def _load_attr_labels(self, results):
method _load_masks_3d (line 1196) | def _load_masks_3d(self, results):
method _load_semantic_seg_3d (line 1221) | def _load_semantic_seg_3d(self, results):
method __call__ (line 1248) | def __call__(self, results):
method __repr__ (line 1278) | def __repr__(self):
class PointToMultiViewDepth (line 1297) | class PointToMultiViewDepth(object):
method __init__ (line 1299) | def __init__(self, grid_config, downsample=1):
method points2depthmap (line 1303) | def points2depthmap(self, points, height, width):
method __call__ (line 1329) | def __call__(self, results):
function mmlabNormalize (line 1389) | def mmlabNormalize(img, mean=[123.675, 116.28, 103.53], std=[58.395, 57....
class PrepareImageInputs (line 1404) | class PrepareImageInputs(object):
method __init__ (line 1415) | def __init__(
method get_rot (line 1434) | def get_rot(self, h):
method img_transform (line 1441) | def img_transform(self, img, post_rot, post_tran, resize, resize_dims,
method img_transform_core (line 1462) | def img_transform_core(self, img, resize_dims, crop, flip, rotate):
method choose_cams (line 1471) | def choose_cams(self):
method sample_augmentation (line 1482) | def sample_augmentation(self, H, W, flip=None, scale=None):
method get_sensor2ego_transformation (line 1512) | def get_sensor2ego_transformation(self,
method get_sensor_transforms (line 1584) | def get_sensor_transforms(self, cam_info, cam_name):
method get_inputs (line 1607) | def get_inputs(self, results, scale=None):
method __call__ (line 1744) | def __call__(self, results):
class LoadAnnotationsBEVDepth (line 1750) | class LoadAnnotationsBEVDepth(object):
method __init__ (line 1753) | def __init__(self, bda_aug_conf, classes, with_2d_bbox=False, with_ego...
method sample_bda_augmentation (line 1761) | def sample_bda_augmentation(self, tta_config=None):
method bev_transform (line 1783) | def bev_transform(self, gt_boxes, rotate_angle, scale_ratio, flip_dx,
method _bboxes_transform (line 1815) | def _bboxes_transform(self, bboxes, centers2d, gt_labels, depths, resi...
method _filter_invisible (line 1851) | def _filter_invisible(self, bboxes, centers2d, gt_labels, depths, fH, ...
method __call__ (line 1877) | def __call__(self, results):
FILE: mmdet3d/datasets/pipelines/test_time_aug.py
class MultiScaleFlipAug (line 12) | class MultiScaleFlipAug:
method __init__ (line 49) | def __init__(self,
method __call__ (line 80) | def __call__(self, results):
method __repr__ (line 110) | def __repr__(self):
class MultiScaleFlipAug3D (line 119) | class MultiScaleFlipAug3D(object):
method __init__ (line 142) | def __init__(self,
method __call__ (line 175) | def __call__(self, results):
method __repr__ (line 223) | def __repr__(self):
class CustomMultiScaleFlipAug3D (line 233) | class CustomMultiScaleFlipAug3D(object):
method __init__ (line 256) | def __init__(self,
method __call__ (line 266) | def __call__(self, results):
method __repr__ (line 311) | def __repr__(self):
class CustomDistMultiScaleFlipAug3D (line 319) | class CustomDistMultiScaleFlipAug3D(object):
method __init__ (line 342) | def __init__(self,
method __call__ (line 348) | def __call__(self, results):
method __repr__ (line 395) | def __repr__(self):
FILE: mmdet3d/datasets/pipelines/transforms_3d.py
class VisualInputsAndGT (line 28) | class VisualInputsAndGT(object):
method __init__ (line 32) | def __init__(self, max=20):
method _draw_point_cloud_ (line 35) | def _draw_point_cloud_(self, point_cloud, img_size):
method world2bev_vis (line 63) | def world2bev_vis(self, x, y):
method world2bev_vis2 (line 66) | def world2bev_vis2(self, x, y):
method __visual__ (line 70) | def __visual__(self, results):
method _render_traj (line 192) | def _render_traj(self, future_traj, points_per_step=10):
method __call__ (line 203) | def __call__(self, results):
class GridMask (line 213) | class GridMask:
method __init__ (line 214) | def __init__(
method __call__ (line 232) | def __call__(self, results):
class AugPoints (line 288) | class AugPoints(object):
method __call__ (line 289) | def __call__(self, results):
class ToEgo (line 308) | class ToEgo(object):
method __init__ (line 309) | def __init__(self, ego_cam='CAM_FRONT',):
method __call__ (line 312) | def __call__(self, results):
class PadMultiViewImage (line 343) | class PadMultiViewImage(object):
method __init__ (line 354) | def __init__(self, size=None, size_divisor=None, pad_val=0):
method _pad_img (line 362) | def _pad_img(self, results):
method __call__ (line 386) | def __call__(self, results):
method __repr__ (line 398) | def __repr__(self):
class RandomDropPointsColor (line 408) | class RandomDropPointsColor(object):
method __init__ (line 420) | def __init__(self, drop_ratio=0.2):
method __call__ (line 425) | def __call__(self, input_dict):
method __repr__ (line 450) | def __repr__(self):
class RandomFlip3D (line 458) | class RandomFlip3D(RandomFlip):
method __init__ (line 476) | def __init__(self,
method random_flip_data_3d (line 494) | def random_flip_data_3d(self, input_dict, direction='horizontal'):
method __call__ (line 535) | def __call__(self, input_dict):
method __repr__ (line 574) | def __repr__(self):
class MultiViewWrapper (line 583) | class MultiViewWrapper(object):
method __init__ (line 603) | def __init__(self,
method __call__ (line 611) | def __call__(self, input_dict):
class RangeLimitedRandomCrop (line 629) | class RangeLimitedRandomCrop(RandomCrop):
method __init__ (line 639) | def __init__(self,
method _crop_data (line 649) | def _crop_data(self, results, crop_size, allow_negative_crop):
class RandomRotate (line 722) | class RandomRotate(Rotate):
method __init__ (line 733) | def __init__(self, range, **kwargs):
method __call__ (line 737) | def __call__(self, results):
class RandomJitterPoints (line 745) | class RandomJitterPoints(object):
method __init__ (line 766) | def __init__(self,
method __call__ (line 783) | def __call__(self, input_dict):
method __repr__ (line 804) | def __repr__(self):
class ObjectSample (line 813) | class ObjectSample(object):
method __init__ (line 825) | def __init__(self, db_sampler, sample_2d=False, use_ground_plane=False):
method remove_points_in_boxes (line 834) | def remove_points_in_boxes(points, boxes):
method __call__ (line 848) | def __call__(self, input_dict):
method __repr__ (line 918) | def __repr__(self):
class ObjectNoise (line 932) | class ObjectNoise(object):
method __init__ (line 947) | def __init__(self,
method __call__ (line 957) | def __call__(self, input_dict):
method __repr__ (line 986) | def __repr__(self):
class GlobalAlignment (line 997) | class GlobalAlignment(object):
method __init__ (line 1011) | def __init__(self, rotation_axis):
method _trans_points (line 1014) | def _trans_points(self, input_dict, trans_factor):
method _rot_points (line 1026) | def _rot_points(self, input_dict, rot_mat):
method _check_rot_mat (line 1039) | def _check_rot_mat(self, rot_mat):
method __call__ (line 1052) | def __call__(self, input_dict):
method __repr__ (line 1077) | def __repr__(self):
class GlobalRotScaleTrans (line 1084) | class GlobalRotScaleTrans(object):
method __init__ (line 1101) | def __init__(self,
method _trans_bbox_points (line 1128) | def _trans_bbox_points(self, input_dict):
method _rot_bbox_points (line 1147) | def _rot_bbox_points(self, input_dict):
method _scale_bbox_points (line 1177) | def _scale_bbox_points(self, input_dict):
method _random_scale (line 1199) | def _random_scale(self, input_dict):
method __call__ (line 1213) | def __call__(self, input_dict):
method __repr__ (line 1239) | def __repr__(self):
class RotScaleTransPoints (line 1252) | class RotScaleTransPoints(object):
method _trans_bbox_points (line 1271) | def _trans_bbox_points(self, input_dict):
method _rot_bbox_points (line 1290) | def _rot_bbox_points(self, input_dict):
method _scale_bbox_points (line 1320) | def _scale_bbox_points(self, input_dict):
method _random_scale (line 1342) | def _random_scale(self, input_dict):
method __call__ (line 1356) | def __call__(self, input_dict):
method __repr__ (line 1377) | def __repr__(self):
class PointShuffle (line 1388) | class PointShuffle(object):
method __call__ (line 1391) | def __call__(self, input_dict):
method __repr__ (line 1415) | def __repr__(self):
class ObjectRangeFilter (line 1420) | class ObjectRangeFilter(object):
method __init__ (line 1427) | def __init__(self, point_cloud_range):
method __call__ (line 1430) | def __call__(self, input_dict):
method __repr__ (line 1470) | def __repr__(self):
class PointsRangeFilter (line 1478) | class PointsRangeFilter(object):
method __init__ (line 1485) | def __init__(self, point_cloud_range):
method __call__ (line 1488) | def __call__(self, input_dict):
method __repr__ (line 1516) | def __repr__(self):
class ObjectNameFilter (line 1524) | class ObjectNameFilter(object):
method __init__ (line 1531) | def __init__(self, classes):
method __call__ (line 1535) | def __call__(self, input_dict):
method __repr__ (line 1559) | def __repr__(self):
class PointSample (line 1567) | class PointSample(object):
method __init__ (line 1581) | def __init__(self, num_points, sample_range=None, replace=False):
method _points_random_sampling (line 1586) | def _points_random_sampling(self,
method __call__ (line 1634) | def __call__(self, results):
method __repr__ (line 1665) | def __repr__(self):
class IndoorPointSample (line 1676) | class IndoorPointSample(PointSample):
method __init__ (line 1686) | def __init__(self, *args, **kwargs):
class IndoorPatchPointSample (line 1693) | class IndoorPatchPointSample(object):
method __init__ (line 1731) | def __init__(self,
method _input_generation (line 1755) | def _input_generation(self, coords, patch_center, coord_max, attributes,
method _patch_points_sampling (line 1796) | def _patch_points_sampling(self, points, sem_mask):
method __call__ (line 1896) | def __call__(self, results):
method __repr__ (line 1923) | def __repr__(self):
class BackgroundPointsFilter (line 1938) | class BackgroundPointsFilter(object):
method __init__ (line 1945) | def __init__(self, bbox_enlarge_range):
method __call__ (line 1956) | def __call__(self, input_dict):
method __repr__ (line 1995) | def __repr__(self):
class VoxelBasedPointSampler (line 2003) | class VoxelBasedPointSampler(object):
method __init__ (line 2015) | def __init__(self, cur_sweep_cfg, prev_sweep_cfg=None, time_dim=3):
method _sample_points (line 2028) | def _sample_points(self, points, sampler, point_dim):
method __call__ (line 2054) | def __call__(self, results):
method __repr__ (line 2122) | def __repr__(self):
class AffineResize (line 2145) | class AffineResize(object):
method __init__ (line 2162) | def __init__(self, img_scale, down_ratio, bbox_clip_border=True):
method __call__ (line 2168) | def __call__(self, results):
method _affine_bboxes (line 2245) | def _affine_bboxes(self, results, matrix):
method _affine_transform (line 2268) | def _affine_transform(self, points, matrix):
method _get_transform_matrix (line 2287) | def _get_transform_matrix(self, center, scale, output_scale):
method _get_ref_point (line 2322) | def _get_ref_point(self, ref_point1, ref_point2):
method __repr__ (line 2333) | def __repr__(self):
class RandomShiftScale (line 2341) | class RandomShiftScale(object):
method __init__ (line 2354) | def __init__(self, shift_scale, aug_prob):
method __call__ (line 2359) | def __call__(self, results):
method __repr__ (line 2392) | def __repr__(self):
FILE: mmdet3d/datasets/s3dis_dataset.py
class S3DISDataset (line 16) | class S3DISDataset(Custom3DDataset):
method __init__ (line 49) | def __init__(self,
method get_ann_info (line 70) | def get_ann_info(self, index):
method get_data_info (line 114) | def get_data_info(self, index):
method _build_default_pipeline (line 139) | def _build_default_pipeline(self):
class _S3DISSegDataset (line 157) | class _S3DISSegDataset(Custom3DSegDataset):
method __init__ (line 201) | def __init__(self,
method get_ann_info (line 225) | def get_ann_info(self, index):
method _build_default_pipeline (line 245) | def _build_default_pipeline(self):
method show (line 273) | def show(self, results, out_dir, show=True, pipeline=None):
method get_scene_idxs (line 297) | def get_scene_idxs(self, scene_idxs):
class S3DISSegDataset (line 312) | class S3DISSegDataset(_S3DISSegDataset):
method __init__ (line 345) | def __init__(self,
method concat_data_infos (line 396) | def concat_data_infos(self, data_infos):
method concat_scene_idxs (line 406) | def concat_scene_idxs(self, scene_idxs):
method _duplicate_to_list (line 422) | def _duplicate_to_list(x, num):
method _check_ann_files (line 426) | def _check_ann_files(self, ann_file):
method _check_scene_idxs (line 433) | def _check_scene_idxs(self, scene_idx, num):
FILE: mmdet3d/datasets/samplers/d_sampler.py
class CustomDistributedSampler (line 6) | class CustomDistributedSampler(_DistributedSampler):
method __init__ (line 8) | def __init__(self,
method __iter__ (line 19) | def __iter__(self):
FILE: mmdet3d/datasets/samplers/infinite_group_each_sample_in_batch_sampler.py
function sync_random_seed (line 14) | def sync_random_seed(seed=None, device='cuda'):
class InfiniteGroupEachSampleInBatchSampler (line 48) | class InfiniteGroupEachSampleInBatchSampler(Sampler):
method __init__ (line 56) | def __init__(self,
method _infinite_group_indices (line 99) | def _infinite_group_indices(self):
method _group_indices_per_global_sample_idx (line 105) | def _group_indices_per_global_sample_idx(self, global_sample_idx):
method __iter__ (line 111) | def __iter__(self):
method __len__ (line 126) | def __len__(self):
method set_epoch (line 130) | def set_epoch(self, epoch):
class InfiniteGroupEachSampleInBatchSamplerEval (line 134) | class InfiniteGroupEachSampleInBatchSamplerEval(Sampler):
method __init__ (line 142) | def __init__(self,
method _infinite_group_indices (line 184) | def _infinite_group_indices(self):
method _group_indices_per_global_sample_idx (line 190) | def _group_indices_per_global_sample_idx(self, global_sample_idx):
method __iter__ (line 196) | def __iter__(self):
method __len__ (line 214) | def __len__(self):
method set_epoch (line 218) | def set_epoch(self, epoch):
class TTADistributedSampler (line 223) | class TTADistributedSampler(Sampler):
method __init__ (line 225) | def __init__(self,
method __iter__ (line 246) | def __iter__(self):
method __len__ (line 251) | def __len__(self):
FILE: mmdet3d/datasets/scannet_dataset.py
class ScanNetDataset (line 18) | class ScanNetDataset(Custom3DDataset):
method __init__ (line 53) | def __init__(self,
method get_data_info (line 77) | def get_data_info(self, index):
method get_ann_info (line 126) | def get_ann_info(self, index):
method prepare_test_data (line 175) | def prepare_test_data(self, index):
method _get_axis_align_matrix (line 197) | def _get_axis_align_matrix(info):
method _build_default_pipeline (line 214) | def _build_default_pipeline(self):
method show (line 232) | def show(self, results, out_dir, show=True, pipeline=None):
class ScanNetSegDataset (line 257) | class ScanNetSegDataset(Custom3DSegDataset):
method __init__ (line 318) | def __init__(self,
method get_ann_info (line 342) | def get_ann_info(self, index):
method _build_default_pipeline (line 362) | def _build_default_pipeline(self):
method show (line 390) | def show(self, results, out_dir, show=True, pipeline=None):
method get_scene_idxs (line 414) | def get_scene_idxs(self, scene_idxs):
method format_results (line 426) | def format_results(self, results, txtfile_prefix=None):
class ScanNetInstanceSegDataset (line 471) | class ScanNetInstanceSegDataset(Custom3DSegDataset):
method get_ann_info (line 482) | def get_ann_info(self, index):
method get_classes_and_palette (line 506) | def get_classes_and_palette(self, classes=None, palette=None):
method _build_default_pipeline (line 525) | def _build_default_pipeline(self):
method evaluate (line 555) | def evaluate(self,
FILE: mmdet3d/datasets/semantickitti_dataset.py
class SemanticKITTIDataset (line 9) | class SemanticKITTIDataset(Custom3DDataset):
method __init__ (line 44) | def __init__(self,
method get_data_info (line 63) | def get_data_info(self, index):
method get_ann_info (line 92) | def get_ann_info(self, index):
FILE: mmdet3d/datasets/sunrgbd_dataset.py
class SUNRGBDDataset (line 16) | class SUNRGBDDataset(Custom3DDataset):
method __init__ (line 49) | def __init__(self,
method get_data_info (line 73) | def get_data_info(self, index):
method get_ann_info (line 122) | def get_ann_info(self, index):
method _build_default_pipeline (line 164) | def _build_default_pipeline(self):
method show (line 183) | def show(self, results, out_dir, show=True, pipeline=None):
method evaluate (line 230) | def evaluate(self,
FILE: mmdet3d/datasets/utils.py
function is_loading_function (line 18) | def is_loading_function(transform):
function get_loading_pipeline (line 53) | def get_loading_pipeline(pipeline):
function extract_result_dict (line 116) | def extract_result_dict(results, key):
function nuscenes_get_rt_matrix (line 145) | def nuscenes_get_rt_matrix(
FILE: mmdet3d/datasets/vector_map.py
class LiDARInstanceLines (line 29) | class LiDARInstanceLines(object):
method __init__ (line 33) | def __init__(self,
method start_end_points (line 57) | def start_end_points(self):
method bbox (line 79) | def bbox(self):
method fixed_num_sampled_points (line 99) | def fixed_num_sampled_points(self):
method fixed_num_sampled_points_ambiguity (line 119) | def fixed_num_sampled_points_ambiguity(self):
method fixed_num_sampled_points_torch (line 140) | def fixed_num_sampled_points_torch(self):
method shift_fixed_num_sampled_points (line 165) | def shift_fixed_num_sampled_points(self):
method shift_fixed_num_sampled_points_v1 (line 203) | def shift_fixed_num_sampled_points_v1(self):
method shift_fixed_num_sampled_points_v2 (line 250) | def shift_fixed_num_sampled_points_v2(self):
method shift_fixed_num_sampled_points_v3 (line 308) | def shift_fixed_num_sampled_points_v3(self):
method shift_fixed_num_sampled_points_v4 (line 377) | def shift_fixed_num_sampled_points_v4(self):
method shift_fixed_num_sampled_points_torch (line 426) | def shift_fixed_num_sampled_points_torch(self):
class VectorizedLocalMap (line 472) | class VectorizedLocalMap(object):
method __init__ (line 480) | def __init__(self,
method gen_vectorized_samples (line 517) | def gen_vectorized_samples(self, location, lidar2global_translation, p...
method get_map_geom (line 575) | def get_map_geom(self, patch_box, patch_angle, layer_names, location, ...
method _one_type_line_geom_to_vectors (line 594) | def _one_type_line_geom_to_vectors(self, line_geom):
method _one_type_line_geom_to_instances (line 608) | def _one_type_line_geom_to_instances(self, line_geom):
method poly_geoms_to_vectors (line 622) | def poly_geoms_to_vectors(self, polygon_geom):
method ped_poly_geoms_to_instances (line 659) | def ped_poly_geoms_to_instances(self, ped_geom):
method poly_geoms_to_instances (line 696) | def poly_geoms_to_instances(self, polygon_geom):
method line_geoms_to_vectors (line 733) | def line_geoms_to_vectors(self, line_geom):
method line_geoms_to_instances (line 740) | def line_geoms_to_instances(self, line_geom):
method ped_geoms_to_vectors (line 748) | def ped_geoms_to_vectors(self, ped_geom):
method get_contour_line (line 768) | def get_contour_line(self,patch_box,patch_angle,layer_name,location, f...
method get_divider_line (line 820) | def get_divider_line(self,patch_box,patch_angle,layer_name,location, f...
method get_ped_crossing_line (line 860) | def get_ped_crossing_line(self, patch_box, patch_angle, location, flip...
method sample_pts_from_line (line 887) | def sample_pts_from_line(self, line):
FILE: mmdet3d/datasets/waymo_dataset.py
class WaymoDataset (line 17) | class WaymoDataset(KittiDataset):
method __init__ (line 57) | def __init__(self,
method _get_pts_filename (line 90) | def _get_pts_filename(self, idx):
method get_data_info (line 95) | def get_data_info(self, index):
method format_results (line 138) | def format_results(self,
method evaluate (line 220) | def evaluate(self,
method bbox2result_kitti (line 360) | def bbox2result_kitti(self,
method convert_valid_bboxes (line 475) | def convert_valid_bboxes(self, box_dict, info):
FILE: mmdet3d/models/backbones/base_pointnet.py
class BasePointNet (line 8) | class BasePointNet(BaseModule, metaclass=ABCMeta):
method __init__ (line 11) | def __init__(self, init_cfg=None, pretrained=None):
method _split_point_feats (line 22) | def _split_point_feats(points):
FILE: mmdet3d/models/backbones/convnext.py
class BaseBackbone (line 23) | class BaseBackbone(BaseModule, metaclass=ABCMeta):
method __init__ (line 29) | def __init__(self, init_cfg=None):
method forward (line 33) | def forward(self, x):
method train (line 41) | def train(self, mode=True):
class LayerNorm2d (line 50) | class LayerNorm2d(nn.LayerNorm):
method __init__ (line 61) | def __init__(self, num_channels: int, **kwargs) -> None:
method forward (line 65) | def forward(self, x):
class ConvNeXtBlock (line 73) | class ConvNeXtBlock(BaseModule):
method __init__ (line 99) | def __init__(self,
method forward (line 139) | def forward(self, x):
class ConvNeXt (line 171) | class ConvNeXt(BaseBackbone):
method __init__ (line 232) | def __init__(self,
method forward (line 340) | def forward(self, x):
method _freeze_stages (line 358) | def _freeze_stages(self):
method train (line 368) | def train(self, mode=True):
FILE: mmdet3d/models/backbones/dgcnn.py
class DGCNNBackbone (line 10) | class DGCNNBackbone(BaseModule):
method __init__ (line 32) | def __init__(self,
method forward (line 75) | def forward(self, points):
FILE: mmdet3d/models/backbones/dla.py
function dla_build_norm_layer (line 12) | def dla_build_norm_layer(cfg, num_features):
class BasicBlock (line 39) | class BasicBlock(BaseModule):
method __init__ (line 55) | def __init__(self,
method forward (line 87) | def forward(self, x, identity=None):
class Root (line 103) | class Root(BaseModule):
method __init__ (line 119) | def __init__(self,
method forward (line 140) | def forward(self, feat_list):
class Tree (line 157) | class Tree(BaseModule):
method __init__ (line 183) | def __init__(self,
method forward (line 261) | def forward(self, x, identity=None, children=None):
class DLANet (line 279) | class DLANet(BaseModule):
method __init__ (line 304) | def __init__(self,
method _make_conv_level (line 382) | def _make_conv_level(self,
method _freeze_stages (line 421) | def _freeze_stages(self):
method forward (line 439) | def forward(self, x):
FILE: mmdet3d/models/backbones/load.py
function save_checkpoint (line 19) | def save_checkpoint(model, filename, optimizer=None, meta=None):
FILE: mmdet3d/models/backbones/mink_resnet.py
class MinkResNet (line 18) | class MinkResNet(nn.Module):
method __init__ (line 37) | def __init__(self, depth, in_channels, num_stages=4, pool=True):
method init_weights (line 62) | def init_weights(self):
method _make_layer (line 72) | def _make_layer(self, block, planes, blocks, stride):
method forward (line 96) | def forward(self, x):
FILE: mmdet3d/models/backbones/multi_backbone.py
class MultiBackbone (line 14) | class MultiBackbone(BaseModule):
method __init__ (line 29) | def __init__(self,
method forward (line 93) | def forward(self, points):
FILE: mmdet3d/models/backbones/nostem_regnet.py
class NoStemRegNet (line 7) | class NoStemRegNet(RegNet):
method __init__ (line 61) | def __init__(self, arch, init_cfg=None, **kwargs):
method _make_stem_layer (line 64) | def _make_stem_layer(self, in_channels, base_channels):
method forward (line 69) | def forward(self, x):
FILE: mmdet3d/models/backbones/pointnet2_sa_msg.py
class PointNet2SAMSG (line 13) | class PointNet2SAMSG(BasePointNet):
method __init__ (line 41) | def __init__(self,
method forward (line 128) | def forward(self, points):
FILE: mmdet3d/models/backbones/pointnet2_sa_ssg.py
class PointNet2SASSG (line 12) | class PointNet2SASSG(BasePointNet):
method __init__ (line 34) | def __init__(self,
method forward (line 90) | def forward(self, points):
FILE: mmdet3d/models/backbones/resnet.py
class CustomResNet (line 11) | class CustomResNet(nn.Module):
method __init__ (line 13) | def __init__(
method forward (line 74) | def forward(self, x):
FILE: mmdet3d/models/backbones/second.py
class SECOND (line 12) | class SECOND(BaseModule):
method __init__ (line 24) | def __init__(self,
method forward (line 78) | def forward(self, x):
FILE: mmdet3d/models/backbones/swin.py
function swin_convert (line 25) | def swin_convert(ckpt):
class PatchEmbed (line 79) | class PatchEmbed(BaseModule):
method __init__ (line 100) | def __init__(self,
method forward (line 150) | def forward(self, x):
class PatchMerging (line 174) | class PatchMerging(BaseModule):
method __init__ (line 192) | def __init__(self,
method forward (line 216) | def forward(self, x, hw_shape):
class WindowMSA (line 244) | class WindowMSA(BaseModule):
method __init__ (line 263) | def __init__(self,
method init_weights (line 300) | def init_weights(self):
method forward (line 303) | def forward(self, x, mask=None):
method double_step_seq (line 346) | def double_step_seq(step1, len1, step2, len2):
class ShiftWindowMSA (line 353) | class ShiftWindowMSA(BaseModule):
method __init__ (line 376) | def __init__(self,
method forward (line 405) | def forward(self, query, hw_shape):
method window_reverse (line 482) | def window_reverse(self, windows, H, W):
method window_partition (line 499) | def window_partition(self, x):
class SwinBlock (line 516) | class SwinBlock(BaseModule):
method __init__ (line 538) | def __init__(self,
method forward (line 581) | def forward(self, x, hw_shape):
class SwinBlockSequence (line 595) | class SwinBlockSequence(BaseModule):
method __init__ (line 620) | def __init__(self,
method forward (line 665) | def forward(self, x, hw_shape):
class SwinTransformer (line 680) | class SwinTransformer(BaseModule):
method __init__ (line 730) | def __init__(self,
method _freeze_stages (line 859) | def _freeze_stages(self):
method init_weights (line 876) | def init_weights(self):
method forward (line 946) | def forward(self, x):
method train (line 973) | def train(self, mode=True):
FILE: mmdet3d/models/backbones/vovnet.py
function dw_conv3x3 (line 101) | def dw_conv3x3(in_channels, out_channels, module_name, postfix, stride=1...
function conv3x3 (line 125) | def conv3x3(in_channels, out_channels, module_name, postfix, stride=1, g...
function conv1x1 (line 145) | def conv1x1(in_channels, out_channels, module_name, postfix, stride=1, g...
class Hsigmoid (line 165) | class Hsigmoid(nn.Module):
method __init__ (line 166) | def __init__(self, inplace=True):
method forward (line 170) | def forward(self, x):
class eSEModule (line 174) | class eSEModule(nn.Module):
method __init__ (line 175) | def __init__(self, channel, reduction=4):
method forward (line 181) | def forward(self, x):
class _OSA_module (line 189) | class _OSA_module(nn.Module):
method __init__ (line 190) | def __init__(
method _forward (line 220) | def _forward(self, x):
method forward (line 242) | def forward(self, x):
class _OSA_stage (line 252) | class _OSA_stage(nn.Sequential):
method __init__ (line 253) | def __init__(
class VoVNetCP (line 288) | class VoVNetCP(BaseModule):
method __init__ (line 289) | def __init__(self, spec_name, input_ch=3, out_features=None,
method _initialize_weights (line 355) | def _initialize_weights(self):
method forward (line 372) | def forward(self, x):
method _freeze_stages (line 384) | def _freeze_stages(self):
method train (line 397) | def train(self, mode=True):
FILE: mmdet3d/models/backbones/vovnet2.py
function dw_conv3x3 (line 92) | def dw_conv3x3(in_channels, out_channels, module_name, postfix, stride=1...
function conv3x3 (line 116) | def conv3x3(in_channels, out_channels, module_name, postfix, stride=1, g...
function conv1x1 (line 136) | def conv1x1(in_channels, out_channels, module_name, postfix, stride=1, g...
class Hsigmoid (line 156) | class Hsigmoid(nn.Module):
method __init__ (line 157) | def __init__(self, inplace=True):
method forward (line 161) | def forward(self, x):
class eSEModule (line 165) | class eSEModule(nn.Module):
method __init__ (line 166) | def __init__(self, channel, reduction=4):
method forward (line 172) | def forward(self, x):
class _OSA_module (line 180) | class _OSA_module(nn.Module):
method __init__ (line 181) | def __init__(
method _forward (line 211) | def _forward(self, x):
method forward (line 233) | def forward(self, x):
class _OSA_stage (line 243) | class _OSA_stage(nn.Sequential):
method __init__ (line 244) | def __init__(
class VoVNet2 (line 279) | class VoVNet2(BaseModule):
method __init__ (line 280) | def __init__(self, spec_name, input_ch=3, out_features=None,
method _initialize_weights (line 346) | def _initialize_weights(self):
method forward (line 351) | def forward(self, x):
method _freeze_stages (line 363) | def _freeze_stages(self):
method train (line 376) | def train(self, mode=True):
FILE: mmdet3d/models/builder.py
function build_backbone (line 31) | def build_backbone(cfg):
function build_neck (line 39) | def build_neck(cfg):
function build_roi_extractor (line 47) | def build_roi_extractor(cfg):
function build_shared_head (line 55) | def build_shared_head(cfg):
function build_head (line 63) | def build_head(cfg):
function build_loss (line 71) | def build_loss(cfg):
function build_detector (line 81) | def build_detector(cfg, train_cfg=None, test_cfg=None):
function build_segmentor (line 99) | def build_segmentor(cfg, train_cfg=None, test_cfg=None):
function build_model (line 113) | def build_model(cfg, train_cfg=None, test_cfg=None):
function build_voxel_encoder (line 125) | def build_voxel_encoder(cfg):
function build_middle_encoder (line 130) | def build_middle_encoder(cfg):
function build_fusion_layer (line 135) | def build_fusion_layer(cfg):
FILE: mmdet3d/models/decode_heads/decode_head.py
class Base3DDecodeHead (line 11) | class Base3DDecodeHead(BaseModule, metaclass=ABCMeta):
method __init__ (line 31) | def __init__(self,
method init_weights (line 62) | def init_weights(self):
method forward (line 69) | def forward(self, inputs):
method forward_train (line 73) | def forward_train(self, inputs, img_metas, pts_semantic_mask, train_cfg):
method forward_test (line 90) | def forward_test(self, inputs, img_metas, test_cfg):
method cls_seg (line 103) | def cls_seg(self, feat):
method losses (line 111) | def losses(self, seg_logit, seg_label):
FILE: mmdet3d/models/decode_heads/dgcnn_head.py
class DGCNNHead (line 10) | class DGCNNHead(Base3DDecodeHead):
method __init__ (line 22) | def __init__(self, fp_channels=(1216, 512), **kwargs):
method _extract_input (line 38) | def _extract_input(self, feat_dict):
method forward (line 51) | def forward(self, feat_dict):
FILE: mmdet3d/models/decode_heads/paconv_head.py
class PAConvHead (line 9) | class PAConvHead(PointNet2Head):
method __init__ (line 21) | def __init__(self,
method forward (line 40) | def forward(self, feat_dict):
FILE: mmdet3d/models/decode_heads/pointnet2_head.py
class PointNet2Head (line 11) | class PointNet2Head(Base3DDecodeHead):
method __init__ (line 23) | def __init__(self,
method _extract_input (line 46) | def _extract_input(self, feat_dict):
method forward (line 62) | def forward(self, feat_dict):
FILE: mmdet3d/models/dense_heads/anchor3d_head.py
class Anchor3DHead (line 16) | class Anchor3DHead(BaseModule, AnchorTrainMixin):
method __init__ (line 42) | def __init__(self,
method _init_assigner_sampler (line 118) | def _init_assigner_sampler(self):
method _init_layers (line 134) | def _init_layers(self):
method forward_single (line 144) | def forward_single(self, x):
method forward (line 161) | def forward(self, feats):
method get_anchors (line 174) | def get_anchors(self, featmap_sizes, input_metas, device='cuda'):
method loss_single (line 194) | def loss_single(self, cls_score, bbox_pred, dir_cls_preds, labels,
method add_sin_difference (line 281) | def add_sin_difference(boxes1, boxes2):
method loss (line 305) | def loss(self,
method get_bboxes (line 376) | def get_bboxes(self,
method get_bboxes_single (line 427) | def get_bboxes_single(self,
FILE: mmdet3d/models/dense_heads/anchor_free_mono3d_head.py
class AnchorFreeMono3DHead (line 15) | class AnchorFreeMono3DHead(BaseMono3DDenseHead):
method __init__ (line 82) | def __init__(
method _init_layers (line 181) | def _init_layers(self):
method _init_cls_convs (line 187) | def _init_cls_convs(self):
method _init_reg_convs (line 207) | def _init_reg_convs(self):
method _init_branch (line 227) | def _init_branch(self, conv_channels=(64), conv_strides=(1)):
method _init_predictor (line 250) | def _init_predictor(self):
method init_weights (line 284) | def init_weights(self):
method forward (line 318) | def forward(self, feats):
method forward_single (line 343) | def forward_single(self, x):
method loss (line 397) | def loss(self,
method get_bboxes (line 446) | def get_bboxes(self,
method get_targets (line 476) | def get_targets(self, points, gt_bboxes_list, gt_labels_list,
method _get_points_single (line 502) | def _get_points_single(self,
method get_points (line 518) | def get_points(self, featmap_sizes, dtype, device, flatten=False):
FILE: mmdet3d/models/dense_heads/base_conv_bbox_head.py
class BaseConvBboxHead (line 11) | class BaseConvBboxHead(BaseModule):
method __init__ (line 22) | def __init__(self,
method _add_conv_branch (line 85) | def _add_conv_branch(self, in_channels, conv_channels):
method forward (line 105) | def forward(self, feats):
FILE: mmdet3d/models/dense_heads/base_mono3d_dense_head.py
class BaseMono3DDenseHead (line 7) | class BaseMono3DDenseHead(BaseModule, metaclass=ABCMeta):
method __init__ (line 10) | def __init__(self, init_cfg=None):
method loss (line 14) | def loss(self, **kwargs):
method get_bboxes (line 19) | def get_bboxes(self, **kwargs):
method forward_train (line 23) | def forward_train(self,
FILE: mmdet3d/models/dense_heads/centerpoint_head.py
class SeparateHead (line 20) | class SeparateHead(BaseModule):
method __init__ (line 38) | def __init__(self,
method init_weights (line 90) | def init_weights(self):
method forward (line 98) | def forward(self, x):
class DCNSeparateHead (line 130) | class DCNSeparateHead(BaseModule):
method __init__ (line 155) | def __init__(self,
method init_weights (line 211) | def init_weights(self):
method forward (line 216) | def forward(self, x):
class CenterHead (line 251) | class CenterHead(BaseModule):
method __init__ (line 281) | def __init__(self,
method forward_single (line 347) | def forward_single(self, x):
method forward (line 368) | def forward(self, input_dict, *args, **kwargs):
method _gather_feat (line 389) | def _gather_feat(self, feat, ind, mask=None):
method get_targets (line 414) | def get_targets(self, gt_bboxes_3d, gt_labels_3d):
method get_targets_single (line 461) | def get_targets_single(self, gt_bboxes_3d, gt_labels_3d):
method loss (line 611) | def loss(self, gt_bboxes_3d, gt_labels_3d, preds_dicts, img_metas=Non...
method loss_ (line 618) | def loss_(self, heatmaps, anno_boxes, inds, masks, preds_dicts, **kwar...
method get_bboxes (line 700) | def get_bboxes(self, preds_dicts, img_metas, img=None, rescale=False):
method get_task_detections (line 797) | def get_task_detections(self, num_class_with_bg, batch_cls_preds,
FILE: mmdet3d/models/dense_heads/centerpoint_head_single_task.py
class SeparateHead (line 19) | class SeparateHead(BaseModule):
method __init__ (line 37) | def __init__(self,
method init_weights (line 87) | def init_weights(self):
method forward (line 94) | def forward(self, x):
class DCNSeparateHead (line 125) | class DCNSeparateHead(BaseModule):
method __init__ (line 150) | def __init__(self,
method init_weights (line 205) | def init_weights(self):
method forward (line 210) | def forward(self, x):
class CenterHead (line 244) | class CenterHead(BaseModule):
method __init__ (line 274) | def __init__(self,
method forward_single (line 334) | def forward_single(self, x):
method forward (line 353) | def forward(self, feats):
method _gather_feat (line 365) | def _gather_feat(self, feat, ind, mask=None):
method get_targets (line 390) | def get_targets(self, gt_bboxes_3d, gt_labels_3d):
method get_targets_single (line 437) | def get_targets_single(self, gt_bboxes_3d, gt_labels_3d):
method loss (line 587) | def loss(self, gt_bboxes_3d, gt_labels_3d, preds_dicts, **kwargs):
method get_bboxes (line 670) | def get_bboxes(self, preds_dicts, img_metas, img=None, rescale=False):
method get_task_detections (line 765) | def get_task_detections(self, batch_cls_preds,
FILE: mmdet3d/models/dense_heads/fcaf3d_head.py
class FCAF3DHead (line 21) | class FCAF3DHead(BaseModule):
method __init__ (line 49) | def __init__(self,
method _make_block (line 77) | def _make_block(in_channels, out_channels):
method _make_up_block (line 93) | def _make_up_block(in_channels, out_channels):
method _init_layers (line 115) | def _init_layers(self, in_channels, out_channels, n_reg_outs, n_classes):
method init_weights (line 144) | def init_weights(self):
method forward (line 151) | def forward(self, x):
method forward_train (line 180) | def forward_train(self, x, gt_bboxes, gt_labels, input_metas):
method forward_test (line 197) | def forward_test(self, x, input_metas):
method _prune (line 211) | def _prune(self, x, scores):
method _forward_single (line 236) | def _forward_single(self, x, scale):
method _loss_single (line 270) | def _loss_single(self, center_preds, bbox_preds, cls_preds, points,
method _loss (line 324) | def _loss(self, center_preds, bbox_preds, cls_preds, points, gt_bboxes,
method _get_bboxes_single (line 362) | def _get_bboxes_single(self, center_preds, bbox_preds, cls_preds, points,
method _get_bboxes (line 399) | def _get_bboxes(self, center_preds, bbox_preds, cls_preds, points,
method _bbox_to_loss (line 429) | def _bbox_to_loss(bbox):
method _bbox_pred_to_bbox (line 450) | def _bbox_pred_to_bbox(points, bbox_pred):
method _get_face_distances (line 495) | def _get_face_distances(points, boxes):
method _get_centerness (line 523) | def _get_centerness(face_distances):
method _get_targets (line 542) | def _get_targets(self, points, gt_bboxes, gt_labels):
method _single_scene_multiclass_nms (line 620) | def _single_scene_multiclass_nms(self, bboxes, scores, input_meta):
FILE: mmdet3d/models/dense_heads/fcos_mono3d_head.py
class FCOSMono3DHead (line 21) | class FCOSMono3DHead(AnchorFreeMono3DHead):
method __init__ (line 50) | def __init__(self,
method _init_layers (line 102) | def _init_layers(self):
method init_weights (line 115) | def init_weights(self):
method forward (line 128) | def forward(self, feats):
method forward_single (line 156) | def forward_single(self, x, scale, stride):
method add_sin_difference (line 192) | def add_sin_difference(boxes1, boxes2):
method get_direction_target (line 216) | def get_direction_target(reg_targets,
method loss (line 255) | def loss(self,
method get_bboxes (line 482) | def get_bboxes(self,
method _get_bboxes_single (line 567) | def _get_bboxes_single(self,
method pts2Dto3D (line 696) | def pts2Dto3D(points, view):
method _get_points_single (line 732) | def _get_points_single(self,
method get_targets (line 744) | def get_targets(self, points, gt_bboxes_list, gt_labels_list,
method _get_target_single (line 852) | def _get_target_single(self, gt_bboxes, gt_labels, gt_bboxes_3d,
FILE: mmdet3d/models/dense_heads/free_anchor3d_head.py
class FreeAnchor3DHead (line 13) | class FreeAnchor3DHead(Anchor3DHead):
method __init__ (line 31) | def __init__(self,
method loss (line 45) | def loss(self,
method positive_bag_loss (line 247) | def positive_bag_loss(self, matched_cls_prob, matched_box_prob):
method negative_bag_loss (line 269) | def negative_bag_loss(self, cls_prob, box_prob):
FILE: mmdet3d/models/dense_heads/groupfree3d_head.py
class PointsObjClsModule (line 24) | class PointsObjClsModule(BaseModule):
method __init__ (line 39) | def __init__(self,
method forward (line 67) | def forward(self, seed_features):
class GeneralSamplingModule (line 81) | class GeneralSamplingModule(nn.Module):
method forward (line 87) | def forward(self, xyz, features, sample_inds):
class GroupFree3DHead (line 110) | class GroupFree3DHead(BaseModule):
method __init__ (line 140) | def __init__(self,
method init_weights (line 253) | def init_weights(self):
method _get_cls_out_channels (line 266) | def _get_cls_out_channels(self):
method _get_reg_out_channels (line 271) | def _get_reg_out_channels(self):
method _extract_input (line 281) | def _extract_input(self, feat_dict):
method forward (line 299) | def forward(self, feat_dict, sample_mod):
method loss (line 394) | def loss(self,
method get_targets (line 537) | def get_targets(self,
method get_targets_single (line 646) | def get_targets_single(self,
method get_bboxes (line 865) | def get_bboxes(self,
method multiclass_nms_single (line 936) | def multiclass_nms_single(self, obj_scores, sem_scores, bbox, points,
FILE: mmdet3d/models/dense_heads/monoflex_head.py
class MonoFlexHead (line 21) | class MonoFlexHead(AnchorFreeMono3DHead):
method __init__ (line 82) | def __init__(self,
method _init_edge_module (line 128) | def _init_edge_module(self):
method init_weights (line 138) | def init_weights(self):
method _init_predictor (line 149) | def _init_predictor(self):
method _init_layers (line 181) | def _init_layers(self):
method forward_train (line 187) | def forward_train(self, x, input_metas, gt_bboxes, gt_labels, gt_bboxe...
method forward (line 234) | def forward(self, feats, input_metas):
method forward_single (line 255) | def forward_single(self, x, input_metas):
method get_bboxes (line 315) | def get_bboxes(self, cls_scores, bbox_preds, input_metas):
method decode_heatmap (line 360) | def decode_heatmap(self,
method get_predictions (line 421) | def get_predictions(self, pred_reg, labels3d, centers2d, reg_mask,
method get_targets (line 460) | def get_targets(self, gt_bboxes_list, gt_labels_list, gt_bboxes_3d_list,
method loss (line 639) | def loss(self,
FILE: mmdet3d/models/dense_heads/parta2_rpn_head.py
class PartA2RPNHead (line 13) | class PartA2RPNHead(Anchor3DHead):
method __init__ (line 50) | 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/pgd_head.py
class PGDHead (line 17) | class PGDHead(FCOSMono3DHead):
method __init__ (line 58) | def __init__(self,
method _init_layers (line 116) | def _init_layers(self):
method _init_predictor (line 128) | def _init_predictor(self):
method init_weights (line 159) | def init_weights(self):
method forward (line 185) | def forward(self, feats):
method forward_single (line 218) | def forward_single(self, x, scale, stride):
method get_proj_bbox2d (line 265) | def get_proj_bbox2d(self,
method get_pos_predictions (line 443) | def get_pos_predictions(self, bbox_preds, dir_cls_preds, depth_cls_preds,
method loss (line 526) | def loss(self,
method get_bboxes (line 795) | def get_bboxes(self,
method _get_bboxes_single (line 912) | def _get_bboxes_single(self,
method get_targets (line 1111) | def get_targets(self, points, gt_bboxes_list, gt_labels_list,
FILE: mmdet3d/models/dense_heads/point_rpn_head.py
class PointRPNHead (line 15) | class PointRPNHead(BaseModule):
method __init__ (line 35) | def __init__(self,
method _make_fc_layers (line 69) | def _make_fc_layers(self, fc_cfg, input_channels, output_channels):
method _get_cls_out_channels (line 92) | def _get_cls_out_channels(self):
method _get_reg_out_channels (line 97) | def _get_reg_out_channels(self):
method forward (line 104) | def forward(self, feat_dict):
method loss (line 127) | def loss(self,
method get_targets (line 172) | def get_targets(self, points, gt_bboxes_3d, gt_labels_3d):
method get_targets_single (line 205) | def get_targets_single(self, points, gt_bboxes_3d, gt_labels_3d):
method get_bboxes (line 246) | def get_bboxes(self,
method class_agnostic_nms (line 284) | def class_agnostic_nms(self, obj_scores, sem_scores, bbox, points,
method _assign_targets_by_points_inside (line 354) | def _assign_targets_by_points_inside(self, bboxes_3d, points):
FILE: mmdet3d/models/dense_heads/shape_aware_head.py
class BaseShapeHead (line 17) | class BaseShapeHead(BaseModule):
method __init__ (line 46) | def __init__(self,
method forward (line 124) | def forward(self, x):
class ShapeAwareHead (line 168) | class ShapeAwareHead(Anchor3DHead):
method __init__ (line 179) | def __init__(self, tasks, assign_per_class=True, init_cfg=None, **kwar...
method init_weights (line 185) | def init_weights(self):
method _init_layers (line 195) | def _init_layers(self):
method forward_single (line 216) | def forward_single(self, x):
method loss_single (line 249) | def loss_single(self, cls_score, bbox_pred, dir_cls_preds, labels,
method loss (line 311) | def loss(self,
method get_bboxes (line 378) | def get_bboxes(self,
method get_bboxes_single (line 430) | def get_bboxes_single(self,
FILE: mmdet3d/models/dense_heads/smoke_mono3d_head.py
class SMOKEMono3DHead (line 16) | class SMOKEMono3DHead(AnchorFreeMono3DHead):
method __init__ (line 49) | def __init__(self,
method forward (line 76) | def forward(self, feats):
method forward_single (line 94) | def forward_single(self, x):
method get_bboxes (line 115) | def get_bboxes(self, cls_scores, bbox_preds, img_metas, rescale=None):
method decode_heatmap (line 166) | def decode_heatmap(self,
method get_predictions (line 224) | def get_predictions(self, labels3d, centers2d, gt_locations, gt_dimens...
method get_targets (line 294) | def get_targets(self, gt_bboxes, gt_labels, gt_bboxes_3d, gt_labels_3d,
method loss (line 430) | def loss(self,
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 85) | def _get_cls_out_channels(self):
method _get_reg_out_channels (line 90) | def _get_reg_out_channels(self):
method _extract_input (line 97) | def _extract_input(self, feat_dict):
method loss (line 115) | def loss(self,
method get_targets (line 221) | def get_targets(self,
method get_targets_single (line 309) | def get_targets_single(self,
method get_bboxes (line 442) | def get_bboxes(self, points, bbox_preds, input_metas, rescale=False):
method multiclass_nms_single (line 475) | def multiclass_nms_single(self, obj_scores, sem_scores, bbox, points,
method _assign_targets_by_points_inside (line 540) | def _assign_targets_by_points_inside(self, bboxes_3d, points):
FILE: mmdet3d/models/dense_heads/train_mixins.py
class AnchorTrainMixin (line 9) | class AnchorTrainMixin(object):
method anchor_target_3d (line 12) | def anchor_target_3d(self,
method anchor_target_3d_single (line 102) | def anchor_target_3d_single(self,
method anchor_target_single_assigner (line 238) | def anchor_target_single_assigner(self,
function get_direction_target (line 319) | def get_direction_target(anchors,
FILE: mmdet3d/models/dense_heads/vote_head.py
class VoteHead (line 18) | class VoteHead(BaseModule):
method __init__ (line 42) | def __init__(self,
method _get_cls_out_channels (line 96) | def _get_cls_out_channels(self):
method _get_reg_out_channels (line 101) | def _get_reg_out_channels(self):
method _extract_input (line 108) | def _extract_input(self, feat_dict):
method forward (line 135) | def forward(self, feat_dict, sample_mod):
method loss (line 222) | def loss(self,
method get_targets (line 350) | def get_targets(self,
method get_targets_single (line 439) | def get_targets_single(self,
method get_bboxes (line 563) | def get_bboxes(self,
method multiclass_nms_single (line 605) | def multiclass_nms_single(self, obj_scores, sem_scores, bbox, points,
FILE: mmdet3d/models/detectors/base.py
class Base3DDetector (line 13) | class Base3DDetector(BaseDetector):
method forward_test (line 16) | def forward_test(self, points, img_metas, img=None, **kwargs):
method forward (line 48) | def forward(self, return_loss=True, **kwargs):
method show_results (line 64) | def show_results(self, data, result, out_dir, show=False, score_thr=No...
FILE: mmdet3d/models/detectors/bevdet.py
function convert_color (line 18) | def convert_color(img_path):
function save_tensor (line 25) | def save_tensor(tensor, path, pad_value=254.0,normalize=False):
class BEVDet (line 40) | class BEVDet(CenterPoint):
method __init__ (line 42) | def __init__(self, img_view_transformer, img_bev_encoder_backbone,
method image_encoder (line 50) | def image_encoder(self, img):
method bev_encoder (line 64) | def bev_encoder(self, x):
method extract_img_feat (line 71) | def extract_img_feat(self, img, img_metas, **kwargs):
method extract_feat (line 82) | def extract_feat(self, points, img, img_metas, **kwargs):
method forward_train (line 88) | def forward_train(self,
method forward_test (line 133) | def forward_test(self,
method aug_test (line 171) | def aug_test(self, points, img_metas, img=None, rescale=False):
method simple_test (line 175) | def simple_test(self,
method forward_dummy (line 216) | def forward_dummy(self,
class BEVDetTRT (line 230) | class BEVDetTRT(BEVDet):
method result_serialize (line 232) | def result_serialize(self, outs):
method result_deserialize (line 239) | def result_deserialize(self, outs):
method forward (line 249) | def forward(
method get_bev_pool_input (line 275) | def get_bev_pool_input(self, input):
class BEVDet4D (line 281) | class BEVDet4D(BEVDet):
method __init__ (line 283) | def __init__(self,
method shift_feature (line 300) | def shift_feature(self, input, trans, rots, bda, bda_adj=None):
method prepare_bev_feat (line 371) | def prepare_bev_feat(self, img, rot, tran, intrin, post_rot, post_tran,
method extract_img_feat_sequential (line 380) | def extract_img_feat_sequential(self, inputs, feat_prev):
method prepare_inputs (line 406) | def prepare_inputs(self, inputs):
method extract_img_feat (line 426) | def extract_img_feat(self,
class BEVDepth4D (line 487) | class BEVDepth4D(BEVDet4D):
method forward_train (line 489) | def forward_train(self,
FILE: mmdet3d/models/detectors/centerpoint.py
class CenterPoint (line 10) | class CenterPoint(MVXTwoStageDetector):
method __init__ (line 13) | def __init__(self,
method with_velocity (line 37) | def with_velocity(self):
method extract_pts_feat (line 42) | def extract_pts_feat(self, pts, img_feats, img_metas):
method forward_pts_train (line 57) | def forward_pts_train(self,
method simple_test_pts (line 83) | def simple_test_pts(self, x, img_metas, rescale=False):
method aug_test_pts (line 95) | def aug_test_pts(self, feats, img_metas, rescale=False):
method aug_test (line 197) | def aug_test(self, points, img_metas, imgs=None, rescale=False):
FILE: mmdet3d/models/detectors/dynamic_voxelnet.py
class DynamicVoxelNet (line 11) | class DynamicVoxelNet(VoxelNet):
method __init__ (line 16) | def __init__(self,
method extract_feat (line 39) | def extract_feat(self, points, img_metas):
method voxelize (line 52) | def voxelize(self, points):
FILE: mmdet3d/models/detectors/fcos_mono3d.py
class FCOSMono3D (line 7) | class FCOSMono3D(SingleStageMono3DDetector):
method __init__ (line 14) | def __init__(self,
FILE: mmdet3d/models/detectors/groupfree3dnet.py
class GroupFree3DNet (line 10) | class GroupFree3DNet(SingleStage3DDetector):
method __init__ (line 13) | def __init__(self,
method forward_train (line 26) | def forward_train(self,
method simple_test (line 62) | def simple_test(self, points, img_metas, imgs=None, rescale=False):
method aug_test (line 84) | def aug_test(self, points, img_metas, imgs=None, rescale=False):
FILE: mmdet3d/models/detectors/h3dnet.py
class H3DNet (line 10) | class H3DNet(TwoStage3DDetector):
method __init__ (line 16) | def __init__(self,
method forward_train (line 35) | def forward_train(self,
method simple_test (line 101) | def simple_test(self, points, img_metas, imgs=None, rescale=False):
method aug_test (line 133) | def aug_test(self, points, img_metas, imgs=None, rescale=False):
method extract_feats (line 171) | def extract_feats(self, points, img_metas):
FILE: mmdet3d/models/detectors/imvotenet.py
function sample_valid_seeds (line 14) | def sample_valid_seeds(mask, num_sampled_seed=1024):
class ImVoteNet (line 57) | class ImVoteNet(Base3DDetector):
method __init__ (line 60) | def __init__(self,
method freeze_img_branch_params (line 171) | def freeze_img_branch_params(self):
method _load_from_state_dict (line 189) | def _load_from_state_dict(self, state_dict, prefix, local_metadata, st...
method train (line 203) | def train(self, mode=True):
method with_img_bbox (line 219) | def with_img_bbox(self):
method with_img_bbox_head (line 226) | def with_img_bbox_head(self):
method with_img_backbone (line 232) | def with_img_backbone(self):
method with_img_neck (line 237) | def with_img_neck(self):
method with_img_rpn (line 242) | def with_img_rpn(self):
method with_img_roi_head (line 247) | def with_img_roi_head(self):
method with_pts_bbox (line 252) | def with_pts_bbox(self):
method with_pts_backbone (line 258) | def with_pts_backbone(self):
method with_pts_neck (line 263) | def with_pts_neck(self):
method extract_feat (line 267) | def extract_feat(self, imgs):
method extract_img_feat (line 271) | def extract_img_feat(self, img):
method extract_img_feats (line 278) | def extract_img_feats(self, imgs):
method extract_pts_feat (line 292) | def extract_pts_feat(self, pts):
method extract_pts_feats (line 304) | def extract_pts_feats(self, pts):
method extract_bboxes_2d (line 310) | def extract_bboxes_2d(self,
method forward_train (line 368) | def forward_train(self,
method forward_test (line 520) | def forward_test(self,
method simple_test_img_only (line 600) | def simple_test_img_only(self,
method simple_test (line 637) | def simple_test(self,
method aug_test_img_only (line 703) | def aug_test_img_only(self, img, img_metas, rescale=False):
method aug_test (line 735) | def aug_test(self,
FILE: mmdet3d/models/detectors/imvoxelnet.py
class ImVoxelNet (line 11) | class ImVoxelNet(BaseDetector):
method __init__ (line 14) | def __init__(self,
method extract_feat (line 37) | def extract_feat(self, img, img_metas):
method forward_train (line 78) | def forward_train(self, img, img_metas, gt_bboxes_3d, gt_labels_3d,
method forward_test (line 96) | def forward_test(self, img, img_metas, **kwargs):
method simple_test (line 109) | def simple_test(self, img, img_metas):
method aug_test (line 128) | def aug_test(self, imgs, img_metas, **kwargs):
FILE: mmdet3d/models/detectors/mink_single_stage.py
class MinkSingleStage3DDetector (line 15) | class MinkSingleStage3DDetector(Base3DDetector):
method __init__ (line 31) | def __init__(self,
method extract_feat (line 47) | def extract_feat(self, points):
method forward_train (line 63) | def forward_train(self, points, gt_bboxes_3d, gt_labels_3d, img_metas):
method simple_test (line 81) | def simple_test(self, points, img_metas, *args, **kwargs):
method aug_test (line 99) | def aug_test(self, points, img_metas, **kwargs):
FILE: mmdet3d/models/detectors/mvx_faster_rcnn.py
class MVXFasterRCNN (line 11) | class MVXFasterRCNN(MVXTwoStageDetector):
method __init__ (line 14) | def __init__(self, **kwargs):
class DynamicMVXFasterRCNN (line 19) | class DynamicMVXFasterRCNN(MVXTwoStageDetector):
method __init__ (line 22) | def __init__(self, **kwargs):
method voxelize (line 27) | def voxelize(self, points):
method extract_pts_feat (line 49) | def extract_pts_feat(self, points, img_feats, img_metas):
FILE: mmdet3d/models/detectors/mvx_two_stage.py
class MVXTwoStageDetector (line 21) | class MVXTwoStageDetector(Base3DDetector):
method __init__ (line 24) | def __init__(self,
method with_img_shared_head (line 106) | def with_img_shared_head(self):
method with_pts_bbox (line 112) | def with_pts_bbox(self):
method with_img_bbox (line 118) | def with_img_bbox(self):
method with_img_backbone (line 124) | def with_img_backbone(self):
method with_pts_backbone (line 129) | def with_pts_backbone(self):
method with_fusion (line 134) | def with_fusion(self):
method with_img_neck (line 140) | def with_img_neck(self):
method with_pts_neck (line 145) | def with_pts_neck(self):
method with_img_rpn (line 150) | def with_img_rpn(self):
method with_img_roi_head (line 155) | def with_img_roi_head(self):
method with_voxel_encoder (line 160) | def with_voxel_encoder(self):
method with_middle_encoder (line 166) | def with_middle_encoder(self):
method extract_img_feat (line 171) | def extract_img_feat(self, img, img_metas):
method extract_pts_feat (line 191) | def extract_pts_feat(self, pts, img_feats, img_metas):
method extract_feat (line 205) | def extract_feat(self, points, img, img_metas):
method voxelize (line 213) | def voxelize(self, points):
method forward_train (line 238) | def forward_train(self,
method forward_pts_train (line 292) | def forward_pts_train(self,
method forward_img_train (line 319) | def forward_img_train(self,
method simple_test_img (line 373) | def simple_test_img(self, x, img_metas, proposals=None, rescale=False):
method simple_test_rpn (line 384) | def simple_test_rpn(self, x, img_metas, rpn_test_cfg):
method simple_test_pts (line 391) | def simple_test_pts(self, x, img_metas, rescale=False):
method simple_test (line 402) | def simple_test(self, points, img_metas, img=None, rescale=False):
method aug_test (line 420) | def aug_test(self, points, img_metas, imgs=None, rescale=False):
method extract_feats (line 430) | def extract_feats(self, points, img_metas, imgs=None):
method aug_test_pts (line 438) | def aug_test_pts(self, feats, img_metas, rescale=False):
method show_results (line 457) | def show_results(self, data, result, out_dir):
FILE: mmdet3d/models/detectors/parta2.py
class PartA2 (line 12) | class PartA2(TwoStage3DDetector):
method __init__ (line 18) | def __init__(self,
method extract_feat (line 43) | def extract_feat(self, points, img_metas):
method voxelize (line 59) | def voxelize(self, points):
method forward_train (line 89) | def forward_train(self,
method simple_test (line 138) | def simple_test(self, points, img_metas, proposals=None, rescale=False):
FILE: mmdet3d/models/detectors/point_rcnn.py
class PointRCNN (line 9) | class PointRCNN(TwoStage3DDetector):
method __init__ (line 25) | def __init__(self,
method extract_feat (line 44) | def extract_feat(self, points):
method forward_train (line 59) | def forward_train(self, points, img_metas, gt_bboxes_3d, gt_labels_3d):
method simple_test (line 110) | def simple_test(self, points, img_metas, imgs=None, rescale=False):
FILE: mmdet3d/models/detectors/sassd.py
class SASSD (line 14) | class SASSD(SingleStage3DDetector):
method __init__ (line 17) | def __init__(self,
method extract_feat (line 41) | def extract_feat(self, points, img_metas=None, test_mode=False):
method voxelize (line 55) | def voxelize(self, points):
method forward_train (line 72) | def forward_train(self,
method simple_test (line 104) | def simple_test(self, points, img_metas, imgs=None, rescale=False):
method aug_test (line 116) | def aug_test(self, points, img_metas, imgs=None, rescale=False):
FILE: mmdet3d/models/detectors/single_stage.py
class SingleStage3DDetector (line 7) | class SingleStage3DDetector(Base3DDetector):
method __init__ (line 24) | def __init__(self,
method forward_dummy (line 42) | def forward_dummy(self, points):
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/single_stage_mono3d.py
class SingleStageMono3DDetector (line 17) | class SingleStageMono3DDetector(SingleStageDetector):
method __init__ (line 24) | def __init__(self,
method extract_feats (line 46) | def extract_feats(self, imgs):
method forward_train (line 51) | def forward_train(self,
method simple_test (line 96) | def simple_test(self, img, img_metas, rescale=False):
method aug_test (line 136) | def aug_test(self, imgs, img_metas, rescale=False):
method show_results (line 206) | def show_results(self, data, result, out_dir, show=False, score_thr=No...
FILE: mmdet3d/models/detectors/smoke_mono3d.py
class SMOKEMono3D (line 7) | class SMOKEMono3D(SingleStageMono3DDetector):
method __init__ (line 13) | def __init__(self,
FILE: mmdet3d/models/detectors/ssd3dnet.py
class SSD3DNet (line 7) | class SSD3DNet(VoteNet):
method __init__ (line 13) | def __init__(self,
FILE: mmdet3d/models/detectors/two_stage.py
class TwoStage3DDetector (line 10) | class TwoStage3DDetector(Base3DDetector, TwoStageDetector):
method __init__ (line 18) | def __init__(self,
FILE: mmdet3d/models/detectors/votenet.py
class VoteNet (line 10) | class VoteNet(SingleStage3DDetector):
method __init__ (line 13) | def __init__(self,
method forward_train (line 28) | def forward_train(self,
method simple_test (line 63) | def simple_test(self, points, img_metas, imgs=None, rescale=False):
method aug_test (line 86) | def aug_test(self, points, img_metas, imgs=None, rescale=False):
FILE: mmdet3d/models/detectors/voxelnet.py
class VoxelNet (line 14) | class VoxelNet(SingleStage3DDetector):
method __init__ (line 17) | def __init__(self,
method extract_feat (line 40) | def extract_feat(self, points, img_metas=None):
method voxelize (line 54) | def voxelize(self, points):
method forward_train (line 71) | def forward_train(self,
method simple_test (line 99) | def simple_test(self, points, img_metas, imgs=None, rescale=False):
method aug_test (line 111) | def aug_test(self, points, img_metas, imgs=None, rescale=False):
FILE: mmdet3d/models/fbbev/detectors/bev_planner.py
function generate_forward_transformation_matrix (line 25) | def generate_forward_transformation_matrix(bda, img_meta_dict=None):
class BEVPlanner (line 34) | class BEVPlanner(CenterPoint):
method __init__ (line 36) | def __init__(self,
method _init_fuse_layers (line 172) | def _init_fuse_layers(self):
method with_specific_component (line 199) | def with_specific_component(self, component_name):
method image_encoder (line 203) | def image_encoder(self, img):
method bev_encoder (line 231) | def bev_encoder(self, x):
method fuse_history (line 244) | def fuse_history(self, curr_bev, img_metas, bda): # align features wit...
method extract_img_bev_feat (line 409) | def extract_img_bev_feat(self, img, img_metas, **kwargs):
method extract_lidar_bev_feat (line 472) | def extract_lidar_bev_feat(self, pts, img_feats, img_metas):
method extract_feat (line 486) | def extract_feat(self, points, img, img_metas, **kwargs):
method forward_train (line 496) | def forward_train(self,
method forward_test (line 622) | def forward_test(self,
method aug_test (line 666) | def aug_test(self,points,
method simple_test (line 675) | def simple_test(self,
method forward_dummy (line 836) | def forward_dummy(self,
method world2bev_vis (line 847) | def world2bev_vis(self, x, y):
method visual_sample (line 850) | def visual_sample(self, results, **kwargs):
method _render_traj (line 985) | def _render_traj(self, future_traj, traj_score=1, colormap='winter', p...
FILE: mmdet3d/models/fbbev/heads/occupancy_head.py
class OccHead (line 24) | class OccHead(BaseModule):
method __init__ (line 25) | def __init__(
method forward_coarse_voxel (line 146) | def forward_coarse_voxel(self, voxel_feats):
method forward (line 185) | def forward(self, voxel_feats, img_feats=None, pts_feats=None, transfo...
method forward_train (line 203) | def forward_train(self, voxel_feats, img_feats=None, pts_feats=None, t...
method loss_voxel (line 214) | def loss_voxel(self, output_voxels, target_voxels, tag):
method loss (line 260) | def loss(self, output_voxels=None,
FILE: mmdet3d/models/fbbev/heads/yolox.py
class YOLOXHeadCustom (line 21) | class YOLOXHeadCustom(BaseDenseHead, BBoxTestMixin):
method __init__ (line 51) | def __init__(self,
method _init_layers (line 132) | def _init_layers(self):
method _build_stacked_convs (line 148) | def _build_stacked_convs(self):
method _build_predictor (line 172) | def _build_predictor(self):
method init_weights (line 180) | def init_weights(self):
method forward_single (line 190) | def forward_single(self, x, cls_convs, reg_convs, conv_cls, conv_reg,
method forward (line 209) | def forward(self, feats):
method _bbox_decode (line 236) | def _bbox_decode(self, priors, bbox_preds):
method _centers2d_decode (line 248) | def _centers2d_decode(self, priors, centers2d):
method _bboxes_nms (line 252) | def _bboxes_nms(self, cls_scores, bboxes, score_factor, cfg):
method loss (line 267) | def loss(self,
method _get_target_single (line 382) | def _get_target_single(self, cls_preds, objectness, priors, decoded_bb...
method _get_l1_target (line 452) | def _get_l1_target(self, l1_target, gt_bboxes, priors, eps=1e-8):
method _get_centers2d_target (line 459) | def _get_centers2d_target(self, centers2d_target, centers2d_labels, pr...
FILE: mmdet3d/models/fbbev/modules/depth_net.py
function convert_color (line 25) | def convert_color(img_path):
function save_tensor (line 32) | def save_tensor(tensor, path, pad_value=254.0,normalize=False):
class NaiveDepthNet (line 48) | class NaiveDepthNet(BaseModule):
method __init__ (line 58) | def __init__(
method forward (line 78) | def forward(self, x, mlp_input=None):
method get_mlp_input (line 100) | def get_mlp_input(self, rot, tran, intrin, post_rot, post_tran, bda):
class _ASPPModule (line 105) | class _ASPPModule(nn.Module):
method __init__ (line 107) | def __init__(self, inplanes, planes, kernel_size, padding, dilation,
method forward (line 124) | def forward(self, x):
method _init_weight (line 130) | def _init_weight(self):
class ASPP (line 139) | class ASPP(nn.Module):
method __init__ (line 141) | def __init__(self, inplanes, mid_channels=256, BatchNorm=nn.BatchNorm2d):
method forward (line 189) | def forward(self, x):
method _init_weight (line 205) | def _init_weight(self):
class Mlp (line 214) | class Mlp(nn.Module):
method __init__ (line 216) | def __init__(self,
method forward (line 232) | def forward(self, x):
class SELayer (line 241) | class SELayer(nn.Module):
method __init__ (line 243) | def __init__(self, channels, act_layer=nn.ReLU, gate_layer=nn.Sigmoid):
method forward (line 251) | def forward(self, x, x_se):
class CM_DepthNet (line 259) | class CM_DepthNet(BaseModule):
method __init__ (line 263) | def __init__(self,
method forward (line 339) | def forward(self, x, mlp_input):
method get_mlp_input (line 372) | def get_mlp_input(self, rot, tran, intrin, post_rot, post_tran, bda):
method get_downsampled_gt_depth (line 399) | def get_downsampled_gt_depth(self, gt_depths):
method get_depth_loss (line 440) | def get_depth_loss(self, depth_labels, depth_preds):
class CM_ContextNet (line 459) | class CM_ContextNet(nn.Module):
method __init__ (line 463) | def __init__(self,
method forward (line 486) | def forward(self, x, mlp_input):
FILE: mmdet3d/models/fbbev/modules/fpn3d.py
class FPN3D (line 15) | class FPN3D(BaseModule):
method __init__ (line 28) | def __init__(self,
method forward (line 71) | def forward(self, inputs):
FILE: mmdet3d/models/fbbev/modules/frpn.py
class FRPN (line 16) | class FRPN(BaseModule):
method __init__ (line 23) | def __init__(
method forward (line 41) | def forward(self, input):
method get_bev_mask_loss (line 49) | def get_bev_mask_loss(self, gt_bev_mask, pred_bev_mask):
FILE: mmdet3d/models/fbbev/modules/occ_loss_utils/focal_loss.py
function py_sigmoid_focal_loss (line 12) | def py_sigmoid_focal_loss(pred,
function py_focal_loss_with_prob (line 62) | def py_focal_loss_with_prob(pred,
function sigmoid_focal_loss (line 115) | def sigmoid_focal_loss(pred,
class CustomFocalLoss (line 163) | class CustomFocalLoss(nn.Module):
method __init__ (line 165) | def __init__(self,
method forward (line 206) | def forward(self,
class CustomMSELoss (line 271) | class CustomMSELoss(nn.Module):
method __init__ (line 279) | def __init__(self, reduction='mean', loss_weight=1.0):
method forward (line 284) | def forward(self,
FILE: mmdet3d/models/fbbev/modules/occ_loss_utils/lovasz_softmax.py
function lovasz_grad (line 22) | def lovasz_grad(gt_sorted):
function iou_binary (line 37) | def iou_binary(preds, labels, EMPTY=1., ignore=None, per_image=True):
function iou (line 57) | def iou(preds, labels, C, EMPTY=1., ignore=None, per_image=False):
function lovasz_hinge (line 82) | def lovasz_hinge(logits, labels, per_image=True, ignore=None):
function lovasz_hinge_flat (line 98) | def lovasz_hinge_flat(logits, labels):
function flatten_binary_scores (line 118) | def flatten_binary_scores(scores, labels, ignore=None):
class StableBCELoss (line 133) | class StableBCELoss(torch.nn.modules.Module):
method __init__ (line 134) | def __init__(self):
method forward (line 136) | def forward(self, input, target):
function binary_xloss (line 142) | def binary_xloss(logits, labels, ignore=None):
function lovasz_softmax (line 157) | def lovasz_softmax(probas, labels, classes='present', per_image=False, i...
function lovasz_softmax_flat (line 176) | def lovasz_softmax_flat(probas, labels, classes='present'):
function flatten_probas (line 207) | def flatten_probas(probas, labels, ignore=None):
function xloss (line 236) | def xloss(logits, labels, ignore=None):
function jaccard_loss (line 242) | def jaccard_loss(probas, labels,ignore=None, smooth = 100, bk_class = No...
function hinge_jaccard_loss (line 270) | def hinge_jaccard_loss(probas, labels,ignore=None, classes = 'present', ...
function isnan (line 307) | def isnan(x):
function mean (line 311) | def mean(l, ignore_nan=False, empty=0):
FILE: mmdet3d/models/fbbev/modules/occ_loss_utils/nusc_param.py
function KL_sep (line 116) | def KL_sep(p, target):
function geo_scal_loss (line 126) | def geo_scal_loss(pred, ssc_target):
function sem_scal_loss (line 153) | def sem_scal_loss(pred, ssc_target):
function CE_ssc_loss (line 200) | def CE_ssc_loss(pred, target, class_weights):
FILE: mmdet3d/models/fbbev/modules/occ_loss_utils/semkitti.py
function inverse_sigmoid (line 58) | def inverse_sigmoid(x, sign='A'):
function KL_sep (line 68) | def KL_sep(p, target):
function geo_scal_loss (line 78) | def geo_scal_loss(pred, ssc_target, ignore_index=255, non_empty_idx=0):
function sem_scal_loss (line 108) | def sem_scal_loss(pred_, ssc_target, ignore_index=255):
function CE_ssc_loss (line 166) | def CE_ssc_loss(pred, target, class_weights=None, ignore_index=255):
function vel_loss (line 182) | def vel_loss(pred, gt):
FILE: mmdet3d/models/fbbev/modules/resnet3d.py
function get_inplanes (line 16) | def get_inplanes():
function conv3x3x3 (line 20) | def conv3x3x3(in_planes, out_planes, stride=1, use_spase_3dtensor=False):
function conv1x1x1 (line 34) | def conv1x1x1(in_planes, out_planes, stride=1, use_spase_3dtensor=False):
class BasicBlock (line 47) | class BasicBlock(BaseModule):
method __init__ (line 50) | def __init__(self, in_planes, planes, stride=1, downsample=None, norm_...
method forward (line 78) | def forward(self, x, debug=False):
class Bottleneck (line 105) | class Bottleneck(BaseModule):
method __init__ (line 108) | def __init__(self, in_planes, planes, stride=1, downsample=None, norm_...
method forward (line 121) | def forward(self, x):
class CustomResNet3D (line 144) | class CustomResNet3D(BaseModule):
method __init__ (line 145) | def __init__(self,
method _downsample_basic_block (line 211) | def _downsample_basic_block(self, x, planes, stride):
method _make_layer (line 222) | def _make_layer(self, block, planes, blocks, shortcut_type, stride=1, ...
method forward (line 251) | def forward(self, x):
function generate_model (line 277) | def generate_model(model_depth, **kwargs):
FILE: mmdet3d/models/fbbev/motion_head/motion_head.py
function get_ego_pos (line 21) | def get_ego_pos(points, pc_range):
function get_rel_pos (line 28) | def get_rel_pos(points, pc_range):
class MotionHead (line 36) | class MotionHead(BaseModule):
method __init__ (line 67) | def __init__(self,
method _init_layers (line 136) | def _init_layers(self):
method forward (line 172) | def forward(self, agent_instances, preds_map_dicts, img_metas=None):
method loss (line 247) | def loss(self,
method get_bboxes (line 302) | def get_bboxes(self, preds_dicts, img_metas, rescale=False):
class MLN (line 336) | class MLN(nn.Module):
method __init__ (line 343) | def __init__(self, c_dim, f_dim=256, use_ln=True):
method init_weight (line 359) | def init_weight(self):
method forward (line 365) | def forward(self, x, c):
FILE: mmdet3d/models/fbbev/motion_head/motion_planner_head.py
function get_ego_pos (line 23) | def get_ego_pos(points, pc_range):
function get_rel_pos (line 30) | def get_rel_pos(points, pc_range):
class MotionPlannerHead (line 38) | class MotionPlannerHead(BaseModule):
method __init__ (line 69) | def __init__(self,
method _init_planer_layers (line 219) | def _init_planer_layers(self):
method _init_layers (line 252) | def _init_layers(self):
method pre_update_memory (line 287) | def pre_update_memory(self, data, fut_traj_from_velo):
method post_update_memory (line 304) | def post_update_memory(self, data, ego_fut_trajs, ego_embeds):
method forward (line 311) | def forward(self,
method loss (line 479) | def loss(self,
method get_motion (line 591) | def get_motion(self, preds_dicts, img_metas, rescale=False):
method get_traj (line 632) | def get_traj(self, preds_dicts, img_metas, rescale=False, gt_ego_fut_...
class MLN (line 707) | class MLN(nn.Module):
method __init__ (line 714) | def __init__(self, c_dim, f_dim=256, use_ln=True):
method init_weight (line 730) | def init_weight(self):
method forward (line 736) | def forward(self, x, c):
FILE: mmdet3d/models/fbbev/motion_head/traj_loss.py
class TrajLoss (line 16) | class TrajLoss(nn.Module):
method __init__ (line 23) | def __init__(self, use_variance=False, cls_loss_weight=1., nll_loss_we...
method forward (line 41) | def forward(self,
function min_ade (line 97) | def min_ade(traj: torch.Tensor, traj_gt: torch.Tensor,
function traj_nll (line 123) | def traj_nll(
function min_fde (line 167) | def min_fde(traj: torch.Tensor, traj_gt: torch.Tensor,
function miss_rate (line 203) | def miss_rate(
FILE: mmdet3d/models/fbbev/planner_head/AD_mlp.py
function get_ego_pos (line 79) | def get_ego_pos(points, pc_range):
function get_rel_pos (line 86) | def get_rel_pos(points, pc_range):
class AD_MLP (line 94) | class AD_MLP(Base3DDetector):
method __init__ (line 125) | def __init__(self,
method _init_layers (line 182) | def _init_layers(self):
method forward_train (line 198) | def forward_train(self, img_metas=None, **kwargs):
method inner_forward (line 212) | def inner_forward(self, img_metas=None, **kwargs):
method forward_test (line 269) | def forward_test(self, **kwargs):
method loss (line 278) | def loss(self,
method aug_test (line 308) | def aug_test(self): pass
method point_sampling (line 311) | def point_sampling(self, reference_points, cam_params=None):
method simple_test (line 341) | def simple_test(self, **kwargs):
method extract_feat (line 386) | def extract_feat(self): pass
method get_bboxes (line 388) | def get_bboxes(self, preds_dicts, img_metas=None, rescale=False, gt_e...
method world2bev_vis (line 489) | def world2bev_vis(self, x, y):
method visual_sample (line 492) | def visual_sample(self, results, gt_bboxes_3d_=None, ego_info=None, ca...
method _render_traj (line 670) | def _render_traj(self, future_traj, traj_score=1, colormap='winter', p...
method _render_traj_v2 (line 685) | def _render_traj_v2(self, future_traj, traj_score=1, colormap='winter'...
FILE: mmdet3d/models/fbbev/planner_head/metric_stp3.py
class PlanningMetric (line 15) | class PlanningMetric():
method __init__ (line 16) | def __init__(self):
method gen_dx_bx (line 39) | def gen_dx_bx(self, xbound, ybound, zbound):
method calculate_birds_eye_view_parameters (line 46) | def calculate_birds_eye_view_parameters(self, x_bounds, y_bounds, z_bo...
method evaluate_single_coll (line 69) | def evaluate_single_coll(self, traj, segmentation, input_gt, gt_traj=N...
method evaluate_coll (line 165) | def evaluate_coll(
method compute_L2 (line 223) | def compute_L2(self, trajs, gt_trajs):
FILE: mmdet3d/models/fbbev/planner_head/naive_planner.py
function get_ego_pos (line 30) | def get_ego_pos(points, pc_range):
function get_rel_pos (line 37) | def get_rel_pos(points, pc_range):
class NaivePlannerHead (line 45) | class NaivePlannerHead(BaseModule):
method __init__ (line 49) | def __init__(self,
method reset_memory (line 157) | def reset_memory(self):
method pre_update_memory (line 161) | def pre_update_memory(self, data, fut_traj_from_velo):
method post_update_memory (line 177) | def post_update_memory(self, data, ego_fut_trajs, ego_embeds):
method _init_layers (line 183) | def _init_layers(self):
method calc_MDE (line 202) | def calc_MDE(self, reference_points_q, reference_points_v, pc_range, m...
method forward (line 231) | def forward(self, results, gt_ego_lcf_feat, gt_ego_fut_cmd, gt_ego_his...
method loss (line 323) | def loss(self,
method get_bboxes (line 357) | def get_bboxes(self, preds_dicts, img_metas, rescale=False, gt_ego_fu...
class MLN (line 460) | class MLN(nn.Module):
method __init__ (line 467) | def __init__(self, c_dim, f_dim=256, use_ln=True):
method init_weight (line 483) | def init_weight(self):
method forward (line 489) | def forward(self, x, c):
FILE: mmdet3d/models/fbbev/planner_head/plan_loss.py
class PlanMapBoundLoss (line 12) | class PlanMapBoundLoss(nn.Module):
method __init__ (line 25) | def __init__(
method forward (line 44) | def forward(self,
function plan_map_bound_loss (line 92) | def plan_map_bound_loss(pred, target, dis_thresh=1.0):
function segments_intersect (line 149) | def segments_intersect(line1_start, line1_end, line2_start, line2_end):
class PlanCollisionLoss (line 182) | class PlanCollisionLoss(nn.Module):
method __init__ (line 195) | def __init__(
method forward (line 212) | def forward(self,
function plan_col_loss (line 264) | def plan_col_loss(
class PlanMapDirectionLoss (line 322) | class PlanMapDirectionLoss(nn.Module):
method __init__ (line 333) | def __init__(
method forward (line 350) | def forward(self,
function plan_map_dir_loss (line 394) | def plan_map_dir_loss(pred, target, dis_thresh=2.0):
class PlanMapDirectionLoss2 (line 454) | class PlanMapDirectionLoss2(nn.Module):
method __init__ (line 465) | def __init__(
method forward (line 482) | def forward(self,
function plan_map_dir_loss2 (line 526) | def plan_map_dir_loss2(pred, target, dis_thresh=2.0):
FILE: mmdet3d/models/fbbev/planner_head/plan_loss_gt.py
class PlanMapBoundLoss_gt (line 16) | class PlanMapBoundLoss_gt(nn.Module):
method __init__ (line 29) | def __init__(
method forward (line 48) | def forward(self,
function plan_map_bound_loss (line 93) | def plan_map_bound_loss(pred, target, dis_thresh=1.0):
function segments_intersect (line 150) | def segments_intersect(line1_start, line1_end, line2_start, line2_end):
class PlanCollisionLoss_gt (line 183) | class PlanCollisionLoss_gt(nn.Module):
method __init__ (line 196) | def __init__(
method forward (line 213) | def forward(self,
function plan_col_loss (line 265) | def plan_col_loss(
class PlanMapDirectionLoss_gt (line 322) | class PlanMapDirectionLoss_gt(nn.Module):
method __init__ (line 333) | def __init__(
method forward (line 350) | def forward(self,
function plan_map_dir_loss (line 394) | def plan_map_dir_loss(pred, target, dis_thresh=2.0):
FILE: mmdet3d/models/fbbev/streammapnet/CustomMSDeformableAttention.py
class CustomMSDeformableAttention (line 32) | class CustomMSDeformableAttention(BaseModule):
method __init__ (line 59) | def __init__(self,
method init_weights (line 111) | def init_weights(self):
method forward (line 134) | def forward(self,
FILE: mmdet3d/models/fbbev/streammapnet/cost.py
function chamfer_distance (line 8) | def chamfer_distance(line1, line2) -> float:
class ClsSigmoidCost (line 28) | class ClsSigmoidCost:
method __init__ (line 34) | def __init__(self, weight=1.):
method __call__ (line 37) | def __call__(self, cls_pred, gt_labels):
class LinesFixNumChamferCost (line 56) | class LinesFixNumChamferCost(object):
method __init__ (line 62) | def __init__(self, weight=1.0, permute=False):
method __call__ (line 66) | def __call__(self, lines_pred, gt_lines):
class LinesL1Cost (line 110) | class LinesL1Cost(object):
method __init__ (line 116) | def __init__(self, weight=1.0, beta=0.0, permute=False):
method __call__ (line 121) | def __call__(self, lines_pred, gt_lines, **kwargs):
class BBoxCostC (line 168) | class BBoxCostC:
method __init__ (line 184) | def __init__(self, weight=1., box_format='xyxy'):
method __call__ (line 189) | def __call__(self, bbox_pred, gt_bboxes):
class IoUCostC (line 209) | class IoUCostC:
method __init__ (line 225) | def __init__(self, iou_mode='giou', weight=1., box_format='xywh'):
method __call__ (line 231) | def __call__(self, bboxes, gt_bboxes):
class DynamicLinesCost (line 253) | class DynamicLinesCost(object):
method __init__ (line 259) | def __init__(self, weight=1.):
method __call__ (line 262) | def __call__(self, lines_pred, lines_gt, masks_pred, masks_gt):
method cal_dist (line 284) | def cal_dist(self, x1, x2):
method get_dynamic_line (line 301) | def get_dynamic_line(self, mat, m1, m2):
class BBoxLogitsCost (line 327) | class BBoxLogitsCost(object):
method __init__ (line 333) | def __init__(self, weight=1.):
method calNLL (line 336) | def calNLL(self, logits, value):
method __call__ (line 353) | def __call__(self, bbox_pred, bbox_gt, **kwargs):
class MapQueriesCost (line 368) | class MapQueriesCost(object):
method __init__ (line 370) | def __init__(self, cls_cost, reg_cost, iou_cost=None):
method __call__ (line 379) | def __call__(self, preds: dict, gts: dict):
FILE: mmdet3d/models/fbbev/streammapnet/fp16_dattn.py
class MultiScaleDeformableAttentionFp16 (line 36) | class MultiScaleDeformableAttentionFp16(BaseModule):
method __init__ (line 38) | def __init__(self, attn_cfg=None,init_cfg=None,**kwarg):
method forward (line 48) | def forward(self, query,
class MultiScaleDeformableAttnFunctionFp32 (line 71) | class MultiScaleDeformableAttnFunctionFp32(Function):
method forward (line 75) | def forward(ctx, value, value_spatial_shapes, value_level_start_index,
method backward (line 112) | def backward(ctx, grad_output):
function multi_scale_deformable_attn_pytorch (line 143) | def multi_scale_deformable_attn_pytorch(value, value_spatial_shapes,
class MultiScaleDeformableAttentionFP32 (line 202) | class MultiScaleDeformableAttentionFP32(BaseModule):
method __init__ (line 227) | def __init__(self,
method init_weights (line 275) | def init_weights(self):
method forward (line 297) | def forward(self,
FILE: mmdet3d/models/fbbev/streammapnet/hungarian_lines_assigner.py
class HungarianLinesAssigner (line 10) | class HungarianLinesAssigner(BaseAssigner):
method __init__ (line 29) | def __init__(self,
method assign (line 39) | def assign(self,
FILE: mmdet3d/models/fbbev/streammapnet/loss.py
class LinesL1Loss (line 12) | class LinesL1Loss(nn.Module):
method __init__ (line 14) | def __init__(self, reduction='mean', loss_weight=1.0, beta=0.5):
method forward (line 28) | def forward(self,
function bce (line 69) | def bce(pred, label, class_weight=None):
class MasksLoss (line 86) | class MasksLoss(nn.Module):
method __init__ (line 88) | def __init__(self, reduction='mean', loss_weight=1.0):
method forward (line 93) | def forward(self,
function ce (line 114) | def ce(pred, label, class_weight=None):
class LenLoss (line 130) | class LenLoss(nn.Module):
method __init__ (line 132) | def __init__(self, reduction='mean', loss_weight=1.0):
method forward (line 137) | def forward(self,
FILE: mmdet3d/models/fbbev/streammapnet/map_utils.py
function normalize_2d_bbox (line 3) | def normalize_2d_bbox(bboxes, pc_range):
function normalize_2d_pts (line 15) | def normalize_2d_pts(pts, pc_range):
function denormalize_2d_bbox (line 25) | def denormalize_2d_bbox(bboxes, pc_range):
function denormalize_2d_pts (line 35) | def denormalize_2d_pts(pts, pc_range):
FILE: mmdet3d/models/fbbev/streammapnet/streammapnet_head.py
class MapDetectorHead (line 20) | class MapDetectorHead(nn.Module):
method __init__ (line 22) | def __init__(self,
method init_weights (line 100) | def init_weights(self):
method _init_embedding (line 137) | def _init_embedding(self):
method _init_branch (line 151) | def _init_branch(self,):
method _prepare_context (line 184) | def _prepare_context(self, bev_features):
method propagate (line 198) | def propagate(self, query_embedding, img_metas, start_of_sequence, ego...
method forward_train (line 280) | def forward_train(self, input_dict, img_metas, map_gt_bboxes_3d, map_g...
method forward_test (line 426) | def forward_test(self, input_dict, img_metas, map_gt_bboxes_3d=None, m...
method world2bev_vis (line 562) | def world2bev_vis(self, x, y):
method visual_sample (line 565) | def visual_sample(self, lines, index, pre=False, **kwargs):
method _get_target_single (line 592) | def _get_target_single(self,
method get_targets (line 675) | def get_targets(self, preds, map_gt_bboxes_3d,
method loss_single (line 730) | def loss_single(self,
method loss (line 806) | def loss(self,
method get_bboxes (line 866) | def get_bboxes(self, preds_dict, img_metas, thr=0.0):
method train (line 920) | def train(self, *args, **kwargs):
method eval (line 926) | def eval(self):
method forward (line 932) | def forward(self, *args, return_loss=True, **kwargs):
FILE: mmdet3d/models/fbbev/streammapnet/transformer.py
class MapTransformerDecoder_new (line 24) | class MapTransformerDecoder_new(BaseModule):
method __init__ (line 32) | def __init__(self,
method forward (line 59) | def forward(self,
class MapTransformerLayer (line 160) | class MapTransformerLayer(BaseTransformerLayer):
method __init__ (line 196) | def __init__(self,
method forward (line 222) | def forward(self,
class MapTransformer (line 328) | class MapTransformer(Transformer):
method __init__ (line 339) | def __init__(self,
method init_layers (line 351) | def init_layers(self):
method init_weights (line 356) | def init_weights(self):
method forward (line 367) | def forward(self,
class PlaceHolderEncoder (line 475) | class PlaceHolderEncoder(nn.Module):
method __init__ (line 477) | def __init__(self, *args, embed_dims=None, **kwargs):
method forward (line 481) | def forward(self, *args, query=None, **kwargs):
FILE: mmdet3d/models/fbbev/streammapnet/utils.py
class StreamTensorMemory (line 10) | class StreamTensorMemory(object):
method __init__ (line 11) | def __init__(self, batch_size):
method memory_list (line 23) | def memory_list(self):
method img_metas_memory (line 30) | def img_metas_memory(self):
method update (line 36) | def update(self, memory, img_metas):
method reset_single (line 41) | def reset_single(self, idx):
method get (line 45) | def get(self, img_metas):
method train (line 75) | def train(self, mode=True):
method eval (line 82) | def eval(self):
class MotionMLP (line 87) | class MotionMLP(nn.Module):
method __init__ (line 94) | def __init__(self, c_dim, f_dim=512, identity=True):
method init_weights (line 108) | def init_weights(self):
method forward (line 117) | def forward(self, x, c):
FILE: mmdet3d/models/fbbev/streampetr/hungarian_assigner_2d.py
class HungarianAssigner2D (line 20) | class HungarianAssigner2D(BaseAssigner):
method __init__ (line 48) | def __init__(self,
method assign (line 58) | def assign(self,
FILE: mmdet3d/models/fbbev/streampetr/hungarian_assigner_3d.py
class HungarianAssigner3D (line 18) | class HungarianAssigner3D(BaseAssigner):
method __init__ (line 19) | def __init__(self,
method assign (line 29) | def assign(self,
FILE: mmdet3d/models/fbbev/streampetr/match_cost.py
class BBox3DL1Cost (line 5) | class BBox3DL1Cost(object):
method __init__ (line 11) | def __init__(self, weight=1.):
method __call__ (line 14) | def __call__(self, bbox_pred, gt_bboxes):
FILE: mmdet3d/models/fbbev/streampetr/nms_free_coder.py
class NMSFreeCoder (line 9) | class NMSFreeCoder(BaseBBoxCoder):
method __init__ (line 21) | def __init__(self,
method encode (line 36) | def encode(self):
method decode_single (line 39) | def decode_single(self, cls_scores, bbox_preds):
method decode (line 90) | def decode(self, preds_dicts, layer_index=-1):
FILE: mmdet3d/models/fbbev/streampetr/petr_transformer.py
function get_ego_pos (line 29) | def get_ego_pos(points, pc_range):
function get_rel_pos (line 36) | def get_rel_pos(points, pc_range):
class Detr3DTransformer (line 44) | class Detr3DTransformer(BaseModule):
method __init__ (line 55) | def __init__(self,
method init_weights (line 61) | def init_weights(self):
method forward (line 70) | def forward(self,
class Detr3DTransformerDecoder (line 153) | class Detr3DTransformerDecoder(TransformerLayerSequence):
method __init__ (line 161) | def __init__(self, embed_dims, *args, predict_refine=True, **kwargs):
method forward (line 165) | def forward(self,
class Detr3DTemporalDecoderLayer (line 254) | class Detr3DTemporalDecoderLayer(BaseModule):
method __init__ (line 290) | def __init__(self,
method _forward (line 372) | def _forward(self,
method forward (line 495) | def forward(self,
class DeformableFeatureAggregationCuda (line 564) | class DeformableFeatureAggregationCuda(BaseModule):
method __init__ (line 565) | def __init__(
method init_weight (line 602) | def init_weight(self):
method forward (line 608) | def forward(self, instance_feature, query_pos, feat_flatten, reference...
method _get_weights (line 626) | def _get_weights(self, instance_feature, anchor_embed, lidar2img_mat):
method feature_sampling (line 645) | def feature_sampling(self, feat_flatten, spatial_flatten, level_start_...
class DeformableFeatureAggregationCuda_v2 (line 675) | class DeformableFeatureAggregationCuda_v2(BaseModule):
method __init__ (line 676) | def __init__(
method init_weight (line 712) | def init_weight(self):
method forward (line 718) | def forward(self, instance_feature, query_pos, feat_flatten, reference...
method _get_weights (line 735) | def _get_weights(self, instance_feature, anchor_embed, lidar2img_mat):
method feature_sampling (line 750) | def feature_sampling(self, feat_flatten, spatial_flatten, level_start_...
class MVDeformableFeatureAggregationCuda (line 782) | class MVDeformableFeatureAggregationCuda(BaseModule):
method __init__ (line 783) | def __init__(
method init_weight (line 815) | def init_weight(self):
method forward (line 820) | def forward(self, instance_feature, query_pos, feat_flatten, reference...
method _get_weights (line 833) | def _get_weights(self, instance_feature, anchor_embed, lidar2img_mat, ...
method feature_sampling (line 848) | def feature_sampling(self, feat_flatten, spatial_flatten, level_start_...
class SparseBEVSelfAttention (line 909) | class SparseBEVSelfAttention(BaseModule):
method __init__ (line 910) | def __init__(self, embed_dims=256, num_heads=8, dropout=0.1, pc_range=...
method init_weights (line 918) | def init_weights(self):
method forward (line 922) | def forward(self,
method calc_points_dists (line 952) | def calc_points_dists(self, reference_points, temp_reference_points, p...
class MotionSelfAttention (line 969) | class MotionSelfAttention(BaseModule):
method __init__ (line 970) | def __init__(self, embed_dims=256, num_heads=8, dropout=0.1, pc_range=...
method init_weights (line 984) | def init_weights(self):
method forward (line 988) | def forward(self,
method calc_ADE (line 1026) | def calc_ADE(self, reference_points_q, reference_points_v, pc_range, *...
method calc_MDE (line 1040) | def calc_MDE(self, reference_points_q, reference_points_v, pc_range, m...
method calc_MDE_v2 (line 1069) | def calc_MDE_v2(self, reference_points_q, reference_points_v, pc_range...
class CustomTransformerDecoder (line 1097) | class CustomTransformerDecoder(TransformerLayerSequence):
method __init__ (line 1104) | def __init__(self, *args, return_intermediate=False, **kwargs):
method forward (line 1109) | def forward(self,
FILE: mmdet3d/models/fbbev/streampetr/streampetr_utils.py
function normalize_bbox (line 3) | def normalize_bbox(bboxes, pc_range):
function denormalize_bbox (line 37) | def denormalize_bbox(normalized_bboxes, pc_range):
function pos2posemb3d (line 66) | def pos2posemb3d(pos, num_pos_feats=128, temperature=10000):
function bevpos2posemb (line 80) | def bevpos2posemb(pos, num_pos_feats=128, temperature=10000):
function pos2posemb1d (line 92) | def pos2posemb1d(pos, num_pos_feats=256, temperature=10000):
function nerf_positional_encoding (line 103) | def nerf_positional_encoding(
function memory_refresh (line 154) | def memory_refresh(memory, prev_exist):
function topk_gather (line 160) | def topk_gather(feat, topk_indexes):
function apply_ltrb (line 173) | def apply_ltrb(locations, pred_ltrb):
function apply_center_offset (line 192) | def apply_center_offset(locations, center_offset):
function locations (line 206) | def locations(features, stride, pad_h, pad_w):
function gaussian_2d (line 236) | def gaussian_2d(shape, sigma=1.0):
function draw_heatmap_gaussian (line 255) | def draw_heatmap_gaussian(heatmap, center, radius, k=1):
class SELayer_Linear (line 286) | class SELayer_Linear(nn.Module):
method __init__ (line 287) | def __init__(self, channels, act_layer=nn.ReLU, gate_layer=nn.Sigmoid):
method forward (line 294) | def forward(self, x, x_se):
class MLN (line 301) | class MLN(nn.Module):
method __init__ (line 308) | def __init__(self, c_dim, f_dim=256):
method reset_parameters (line 322) | def reset_parameters(self):
method forward (line 328) | def forward(self, x, c):
function transform_reference_points (line 338) | def transform_reference_points(reference_points, egopose, reverse=False,...
FILE: mmdet3d/models/fbbev/streampetr/streampetr_v2.py
class SparseHead4BEV (line 27) | class SparseHead4BEV(AnchorFreeHead):
method __init__ (line 58) | def __init__(self,
method _init_layers (line 209) | def _init_layers(self):
method temporal_alignment (line 264) | def temporal_alignment(self, query_pos, tgt, reference_points):
method prepare_for_dn (line 300) | def prepare_for_dn(self, batch_size, reference_points, img_metas, gt_b...
method init_weights (line 385) | def init_weights(self):
method reset_memory (line 398) | def reset_memory(self):
method pre_update_memory (line 405) | def pre_update_memory(self, data):
method post_update_memory (line 433) | def post_update_memory(self, data, rec_ego_pose, all_cls_scores, all_b...
method forward (line 471) | def forward(self, input_dict, img_metas, gt_bboxes_3d=None, gt_labels...
method prepare_for_loss (line 608) | def prepare_for_loss(self, mask_dict):
method _get_target_single (line 627) | def _get_target_single(self,
method get_targets (line 687) | def get_targets(self,
method loss_single (line 738) | def loss_single(self,
method dn_loss_single (line 807) | def dn_loss_single(self,
method loss (line 865) | def loss(self,
method get_bboxes (line 975) | def get_bboxes(self, preds_dicts, img_metas, rescale=False):
class MLN (line 998) | class MLN(nn.Module):
method __init__ (line 1005) | def __init__(self, c_dim, f_dim=256, use_ln=True):
method init_weight (line 1021) | def init_weight(self):
method forward (line 1027) | def forward(self, x, c):
FILE: mmdet3d/models/fbbev/track_head/instances.py
function topk_gather (line 16) | def topk_gather(feat, topk_indexes):
class Instances (line 28) | class Instances:
method __init__ (line 51) | def __init__(self, image_size: Tuple[int, int], **kwargs: Any):
method image_size (line 63) | def image_size(self) -> Tuple[int, int]:
method __setattr__ (line 70) | def __setattr__(self, name: str, val: Any) -> None:
method __getattr__ (line 76) | def __getattr__(self, name: str) -> Any:
method set (line 81) | def set(self, name: str, value: Any) -> None:
method has (line 94) | def has(self, name: str) -> bool:
method remove (line 101) | def remove(self, name: str) -> None:
method get (line 107) | def get(self, name: str) -> Any:
method get_fields (line 113) | def get_fields(self) -> Dict[str, Any]:
method to (line 122) | def to(self, *args: Any, **kwargs: Any) -> "Instances":
method numpy (line 134) | def numpy(self):
method instances_topk_gather (line 143) | def instances_topk_gather(self, topk_indexes, valid_key_set=None):
method __getitem__ (line 153) | def __getitem__(self, item: Union[int, slice, torch.BoolTensor]) -> "I...
method __len__ (line 183) | def __len__(self) -> int:
method __iter__ (line 189) | def __iter__(self):
method cat (line 193) | def cat(instance_lists: List["Instances"], dim=0) -> "Instances":
method clone (line 229) | def clone(self):
method detach (line 237) | def detach(self):
method __str__ (line 246) | def __str__(self) -> str:
FILE: mmdet3d/models/fbbev/track_head/losses/tracking_loss.py
class TrackingLoss (line 19) | class TrackingLoss(TrackingLossBase):
method __init__ (line 20) | def __init__(self,
method loss_single_frame (line 26) | def loss_single_frame(self,
FILE: mmdet3d/models/fbbev/track_head/losses/tracking_loss_base.py
class TrackingLossBase (line 24) | class TrackingLossBase(nn.Module):
method __init__ (line 27) | def __init__(self,
method _get_target_single (line 102) | def _get_target_single(self,
method get_targets (line 166) | def get_targets(self,
method loss_single_decoder (line 218) | def loss_single_decoder(self,
method loss_single_frame (line 299) | def loss_single_frame(self,
method forward (line 383) | def forward(self,
function nan_to_num (line 400) | def nan_to_num(x, nan=0.0, posinf=None, neginf=None):
FILE: mmdet3d/models/fbbev/track_head/losses/tracking_loss_combo.py
class TrackingLossCombo (line 26) | class TrackingLossCombo(TrackingLoss):
method __init__ (line 29) | def __init__(self,
method loss_prediction (line 58) | def loss_prediction(self,
method loss_mem_bank (line 71) | def loss_mem_bank(self,
method forward (line 140) | def forward(self,
function nan_to_num (line 158) | def nan_to_num(x, nan=0.0, posinf=None, neginf=None):
FILE: mmdet3d/models/fbbev/track_head/losses/tracking_loss_mem_bank.py
class TrackingLossMemBank (line 16) | class TrackingLossMemBank(TrackingLoss):
method __init__ (line 17) | def __init__(self,
method loss_mem_bank (line 43) | def loss_mem_bank(self,
method forward (line 112) | def forward(self,
FILE: mmdet3d/models/fbbev/track_head/losses/tracking_loss_prediction.py
class TrackingLossPrediction (line 20) | class TrackingLossPrediction(TrackingLoss):
method __init__ (line 23) | def __init__(self,
method loss_prediction (line 49) | def loss_prediction(self,
method forward (line 63) | def forward(self,
function nan_to_num (line 81) | def nan_to_num(x, nan=0.0, posinf=None, neginf=None):
FILE: mmdet3d/models/fbbev/track_head/runtime_tracker.py
class RunTimeTracker (line 9) | class RunTimeTracker:
method __init__ (line 10) | def __init__(self, output_threshold=0.2, score_threshold=0.4,
method update_active_tracks (line 28) | def update_active_tracks(self, track_instances, active_mask):
method get_active_mask (line 46) | def get_active_mask(self, track_instances, training=True):
method empty (line 51) | def empty(self):
FILE: mmdet3d/models/fbbev/track_head/streampetr_utils.py
function normalize_bbox (line 3) | def normalize_bbox(bboxes, pc_range):
function denormalize_bbox (line 37) | def denormalize_bbox(normalized_bboxes, pc_range):
function pos2posemb3d (line 66) | def pos2posemb3d(pos, num_pos_feats=128, temperature=10000):
function bevpos2posemb (line 80) | def bevpos2posemb(pos, num_pos_feats=128, temperature=10000):
function pos2posemb1d (line 92) | def pos2posemb1d(pos, num_pos_feats=256, temperature=10000):
function nerf_positional_encoding (line 103) | def nerf_positional_encoding(
function memory_refresh (line 154) | def memory_refresh(memory, prev_exist):
function topk_gather (line 160) | def topk_gather(feat, topk_indexes):
function apply_ltrb (line 173) | def apply_ltrb(locations, pred_ltrb):
function apply_center_offset (line 192) | def apply_center_offset(locations, center_offset):
function locations (line 206) | def locations(features, stride, pad_h, pad_w):
function gaussian_2d (line 236) | def gaussian_2d(shape, sigma=1.0):
function draw_heatmap_gaussian (line 255) | def draw_heatmap_gaussian(heatmap, center, radius, k=1):
class SELayer_Linear (line 286) | class SELayer_Linear(nn.Module):
method __init__ (line 287) | def __init__(self, channels, act_layer=nn.ReLU, gate_layer=nn.Sigmoid):
method forward (line 294) | def forward(self, x, x_se):
class MLN (line 301) | class MLN(nn.Module):
method __init__ (line 308) | def __init__(self, c_dim, f_dim=256):
method reset_parameters (line 322) | def reset_parameters(self):
method forward (line 328) | def forward(self, x, c):
function transform_reference_points (line 338) | def transform_reference_points(reference_points, egopose, reverse=False,...
function transform_velo (line 355) | def transform_velo(velo, egopose, reverse=False, translation=False):
FILE: mmdet3d/models/fbbev/track_head/track_nms_free_coder.py
class TrackNMSFreeCoder (line 18) | class TrackNMSFreeCoder(BaseBBoxCoder):
method __init__ (line 30) | def __init__(self,
method encode (line 47) | def encode(self):
method decode_single (line 50) | def decode_single(self, cls_scores, bbox_preds, obj_idxes=None, track_...
method decode (line 155) | def decode(self, preds_dicts, layer_index=-1):
FILE: mmdet3d/models/fbbev/track_head/trackpetr.py
class TackerHead (line 29) | class TackerHead(AnchorFreeHead):
method __init__ (line 60) | def __init__(self,
method _init_layers (line 182) | def _init_layers(self):
method init_weights (line 237) | def init_weights(self):
method reset_history_track_instances (line 251) | def reset_history_track_instances(self):
method generate_empty_instance (line 254) | def generate_empty_instance(self, B, init_memory_instances=False):
method instance_temporal_alignment (line 375) | def instance_temporal_alignment(self):
method pre_update_instances (line 409) | def pre_update_instances(self, data):
method post_update_instances (line 452) | def post_update_instances(self, data, rec_ego_pose, all_cls_scores, al...
method post_merge_instances (line 485) | def post_merge_instances(self, data, kept_indicator=0):
method forward (line 518) | def forward(self, input_dict, img_metas, gt_bboxes_3d=None, gt_labels...
method loss (line 646) | def loss(self,
method get_targets (line 690) | def get_targets(self):
method forward_tracking (line 693) | def forward_tracking(self, input_dict, img_metas):
method get_bboxes (line 723) | def get_bboxes(self, preds_dicts, img_metas, rescale=False):
class MLN (line 749) | class MLN(nn.Module):
method __init__ (line 756) | def __init__(self, c_dim, f_dim=256, use_ln=True):
method init_weight (line 772) | def init_weight(self):
method forward (line 778) | def forward(self, x, c):
FILE: mmdet3d/models/fbbev/track_head/utils.py
class StreamTensorMemory (line 10) | class StreamTensorMemory(object):
method __init__ (line 11) | def __init__(self, batch_size):
method memory_list (line 23) | def memory_list(self):
method img_metas_memory (line 30) | def img_metas_memory(self):
method update (line 36) | def update(self, memory, img_metas):
method reset_single (line 41) | def reset_single(self, idx):
method get (line 45) | def get(self, img_metas):
method train (line 75) | def train(self, mode=True):
method eval (line 82) | def eval(self):
class MotionMLP (line 87) | class MotionMLP(nn.Module):
method __init__ (line 94) | def __init__(self, c_dim, f_dim=512, identity=True):
method init_weights (line 108) | def init_weights(self):
method forward (line 117) | def forward(self, x, c):
FILE: mmdet3d/models/fbbev/utils/bricks.py
function compute_allocation (line 12) | def compute_allocation(obj) -> int:
function convert_color (line 44) | def convert_color(img_path):
function save_tensor (line 51) | def save_tensor(tensor, path, pad_value=254.0,normalize=False):
function run_time (line 71) | def run_time(name):
FILE: mmdet3d/models/fbbev/utils/draw_bbox.py
function plot_rect3d_on_img (line 22) | def plot_rect3d_on_img(img,
function draw_lidar_bbox3d_on_img (line 95) | def draw_lidar_bbox3d_on_img(bboxes3d,
function show_multi_modality_result (line 171) | def show_multi_modality_result(img,
FILE: mmdet3d/models/fbbev/utils/eval_hook.py
function _calc_dynamic_intervals (line 20) | def _calc_dynamic_intervals(start_interval, dynamic_interval_list):
class CustomDistEvalHook (line 32) | class CustomDistEvalHook(BaseDistEvalHook):
method __init__ (line 34) | def __init__(self, *args, dynamic_intervals=None, work_dir='test', **...
method _decide_interval (line 41) | def _decide_interval(self, runner):
method before_train_epoch (line 48) | def before_train_epoch(self, runner):
method before_train_iter (line 53) | def before_train_iter(self, runner):
method _do_evaluate (line 57) | def _do_evaluate(self, runner):
method evaluate (line 122) | def evaluate(self, runner, results):
FILE: mmdet3d/models/fbbev/utils/grid_mask.py
class Grid (line 6) | class Grid(object):
method __init__ (line 7) | def __init__(self, use_h, use_w, rotate = 1, offset=False, ratio = 0.5...
method set_prob (line 17) | def set_prob(self, epoch, max_epoch):
method __call__ (line 20) | def __call__(self, img, label):
class GridMask (line 69) | class GridMask(nn.Module):
method __init__ (line 70) | def __init__(self, use_h, use_w, rotate = 1, offset=False, ratio = 0.5...
method set_prob (line 81) | def set_prob(self, epoch, max_epoch):
method forward (line 84) | def forward(self, x):
FILE: mmdet3d/models/fbbev/utils/timer_cp.py
class TimerCP (line 7) | class TimerCP(CheckpointHook):
method __init__ (line 11) | def __init__(self, period=14400):
method before_run (line 16) | def before_run(self, runner):
method after_train_epoch (line 20) | def after_train_epoch(self, runner):
method before_train_iter (line 23) | def before_train_iter(self, runner):
method _save_checkpoint (line 35) | def _save_checkpoint(self, runner):
FILE: mmdet3d/models/fbbev/utils/wechat_logger.py
class GradChecker (line 22) | class GradChecker(Hook):
method after_train_iter (line 23) | def after_train_iter(self, runner):
class MyWechatLoggerHook (line 45) | class MyWechatLoggerHook(LoggerHook):
method __init__ (line 62) | def __init__(self,
method before_run (line 77) | def before_run(self, runner) -> None:
method get_table_text (line 81) | def get_table_text(self, runner, tags):
method log (line 97) | def log(self, runner) -> None:
method _send (line 117) | def _send(self, runner, text) -> None:
method after_run (line 140) | def after_run(self, runner) -> None:
FILE: mmdet3d/models/fbbev/view_transformation/backward_projection/backward_projection.py
class BackwardProjection (line 35) | class BackwardProjection(BaseModule):
method __init__ (line 47) | def __init__(self,
method _init_layers (line 76) | def _init_layers(self):
method init_weights (line 80) | def init_weights(self):
method forward (line 85) | def forward(self, mlvl_feats, img_metas, lss_bev=None, gt_bboxes_3d=No...
FILE: mmdet3d/models/fbbev/view_transformation/backward_projection/bevformer_utils/bevformer.py
class BEVFormer (line 23) | class BEVFormer(BaseModule):
method __init__ (line 34) | def __init__(self,
method init_layers (line 52) | def init_layers(self):
method init_weights (line 58) | def init_weights(self):
method forward (line 72) | def forward(
FILE: mmdet3d/models/fbbev/view_transformation/backward_projection/bevformer_utils/bevformer_encoder.py
class bevformer_encoder (line 28) | class bevformer_encoder(TransformerLayerSequence):
method __init__ (line 39) | def __init__(self, *args, pc_range=None, grid_config=None, data_config...
method get_reference_points (line 52) | def get_reference_points(self,H, W, Z=8, dim='3d', bs=1, device='cuda'...
method point_sampling (line 92) | def point_sampling(self, reference_points, pc_range, img_metas, cam_p...
method forward (line 124) | def forward(self,
class BEVFormerEncoderLayer (line 207) | class BEVFormerEncoderLayer(MyCustomBaseTransformerLayer):
method __init__ (line 228) | def __init__(self,
method forward (line 251) | def forward(self,
FILE: mmdet3d/models/fbbev/view_transformation/backward_projection/bevformer_utils/custom_base_transformer_layer.py
class MyCustomBaseTransformerLayer (line 38) | class MyCustomBaseTransformerLayer(BaseModule):
method __init__ (line 72) | def __init__(self,
method forward (line 167) | def forward(self,
FILE: mmdet3d/models/fbbev/view_transformation/backward_projection/bevformer_utils/multi_scale_deformable_attn_function.py
class MultiScaleDeformableAttnFunction_fp16 (line 15) | class MultiScaleDeformableAttnFunction_fp16(Function):
method forward (line 19) | def forward(ctx, value, value_spatial_shapes, value_level_start_index,
method backward (line 57) | def backward(ctx, grad_output):
class MultiScaleDeformableAttnFunction_fp32 (line 90) | class MultiScaleDeformableAttnFunction_fp32(Function):
method forward (line 94) | def forward(ctx, value, value_spatial_shapes, value_level_start_index,
method backward (line 133) | def backward(ctx, grad_output):
FILE: mmdet3d/models/fbbev/view_transformation/backward_projection/bevformer_utils/positional_encoding.py
class CustormLearnedPositionalEncoding (line 12) | class CustormLearnedPositionalEncoding(BaseModule):
method __init__ (line 26) | def __init__(self,
method forward (line 38) | def forward(self, bs, h, w, device):
method __repr__ (line 62) | def __repr__(self):
FILE: mmdet3d/models/fbbev/view_transformation/backward_projection/bevformer_utils/spatial_cross_attention_depth.py
class DA_SpatialCrossAttention (line 31) | class DA_SpatialCrossAttention(BaseModule):
method __init__ (line 44) | def __init__(self,
method init_weight (line 80) | def init_weight(self):
method forward (line 85) | def forward(self,
class DA_MSDeformableAttention (line 228) | class DA_MSDeformableAttention(BaseModule):
method __init__ (line 253) | def __init__(self,
method init_weights (line 306) | def init_weights(self):
method forward (line 331) | def forward(self,
FILE: mmdet3d/models/fbbev/view_transformation/forward_projection/view_transformer.py
function gen_dx_bx (line 16) | def gen_dx_bx(xbound, ybound, zbound):
class LSSViewTransformerFunction (line 24) | class LSSViewTransformerFunction(BaseModule):
method __init__ (line 43) | def __init__(
method create_grid_infos (line 69) | def create_grid_infos(self, x, y, z, **kwargs):
method create_frustum (line 87) | def create_frustum(self, depth_cfg, input_size, downsample):
method get_lidar_coor (line 111) | def get_lidar_coor(self, rots, trans, cam2imgs, post_rots, post_trans,
method init_acceleration_v2 (line 153) | def init_acceleration_v2(self, coor):
method voxel_pooling_v2 (line 174) | def voxel_pooling_v2(self, coor, depth, feat):
method voxel_pooling_prepare_v2 (line 200) | def voxel_pooling_prepare_v2(self, coor):
method pre_compute (line 260) | def pre_compute(self, cam_params):
method view_transform_core (line 266) | def view_transform_core(self, cam_params, depth, tran_feat):
method view_transform (line 290) | def view_transform(self, cam_params, depth, tran_feat):
method forward (line 296) | def forward(self, cam_params, context, depth, **kwargs):
method get_mlp_input (line 309) | def get_mlp_input(self, rot, tran, intrin, post_rot, post_tran, bda):
class LSSViewTransformerFunction3D (line 315) | class LSSViewTransformerFunction3D(BaseModule):
method __init__ (line 334) | def __init__(
method create_grid_infos (line 370) | def create_grid_infos(self, x, y, z, **kwargs):
method create_frustum (line 388) | def create_frustum(self, depth_cfg, input_size, downsample):
method get_cam2ego_coor (line 412) | def get_cam2ego_coor(self, input, downsample=1):
method get_lidar_coor (line 457) | def get_lidar_coor(self, rots, trans, cam2imgs, post_rots, post_trans,
method init_acceleration_v2 (line 499) | def init_acceleration_v2(self, coor):
method voxel_pooling_v2 (line 520) | def voxel_pooling_v2(self, coor, depth, feat):
method voxel_pooling_prepare_v2 (line 546) | def voxel_pooling_prepare_v2(self, coor):
method pre_compute (line 606) | def pre_compute(self, cam_params):
method view_transform_core (line 612) | def view_transform_core(self, cam_params, depth, tran_feat):
method view_transform (line 638) | def view_transform(self, cam_params, depth, tran_feat):
method forward (line 645) | def forward(self, cam_params, context, depth, **kwargs):
method get_mlp_input (line 661) | def get_mlp_input(self, rot, tran, intrin, post_rot, post_tran, bda):
FILE: mmdet3d/models/fusion_layers/coord_transform.py
function apply_3d_transformation (line 9) | def apply_3d_transformation(pcd, coord_type, img_meta, reverse=False):
function extract_2d_info (line 95) | def extract_2d_info(img_meta, tensor):
function bbox_2d_transform (line 123) | def bbox_2d_transform(img_meta, bbox_2d, ori2new):
function coord_2d_transform (line 177) | def coord_2d_transform(img_meta, coord_2d, ori2new):
FILE: mmdet3d/models/fusion_layers/point_fusion.py
function point_sample (line 14) | def point_sample(img_meta,
class PointFusion (line 95) | class PointFusion(BaseModule):
method __init__ (line 130) | def __init__(self,
method forward (line 210) | def forward(self, img_feats, pts, pts_feats, img_metas):
method obtain_mlvl_feats (line 237) | def obtain_mlvl_feats(self, img_feats, pts, img_metas):
method sample_single (line 270) | def sample_single(self, img_feats, pts, img_meta):
FILE: mmdet3d/models/fusion_layers/vote_fusion.py
class VoteFusion (line 13) | class VoteFusion(nn.Module):
method __init__ (line 21) | def __init__(self, num_classes=10, max_imvote_per_pixel=3):
method forward (line 26) | 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 11) | def axis_aligned_iou_loss(pred, target):
class AxisAlignedIoULoss (line 31) | class AxisAlignedIoULoss(nn.Module):
method __init__ (line 40) | def __init__(self, reduction='mean', loss_weight=1.0):
method forward (line 46) | def forward(self,
FILE: mmdet3d/models/losses/chamfer_distance.py
function chamfer_distance (line 9) | def chamfer_distance(src,
class ChamferDistance (line 76) | class ChamferDistance(nn.Module):
method __init__ (line 88) | def __init__(self,
method forward (line 102) | def forward(self,
FILE: mmdet3d/models/losses/multibin_loss.py
function multibin_loss (line 11) | def multibin_loss(pred_orientations, gt_orientations, num_dir_bins=4):
class MultiBinLoss (line 61) | class MultiBinLoss(nn.Module):
method __init__ (line 71) | def __init__(self, reduction='none', loss_weight=1.0):
method forward (line 77) | def forward(self, pred, target, num_dir_bins, reduction_override=None):
FILE: mmdet3d/models/losses/paconv_regularization_loss.py
function weight_correlation (line 10) | def weight_correlation(conv):
function paconv_regularization_loss (line 47) | def paconv_regularization_loss(modules, reduction):
class PAConvRegularizationLoss (line 72) | class PAConvRegularizationLoss(nn.Module):
method __init__ (line 84) | def __init__(self, reduction='mean', loss_weight=1.0):
method forward (line 90) | def forward(self, modules, reduction_override=None, **kwargs):
FILE: mmdet3d/models/losses/rotated_iou_loss.py
function rotated_iou_3d_loss (line 11) | def rotated_iou_3d_loss(pred, target):
class RotatedIoU3DLoss (line 30) | class RotatedIoU3DLoss(nn.Module):
method __init__ (line 39) | def __init__(self, reduction='mean', loss_weight=1.0):
method forward (line 44) | def forward(self,
FILE: mmdet3d/models/losses/uncertain_smooth_l1_loss.py
function uncertain_smooth_l1_loss (line 10) | def uncertain_smooth_l1_loss(pred, target, sigma, alpha=1.0, beta=1.0):
function uncertain_l1_loss (line 39) | def uncertain_l1_loss(pred, target, sigma, alpha=1.0):
class UncertainSmoothL1Loss (line 62) | class UncertainSmoothL1Loss(nn.Module):
method __init__ (line 79) | def __init__(self, alpha=1.0, beta=1.0, reduction='mean', loss_weight=...
method forward (line 87) | def forward(self,
class UncertainL1Loss (line 126) | class UncertainL1Loss(nn.Module):
method __init__ (line 137) | def __init__(self, alpha=1.0, reduction='mean', loss_weight=1.0):
method forward (line 144) | def forward(self,
FILE: mmdet3d/models/middle_encoders/pillar_scatter.py
class PointPillarsScatter (line 10) | class PointPillarsScatter(nn.Module):
method __init__ (line 20) | def __init__(self, in_channels, output_shape):
method forward (line 29) | def forward(self, voxel_features, coors, batch_size=None):
method forward_single (line 38) | def forward_single(self, voxel_features, coors):
method forward_batch (line 62) | def forward_batch(self, voxel_features, coors, batch_size):
FILE: mmdet3d/models/middle_encoders/sparse_encoder.py
class SparseEncoder (line 18) | class SparseEncoder(nn.Module):
method __init__ (line 42) | def __init__(self,
method forward (line 107) | def forward(self, voxel_features, coors, batch_size):
method make_encoder_layers (line 139) | def make_encoder_layers(self,
class MySparseEncoder (line 217) | class MySparseEncoder(nn.Module):
method __init__ (line 241) | def __init__(self,
method forward (line 306) | def forward(self, voxel_features, coors, batch_size):
method make_encoder_layers (line 339) | def make_encoder_layers(self,
class SparseEncoderSASSD (line 417) | class SparseEncoderSASSD(SparseEncoder):
method __init__ (line 441) | def __init__(self,
method forward (line 469) | def forward(self, voxel_features, coors, batch_size, test_mode=False):
method get_auxiliary_targets (line 538) | def get_auxiliary_targets(self, nxyz, gt_boxes3d, enlarge=1.0):
method calculate_pts_offsets (line 571) | def calculate_pts_offsets(self, points, boxes):
method aux_loss (line 609) | def aux_loss(self, points, point_cls, point_reg, gt_bboxes):
method make_auxiliary_points (line 654) | def make_auxiliary_points(self,
FILE: mmdet3d/models/middle_encoders/sparse_unet.py
class SparseUNet (line 19) | class SparseUNet(BaseModule):
method __init__ (line 38) | def __init__(self,
method forward (line 106) | def forward(self, voxel_features, coors, batch_size):
method decoder_layer_forward (line 157) | def decoder_layer_forward(self, x_lateral, x_bottom, lateral_layer,
method reduce_channel (line 181) | def reduce_channel(x, out_channels):
method make_encoder_layers (line 199) | def make_encoder_layers(self, make_block, norm_cfg, in_channels):
method make_decoder_layers (line 245) | def make_decoder_layers(self, make_block, norm_cfg, in_channels):
FILE: mmdet3d/models/model_utils/edge_fusion_module.py
class EdgeFusionModule (line 8) | class EdgeFusionModule(BaseModule):
method __init__ (line 23) | def __init__(self,
method forward (line 42) | def forward(self, features, fused_features, edge_indices, edge_lens,
FILE: mmdet3d/models/model_utils/transformer.py
class GroupFree3DMHA (line 8) | class GroupFree3DMHA(MultiheadAttention):
method __init__ (line 30) | def __init__(self,
method forward (line 42) | def forward(self,
class ConvBNPositionalEncoding (line 112) | class ConvBNPositionalEncoding(nn.Module):
method __init__ (line 121) | def __init__(self, input_channel, num_pos_feats=288):
method forward (line 128) | def forward(self, xyz):
FILE: mmdet3d/models/model_utils/vote_module.py
class VoteModule (line 10) | class VoteModule(nn.Module):
method __init__ (line 38) | def __init__(self,
method forward (line 89) | def forward(self, seed_points, seed_feats):
method get_loss (line 153) | def get_loss(self, seed_points, vote_points, seed_indices,
FILE: mmdet3d/models/necks/dla_neck.py
function fill_up_weights (line 12) | def fill_up_weights(up):
class IDAUpsample (line 29) | class IDAUpsample(BaseModule):
method __init__ (line 44) | def __init__(
method forward (line 93) | def forward(self, mlvl_features, start_level, end_level):
class DLAUpsample (line 110) | class DLAUpsample(BaseModule):
method __init__ (line 128) | def __init__(self,
method forward (line 152) | def forward(self, mlvl_features):
class DLANeck (line 171) | class DLANeck(BaseModule):
method __init__ (line 187) | def __init__(self,
method forward (line 210) | def forward(self, x):
method init_weights (line 219) | def init_weights(self):
FILE: mmdet3d/models/necks/fpn.py
class CustomFPN (line 12) | class CustomFPN(BaseModule):
method __init__ (line 63) | def __init__(self,
method forward (line 157) | def forward(self, inputs):
FILE: mmdet3d/models/necks/imvoxel_neck.py
class OutdoorImVoxelNeck (line 9) | class OutdoorImVoxelNeck(nn.Module):
method __init__ (line 17) | def __init__(self, in_channels, out_channels):
method forward (line 50) | def forward(self, x):
method init_weights (line 64) | def init_weights(self):
class ResModule (line 69) | class ResModule(nn.Module):
method __init__ (line 76) | def __init__(self, n_channels):
method forward (line 96) | def forward(self, x):
FILE: mmdet3d/models/necks/lss_fpn.py
class FPN_LSS (line 11) | class FPN_LSS(nn.Module):
method __init__ (line 13) | def __init__(self,
method forward (line 90) | def forward(self, feats):
FILE: mmdet3d/models/necks/pointnet2_fp_neck.py
class PointNetFPNeck (line 10) | class PointNetFPNeck(BaseModule):
method __init__ (line 34) | def __init__(self, fp_channels, init_cfg=None):
method _extract_input (line 42) | def _extract_input(self, feat_dict):
method forward (line 64) | def forward(self, feat_dict):
FILE: mmdet3d/models/necks/second_fpn.py
class SECONDFPN (line 12) | class SECONDFPN(BaseModule):
method __init__ (line 26) | def __init__(self,
method forward (line 75) | def forward(self, x):
FILE: mmdet3d/models/necks/view_transformer.py
class LSSViewTransformer (line 16) | class LSSViewTransformer(BaseModule):
method __init__ (line 35) | def __init__(
method create_grid_infos (line 60) | def create_grid_infos(self, x, y, z, **kwargs):
method create_frustum (line 78) | def create_frustum(self, depth_cfg, input_size, downsample):
method get_lidar_coor (line 102) | def get_lidar_
Condensed preview — 481 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (4,559K chars).
[
{
"path": ".gitignore",
"chars": 1924,
"preview": "# Byte-compiled / optimized / DLL files\n__pycache__/\n*.py[cod]\n*.vsix\n*$py.class\n*.ipynb\n*.zip\n# C extensions\n*.so\n*.npz"
},
{
"path": "README.md",
"chars": 1755,
"preview": "# Is Ego Status All You Need for Open-Loop End-to-End Autonomous Driving?\n\n### [arXiv](http://arxiv.org/abs/2312.03031) "
},
{
"path": "configs/_base_/datasets/coco_instance.py",
"chars": 1718,
"preview": "dataset_type = 'CocoDataset'\ndata_root = 'data/coco/'\nimg_norm_cfg = dict(\n mean=[123.675, 116.28, 103.53], std=[58.3"
},
{
"path": "configs/_base_/datasets/kitti-3d-3class.py",
"chars": 5095,
"preview": "# dataset settings\ndataset_type = 'KittiDataset'\ndata_root = 'data/kitti/'\nclass_names = ['Pedestrian', 'Cyclist', 'Car'"
},
{
"path": "configs/_base_/datasets/kitti-3d-car.py",
"chars": 4503,
"preview": "# dataset settings\ndataset_type = 'KittiDataset'\ndata_root = 'data/kitti/'\nclass_names = ['Car']\npoint_cloud_range = [0,"
},
{
"path": "configs/_base_/datasets/kitti-mono3d.py",
"chars": 3054,
"preview": "dataset_type = 'KittiMonoDataset'\ndata_root = 'data/kitti/'\nclass_names = ['Pedestrian', 'Cyclist', 'Car']\ninput_modalit"
},
{
"path": "configs/_base_/datasets/lyft-3d.py",
"chars": 4568,
"preview": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range"
},
{
"path": "configs/_base_/datasets/nuim_instance.py",
"chars": 1991,
"preview": "dataset_type = 'CocoDataset'\ndata_root = 'data/nuimages/'\nclass_names = [\n 'car', 'truck', 'trailer', 'bus', 'constru"
},
{
"path": "configs/_base_/datasets/nus-3d.py",
"chars": 4973,
"preview": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range"
},
{
"path": "configs/_base_/datasets/nus-mono3d.py",
"chars": 3230,
"preview": "dataset_type = 'NuScenesMonoDataset'\ndata_root = 'data/nuscenes/'\nclass_names = [\n 'car', 'truck', 'trailer', 'bus', "
},
{
"path": "configs/_base_/datasets/range100_lyft-3d.py",
"chars": 4572,
"preview": "# If point cloud range is changed, the models should also change their point\n# cloud range accordingly\npoint_cloud_range"
},
{
"path": "configs/_base_/datasets/s3dis-3d-5class.py",
"chars": 3562,
"preview": "# dataset settings\ndataset_type = 'S3DISDataset'\ndata_root = './data/s3dis/'\nclass_names = ('table', 'chair', 'sofa', 'b"
},
{
"path": "configs/_base_/datasets/s3dis_seg-3d-13class.py",
"chars": 5136,
"preview": "# dataset settings\ndataset_type = 'S3DISSegDataset'\ndata_root = './data/s3dis/'\nclass_names = ('ceiling', 'floor', 'wall"
},
{
"path": "configs/_base_/datasets/scannet-3d-18class.py",
"chars": 4819,
"preview": "# dataset settings\ndataset_type = 'ScanNetDataset'\ndata_root = './data/scannet/'\nclass_names = ('cabinet', 'bed', 'chair"
},
{
"path": "configs/_base_/datasets/scannet_seg-3d-20class.py",
"chars": 5074,
"preview": "# dataset settings\ndataset_type = 'ScanNetSegDataset'\ndata_root = './data/scannet/'\nclass_names = ('wall', 'floor', 'cab"
},
{
"path": "configs/_base_/datasets/sunrgbd-3d-10class.py",
"chars": 4063,
"preview": "dataset_type = 'SUNRGBDDataset'\ndata_root = 'data/sunrgbd/'\nclass_names = ('bed', 'table', 'sofa', 'chair', 'toilet', 'd"
},
{
"path": "configs/_base_/datasets/waymoD5-3d-3class.py",
"chars": 4779,
"preview": "# dataset settings\n# D5 in the config name means the whole dataset is divided into 5 folds\n# We only use one fold for ef"
},
{
"path": "configs/_base_/datasets/waymoD5-3d-car.py",
"chars": 4683,
"preview": "# dataset settings\n# D5 in the config name means the whole dataset is divided into 5 folds\n# We only use one fold for ef"
},
{
"path": "configs/_base_/default_runtime.py",
"chars": 667,
"preview": "checkpoint_config = dict(interval=1)\n# yapf:disable push\n# By default we use textlogger hook and tensorboard\n# For more "
},
{
"path": "configs/_base_/init.py",
"chars": 8702,
"preview": "# Copyright (c) Phigent Robotics. All rights reserved.\n\n_base_ = ['../_base_/datasets/nus-3d.py', '../_base_/default_run"
},
{
"path": "configs/_base_/models/3dssd.py",
"chars": 3085,
"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": 6966,
"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/dgcnn.py",
"chars": 980,
"preview": "# model settings\nmodel = dict(\n type='EncoderDecoder3D',\n backbone=dict(\n type='DGCNNBackbone',\n in_"
},
{
"path": "configs/_base_/models/fcaf3d.py",
"chars": 497,
"preview": "model = dict(\n type='MinkSingleStage3DDetector',\n voxel_size=.01,\n backbone=dict(type='MinkResNet', in_channels"
},
{
"path": "configs/_base_/models/fcos3d.py",
"chars": 2432,
"preview": "model = dict(\n type='FCOSMono3D',\n backbone=dict(\n type='ResNet',\n depth=101,\n num_stages=4,\n"
},
{
"path": "configs/_base_/models/groupfree3d.py",
"chars": 2593,
"preview": "model = dict(\n type='GroupFree3DNet',\n backbone=dict(\n type='PointNet2SASSG',\n in_channels=3,\n "
},
{
"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": 3294,
"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": 3177,
"preview": "voxel_size = [0.16, 0.16, 4]\n\nmodel = dict(\n type='VoxelNet',\n voxel_layer=dict(\n max_num_points=32, # max"
},
{
"path": "configs/_base_/models/hv_pointpillars_secfpn_waymo.py",
"chars": 3963,
"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": 2909,
"preview": "voxel_size = [0.05, 0.05, 0.1]\n\nmodel = dict(\n type='VoxelNet',\n voxel_layer=dict(\n max_num_points=5,\n "
},
{
"path": "configs/_base_/models/hv_second_secfpn_waymo.py",
"chars": 3479,
"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": 3563,
"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": 4144,
"preview": "# model settings\nmodel = dict(\n type='MaskRCNN',\n pretrained='torchvision://resnet50',\n backbone=dict(\n "
},
{
"path": "configs/_base_/models/paconv_cuda_ssg.py",
"chars": 180,
"preview": "_base_ = './paconv_ssg.py'\n\nmodel = dict(\n backbone=dict(\n sa_cfg=dict(\n type='PAConvCUDASAModule',"
},
{
"path": "configs/_base_/models/paconv_ssg.py",
"chars": 2005,
"preview": "# model settings\nmodel = dict(\n type='EncoderDecoder3D',\n backbone=dict(\n type='PointNet2SASSG',\n in"
},
{
"path": "configs/_base_/models/parta2.py",
"chars": 7012,
"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='P"
},
{
"path": "configs/_base_/models/pgd.py",
"chars": 1787,
"preview": "_base_ = './fcos3d.py'\n# model settings\nmodel = dict(\n bbox_head=dict(\n _delete_=True,\n type='PGDHead',"
},
{
"path": "configs/_base_/models/point_rcnn.py",
"chars": 5132,
"preview": "model = dict(\n type='PointRCNN',\n backbone=dict(\n type='PointNet2SAMSG',\n in_channels=4,\n num"
},
{
"path": "configs/_base_/models/pointnet2_msg.py",
"chars": 1223,
"preview": "_base_ = './pointnet2_ssg.py'\n\n# model settings\nmodel = dict(\n backbone=dict(\n _delete_=True,\n type='Po"
},
{
"path": "configs/_base_/models/pointnet2_ssg.py",
"chars": 1266,
"preview": "# model settings\nmodel = dict(\n type='EncoderDecoder3D',\n backbone=dict(\n type='PointNet2SASSG',\n in"
},
{
"path": "configs/_base_/models/smoke.py",
"chars": 1737,
"preview": "model = dict(\n type='SMOKEMono3D',\n backbone=dict(\n type='DLANet',\n depth=34,\n in_channels=3,"
},
{
"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/cosine.py",
"chars": 536,
"preview": "# This schedule is mainly used by models with dynamic voxelization\n# optimizer\nlr = 0.003 # max learning rate\noptimizer"
},
{
"path": "configs/_base_/schedules/cyclic_20e.py",
"chars": 797,
"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": 1573,
"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": 319,
"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": 459,
"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": 399,
"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/_base_/schedules/seg_cosine_100e.py",
"chars": 337,
"preview": "# optimizer\n# This schedule is mainly used on S3DIS dataset in segmentation task\noptimizer = dict(type='SGD', lr=0.1, mo"
},
{
"path": "configs/_base_/schedules/seg_cosine_150e.py",
"chars": 361,
"preview": "# optimizer\n# This schedule is mainly used on S3DIS dataset in segmentation task\noptimizer = dict(type='SGD', lr=0.2, we"
},
{
"path": "configs/_base_/schedules/seg_cosine_200e.py",
"chars": 349,
"preview": "# optimizer\n# This schedule is mainly used on ScanNet dataset in segmentation task\noptimizer = dict(type='Adam', lr=0.00"
},
{
"path": "configs/_base_/schedules/seg_cosine_50e.py",
"chars": 347,
"preview": "# optimizer\n# This schedule is mainly used on S3DIS dataset in segmentation task\noptimizer = dict(type='Adam', lr=0.001,"
},
{
"path": "configs/bev_next/bev_planner.py",
"chars": 12181,
"preview": "# Copyright (c) 2023-2024, NVIDIA Corporation & Affiliates. All rights reserved. \n# \n# This work is made available under"
},
{
"path": "configs/bev_next/bev_planner_plus.py",
"chars": 12242,
"preview": "# Copyright (c) 2023-2024, NVIDIA Corporation & Affiliates. All rights reserved. \n# \n# This work is made available under"
},
{
"path": "configs/bev_next/bev_planner_plus_plus.py",
"chars": 12263,
"preview": "# Copyright (c) 2023-2024, NVIDIA Corporation & Affiliates. All rights reserved. \n# \n# This work is made available under"
},
{
"path": "configs/bev_next/bev_planner_w_map.py",
"chars": 15304,
"preview": "# Copyright (c) 2023-2024, NVIDIA Corporation & Affiliates. All rights reserved. \n# \n# This work is made available under"
},
{
"path": "configs/bev_next/det_pretrain_320x800_vov_36ep.py",
"chars": 12288,
"preview": "# Copyright (c) 2023-2024, NVIDIA Corporation & Affiliates. All rights reserved. \n# \n# This work is made available under"
},
{
"path": "configs/bev_next/det_pretrain_640x1600_vov_36ep.py",
"chars": 12288,
"preview": "# Copyright (c) 2023-2024, NVIDIA Corporation & Affiliates. All rights reserved. \n# \n# This work is made available under"
},
{
"path": "configs/bev_next/map_pretrain.py",
"chars": 15179,
"preview": "# Copyright (c) 2023-2024, NVIDIA Corporation & Affiliates. All rights reserved. \n# \n# This work is made available under"
},
{
"path": "mmdet3d/__init__.py",
"chars": 1736,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\n\nimport mmdet\nimport mmseg\nfrom .version import __version__,"
},
{
"path": "mmdet3d/apis/__init__.py",
"chars": 631,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .inference import (convert_SyncBN, inference_detector,\n "
},
{
"path": "mmdet3d/apis/inference.py",
"chars": 17939,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport re\nfrom copy import deepcopy\nfrom os import path as osp\n\nimport m"
},
{
"path": "mmdet3d/apis/test.py",
"chars": 9529,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom os import path as osp\n\nimport mmcv\nimport torch\nfrom mmcv.image imp"
},
{
"path": "mmdet3d/apis/train.py",
"chars": 13078,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport random\nimport warnings\n\nimport numpy as np\nimport torch\nfrom mmcv"
},
{
"path": "mmdet3d/core/__init__.py",
"chars": 437,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .anchor import * # noqa: F401, F403\nfrom .bbox import * # noqa: F"
},
{
"path": "mmdet3d/core/anchor/__init__.py",
"chars": 439,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom mmdet.core.anchor import build_prior_generator\nfrom .anchor_3d_gene"
},
{
"path": "mmdet3d/core/anchor/anchor_3d_generator.py",
"chars": 17867,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\nimport torch\n\nfrom mmdet.core.anchor import ANCHOR_GENERATOR"
},
{
"path": "mmdet3d/core/bbox/__init__.py",
"chars": 1785,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .assigners import AssignResult, BaseAssigner, MaxIoUAssigner\nfrom ."
},
{
"path": "mmdet3d/core/bbox/assigners/__init__.py",
"chars": 181,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom mmdet.core.bbox import AssignResult, BaseAssigner, MaxIoUAssigner\n\n"
},
{
"path": "mmdet3d/core/bbox/box_np_ops.py",
"chars": 30875,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\n# TODO: clean the functions in this file and move the APIs into box stru"
},
{
"path": "mmdet3d/core/bbox/coders/__init__.py",
"chars": 892,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom mmdet.core.bbox import build_bbox_coder\nfrom .anchor_free_bbox_code"
},
{
"path": "mmdet3d/core/bbox/coders/anchor_free_bbox_coder.py",
"chars": 4365,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom mmdet.core.bbox.builder import BBO"
},
{
"path": "mmdet3d/core/bbox/coders/centerpoint_bbox_coders.py",
"chars": 8687,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\n\nfrom mmdet.core.bbox import BaseBBoxCoder\nfrom mmdet.core."
},
{
"path": "mmdet3d/core/bbox/coders/delta_xyzwhlr_bbox_coder.py",
"chars": 3167,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\n\nfrom mmdet.core.bbox import BaseBBoxCoder\nfrom mmdet.core."
},
{
"path": "mmdet3d/core/bbox/coders/fcos3d_bbox_coder.py",
"chars": 5133,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom mmdet.core.bbox import BaseBBoxCod"
},
{
"path": "mmdet3d/core/bbox/coders/groupfree3d_bbox_coder.py",
"chars": 7252,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom mmdet.core.bbox.builder import BBO"
},
{
"path": "mmdet3d/core/bbox/coders/monoflex_bbox_coder.py",
"chars": 20306,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\nfrom torch.nn import functional as F\n\nfr"
},
{
"path": "mmdet3d/core/bbox/coders/partial_bin_based_bbox_coder.py",
"chars": 9144,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom mmdet.core.bbox import BaseBBoxCod"
},
{
"path": "mmdet3d/core/bbox/coders/pgd_bbox_coder.py",
"chars": 5372,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\nfrom torch.nn import functional as F\n\nfr"
},
{
"path": "mmdet3d/core/bbox/coders/point_xyzwhlr_bbox_coder.py",
"chars": 4541,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom mmdet.core.bbox import BaseBBoxCod"
},
{
"path": "mmdet3d/core/bbox/coders/smoke_bbox_coder.py",
"chars": 8286,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom mmdet.core.bbox import BaseBBoxCod"
},
{
"path": "mmdet3d/core/bbox/iou_calculators/__init__.py",
"chars": 492,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .iou3d_calculator import (AxisAlignedBboxOverlaps3D, BboxOverlaps3D"
},
{
"path": "mmdet3d/core/bbox/iou_calculators/iou3d_calculator.py",
"chars": 12808,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\n\nfrom mmdet.core.bbox import bbox_overlaps\nfrom mmdet.core."
},
{
"path": "mmdet3d/core/bbox/samplers/__init__.py",
"chars": 648,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom mmdet.core.bbox.samplers import (BaseSampler, CombinedSampler,\n "
},
{
"path": "mmdet3d/core/bbox/samplers/iou_neg_piecewise_sampler.py",
"chars": 8269,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\n\nfrom mmdet.core.bbox.builder import BBOX_SAMPLERS\nfrom . i"
},
{
"path": "mmdet3d/core/bbox/structures/__init__.py",
"chars": 851,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .base_box3d import BaseInstance3DBoxes\nfrom .box_3d_mode import Box"
},
{
"path": "mmdet3d/core/bbox/structures/base_box3d.py",
"chars": 21356,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport warnings\nfrom abc import abstractmethod\n\nimport numpy as np\nimpor"
},
{
"path": "mmdet3d/core/bbox/structures/box_3d_mode.py",
"chars": 7165,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom enum import IntEnum, unique\n\nimport numpy as np\nimport torch\n\nfrom "
},
{
"path": "mmdet3d/core/bbox/structures/cam_box3d.py",
"chars": 13736,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom ...points import BasePoints\nfrom ."
},
{
"path": "mmdet3d/core/bbox/structures/coord_3d_mode.py",
"chars": 9096,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom enum import IntEnum, unique\n\nimport numpy as np\nimport torch\n\nfrom "
},
{
"path": "mmdet3d/core/bbox/structures/custom_box.py",
"chars": 4824,
"preview": "# nuScenes dev-kit.\n# Code written by Oscar Beijbom, 2018.\n\nimport copy\nimport os.path as osp\nimport struct\nfrom abc imp"
},
{
"path": "mmdet3d/core/bbox/structures/depth_box3d.py",
"chars": 10801,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom mmdet3d.core.points import BasePoi"
},
{
"path": "mmdet3d/core/bbox/structures/lidar_box3d.py",
"chars": 8115,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\nfrom mmdet3d.core.points import BasePoi"
},
{
"path": "mmdet3d/core/bbox/structures/utils.py",
"chars": 11768,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom logging import warning\n\nimport numpy as np\nimport torch\n\nfrom mmdet"
},
{
"path": "mmdet3d/core/bbox/transforms.py",
"chars": 2398,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\n\n\ndef bbox3d_mapping_back(bboxes, scale_factor, flip_horizo"
},
{
"path": "mmdet3d/core/bbox/util.py",
"chars": 1466,
"preview": "import torch\n\ndef normalize_bbox(bboxes, pc_range):\n\n cx = bboxes[..., 0:1]\n cy = bboxes[..., 1:2]\n cz = bboxes"
},
{
"path": "mmdet3d/core/evaluation/__init__.py",
"chars": 379,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .indoor_eval import indoor_eval\nfrom .instance_seg_eval import inst"
},
{
"path": "mmdet3d/core/evaluation/indoor_eval.py",
"chars": 11074,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\nfrom mmcv.utils import print_log\nfrom te"
},
{
"path": "mmdet3d/core/evaluation/instance_seg_eval.py",
"chars": 5185,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nfrom mmcv.utils import print_log\nfrom terminaltables "
},
{
"path": "mmdet3d/core/evaluation/kitti_utils/__init__.py",
"chars": 151,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .eval import kitti_eval, kitti_eval_coco_style\n\n__all__ = ['kitti_e"
},
{
"path": "mmdet3d/core/evaluation/kitti_utils/eval.py",
"chars": 37912,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport gc\nimport io as sysio\n\nimport numba\nimport numpy as np\n\n\n@numba.j"
},
{
"path": "mmdet3d/core/evaluation/kitti_utils/rotate_iou.py",
"chars": 13153,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\n#####################\n# Based on https://github.com/hongzhenwang/RRPN-re"
},
{
"path": "mmdet3d/core/evaluation/lyft_eval.py",
"chars": 10356,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom os import path as osp\n\nimport mmcv\nimport numpy as np\nfrom lyft_dat"
},
{
"path": "mmdet3d/core/evaluation/scannet_utils/__init__.py",
"chars": 167,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .evaluate_semantic_instance import evaluate_matches, scannet_eval\n\n"
},
{
"path": "mmdet3d/core/evaluation/scannet_utils/evaluate_semantic_instance.py",
"chars": 15624,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\n# adapted from https://github.com/ScanNet/ScanNet/blob/master/BenchmarkS"
},
{
"path": "mmdet3d/core/evaluation/scannet_utils/util_3d.py",
"chars": 2607,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\n# adapted from https://github.com/ScanNet/ScanNet/blob/master/BenchmarkS"
},
{
"path": "mmdet3d/core/evaluation/seg_eval.py",
"chars": 3746,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nfrom mmcv.utils import print_log\nfrom terminaltables "
},
{
"path": "mmdet3d/core/evaluation/waymo_utils/__init__.py",
"chars": 126,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .prediction_kitti_to_waymo import KITTI2Waymo\n\n__all__ = ['KITTI2Wa"
},
{
"path": "mmdet3d/core/evaluation/waymo_utils/prediction_kitti_to_waymo.py",
"chars": 9699,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nr\"\"\"Adapted from `Waymo to KITTI converter\n <https://github.com/caizh"
},
{
"path": "mmdet3d/core/hook/__init__.py",
"chars": 231,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .ema import MEGVIIEMAHook\nfrom .utils import is_parallel\nfrom .sequ"
},
{
"path": "mmdet3d/core/hook/ema.py",
"chars": 4982,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\n# modified from megvii-bevdepth.\nimport math\nimport os\nfrom copy import "
},
{
"path": "mmdet3d/core/hook/forge_load.py",
"chars": 3530,
"preview": "# -*- coding: utf-8 -*-\n#!/usr/bin/python \n##################################################\n# A"
},
{
"path": "mmdet3d/core/hook/sequentialsontrol.py",
"chars": 1443,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom mmcv.runner.hooks import HOOKS, Hook\nfrom mmdet3d.core.hook.utils i"
},
{
"path": "mmdet3d/core/hook/utils.py",
"chars": 319,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom torch import nn\n\n__all__ = ['is_parallel']\n\n\ndef is_parallel(model)"
},
{
"path": "mmdet3d/core/points/__init__.py",
"chars": 921,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .base_points import BasePoints\nfrom .cam_points import CameraPoints"
},
{
"path": "mmdet3d/core/points/base_points.py",
"chars": 16601,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport warnings\nfrom abc import abstractmethod\n\nimport numpy as np\nimpor"
},
{
"path": "mmdet3d/core/points/cam_points.py",
"chars": 2475,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .base_points import BasePoints\n\n\nclass CameraPoints(BasePoints):\n "
},
{
"path": "mmdet3d/core/points/depth_points.py",
"chars": 2342,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .base_points import BasePoints\n\n\nclass DepthPoints(BasePoints):\n "
},
{
"path": "mmdet3d/core/points/lidar_points.py",
"chars": 2342,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .base_points import BasePoints\n\n\nclass LiDARPoints(BasePoints):\n "
},
{
"path": "mmdet3d/core/post_processing/__init__.py",
"chars": 663,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom mmdet.core.post_processing import (merge_aug_bboxes, merge_aug_mask"
},
{
"path": "mmdet3d/core/post_processing/box3d_nms.py",
"chars": 10783,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numba\nimport numpy as np\nimport torch\nfrom mmcv.ops import nms, n"
},
{
"path": "mmdet3d/core/post_processing/merge_augs.py",
"chars": 3494,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\n\nfrom mmdet3d.core.post_processing import nms_bev, nms_norm"
},
{
"path": "mmdet3d/core/utils/__init__.py",
"chars": 416,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .array_converter import ArrayConverter, array_converter\nfrom .gauss"
},
{
"path": "mmdet3d/core/utils/array_converter.py",
"chars": 13217,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport functools\nfrom inspect import getfullargspec\n\nimport numpy as np\n"
},
{
"path": "mmdet3d/core/utils/gaussian.py",
"chars": 5252,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\n\n\ndef gaussian_2d(shape, sigma=1):\n \""
},
{
"path": "mmdet3d/core/visualizer/__init__.py",
"chars": 234,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .show_result import (show_multi_modality_result, show_result,\n "
},
{
"path": "mmdet3d/core/visualizer/image_vis.py",
"chars": 7947,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\n\nimport cv2\nimport numpy as np\nimport torch\nfrom matplotlib "
},
{
"path": "mmdet3d/core/visualizer/open3d_vis.py",
"chars": 18452,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\n\nimport numpy as np\nimport torch\n\ntry:\n import open3d as "
},
{
"path": "mmdet3d/core/visualizer/show_result.py",
"chars": 10994,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom os import path as osp\n\nimport mmcv\nimport numpy as np\nimport trimes"
},
{
"path": "mmdet3d/core/voxel/__init__.py",
"chars": 190,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .builder import build_voxel_generator\nfrom .voxel_generator import "
},
{
"path": "mmdet3d/core/voxel/builder.py",
"chars": 484,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\n\nfrom . import voxel_generator\n\n\ndef build_voxel_generator(c"
},
{
"path": "mmdet3d/core/voxel/voxel_generator.py",
"chars": 11430,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numba\nimport numpy as np\n\n\nclass VoxelGenerator(object):\n \"\"\"V"
},
{
"path": "mmdet3d/datasets/__init__.py",
"chars": 2711,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\n# from mmdet.datasets.builder import build_dataloader, \nfrom .builder im"
},
{
"path": "mmdet3d/datasets/builder.py",
"chars": 6857,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport platform\nfrom functools import partial\n\nfrom mmcv.utils import Re"
},
{
"path": "mmdet3d/datasets/custom_3d.py",
"chars": 16584,
"preview": "# Copyright (c) 2022-2023, NVIDIA Corporation & Affiliates. All rights reserved. \n# \n# This work is made available under"
},
{
"path": "mmdet3d/datasets/custom_3d_seg.py",
"chars": 17169,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport tempfile\nimport warnings\nfrom os import path as osp\n\nimport mmcv\n"
},
{
"path": "mmdet3d/datasets/dataset_wrappers.py",
"chars": 2613,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\n\nfrom .builder import DATASETS\n\n\n@DATASETS.register_m"
},
{
"path": "mmdet3d/datasets/evals/eval_utils.py",
"chars": 40354,
"preview": "import json\nimport torch\nimport tqdm\nfrom typing import List, Dict, Tuple, Callable, Union\nfrom nuscenes import NuScenes"
},
{
"path": "mmdet3d/datasets/evals/map_api.py",
"chars": 116037,
"preview": "# nuScenes dev-kit.\n# Code written by Sergi Adipraja Widjaja, 2019.\n# + Map mask by Kiwoo Shin, 2019.\n# + Methods operat"
},
{
"path": "mmdet3d/datasets/evals/metric_utils.py",
"chars": 4008,
"preview": "import torch\nimport math\nimport numpy as np\nfrom typing import List, Dict, Tuple, Callable, Union\n\ndef min_ade(traj: tor"
},
{
"path": "mmdet3d/datasets/evals/nuscenes_eval_motion.py",
"chars": 36724,
"preview": "import argparse\nimport copy\nimport json\nimport os\nimport time\nfrom typing import Tuple, Dict, Any\nimport numpy as np\n\nfr"
},
{
"path": "mmdet3d/datasets/evaluation/AP.py",
"chars": 4587,
"preview": "import numpy as np\nfrom .distance import chamfer_distance, frechet_distance, chamfer_distance_batch\nfrom typing import L"
},
{
"path": "mmdet3d/datasets/evaluation/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "mmdet3d/datasets/evaluation/distance.py",
"chars": 2143,
"preview": "from scipy.spatial import distance\nfrom numpy.typing import NDArray\nimport torch\n\ndef chamfer_distance(line1: NDArray, l"
},
{
"path": "mmdet3d/datasets/evaluation/raster_eval.py",
"chars": 3427,
"preview": "import torch\nfrom mmdet3d.datasets import build_dataset, build_dataloader\nimport mmcv\nfrom functools import cached_prope"
},
{
"path": "mmdet3d/datasets/evaluation/vector_eval.py",
"chars": 11483,
"preview": "from functools import partial\nimport numpy as np\nfrom multiprocessing import Pool\nfrom mmdet3d.datasets import build_dat"
},
{
"path": "mmdet3d/datasets/kitti2d_dataset.py",
"chars": 8796,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\nimport numpy as np\n\nfrom mmdet.datasets import CustomDataset"
},
{
"path": "mmdet3d/datasets/kitti_dataset.py",
"chars": 32038,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport os\nimport tempfile\nfrom os import path as osp\n\nimport"
},
{
"path": "mmdet3d/datasets/kitti_mono_dataset.py",
"chars": 23468,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport tempfile\nfrom os import path as osp\n\nimport mmcv\nimpo"
},
{
"path": "mmdet3d/datasets/lyft_dataset.py",
"chars": 22415,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport os\nimport tempfile\nfrom os import path as osp\n\nimport mmcv\nimport"
},
{
"path": "mmdet3d/datasets/map_utils/mean_ap.py",
"chars": 14446,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom multiprocessing import Pool\nfrom shapely.geometry import LineString"
},
{
"path": "mmdet3d/datasets/map_utils/tpfp.py",
"chars": 11791,
"preview": "import mmcv\nimport numpy as np\n\nfrom mmdet.core.evaluation.bbox_overlaps import bbox_overlaps\nfrom .tpfp_chamfer import "
},
{
"path": "mmdet3d/datasets/map_utils/tpfp_chamfer.py",
"chars": 11126,
"preview": "# from ..chamfer_dist import ChamferDistance\nimport numpy as np\nfrom shapely.geometry import LineString, Polygon\nfrom sh"
},
{
"path": "mmdet3d/datasets/nuscenes_dataset.py",
"chars": 89009,
"preview": "# Copyright (c) 2022-2023, NVIDIA Corporation & Affiliates. All rights reserved. \n# \n# This work is made available under"
},
{
"path": "mmdet3d/datasets/nuscenes_eval.py",
"chars": 36400,
"preview": "import argparse\nimport copy\nimport json\nimport os\nimport time\nfrom typing import Tuple, Dict, Any\nimport torch\nimport nu"
},
{
"path": "mmdet3d/datasets/nuscenes_mono_dataset.py",
"chars": 34219,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport tempfile\nimport warnings\nfrom os import path as osp\n\n"
},
{
"path": "mmdet3d/datasets/occ_metrics.py",
"chars": 14978,
"preview": "import numpy as np\nimport os\nfrom pathlib import Path\nfrom tqdm import tqdm\nimport pickle as pkl\nimport argparse\nimport "
},
{
"path": "mmdet3d/datasets/occupancy_eval.py",
"chars": 1808,
"preview": "from .occ_metrics import Metric_mIoU, Metric_FScore\nimport argparse\nimport os \nimport sys\nimport nunmpy as np\n\ndef parse"
},
{
"path": "mmdet3d/datasets/pipelines/__init__.py",
"chars": 2188,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .compose import Compose\nfrom .dbsampler import DataBaseSampler\nfrom"
},
{
"path": "mmdet3d/datasets/pipelines/compose.py",
"chars": 2002,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport collections\n\nfrom mmcv.utils import build_from_cfg\n\nfrom mmdet.da"
},
{
"path": "mmdet3d/datasets/pipelines/data_augment_utils.py",
"chars": 17088,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport warnings\n\nimport numba\nimport numpy as np\nfrom numba.core.errors "
},
{
"path": "mmdet3d/datasets/pipelines/dbsampler.py",
"chars": 13213,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport os\nimport warnings\n\nimport mmcv\nimport numpy as np\n\nf"
},
{
"path": "mmdet3d/datasets/pipelines/formating.py",
"chars": 13103,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nfrom mmcv.parallel import DataContainer as DC\n\nfrom m"
},
{
"path": "mmdet3d/datasets/pipelines/loading.py",
"chars": 81416,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\nimport numpy as np\nimport torch\nfrom PIL import Image\nfrom p"
},
{
"path": "mmdet3d/datasets/pipelines/test_time_aug.py",
"chars": 16532,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport warnings\nfrom copy import deepcopy\n\nimport mmcv\n\nfrom ..builder i"
},
{
"path": "mmdet3d/datasets/pipelines/transforms_3d.py",
"chars": 94462,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport random\nimport warnings\n\nimport cv2\nimport numpy as np\nfrom mmcv i"
},
{
"path": "mmdet3d/datasets/s3dis_dataset.py",
"chars": 17328,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom os import path as osp\n\nimport numpy as np\n\nfrom mmdet3d.core import"
},
{
"path": "mmdet3d/datasets/samplers/__init__.py",
"chars": 208,
"preview": "from .infinite_group_each_sample_in_batch_sampler import InfiniteGroupEachSampleInBatchSampler, InfiniteGroupEachSampleI"
},
{
"path": "mmdet3d/datasets/samplers/d_sampler.py",
"chars": 1370,
"preview": "import math\n\nimport torch\nfrom torch.utils.data import DistributedSampler as _DistributedSampler\nfrom torch.utils.data.s"
},
{
"path": "mmdet3d/datasets/samplers/infinite_group_each_sample_in_batch_sampler.py",
"chars": 9220,
"preview": "\n \n\nimport itertools\nimport copy\n\nimport numpy as np\nimport torch\nimport torch.distributed as dist\nfrom mmcv.runner impo"
},
{
"path": "mmdet3d/datasets/scannet_dataset.py",
"chars": 23888,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport tempfile\nimport warnings\nfrom os import path as osp\n\nimport numpy"
},
{
"path": "mmdet3d/datasets/semantickitti_dataset.py",
"chars": 4251,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom os import path as osp\n\nfrom .builder import DATASETS\nfrom .custom_3"
},
{
"path": "mmdet3d/datasets/sunrgbd_dataset.py",
"chars": 11194,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom collections import OrderedDict\nfrom os import path as osp\n\nimport n"
},
{
"path": "mmdet3d/datasets/utils.py",
"chars": 10015,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport mmcv\n\n# yapf: disable\nfrom mmdet3d.datasets.pipelines import (Col"
},
{
"path": "mmdet3d/datasets/vector_map.py",
"chars": 43449,
"preview": "import os\nimport json\nimport copy\nimport tempfile\nfrom typing import Dict, List\n\nimport numpy as np\nimport pyquaternion\n"
},
{
"path": "mmdet3d/datasets/waymo_dataset.py",
"chars": 23153,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport os\nimport tempfile\nfrom os import path as osp\n\nimport mmcv\nimport"
},
{
"path": "mmdet3d/models/__init__.py",
"chars": 1485,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .backbones import * # noqa: F401,F403\nfrom .builder import (BACKBO"
},
{
"path": "mmdet3d/models/backbones/__init__.py",
"chars": 758,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom mmdet.models.backbones import SSDVGG, HRNet, ResNet, ResNetV1d, Res"
},
{
"path": "mmdet3d/models/backbones/base_pointnet.py",
"chars": 1336,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport warnings\nfrom abc import ABCMeta\n\nfrom mmcv.runner import BaseMod"
},
{
"path": "mmdet3d/models/backbones/convnext.py",
"chars": 13902,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom functools import partial\nfrom itertools import chain\nfrom typing im"
},
{
"path": "mmdet3d/models/backbones/dgcnn.py",
"chars": 3723,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom mmcv.runner import BaseModule, auto_fp16\nfrom torch import nn as nn"
},
{
"path": "mmdet3d/models/backbones/dla.py",
"chars": 14800,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport warnings\n\nimport torch\nfrom mmcv.cnn import build_conv_layer, bui"
},
{
"path": "mmdet3d/models/backbones/load.py",
"chars": 2882,
"preview": "# Copyright (c) Open-MMLab. All rights reserved.\nimport os.path as osp\nimport time\nfrom tempfile import TemporaryDirecto"
},
{
"path": "mmdet3d/models/backbones/mink_resnet.py",
"chars": 4128,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\n# Follow https://github.com/NVIDIA/MinkowskiEngine/blob/master/examples/"
},
{
"path": "mmdet3d/models/backbones/multi_backbone.py",
"chars": 4707,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport warnings\n\nimport torch\nfrom mmcv.cnn import ConvModul"
},
{
"path": "mmdet3d/models/backbones/nostem_regnet.py",
"chars": 3352,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom mmdet.models.backbones import RegNet\nfrom ..builder import BACKBONE"
},
{
"path": "mmdet3d/models/backbones/pointnet2_sa_msg.py",
"chars": 7289,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\nfrom mmcv.cnn import ConvModule\nfrom mmcv.runner import aut"
},
{
"path": "mmdet3d/models/backbones/pointnet2_sa_ssg.py",
"chars": 5552,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport torch\nfrom mmcv.runner import auto_fp16\nfrom torch import nn as n"
},
{
"path": "mmdet3d/models/backbones/resnet.py",
"chars": 2987,
"preview": "# Copyright (c) Phigent Robotics. All rights reserved.\n\nimport torch.utils.checkpoint as checkpoint\nfrom torch import nn"
},
{
"path": "mmdet3d/models/backbones/second.py",
"chars": 3245,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport warnings\n\nfrom mmcv.cnn import build_conv_layer, build_norm_layer"
},
{
"path": "mmdet3d/models/backbones/swin.py",
"chars": 37205,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport warnings\nfrom copy import deepcopy\n\nimport torch\nimport torch.nn "
},
{
"path": "mmdet3d/models/backbones/vovnet.py",
"chars": 12917,
"preview": "# ------------------------------------------------------------------------\n# Copyright (c) 2022 megvii-model. All Rights"
},
{
"path": "mmdet3d/models/backbones/vovnet2.py",
"chars": 12001,
"preview": "from collections import OrderedDict\nfrom mmcv.runner import BaseModule\nfrom mmdet.models.builder import BACKBONES\nimport"
},
{
"path": "mmdet3d/models/builder.py",
"chars": 4316,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport warnings\n\nfrom mmcv.cnn import MODELS as MMCV_MODELS\nfrom mmcv.ut"
},
{
"path": "mmdet3d/models/decode_heads/__init__.py",
"chars": 216,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nfrom .dgcnn_head import DGCNNHead\nfrom .paconv_head import PAConvHead\nfr"
}
]
// ... and 281 more files (download for full content)
About this extraction
This page contains the full source code of the NVlabs/BEV-Planner GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 481 files (4.2 MB), approximately 1.1M tokens, and a symbol index with 3065 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.