Showing preview only (4,385K chars total). Download the full file or copy to clipboard to get everything.
Repository: megvii-research/Far3D
Branch: main
Commit: 5efb9d73a246
Files: 95
Total size: 4.2 MB
Directory structure:
gitextract_puxntax1/
├── LICENSE
├── README.md
├── docs/
│ └── get_started.md
├── projects/
│ ├── configs/
│ │ └── far3d.py
│ └── mmdet3d_plugin/
│ ├── __init__.py
│ ├── core/
│ │ ├── apis/
│ │ │ ├── __init__.py
│ │ │ ├── mmdet_train.py
│ │ │ ├── test.py
│ │ │ └── train.py
│ │ ├── bbox/
│ │ │ ├── assigners/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── hungarian_assigner_2d.py
│ │ │ │ └── hungarian_assigner_3d.py
│ │ │ ├── coders/
│ │ │ │ ├── __init__.py
│ │ │ │ └── nms_free_coder.py
│ │ │ ├── match_costs/
│ │ │ │ ├── __init__.py
│ │ │ │ └── match_cost.py
│ │ │ └── util.py
│ │ └── evaluation/
│ │ ├── __init__.py
│ │ └── eval_hooks.py
│ ├── datasets/
│ │ ├── __init__.py
│ │ ├── argoverse2_dataset.py
│ │ ├── argoverse2_dataset_t.py
│ │ ├── av2_eval_util.py
│ │ ├── av2_utils.py
│ │ ├── builder.py
│ │ ├── eval_recall.py
│ │ ├── nuscenes_dataset.py
│ │ ├── pipelines/
│ │ │ ├── __init__.py
│ │ │ ├── custom_pipeline.py
│ │ │ ├── formating.py
│ │ │ └── transform_3d.py
│ │ ├── samplers/
│ │ │ ├── __init__.py
│ │ │ ├── distributed_sampler.py
│ │ │ ├── group_sampler.py
│ │ │ └── sampler.py
│ │ └── summarize_metrics_av2.py
│ └── models/
│ ├── backbones/
│ │ ├── __init__.py
│ │ ├── vovnet.py
│ │ └── vovnetcp.py
│ ├── dense_heads/
│ │ ├── __init__.py
│ │ ├── farhead.py
│ │ └── yolox_head.py
│ ├── depth_predictor/
│ │ ├── __init__.py
│ │ ├── ddn_loss/
│ │ │ ├── __init__.py
│ │ │ ├── balancer.py
│ │ │ ├── ddn_loss.py
│ │ │ └── focalloss.py
│ │ └── depth_predictor.py
│ ├── detectors/
│ │ ├── __init__.py
│ │ └── far3d.py
│ ├── necks/
│ │ ├── __init__.py
│ │ ├── cp_fpn.py
│ │ └── second_fpn.py
│ └── utils/
│ ├── __init__.py
│ ├── attention.py
│ ├── deformable_aggregation.py
│ ├── detr3d_transformer.py
│ ├── grid_mask.py
│ ├── hook.py
│ ├── layer_decay_optimizer_constructor.py
│ ├── misc.py
│ ├── petr_transformer.py
│ ├── positional_encoding.py
│ ├── sparse_blocks.py
│ └── warmup_fp16_optimizer.py
├── py38.yaml
└── tools/
├── analysis_tools/
│ └── benchmark.py
├── create_data_nusc.py
├── create_infos_av2/
│ ├── create_av2_infos.py
│ └── gather_argo2_anno_feather.py
├── data_converter/
│ ├── __init__.py
│ ├── info2coco.py
│ └── nuscenes_converter.py
├── dist_test.sh
├── dist_test_visualize.sh
├── dist_train.sh
├── filter_ckpt.py
├── multi_dist_train.sh
├── slurm_test.sh
├── slurm_train.sh
├── test.py
├── test_and_visualize.py
├── train.py
├── visual/
│ ├── __init__.py
│ ├── check_img_label.py
│ ├── vis_2d.ipynb
│ ├── vis_3dpred.py
│ ├── vis_3dpred_depth_stat.py
│ ├── vis_3dpred_depth_stat2.py
│ ├── vis_attention.py
│ ├── vis_av2.py
│ ├── vis_util.py
│ └── vis_yolox.py
├── visual_nuscenes.py
└── visualize.py
================================================
FILE CONTENTS
================================================
================================================
FILE: LICENSE
================================================
Far3D
Apache License
Version 2.0, January 2004
http://www.apache.org/licenses/
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
1. Definitions.
"License" shall mean the terms and conditions for use, reproduction,
and distribution as defined by Sections 1 through 9 of this document.
"Licensor" shall mean the copyright owner or entity authorized by
the copyright owner that is granting the License.
"Legal Entity" shall mean the union of the acting entity and all
other entities that control, are controlled by, or are under common
control with that entity. For the purposes of this definition,
"control" means (i) the power, direct or indirect, to cause the
direction or management of such entity, whether by contract or
otherwise, or (ii) ownership of fifty percent (50%) or more of the
outstanding shares, or (iii) beneficial ownership of such entity.
"You" (or "Your") shall mean an individual or Legal Entity
exercising permissions granted by this License.
"Source" form shall mean the preferred form for making modifications,
including but not limited to software source code, documentation
source, and configuration files.
"Object" form shall mean any form resulting from mechanical
transformation or translation of a Source form, including but
not limited to compiled object code, generated documentation,
and conversions to other media types.
"Work" shall mean the work of authorship, whether in Source or
Object form, made available under the License, as indicated by a
copyright notice that is included in or attached to the work
(an example is provided in the Appendix below).
"Derivative Works" shall mean any work, whether in Source or Object
form, that is based on (or derived from) the Work and for which the
editorial revisions, annotations, elaborations, or other modifications
represent, as a whole, an original work of authorship. For the purposes
of this License, Derivative Works shall not include works that remain
separable from, or merely link (or bind by name) to the interfaces of,
the Work and Derivative Works thereof.
"Contribution" shall mean any work of authorship, including
the original version of the Work and any modifications or additions
to that Work or Derivative Works thereof, that is intentionally
submitted to Licensor for inclusion in the Work by the copyright owner
or by an individual or Legal Entity authorized to submit on behalf of
the copyright owner. For the purposes of this definition, "submitted"
means any form of electronic, verbal, or written communication sent
to the Licensor or its representatives, including but not limited to
communication on electronic mailing lists, source code control systems,
and issue tracking systems that are managed by, or on behalf of, the
Licensor for the purpose of discussing and improving the Work, but
excluding communication that is conspicuously marked or otherwise
designated in writing by the copyright owner as "Not a Contribution."
"Contributor" shall mean Licensor and any individual or Legal Entity
on behalf of whom a Contribution has been received by Licensor and
subsequently incorporated within the Work.
2. Grant of Copyright License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
copyright license to reproduce, prepare Derivative Works of,
publicly display, publicly perform, sublicense, and distribute the
Work and such Derivative Works in Source or Object form.
3. Grant of Patent License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
(except as stated in this section) patent license to make, have made,
use, offer to sell, sell, import, and otherwise transfer the Work,
where such license applies only to those patent claims licensable
by such Contributor that are necessarily infringed by their
Contribution(s) alone or by combination of their Contribution(s)
with the Work to which such Contribution(s) was submitted. If You
institute patent litigation against any entity (including a
cross-claim or counterclaim in a lawsuit) alleging that the Work
or a Contribution incorporated within the Work constitutes direct
or contributory patent infringement, then any patent licenses
granted to You under this License for that Work shall terminate
as of the date such litigation is filed.
4. Redistribution. You may reproduce and distribute copies of the
Work or Derivative Works thereof in any medium, with or without
modifications, and in Source or Object form, provided that You
meet the following conditions:
(a) You must give any other recipients of the Work or
Derivative Works a copy of this License; and
(b) You must cause any modified files to carry prominent notices
stating that You changed the files; and
(c) You must retain, in the Source form of any Derivative Works
that You distribute, all copyright, patent, trademark, and
attribution notices from the Source form of the Work,
excluding those notices that do not pertain to any part of
the Derivative Works; and
(d) If the Work includes a "NOTICE" text file as part of its
distribution, then any Derivative Works that You distribute must
include a readable copy of the attribution notices contained
within such NOTICE file, excluding those notices that do not
pertain to any part of the Derivative Works, in at least one
of the following places: within a NOTICE text file distributed
as part of the Derivative Works; within the Source form or
documentation, if provided along with the Derivative Works; or,
within a display generated by the Derivative Works, if and
wherever such third-party notices normally appear. The contents
of the NOTICE file are for informational purposes only and
do not modify the License. You may add Your own attribution
notices within Derivative Works that You distribute, alongside
or as an addendum to the NOTICE text from the Work, provided
that such additional attribution notices cannot be construed
as modifying the License.
You may add Your own copyright statement to Your modifications and
may provide additional or different license terms and conditions
for use, reproduction, or distribution of Your modifications, or
for any such Derivative Works as a whole, provided Your use,
reproduction, and distribution of the Work otherwise complies with
the conditions stated in this License.
5. Submission of Contributions. Unless You explicitly state otherwise,
any Contribution intentionally submitted for inclusion in the Work
by You to the Licensor shall be under the terms and conditions of
this License, without any additional terms or conditions.
Notwithstanding the above, nothing herein shall supersede or modify
the terms of any separate license agreement you may have executed
with Licensor regarding such Contributions.
6. Trademarks. This License does not grant permission to use the trade
names, trademarks, service marks, or product names of the Licensor,
except as required for reasonable and customary use in describing the
origin of the Work and reproducing the content of the NOTICE file.
7. Disclaimer of Warranty. Unless required by applicable law or
agreed to in writing, Licensor provides the Work (and each
Contributor provides its Contributions) on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
implied, including, without limitation, any warranties or conditions
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
PARTICULAR PURPOSE. You are solely responsible for determining the
appropriateness of using or redistributing the Work and assume any
risks associated with Your exercise of permissions under this License.
8. Limitation of Liability. In no event and under no legal theory,
whether in tort (including negligence), contract, or otherwise,
unless required by applicable law (such as deliberate and grossly
negligent acts) or agreed to in writing, shall any Contributor be
liable to You for damages, including any direct, indirect, special,
incidental, or consequential damages of any character arising as a
result of this License or out of the use or inability to use the
Work (including but not limited to damages for loss of goodwill,
work stoppage, computer failure or malfunction, or any and all
other commercial damages or losses), even if such Contributor
has been advised of the possibility of such damages.
9. Accepting Warranty or Additional Liability. While redistributing
the Work or Derivative Works thereof, You may choose to offer,
and charge a fee for, acceptance of support, warranty, indemnity,
or other liability obligations and/or rights consistent with this
License. However, in accepting such obligations, You may act only
on Your own behalf and on Your sole responsibility, not on behalf
of any other Contributor, and only if You agree to indemnify,
defend, and hold each Contributor harmless for any liability
incurred by, or claims asserted against, such Contributor by reason
of your accepting any such warranty or additional liability.
END OF TERMS AND CONDITIONS
Copyright (c) 2023 Megvii Inc. All rights reserved.
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
================================================
FILE: README.md
================================================
<div align="center">
<h1>Far3D</h1>
<h3> [AAAI2024] Expanding the Horizon for Surround-view 3D Object Detection </h3>
</div>
[](https://paperswithcode.com/sota/3d-object-detection-on-nuscenes-camera-only?p=far3d-expanding-the-horizon-for-surround-view)
[](https://arxiv.org/abs/2308.09616)
## Introduction
This repository is an official implementation of Far3D.

Expanding existing methods directly to cover long distances poses challenges such as heavy computation costs and unstable convergence.
To address these limitations, we proposes a novel sparse query-based framework, dubbed Far3D. By utilizing high-quality 2D object priors, we generate 3D adaptive queries that complement the 3D global queries.
To efficiently capture discriminative features across different views and scales for long-range objects, we introduce a perspective-aware aggregation module. Additionally, we propose a range-modulated 3D denoising approach to address query error propagation and mitigate convergence issues in long-range tasks.
## News
- [2023/08/01] We release the paper on [Arxiv]((https://arxiv.org/abs/2308.09616)).
- [2023/08/01] Far3D achieves comparable performance (31.6 mAP, 23.9 CDS) on long-range Argoverse2 dataset, as well as achieving SoTA performance (63.5 mAP, 68.7 NDS) on nuScenes Camera Only.
## Getting Started
Our pipeline follows [StreamPETR](https://github.com/exiawsh/StreamPETR), and you can follow [Get Started](./docs/get_started.md) step by step.
* If you have used StreamPETR before, it is easy to run Far3D without additional extensive installation.
Quick Train & Evaluation
Train the model
```angular2html
tools/dist_train.sh projects/configs/far3d.py 8 --work-dir work_dirs/far3d/
```
Evaluation
```angular2html
tools/dist_test.sh projects/configs/far3d.py work_dirs/far3d/iter_82548.pth 8 --eval bbox
```
## Results on Argoverse 2 Val Set.
| Model | Backbone | Input size | mAP | CDS | Config | Download |
| :---: | :---: | :---: | :---: | :---:| :---: | :---:|
| BEVStereo | VoV-99 | (960, 640) | 0.146 | 0.104 | -- | -- |
| SOLOFusion | VoV-99 | (960, 640) | 0.149 | 0.106 | -- | -- |
| PETR | VoV-99 | (960, 640) | 0.176 | 0.122 | -- | -- |
| Sparse4Dv2 | VoV-99 | (960, 640) | 0.189 | 0.134 | -- | -- |
| StreamPETR | VoV-99 | (960, 640) | 0.203 | 0.146| -- | -- |
| Far3D | VoV-99 | (960, 640) | **0.244** | **0.181**| [config](projects/configs/far3d.py) | [model](https://github.com/megvii-research/Far3D/releases/download/v1.0/iter_82548.pth)/[log](https://github.com/megvii-research/Far3D/releases/download/v1.0/far3d.log)|
**Notes**
- [This config](projects/configs/far3d.py) can be used to reproduce the results on Argoverse 2.
- For nuScenes version, due to the inconsistent data and evaluation processes, we do not incorporate it to this repo. One can transfer our model part to StreamPETR repo for nuScenes dataset.
## Acknowledgements
We thank these great works and open-source codebases:
* 3D Detection. [StreamPETR](https://github.com/exiawsh/StreamPETR), [MMDetection3d](https://github.com/open-mmlab/mmdetection3d), [DETR3D](https://github.com/WangYueFt/detr3d), [PETR](https://github.com/megvii-research/PETR), [BEVFormer](https://github.com/fundamentalvision/BEVFormer), [SOLOFusion](https://github.com/Divadi/SOLOFusion), [Sparse4D](https://github.com/linxuewu/Sparse4D).
## Citation
If you find Far3D is useful in your research or applications, please consider giving us a star 🌟 and citing it by the following BibTeX entry.
```bibtex
@article{jiang2023far3d,
title={Far3D: Expanding the Horizon for Surround-view 3D Object Detection},
author={Jiang, Xiaohui and Li, Shuailin and Liu, Yingfei and Wang, Shihao and Jia, Fan and Wang, Tiancai and Han, Lijin and Zhang, Xiangyu},
journal={arXiv preprint arXiv:2308.09616},
year={2023}
}
```
================================================
FILE: docs/get_started.md
================================================
# Get Started
Note our Far3D inherit from the repo of [StreamPETR](https://github.com/exiawsh/StreamPETR/), thus many parts can be used in similar style.
## 1. Setup
Please following [Setup instructions](https://github.com/exiawsh/StreamPETR/blob/main/docs/setup.md) to build environment and compile mmdet3d. We also provide detailed conda environment file [here](../py38.yaml).
**Instruction Steps**
1. Create a conda virtual environment and activate it.
2. Install PyTorch and torchvision following the official instructions.
3. Install flash-attn (optional).
4. Clone Far3D.
5. Install mmdet3d.
## 2. Data preparation
We use Argoverse 2 dataset and NuScenes dataset for experiments.
- NuScenes dataset preparation can refer to [Preparation](https://github.com/exiawsh/StreamPETR/blob/main/docs/data_preparation.md).
- Similarly, after downloading [Argoverse 2 sensor dataset](https://www.argoverse.org/av2.html#download-link), it can be processed following above pipelines and [create_av2_infos.py](../tools/create_infos_av2/create_av2_infos.py).
```angular2html
# first modify args such as split, dataset_dir.
python tools/create_infos_av2/gather_argo2_anno_feather.py
python tools/create_infos_av2/create_av2_infos.py
```
**Notes**:
- Due to the huge strorage of Argoverse 2 dataset, we read data from s3 path. If any need to load from local disk or other paths, please modify [AV2LoadMultiViewImageFromFiles](../projects/mmdet3d_plugin/datasets/pipelines/custom_pipeline.py) for your convenience.
- For Argoverse 2, its 3D labels are in ego coordinates. The ego-motion transformation refer to [Argoverse2DatasetT](projects/mmdet3d_plugin/datasets/argoverse2_dataset_t.py).
## 3. Training & Inference
Train the model
```angular2html
tools/dist_train.sh projects/configs/far3d.py 8 --work-dir work_dirs/far3d/
```
Evaluation
```angular2html
tools/dist_test.sh projects/configs/far3d.py work_dirs/far3d/iter_82548.pth 8 --eval bbox
```
* You can also refer to [StreamPETR](https://github.com/exiawsh/StreamPETR/blob/main/docs/training_inference.md) for more training recipes.
================================================
FILE: projects/configs/far3d.py
================================================
_base_ = [
'../../../mmdetection3d/configs/_base_/default_runtime.py'
]
backbone_norm_cfg = dict(type='LN', requires_grad=True)
plugin=True
plugin_dir='projects/mmdet3d_plugin/'
# If point cloud range is changed, the models should also change their point
# cloud range accordingly
point_cloud_range = [-152.4, -152.4, -5.0, 152.4, 152.4, 5.0]
voxel_size = [0.2, 0.2, 8]
img_norm_cfg = dict(
mean=[103.530, 116.280, 123.675], std=[57.375, 57.120, 58.395], to_rgb=False)
class_names = ['ARTICULATED_BUS', 'BICYCLE', 'BICYCLIST', 'BOLLARD', 'BOX_TRUCK', 'BUS',
'CONSTRUCTION_BARREL', 'CONSTRUCTION_CONE', 'DOG', 'LARGE_VEHICLE',
'MESSAGE_BOARD_TRAILER', 'MOBILE_PEDESTRIAN_CROSSING_SIGN', 'MOTORCYCLE',
'MOTORCYCLIST', 'PEDESTRIAN', 'REGULAR_VEHICLE', 'SCHOOL_BUS', 'SIGN',
'STOP_SIGN', 'STROLLER', 'TRUCK', 'TRUCK_CAB', 'VEHICULAR_TRAILER',
'WHEELCHAIR', 'WHEELED_DEVICE','WHEELED_RIDER']
num_gpus = 8
batch_size = 1
num_iters_per_epoch = 110071 // (num_gpus * batch_size)
num_epochs = 6
embed_dims=256
queue_length = 1
num_frame_losses = 1
collect_keys=['lidar2img', 'intrinsics', 'extrinsics','timestamp', 'img_timestamp', 'ego_pose', 'ego_pose_inv']
depthnet_config = {'type': 0, 'hidden_dim': 256, 'num_depth_bins': 50, 'depth_min': 1e-1, 'depth_max': 110, 'stride': 8}
input_modality = dict(
use_lidar=False,
use_camera=True,
use_radar=False,
use_map=False,
use_external=True)
model = dict(
type='Far3D',
use_grid_mask=True,
stride=[8, 16, 32, 64],
position_level=[0, 1, 2, 3],
img_backbone=dict(
type='VoVNet', ###use checkpoint to save memory
spec_name='V-99-eSE',
norm_eval=True,
frozen_stages=-1,
input_ch=3,
out_features=('stage2','stage3','stage4','stage5',)),
img_neck=dict(
type='FPN', ###remove unused parameters
start_level=1,
add_extra_convs='on_output',
relu_before_extra_convs=True,
in_channels=[256, 512, 768, 1024],
out_channels=256,
num_outs=4),
img_roi_head=dict(
type='YOLOXHeadCustom',
num_classes=26,
in_channels=256,
strides=[8, 16, 32, 64],
train_cfg=dict(assigner=dict(type='SimOTAAssigner', center_radius=2.5)),
test_cfg=dict(score_thr=0.01, nms=dict(type='nms', iou_threshold=0.65)),
pred_with_depth=True,
depthnet_config=depthnet_config,
reg_depth_level='p3',
pred_depth_var=False, # note 2d depth uncertainty
loss_depth2d=dict(type='L1Loss', loss_weight=1.0),
sample_with_score=True, # note threshold
threshold_score=0.1,
topk_proposal=None,
return_context_feat=True,
),
pts_bbox_head=dict(
type='FarHead',
num_classes=26,
in_channels=256,
num_query=644,
memory_len=1024,
topk_proposals=256,
num_propagated=256,
scalar=10, ##noise groups
noise_scale = 1.0,
dn_weight= 1.0, ##dn loss weight
split = 0.75, ###positive rate
offset=0.5,
offset_p=0.0,
num_smp_per_gt=3,
with_dn=True,
with_ego_pos=True,
add_query_from_2d=True,
pred_box_var=False, # note add box uncertainty
depthnet_config=depthnet_config,
train_use_gt_depth=True,
add_multi_depth_proposal=True,
multi_depth_config={'topk': 1, 'range_min': 30,}, # 'bin_unit': 1, 'step_num': 4,
return_bbox2d_scores=True,
return_context_feat=True,
code_size=8,
code_weights = [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0],
transformer=dict(
type='Detr3DTransformer',
decoder=dict(
type='Detr3DTransformerDecoder',
embed_dims=256,
num_layers=6,
transformerlayers=dict(
type='Detr3DTemporalDecoderLayer',
batch_first=True,
attn_cfgs=[
dict(
type='MultiheadAttention',
embed_dims=256,
num_heads=8,
dropout=0.1),
dict(
type='DeformableFeatureAggregationCuda',
embed_dims=256,
num_groups=8,
num_levels=4,
num_cams=7,
dropout=0.1,
num_pts=13,
bias=2.),
],
feedforward_channels=2048,
ffn_dropout=0.1,
with_cp=True, ###use checkpoint to save memory
operation_order=('self_attn', 'norm', 'cross_attn', 'norm',
'ffn', 'norm')),
)),
bbox_coder=dict(
type='NMSFreeCoder',
post_center_range=point_cloud_range,
pc_range=point_cloud_range,
max_num=300,
voxel_size=voxel_size,
num_classes=26),
loss_cls=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=2.0),
loss_bbox=dict(type='L1Loss', loss_weight=0.25),
loss_iou=dict(type='GIoULoss', loss_weight=0.0),),
# 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=dict(
type='HungarianAssigner3D',
cls_cost=dict(type='FocalLossCost', weight=2.0),
reg_cost=dict(type='BBox3DL1Cost', weight=0.25),
iou_cost=dict(type='IoUCost', weight=0.0), # Fake cost. This is just to make it compatible with DETR head.
pc_range=point_cloud_range),)))
dataset_type = 'Argoverse2DatasetT'
data_root = 'data/av2/'
file_client_args = dict(backend='disk')
ida_aug_conf = {
"resize_lim": (0.47, 0.55),
"final_dim": (640, 960),
"final_dim_f": (640, 720),
"bot_pct_lim": (0.0, 0.0),
"rot_lim": (0.0, 0.0),
"rand_flip": False,
}
train_pipeline = [
dict(type='AV2LoadMultiViewImageFromFiles', to_float32=True),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_bbox=True,
with_label=True, with_bbox_depth=True),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
dict(type='AV2ResizeCropFlipRotImageV2', data_aug_conf=ida_aug_conf),
dict(type='NormalizeMultiviewImage', **img_norm_cfg),
dict(type='AV2PadMultiViewImage', size='same2max'),
dict(type='AV2DownsampleQuantizeInstanceDepthmap', downsample=depthnet_config['stride'], depth_config=depthnet_config),
dict(type='PETRFormatBundle3D', class_names=class_names, collect_keys=collect_keys + ['prev_exists']),
dict(type='Collect3D', keys=['gt_bboxes_3d', 'gt_labels_3d', 'img', 'gt_bboxes', 'gt_labels', 'centers2d', 'depths', 'prev_exists'] + collect_keys,
meta_keys=('filename', 'ori_shape', 'img_shape', 'pad_shape', 'scale_factor', 'flip', 'box_mode_3d', 'box_type_3d', 'img_norm_cfg', 'scene_token', 'gt_bboxes_3d','gt_labels_3d', 'ins_depthmap', 'ins_depthmap_mask'))
]
test_pipeline = [
dict(type='AV2LoadMultiViewImageFromFiles', to_float32=True),
dict(type='AV2ResizeCropFlipRotImageV2', data_aug_conf=ida_aug_conf),
dict(type='NormalizeMultiviewImage', **img_norm_cfg),
dict(type='AV2PadMultiViewImage', size='same2max'),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='PETRFormatBundle3D',
collect_keys=collect_keys,
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['img'] + collect_keys,
meta_keys=('filename', 'ori_shape', 'img_shape','pad_shape', 'scale_factor', 'flip', 'box_mode_3d', 'box_type_3d', 'img_norm_cfg', 'scene_token'))
])
]
data = dict(
samples_per_gpu=batch_size,
workers_per_gpu=4,
train=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'av2_train_infos.pkl',
split='train',
load_interval=1,
num_frame_losses=num_frame_losses,
seq_split_num=2,
seq_mode=True,
pipeline=train_pipeline,
classes=class_names,
modality=input_modality,
collect_keys=collect_keys + ['img', 'prev_exists', 'img_metas'],
queue_length=queue_length,
test_mode=False,
use_valid_flag=False,
interval_test=True,
box_type_3d='LiDAR'),
val=dict(
type=dataset_type,
pipeline=test_pipeline,
data_root=data_root,
collect_keys=collect_keys + ['img', 'img_metas'],
queue_length=queue_length,
ann_file=data_root + 'av2_val_infos.pkl',
split='val',
load_interval=1,
classes=class_names,
modality=input_modality,
interval_test=True,),
test=dict(
type=dataset_type,
pipeline=test_pipeline,
data_root=data_root,
collect_keys=collect_keys + ['img', 'img_metas'],
queue_length=queue_length,
ann_file=data_root + 'av2_val_infos.pkl',
split='val',
load_interval=1,
classes=class_names,
modality=input_modality,
interval_test=True,),
shuffler_sampler=dict(type='InfiniteGroupEachSampleInBatchSampler'),
nonshuffler_sampler=dict(type='DistributedSampler'),
)
optimizer = dict(
type='AdamW',
lr=2e-4, # bs 8: 2e-4 || bs 16: 4e-4
paramwise_cfg=dict(
custom_keys={
'img_backbone': dict(lr_mult=0.1), # 0.5 only for Focal-PETR with R50-in1k pretrained weights
}),
weight_decay=0.01)
optimizer_config = dict(type='Fp16OptimizerHook', loss_scale='dynamic', grad_clip=dict(max_norm=35, norm_type=2))
# learning policy
lr_config = dict(
policy='CosineAnnealing',
warmup='linear',
warmup_iters=500,
warmup_ratio=1.0 / 3,
min_lr_ratio=1e-3,
)
evaluation = dict(interval=num_iters_per_epoch*num_epochs, pipeline=test_pipeline)
find_unused_parameters=False #### when use checkpoint, find_unused_parameters must be False
checkpoint_config = dict(interval=num_iters_per_epoch, max_keep_ckpts=1)
custom_hooks = [dict(type="UseGtDepthHook", stop_gt_depth_iter=22000)]
runner = dict(
type='IterBasedRunner', max_iters=num_epochs * num_iters_per_epoch)
load_from='ckpts/fcos3d_vovnet_imgbackbone-remapped.pth'
resume_from=None
# fps: 6.4 img / s
================================================
FILE: projects/mmdet3d_plugin/__init__.py
================================================
from .core.bbox.assigners.hungarian_assigner_3d import HungarianAssigner3D
from .core.bbox.coders.nms_free_coder import NMSFreeCoder
from .core.bbox.match_costs import BBox3DL1Cost
from .datasets import CustomNuScenesDataset, Argoverse2DatasetT
from .datasets.pipelines import *
from .models.dense_heads import *
from .models.detectors import *
from .models.necks import *
from .models.backbones import *
================================================
FILE: projects/mmdet3d_plugin/core/apis/__init__.py
================================================
from .train import custom_train_model
from .mmdet_train import custom_train_detector
from .test import custom_multi_gpu_test
================================================
FILE: projects/mmdet3d_plugin/core/apis/mmdet_train.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Zhiqi Li
# ---------------------------------------------
# ---------------------------------------------
# Modified by Shihao Wang
# ---------------------------------------------
import random
import warnings
import numpy as np
import torch
import torch.distributed as dist
from mmcv.parallel import MMDataParallel, MMDistributedDataParallel
from mmcv.runner import (HOOKS, DistSamplerSeedHook, EpochBasedRunner,
Fp16OptimizerHook, OptimizerHook, build_optimizer,
build_runner, get_dist_info)
from mmcv.utils import build_from_cfg
from mmdet.core import EvalHook
from mmdet.datasets import (build_dataset,
replace_ImageToTensor)
from mmdet.utils import get_root_logger
import time
import os.path as osp
from projects.mmdet3d_plugin.datasets.builder import build_dataloader
from projects.mmdet3d_plugin.core.evaluation.eval_hooks import CustomDistEvalHook
from projects.mmdet3d_plugin.datasets import custom_build_dataset
def custom_train_detector(model,
dataset,
cfg,
distributed=False,
validate=False,
timestamp=None,
eval_model=None,
meta=None):
logger = get_root_logger(cfg.log_level)
# prepare data loaders
dataset = dataset if isinstance(dataset, (list, tuple)) else [dataset]
#assert len(dataset)==1s
if 'imgs_per_gpu' in cfg.data:
logger.warning('"imgs_per_gpu" is deprecated in MMDet V2.0. '
'Please use "samples_per_gpu" instead')
if 'samples_per_gpu' in cfg.data:
logger.warning(
f'Got "imgs_per_gpu"={cfg.data.imgs_per_gpu} and '
f'"samples_per_gpu"={cfg.data.samples_per_gpu}, "imgs_per_gpu"'
f'={cfg.data.imgs_per_gpu} is used in this experiments')
else:
logger.warning(
'Automatically set "samples_per_gpu"="imgs_per_gpu"='
f'{cfg.data.imgs_per_gpu} in this experiments')
cfg.data.samples_per_gpu = cfg.data.imgs_per_gpu
data_loaders = [
build_dataloader(
ds,
cfg.data.samples_per_gpu,
cfg.data.workers_per_gpu,
# cfg.gpus will be ignored if distributed
len(cfg.gpu_ids),
dist=distributed,
seed=cfg.seed,
shuffler_sampler=cfg.data.shuffler_sampler, # dict(type='DistributedGroupSampler'),
nonshuffler_sampler=cfg.data.nonshuffler_sampler, # dict(type='DistributedSampler'),
runner_type=cfg.runner,
) for ds in dataset
]
# put model on gpus
if distributed:
find_unused_parameters = cfg.get('find_unused_parameters', False)
# Sets the `find_unused_parameters` parameter in
# torch.nn.parallel.DistributedDataParallel
model = MMDistributedDataParallel(
model.cuda(),
device_ids=[torch.cuda.current_device()],
broadcast_buffers=False,
find_unused_parameters=find_unused_parameters)
if eval_model is not None:
eval_model = MMDistributedDataParallel(
eval_model.cuda(),
device_ids=[torch.cuda.current_device()],
broadcast_buffers=False,
find_unused_parameters=find_unused_parameters)
else:
model = MMDataParallel(
model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids)
if eval_model is not None:
eval_model = MMDataParallel(
eval_model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids)
# build runner
optimizer = build_optimizer(model, cfg.optimizer)
if 'runner' not in cfg:
cfg.runner = {
'type': 'EpochBasedRunner',
'max_epochs': cfg.total_epochs
}
warnings.warn(
'config is now expected to have a `runner` section, '
'please set `runner` in your config.', UserWarning)
else:
if 'total_epochs' in cfg:
assert cfg.total_epochs == cfg.runner.max_epochs
if eval_model is not None:
runner = build_runner(
cfg.runner,
default_args=dict(
model=model,
eval_model=eval_model,
optimizer=optimizer,
work_dir=cfg.work_dir,
logger=logger,
meta=meta))
else:
runner = build_runner(
cfg.runner,
default_args=dict(
model=model,
optimizer=optimizer,
work_dir=cfg.work_dir,
logger=logger,
meta=meta))
# an ugly workaround to make .log and .log.json filenames the same
runner.timestamp = timestamp
# fp16 setting
fp16_cfg = cfg.get('fp16', None)
if fp16_cfg is not None:
optimizer_config = Fp16OptimizerHook(
**cfg.optimizer_config, **fp16_cfg, distributed=distributed)
elif distributed and 'type' not in cfg.optimizer_config:
optimizer_config = OptimizerHook(**cfg.optimizer_config)
else:
optimizer_config = cfg.optimizer_config
# register hooks
runner.register_training_hooks(cfg.lr_config, optimizer_config,
cfg.checkpoint_config, cfg.log_config,
cfg.get('momentum_config', None))
# register profiler hook
#trace_config = dict(type='tb_trace', dir_name='work_dir')
#profiler_config = dict(on_trace_ready=trace_config)
#runner.register_profiler_hook(profiler_config)
if distributed:
if isinstance(runner, EpochBasedRunner):
runner.register_hook(DistSamplerSeedHook())
# register eval hooks
if validate:
# Support batch_size > 1 in validation
val_samples_per_gpu = cfg.data.val.pop('samples_per_gpu', 1)
if val_samples_per_gpu > 1:
assert False
# Replace 'ImageToTensor' to 'DefaultFormatBundle'
cfg.data.val.pipeline = replace_ImageToTensor(
cfg.data.val.pipeline)
val_dataset = custom_build_dataset(cfg.data.val, dict(test_mode=True))
val_dataloader = build_dataloader(
val_dataset,
samples_per_gpu=val_samples_per_gpu,
workers_per_gpu=cfg.data.workers_per_gpu,
dist=distributed,
shuffle=False,
shuffler_sampler=cfg.data.shuffler_sampler, # dict(type='DistributedGroupSampler'),
nonshuffler_sampler=cfg.data.nonshuffler_sampler, # dict(type='DistributedSampler'),
)
eval_cfg = cfg.get('evaluation', {})
eval_cfg['by_epoch'] = cfg.runner['type'] != 'IterBasedRunner'
eval_cfg['jsonfile_prefix'] = osp.join('val', cfg.work_dir, time.ctime().replace(' ','_').replace(':','_'))
eval_hook = CustomDistEvalHook if distributed else EvalHook
runner.register_hook(eval_hook(val_dataloader, **eval_cfg))
# user-defined hooks
if cfg.get('custom_hooks', None):
custom_hooks = cfg.custom_hooks
assert isinstance(custom_hooks, list), \
f'custom_hooks expect list type, but got {type(custom_hooks)}'
for hook_cfg in cfg.custom_hooks:
assert isinstance(hook_cfg, dict), \
'Each item in custom_hooks expects dict type, but got ' \
f'{type(hook_cfg)}'
hook_cfg = hook_cfg.copy()
priority = hook_cfg.pop('priority', 'NORMAL')
hook = build_from_cfg(hook_cfg, HOOKS)
runner.register_hook(hook, priority=priority)
if cfg.resume_from:
runner.resume(cfg.resume_from)
# runner.resume(cfg.resume_from, resume_optimizer=cfg.get('resume_optimizer', True))
elif cfg.load_from:
runner.load_checkpoint(cfg.load_from)
runner.run(data_loaders, cfg.workflow)
================================================
FILE: projects/mmdet3d_plugin/core/apis/test.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Zhiqi Li
# ---------------------------------------------
import os.path as osp
import pickle
import shutil
import tempfile
import time
import mmcv
import torch
import torch.distributed as dist
from mmcv.image import tensor2imgs
from mmcv.runner import get_dist_info
from mmdet.core import encode_mask_results
import mmcv
import numpy as np
import pycocotools.mask as mask_util
def custom_encode_mask_results(mask_results):
"""Encode bitmap mask to RLE code. Semantic Masks only
Args:
mask_results (list | tuple[list]): bitmap mask results.
In mask scoring rcnn, mask_results is a tuple of (segm_results,
segm_cls_score).
Returns:
list | tuple: RLE encoded mask.
"""
cls_segms = mask_results
num_classes = len(cls_segms)
encoded_mask_results = []
for i in range(len(cls_segms)):
encoded_mask_results.append(
mask_util.encode(
np.array(
cls_segms[i][:, :, np.newaxis], order='F',
dtype='uint8'))[0]) # encoded with RLE
return [encoded_mask_results]
def custom_multi_gpu_test(model, data_loader, tmpdir=None, gpu_collect=False):
"""Test model with multiple gpus.
This method tests model with multiple gpus and collects the results
under two different modes: gpu and cpu modes. By setting 'gpu_collect=True'
it encodes results to gpu tensors and use gpu communication for results
collection. On cpu mode it saves the results on different gpus to 'tmpdir'
and collects them by the rank 0 worker.
Args:
model (nn.Module): Model to be tested.
data_loader (nn.Dataloader): Pytorch data loader.
tmpdir (str): Path of directory to save the temporary results from
different gpus under cpu mode.
gpu_collect (bool): Option to use either gpu or cpu to collect results.
Returns:
list: The prediction results.
"""
model.eval()
bbox_results = []
mask_results = []
dataset = data_loader.dataset
rank, world_size = get_dist_info()
if rank == 0:
prog_bar = mmcv.ProgressBar(len(dataset))
time.sleep(2) # This line can prevent deadlock problem in some cases.
have_mask = False
for i, data in enumerate(data_loader):
with torch.no_grad():
result = model(return_loss=False, rescale=True, **data)
# encode mask results
if isinstance(result, dict):
if 'bbox_results' in result.keys():
bbox_result = result['bbox_results']
batch_size = len(result['bbox_results'])
bbox_results.extend(bbox_result)
if 'mask_results' in result.keys() and result['mask_results'] is not None:
mask_result = custom_encode_mask_results(result['mask_results'])
mask_results.extend(mask_result)
have_mask = True
else:
batch_size = len(result)
bbox_results.extend(result)
#if isinstance(result[0], tuple):
# assert False, 'this code is for instance segmentation, which our code will not utilize.'
# result = [(bbox_results, encode_mask_results(mask_results))
# for bbox_results, mask_results in result]
if rank == 0:
for _ in range(batch_size * world_size):
prog_bar.update()
# collect results from all ranks
if gpu_collect:
bbox_results = collect_results_gpu(bbox_results, len(dataset))
if have_mask:
mask_results = collect_results_gpu(mask_results, len(dataset))
else:
mask_results = None
else:
bbox_results = collect_results_cpu(bbox_results, len(dataset), tmpdir)
tmpdir = tmpdir+'_mask' if tmpdir is not None else None
if have_mask:
mask_results = collect_results_cpu(mask_results, len(dataset), tmpdir)
else:
mask_results = None
if mask_results is None:
return bbox_results
return {'bbox_results': bbox_results, 'mask_results': mask_results}
def collect_results_cpu(result_part, size, tmpdir=None):
rank, world_size = get_dist_info()
# create a tmp dir if it is not specified
if tmpdir is None:
MAX_LEN = 512
# 32 is whitespace
dir_tensor = torch.full((MAX_LEN, ),
32,
dtype=torch.uint8,
device='cuda')
if rank == 0:
mmcv.mkdir_or_exist('.dist_test')
tmpdir = tempfile.mkdtemp(dir='.dist_test')
tmpdir = torch.tensor(
bytearray(tmpdir.encode()), dtype=torch.uint8, device='cuda')
dir_tensor[:len(tmpdir)] = tmpdir
dist.broadcast(dir_tensor, 0)
tmpdir = dir_tensor.cpu().numpy().tobytes().decode().rstrip()
else:
mmcv.mkdir_or_exist(tmpdir)
# dump the part result to the dir
mmcv.dump(result_part, osp.join(tmpdir, f'part_{rank}.pkl'))
dist.barrier()
# collect all parts
if rank != 0:
return None
else:
# load results of all parts from tmp dir
part_list = []
for i in range(world_size):
part_file = osp.join(tmpdir, f'part_{i}.pkl')
part_list.append(mmcv.load(part_file))
# sort the results
ordered_results = []
'''
bacause we change the sample of the evaluation stage to make sure that each gpu will handle continuous sample,
'''
#for res in zip(*part_list):
for res in part_list:
ordered_results.extend(list(res))
# the dataloader may pad some samples
ordered_results = ordered_results[:size]
# remove tmp dir
shutil.rmtree(tmpdir)
return ordered_results
def collect_results_gpu(result_part, size):
collect_results_cpu(result_part, size)
================================================
FILE: projects/mmdet3d_plugin/core/apis/train.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Zhiqi Li
# ---------------------------------------------
# ---------------------------------------------
# Modified by Shihao Wang
# ---------------------------------------------
from .mmdet_train import custom_train_detector
from mmseg.apis import train_segmentor
from mmdet.apis import train_detector
def custom_train_model(model,
dataset,
cfg,
distributed=False,
validate=False,
timestamp=None,
eval_model=None,
meta=None):
"""A function wrapper for launching model training according to cfg.
Because we need different eval_hook in runner. Should be deprecated in the
future.
"""
if cfg.model.type in ['EncoderDecoder3D']:
assert False
else:
custom_train_detector(
model,
dataset,
cfg,
distributed=distributed,
validate=validate,
timestamp=timestamp,
eval_model=eval_model,
meta=meta)
def train_model(model,
dataset,
cfg,
distributed=False,
validate=False,
timestamp=None,
meta=None):
"""A function wrapper for launching model training according to cfg.
Because we need different eval_hook in runner. Should be deprecated in the
future.
"""
if cfg.model.type in ['EncoderDecoder3D']:
train_segmentor(
model,
dataset,
cfg,
distributed=distributed,
validate=validate,
timestamp=timestamp,
meta=meta)
else:
train_detector(
model,
dataset,
cfg,
distributed=distributed,
validate=validate,
timestamp=timestamp,
meta=meta)
================================================
FILE: projects/mmdet3d_plugin/core/bbox/assigners/__init__.py
================================================
from .hungarian_assigner_3d import HungarianAssigner3D
from .hungarian_assigner_3d import HungarianAssigner3DPolar
from .hungarian_assigner_2d import HungarianAssigner2D
================================================
FILE: projects/mmdet3d_plugin/core/bbox/assigners/hungarian_assigner_2d.py
================================================
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Shihao Wang
# ---------------------------------------------
import torch
from mmdet.core.bbox.builder import BBOX_ASSIGNERS
from mmdet.core.bbox.assigners import AssignResult
from mmdet.core.bbox.assigners import BaseAssigner
from mmdet.core.bbox.match_costs import build_match_cost
from mmdet.core import bbox_cxcywh_to_xyxy
try:
from scipy.optimize import linear_sum_assignment
except ImportError:
linear_sum_assignment = None
@BBOX_ASSIGNERS.register_module()
class HungarianAssigner2D(BaseAssigner):
"""Computes one-to-one matching between predictions and ground truth.
This class computes an assignment between the targets and the predictions
based on the costs. The costs are weighted sum of three components:
classification cost, regression L1 cost and regression iou cost. The
targets don't include the no_object, so generally there are more
predictions than targets. After the one-to-one matching, the un-matched
are treated as backgrounds. Thus each query prediction will be assigned
with `0` or a positive integer indicating the ground truth index:
- 0: negative sample, no assigned gt
- positive integer: positive sample, index (1-based) of assigned gt
Args:
cls_weight (int | float, optional): The scale factor for classification
cost. Default 1.0.
bbox_weight (int | float, optional): The scale factor for regression
L1 cost. Default 1.0.
iou_weight (int | float, optional): The scale factor for regression
iou cost. Default 1.0.
iou_calculator (dict | optional): The config for the iou calculation.
Default type `BboxOverlaps2D`.
iou_mode (str | optional): "iou" (intersection over union), "iof"
(intersection over foreground), or "giou" (generalized
intersection over union). Default "giou".
"""
def __init__(self,
cls_cost=dict(type='ClassificationCost', weight=1.),
reg_cost=dict(type='BBoxL1Cost', weight=1.0),
iou_cost=dict(type='IoUCost', iou_mode='giou', weight=1.0),
centers2d_cost=dict(type='BBox3DL1Cost', weight=1.0)):
self.cls_cost = build_match_cost(cls_cost)
self.reg_cost = build_match_cost(reg_cost)
self.iou_cost = build_match_cost(iou_cost)
self.centers2d_cost = build_match_cost(centers2d_cost)
def assign(self,
bbox_pred,
cls_pred,
pred_centers2d,
gt_bboxes,
gt_labels,
centers2d,
img_meta,
gt_bboxes_ignore=None,
eps=1e-7):
"""Computes one-to-one matching based on the weighted costs.
This method assign each query prediction to a ground truth or
background. The `assigned_gt_inds` with -1 means don't care,
0 means negative sample, and positive number is the index (1-based)
of assigned gt.
The assignment is done in the following steps, the order matters.
1. assign every prediction to -1
2. compute the weighted costs
3. do Hungarian matching on CPU based on the costs
4. assign all to 0 (background) first, then for each matched pair
between predictions and gts, treat this prediction as foreground
and assign the corresponding gt index (plus 1) to it.
Args:
bbox_pred (Tensor): Predicted boxes with normalized coordinates
(cx, cy, w, h), which are all in range [0, 1]. Shape
[num_query, 4].
cls_pred (Tensor): Predicted classification logits, shape
[num_query, num_class].
gt_bboxes (Tensor): Ground truth boxes with unnormalized
coordinates (x1, y1, x2, y2). Shape [num_gt, 4].
gt_labels (Tensor): Label of `gt_bboxes`, shape (num_gt,).
img_meta (dict): Meta information for current image.
gt_bboxes_ignore (Tensor, optional): Ground truth bboxes that are
labelled as `ignored`. Default None.
eps (int | float, optional): A value added to the denominator for
numerical stability. Default 1e-7.
Returns:
:obj:`AssignResult`: The assigned result.
"""
assert gt_bboxes_ignore is None, \
'Only case when gt_bboxes_ignore is None is supported.'
num_gts, num_bboxes = gt_bboxes.size(0), bbox_pred.size(0)
# 1. assign -1 by default
assigned_gt_inds = bbox_pred.new_full((num_bboxes, ),
-1,
dtype=torch.long)
assigned_labels = bbox_pred.new_full((num_bboxes, ),
-1,
dtype=torch.long)
if num_gts == 0 or num_bboxes == 0:
# No ground truth or boxes, return empty assignment
if num_gts == 0:
# No ground truth, assign all to background
assigned_gt_inds[:] = 0
return AssignResult(
num_gts, assigned_gt_inds, None, labels=assigned_labels)
img_h, img_w, _ = img_meta['pad_shape']
factor = gt_bboxes.new_tensor([img_w, img_h, img_w,
img_h]).unsqueeze(0)
# 2. compute the weighted costs
# classification and bboxcost.
cls_cost = self.cls_cost(cls_pred, gt_labels)
# regression L1 cost
normalize_gt_bboxes = gt_bboxes / factor
reg_cost = self.reg_cost(bbox_pred, normalize_gt_bboxes)
# regression iou cost, defaultly giou is used in official DETR.
bboxes = bbox_cxcywh_to_xyxy(bbox_pred) * factor
iou_cost = self.iou_cost(bboxes, gt_bboxes)
# center2d L1 cost
normalize_centers2d = centers2d / factor[:, 0:2]
centers2d_cost = self.centers2d_cost(pred_centers2d, normalize_centers2d)
# weighted sum of above four costs
cost = cls_cost + reg_cost + iou_cost + centers2d_cost
cost = torch.nan_to_num(cost, nan=100.0, posinf=100.0, neginf=-100.0)
# 3. do Hungarian matching on CPU using linear_sum_assignment
cost = cost.detach().cpu()
if linear_sum_assignment is None:
raise ImportError('Please run "pip install scipy" '
'to install scipy first.')
matched_row_inds, matched_col_inds = linear_sum_assignment(cost)
matched_row_inds = torch.from_numpy(matched_row_inds).to(
bbox_pred.device)
matched_col_inds = torch.from_numpy(matched_col_inds).to(
bbox_pred.device)
# 4. assign backgrounds and foregrounds
# assign all indices to backgrounds first
assigned_gt_inds[:] = 0
# assign foregrounds based on matching results
assigned_gt_inds[matched_row_inds] = matched_col_inds + 1
assigned_labels[matched_row_inds] = gt_labels[matched_col_inds]
return AssignResult(
num_gts, assigned_gt_inds, None, labels=assigned_labels)
================================================
FILE: projects/mmdet3d_plugin/core/bbox/assigners/hungarian_assigner_3d.py
================================================
# ------------------------------------------------------------------------
# Modified from DETR3D (https://github.com/WangYueFt/detr3d)
# Copyright (c) 2021 Wang, Yue
# ------------------------------------------------------------------------
import torch
from mmdet.core.bbox.builder import BBOX_ASSIGNERS
from mmdet.core.bbox.assigners import AssignResult
from mmdet.core.bbox.assigners import BaseAssigner
from mmdet.core.bbox.match_costs import build_match_cost
from projects.mmdet3d_plugin.core.bbox.util import normalize_bbox, normalize_bbox_polar
try:
from scipy.optimize import linear_sum_assignment
except ImportError:
linear_sum_assignment = None
@BBOX_ASSIGNERS.register_module()
class HungarianAssigner3D(BaseAssigner):
def __init__(self,
cls_cost=dict(type='ClassificationCost', weight=1.),
reg_cost=dict(type='BBoxL1Cost', weight=1.0),
iou_cost=dict(type='IoUCost', weight=0.0),
pc_range=None):
self.cls_cost = build_match_cost(cls_cost)
self.reg_cost = build_match_cost(reg_cost)
self.iou_cost = build_match_cost(iou_cost)
self.pc_range = pc_range
def assign(self,
bbox_pred,
cls_pred,
gt_bboxes,
gt_labels,
gt_bboxes_ignore=None,
code_weights=None,
with_velo=False,
eps=1e-7):
assert gt_bboxes_ignore is None, \
'Only case when gt_bboxes_ignore is None is supported.'
num_gts, num_bboxes = gt_bboxes.size(0), bbox_pred.size(0)
# 1. assign -1 by default
assigned_gt_inds = bbox_pred.new_full((num_bboxes, ),
-1,
dtype=torch.long)
assigned_labels = bbox_pred.new_full((num_bboxes, ),
-1,
dtype=torch.long)
if num_gts == 0 or num_bboxes == 0:
# No ground truth or boxes, return empty assignment
if num_gts == 0:
# No ground truth, assign all to background
assigned_gt_inds[:] = 0
return AssignResult(
num_gts, assigned_gt_inds, None, labels=assigned_labels)
# 2. compute the weighted costs
# classification and bboxcost.
cls_cost = self.cls_cost(cls_pred, gt_labels)
# regression L1 cost
normalized_gt_bboxes = normalize_bbox(gt_bboxes, self.pc_range)
if code_weights is not None:
bbox_pred = bbox_pred * code_weights
normalized_gt_bboxes = normalized_gt_bboxes * code_weights
if with_velo:
reg_cost = self.reg_cost(bbox_pred, normalized_gt_bboxes)
else:
reg_cost = self.reg_cost(bbox_pred[:, :8], normalized_gt_bboxes[:, :8])
# weighted sum of above two costs
cost = cls_cost + reg_cost
# 3. do Hungarian matching on CPU using linear_sum_assignment
cost = cost.detach().cpu()
if linear_sum_assignment is None:
raise ImportError('Please run "pip install scipy" '
'to install scipy first.')
cost = torch.nan_to_num(cost, nan=100.0, posinf=100.0, neginf=-100.0)
matched_row_inds, matched_col_inds = linear_sum_assignment(cost)
matched_row_inds = torch.from_numpy(matched_row_inds).to(
bbox_pred.device)
matched_col_inds = torch.from_numpy(matched_col_inds).to(
bbox_pred.device)
# 4. assign backgrounds and foregrounds
# assign all indices to backgrounds first
assigned_gt_inds[:] = 0
# assign foregrounds based on matching results
assigned_gt_inds[matched_row_inds] = matched_col_inds + 1
assigned_labels[matched_row_inds] = gt_labels[matched_col_inds]
return AssignResult(
num_gts, assigned_gt_inds, None, labels=assigned_labels)
@BBOX_ASSIGNERS.register_module()
class HungarianAssigner3DPolar(BaseAssigner):
def __init__(self,
cls_cost=dict(type='ClassificationCost', weight=1.),
reg_cost=dict(type='BBoxL1Cost', weight=1.0),
iou_cost=dict(type='IoUCost', weight=0.0),
pc_range=None):
self.cls_cost = build_match_cost(cls_cost)
self.reg_cost = build_match_cost(reg_cost)
self.iou_cost = build_match_cost(iou_cost)
self.pc_range = pc_range
def assign(self,
bbox_pred,
cls_pred,
gt_bboxes,
gt_labels,
gt_bboxes_ignore=None,
code_weights=None,
with_velo=False,
eps=1e-7):
assert gt_bboxes_ignore is None, \
'Only case when gt_bboxes_ignore is None is supported.'
num_gts, num_bboxes = gt_bboxes.size(0), bbox_pred.size(0)
# 1. assign -1 by default
assigned_gt_inds = bbox_pred.new_full((num_bboxes, ),
-1,
dtype=torch.long)
assigned_labels = bbox_pred.new_full((num_bboxes, ),
-1,
dtype=torch.long)
if num_gts == 0 or num_bboxes == 0:
# No ground truth or boxes, return empty assignment
if num_gts == 0:
# No ground truth, assign all to background
assigned_gt_inds[:] = 0
return AssignResult(
num_gts, assigned_gt_inds, None, labels=assigned_labels)
# 2. compute the weighted costs
# classification and bboxcost.
cls_cost = self.cls_cost(cls_pred, gt_labels)
# regression L1 cost
normalized_gt_bboxes = normalize_bbox_polar(gt_bboxes, self.pc_range)
if code_weights is not None:
bbox_pred = bbox_pred * code_weights
normalized_gt_bboxes = normalized_gt_bboxes * code_weights
if with_velo:
reg_cost = self.reg_cost(bbox_pred, normalized_gt_bboxes)
else:
reg_cost = self.reg_cost(bbox_pred[:, :8], normalized_gt_bboxes[:, :8])
# weighted sum of above two costs
cost = cls_cost + reg_cost
# 3. do Hungarian matching on CPU using linear_sum_assignment
cost = cost.detach().cpu()
if linear_sum_assignment is None:
raise ImportError('Please run "pip install scipy" '
'to install scipy first.')
cost = torch.nan_to_num(cost, nan=100.0, posinf=100.0, neginf=-100.0)
matched_row_inds, matched_col_inds = linear_sum_assignment(cost)
matched_row_inds = torch.from_numpy(matched_row_inds).to(
bbox_pred.device)
matched_col_inds = torch.from_numpy(matched_col_inds).to(
bbox_pred.device)
# 4. assign backgrounds and foregrounds
# assign all indices to backgrounds first
assigned_gt_inds[:] = 0
# assign foregrounds based on matching results
assigned_gt_inds[matched_row_inds] = matched_col_inds + 1
assigned_labels[matched_row_inds] = gt_labels[matched_col_inds]
return AssignResult(
num_gts, assigned_gt_inds, None, labels=assigned_labels)
================================================
FILE: projects/mmdet3d_plugin/core/bbox/coders/__init__.py
================================================
from .nms_free_coder import NMSFreeCoder, NMSFreeCoderPolar
================================================
FILE: projects/mmdet3d_plugin/core/bbox/coders/nms_free_coder.py
================================================
import torch
from mmdet.core.bbox import BaseBBoxCoder
from mmdet.core.bbox.builder import BBOX_CODERS
from projects.mmdet3d_plugin.core.bbox.util import denormalize_bbox, denormalize_bbox_polar
@BBOX_CODERS.register_module()
class NMSFreeCoder(BaseBBoxCoder):
"""Bbox coder for NMS-free detector.
Args:
pc_range (list[float]): Range of point cloud.
post_center_range (list[float]): Limit of the center.
Default: None.
max_num (int): Max number to be kept. Default: 100.
score_threshold (float): Threshold to filter boxes based on score.
Default: None.
code_size (int): Code size of bboxes. Default: 9
"""
def __init__(self,
pc_range,
voxel_size=None,
post_center_range=None,
max_num=100,
score_threshold=None,
num_classes=10):
self.pc_range = pc_range
self.voxel_size = voxel_size
self.post_center_range = post_center_range
self.max_num = max_num
self.score_threshold = score_threshold
self.num_classes = num_classes
def encode(self):
pass
def decode_single(self, cls_scores, bbox_preds):
"""Decode bboxes.
Args:
cls_scores (Tensor): Outputs from the classification head, \
shape [num_query, cls_out_channels]. Note \
cls_out_channels should includes background.
bbox_preds (Tensor): Outputs from the regression \
head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \
Shape [num_query, 9].
Returns:
list[dict]: Decoded boxes.
"""
max_num = self.max_num
cls_scores = cls_scores.sigmoid()
scores, indexs = cls_scores.view(-1).topk(max_num)
labels = indexs % self.num_classes
bbox_index = torch.div(indexs, self.num_classes, rounding_mode='floor')
bbox_preds = bbox_preds[bbox_index]
final_box_preds = denormalize_bbox(bbox_preds, self.pc_range)
final_scores = scores
final_preds = labels
# use score threshold
if self.score_threshold is not None:
thresh_mask = final_scores >= self.score_threshold
if self.post_center_range is not None:
self.post_center_range = torch.tensor(self.post_center_range, device=scores.device)
mask = (final_box_preds[..., :3] >=
self.post_center_range[:3]).all(1)
mask &= (final_box_preds[..., :3] <=
self.post_center_range[3:]).all(1)
if self.score_threshold:
mask &= thresh_mask
boxes3d = final_box_preds[mask]
scores = final_scores[mask]
labels = final_preds[mask]
predictions_dict = {
'bboxes': boxes3d,
'scores': scores,
'labels': labels,
}
else:
raise NotImplementedError(
'Need to reorganize output as a batch, only '
'support post_center_range is not None for now!')
return predictions_dict
def decode(self, preds_dicts):
"""Decode bboxes.
Args:
all_cls_scores (Tensor): Outputs from the classification head, \
shape [nb_dec, bs, num_query, cls_out_channels]. Note \
cls_out_channels should includes background.
all_bbox_preds (Tensor): Sigmoid outputs from the regression \
head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \
Shape [nb_dec, bs, num_query, 9].
Returns:
list[dict]: Decoded boxes.
"""
all_cls_scores = preds_dicts['all_cls_scores'][-1]
all_bbox_preds = preds_dicts['all_bbox_preds'][-1]
batch_size = all_cls_scores.size()[0]
predictions_list = []
for i in range(batch_size):
predictions_list.append(self.decode_single(all_cls_scores[i], all_bbox_preds[i]))
return predictions_list
@BBOX_CODERS.register_module()
class NMSFreeCoderPolar(BaseBBoxCoder):
"""Bbox coder for NMS-free detector.
Args:
pc_range (list[float]): Range of point cloud.
post_center_range (list[float]): Limit of the center.
Default: None.
max_num (int): Max number to be kept. Default: 100.
score_threshold (float): Threshold to filter boxes based on score.
Default: None.
code_size (int): Code size of bboxes. Default: 9
"""
def __init__(self,
pc_range,
voxel_size=None,
post_center_range=None,
max_num=100,
score_threshold=None,
num_classes=10):
self.pc_range = pc_range
self.voxel_size = voxel_size
self.post_center_range = post_center_range
self.max_num = max_num
self.score_threshold = score_threshold
self.num_classes = num_classes
def encode(self):
pass
def decode_single(self, cls_scores, bbox_preds):
"""Decode bboxes.
Args:
cls_scores (Tensor): Outputs from the classification head, \
shape [num_query, cls_out_channels]. Note \
cls_out_channels should includes background.
bbox_preds (Tensor): Outputs from the regression \
head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \
Shape [num_query, 9].
Returns:
list[dict]: Decoded boxes.
"""
max_num = self.max_num
cls_scores = cls_scores.sigmoid()
scores, indexs = cls_scores.view(-1).topk(max_num)
labels = indexs % self.num_classes
bbox_index = torch.div(indexs, self.num_classes, rounding_mode='floor')
bbox_preds = bbox_preds[bbox_index]
final_box_preds = denormalize_bbox_polar(bbox_preds, self.pc_range)
final_scores = scores
final_preds = labels
# use score threshold
if self.score_threshold is not None:
thresh_mask = final_scores >= self.score_threshold
if self.post_center_range is not None:
self.post_center_range = torch.tensor(self.post_center_range, device=scores.device)
mask = (final_box_preds[..., :3] >=
self.post_center_range[:3]).all(1)
mask &= (final_box_preds[..., :3] <=
self.post_center_range[3:]).all(1)
if self.score_threshold:
mask &= thresh_mask
boxes3d = final_box_preds[mask]
scores = final_scores[mask]
labels = final_preds[mask]
predictions_dict = {
'bboxes': boxes3d,
'scores': scores,
'labels': labels
}
else:
raise NotImplementedError(
'Need to reorganize output as a batch, only '
'support post_center_range is not None for now!')
return predictions_dict
def decode(self, preds_dicts):
"""Decode bboxes.
Args:
all_cls_scores (Tensor): Outputs from the classification head, \
shape [nb_dec, bs, num_query, cls_out_channels]. Note \
cls_out_channels should includes background.
all_bbox_preds (Tensor): Sigmoid outputs from the regression \
head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \
Shape [nb_dec, bs, num_query, 9].
Returns:
list[dict]: Decoded boxes.
"""
all_cls_scores = preds_dicts['all_cls_scores'][-1]
all_bbox_preds = preds_dicts['all_bbox_preds'][-1]
batch_size = all_cls_scores.size()[0]
predictions_list = []
for i in range(batch_size):
predictions_list.append(self.decode_single(all_cls_scores[i], all_bbox_preds[i]))
return predictions_list
================================================
FILE: projects/mmdet3d_plugin/core/bbox/match_costs/__init__.py
================================================
from mmdet.core.bbox.match_costs import build_match_cost
from .match_cost import BBox3DL1Cost
__all__ = ['build_match_cost', 'BBox3DL1Cost']
================================================
FILE: projects/mmdet3d_plugin/core/bbox/match_costs/match_cost.py
================================================
import torch
from mmdet.core.bbox.match_costs.builder import MATCH_COST
@MATCH_COST.register_module()
class BBox3DL1Cost(object):
"""BBox3DL1Cost.
Args:
weight (int | float, optional): loss_weight
"""
def __init__(self, weight=1.):
self.weight = weight
def __call__(self, bbox_pred, gt_bboxes):
"""
Args:
bbox_pred (Tensor): Predicted boxes with normalized coordinates
(cx, cy, w, h), which are all in range [0, 1]. Shape
[num_query, 4].
gt_bboxes (Tensor): Ground truth boxes with normalized
coordinates (x1, y1, x2, y2). Shape [num_gt, 4].
Returns:
torch.Tensor: bbox_cost value with weight
"""
bbox_cost = torch.cdist(bbox_pred, gt_bboxes, p=1)
return bbox_cost * self.weight
================================================
FILE: projects/mmdet3d_plugin/core/bbox/util.py
================================================
import torch
import math
def normalize_bbox(bboxes, pc_range):
cx = bboxes[..., 0:1]
cy = bboxes[..., 1:2]
cz = bboxes[..., 2:3]
w = bboxes[..., 3:4].log()
l = bboxes[..., 4:5].log()
h = bboxes[..., 5:6].log()
rot = bboxes[..., 6:7]
if bboxes.size(-1) > 7:
vx = bboxes[..., 7:8]
vy = bboxes[..., 8:9]
normalized_bboxes = torch.cat(
(cx, cy, cz, w, l, h, rot.sin(), rot.cos(), vx, vy), dim=-1
)
else:
normalized_bboxes = torch.cat(
(cx, cy, cz, w, l, h, rot.sin(), rot.cos()), dim=-1
)
return normalized_bboxes
def denormalize_bbox(normalized_bboxes, pc_range):
# rotation
rot_sine = normalized_bboxes[..., 6:7]
rot_cosine = normalized_bboxes[..., 7:8]
rot = torch.atan2(rot_sine, rot_cosine)
# center in the bev
cx = normalized_bboxes[..., 0:1]
cy = normalized_bboxes[..., 1:2]
cz = normalized_bboxes[..., 2:3]
# size
w = normalized_bboxes[..., 3:4]
l = normalized_bboxes[..., 4:5]
h = normalized_bboxes[..., 5:6]
w = w.exp()
l = l.exp()
h = h.exp()
if normalized_bboxes.size(-1) > 8:
# velocity
vx = normalized_bboxes[:, 8:9]
vy = normalized_bboxes[:, 9:10]
denormalized_bboxes = torch.cat([cx, cy, cz, w, l, h, rot, vx, vy], dim=-1)
else:
denormalized_bboxes = torch.cat([cx, cy, cz, w, l, h, rot], dim=-1)
return denormalized_bboxes
def normalize_bbox_polar(bboxes, pc_range):
cx = bboxes[..., 0:1]
cy = bboxes[..., 1:2]
theta_center = torch.atan2(cx, cy)
theta_center = theta_center
radius_center = torch.sqrt(cx**2 + cy**2)
cx = theta_center
cy = radius_center
cz = bboxes[..., 2:3]
w = bboxes[..., 3:4].log()
l = bboxes[..., 4:5].log()
h = bboxes[..., 5:6].log()
rot = bboxes[..., 6:7]
if bboxes.size(-1) > 7:
vx = bboxes[..., 7:8]
vy = bboxes[..., 8:9]
normalized_bboxes = torch.cat(
(cx, cy, cz, w, l, h, rot.sin(), rot.cos(), vx, vy), dim=-1
)
else:
normalized_bboxes = torch.cat(
(cx, cy, cz, w, l, h, rot.sin(), rot.cos()), dim=-1
)
return normalized_bboxes
def denormalize_bbox_polar(normalized_bboxes, pc_range):
# rotation
rot_sine = normalized_bboxes[..., 6:7]
rot_cosine = normalized_bboxes[..., 7:8]
rot = torch.atan2(rot_sine, rot_cosine)
# center in the bev
theta_center = normalized_bboxes[..., 0:1]
radius_center = normalized_bboxes[..., 1:2]
cx = theta_center.sin() * radius_center
cy = theta_center.cos() * radius_center
cz = normalized_bboxes[..., 2:3]
# size
w = normalized_bboxes[..., 3:4]
l = normalized_bboxes[..., 4:5]
h = normalized_bboxes[..., 5:6]
w = w.exp()
l = l.exp()
h = h.exp()
if normalized_bboxes.size(-1) > 8:
# velocity
vx = normalized_bboxes[:, 8:9]
vy = normalized_bboxes[:, 9:10]
denormalized_bboxes = torch.cat([cx, cy, cz, w, l, h, rot, vx, vy], dim=-1)
else:
denormalized_bboxes = torch.cat([cx, cy, cz, w, l, h, rot], dim=-1)
return denormalized_bboxes
================================================
FILE: projects/mmdet3d_plugin/core/evaluation/__init__.py
================================================
from .eval_hooks import CustomDistEvalHook
================================================
FILE: projects/mmdet3d_plugin/core/evaluation/eval_hooks.py
================================================
# Note: Considering that MMCV's EvalHook updated its interface in V1.3.16,
# in order to avoid strong version dependency, we did not directly
# inherit EvalHook but BaseDistEvalHook.
import bisect
import os.path as osp
import mmcv
import torch.distributed as dist
from mmcv.runner import DistEvalHook as BaseDistEvalHook
from mmcv.runner import EvalHook as BaseEvalHook
from torch.nn.modules.batchnorm import _BatchNorm
from mmdet.core.evaluation.eval_hooks import DistEvalHook
def _calc_dynamic_intervals(start_interval, dynamic_interval_list):
assert mmcv.is_list_of(dynamic_interval_list, tuple)
dynamic_milestones = [0]
dynamic_milestones.extend(
[dynamic_interval[0] for dynamic_interval in dynamic_interval_list])
dynamic_intervals = [start_interval]
dynamic_intervals.extend(
[dynamic_interval[1] for dynamic_interval in dynamic_interval_list])
return dynamic_milestones, dynamic_intervals
class CustomDistEvalHook(BaseDistEvalHook):
def __init__(self, *args, dynamic_intervals=None, **kwargs):
super(CustomDistEvalHook, self).__init__(*args, **kwargs)
self.use_dynamic_intervals = dynamic_intervals is not None
if self.use_dynamic_intervals:
self.dynamic_milestones, self.dynamic_intervals = \
_calc_dynamic_intervals(self.interval, dynamic_intervals)
def _decide_interval(self, runner):
if self.use_dynamic_intervals:
progress = runner.epoch if self.by_epoch else runner.iter
step = bisect.bisect(self.dynamic_milestones, (progress + 1))
# Dynamically modify the evaluation interval
self.interval = self.dynamic_intervals[step - 1]
def before_train_epoch(self, runner):
"""Evaluate the model only at the start of training by epoch."""
self._decide_interval(runner)
super().before_train_epoch(runner)
def before_train_iter(self, runner):
self._decide_interval(runner)
super().before_train_iter(runner)
def _do_evaluate(self, runner):
"""perform evaluation and save ckpt."""
# Synchronization of BatchNorm's buffer (running_mean
# and running_var) is not supported in the DDP of pytorch,
# which may cause the inconsistent performance of models in
# different ranks, so we broadcast BatchNorm's buffers
# of rank 0 to other ranks to avoid this.
if self.broadcast_bn_buffer:
model = runner.model
for name, module in model.named_modules():
if isinstance(module,
_BatchNorm) and module.track_running_stats:
dist.broadcast(module.running_var, 0)
dist.broadcast(module.running_mean, 0)
if not self._should_evaluate(runner):
return
tmpdir = self.tmpdir
if tmpdir is None:
tmpdir = osp.join(runner.work_dir, '.eval_hook')
from projects.mmdet3d_plugin.core.apis.test import custom_multi_gpu_test # to solve circlur import
results = custom_multi_gpu_test(
runner.model,
self.dataloader,
tmpdir=tmpdir,
gpu_collect=self.gpu_collect)
if runner.rank == 0:
print('\n')
runner.log_buffer.output['eval_iter_num'] = len(self.dataloader)
key_score = self.evaluate(runner, results)
if self.save_best:
self._save_ckpt(runner, key_score)
================================================
FILE: projects/mmdet3d_plugin/datasets/__init__.py
================================================
from .nuscenes_dataset import CustomNuScenesDataset
from .builder import custom_build_dataset
from .argoverse2_dataset import Argoverse2Dataset
from .argoverse2_dataset_t import Argoverse2DatasetT
__all__ = [
'CustomNuScenesDataset'
]
================================================
FILE: projects/mmdet3d_plugin/datasets/argoverse2_dataset.py
================================================
import mmcv
import torch
import numpy as np
from .av2_utils import yaw_to_quat
from mmdet3d.core.bbox import LiDARInstance3DBoxes
from mmdet.datasets import DATASETS
from mmdet3d.datasets.custom_3d import Custom3DDataset
from av2.evaluation.detection.constants import CompetitionCategories
from pathlib import Path
from .av2_utils import DetectionCfg
from .av2_eval_util import evaluate
from av2.utils.io import read_feather
from os import path as osp
LABEL_ATTR = (
"tx_m","ty_m","tz_m","length_m","width_m","height_m","qw","qx","qy","qz",
)
@DATASETS.register_module()
class Argoverse2Dataset(Custom3DDataset):
CLASSES = tuple(x.value for x in CompetitionCategories)
def __init__(self,
ann_file,
split,
pipeline=None,
data_root=None,
classes=None,
load_interval=1,
modality=None,
box_type_3d='LiDAR',
filter_empty_gt=True,
test_mode=False,
use_valid_flag=False,
**kwargs
):
self.load_interval = load_interval
super().__init__(
data_root=data_root,
ann_file=ann_file,
pipeline=pipeline,
classes=classes,
modality=modality,
box_type_3d=box_type_3d,
filter_empty_gt=filter_empty_gt,
test_mode=test_mode,
**kwargs,
)
self.split = split
self.use_valid_flag = use_valid_flag
if self.modality is None:
self.modality = dict(
use_camera=True,
use_lidar=False,
use_radar=False,
use_map=False,
use_external=False,
)
def get_cat_ids(self, idx):
"""Get category distribution of single scene.
Args:
idx (int): Index of the data_info.
Returns:
dict[list]: for each category, if the current scene
contains such boxes, store a list containing idx,
otherwise, store empty list.
"""
info = self.data_infos[idx]
if self.use_valid_flag:
mask = info['valid_flag']
gt_names = set(info['gt3d_infos']['gt_names'][mask])
else:
gt_names = set(info['gt3d_infos']['gt_names'])
cat_ids = []
for name in gt_names:
if name in self.CLASSES:
cat_ids.append(self.cat2id[name])
return cat_ids
def load_annotations(self, ann_file):
"""Load annotations from ann_file.
Args:
ann_file (str): Path of the annotation file.
Returns:
list[dict]: List of annotations sorted by timestamps.
"""
data = mmcv.load(ann_file, file_format='pkl')
data_infos = data['infos'][::self.load_interval]
return data_infos
def get_data_info(self, index):
"""Get data info according to the given index.
Args:
index (int): Index of the sample data to get.
Returns:
dict: Data information that will be passed to the data
preprocessing pipelines. It includes the following keys:
- sample_idx (str): Sample index.
- pts_filename (str): Filename of point clouds.
- sweeps (list[dict]): Infos of sweeps.
- timestamp (float): Sample timestamp.
- img_filename (str, optional): Image filename.
- lidar2img (list[np.ndarray], optional): Transformations
from lidar to different cameras.
- ann_info (dict): Annotation info.
"""
info = self.data_infos[index]
# standard protocol modified from SECOND.Pytorch
input_dict = dict(
scene_idx=info['scene_id'],
timestamp=info['lidar_timestamp_ns'],
)
if self.modality['use_camera']:
image_paths = []
image_raw_paths = []
lidar2img_rts = []
distotions = []
intrinsics = []
extrinsics = []
img_timestamp = []
city_SE3_ego_lidar_t = info['city_SE3_ego_lidar_t']
for _, cam_info in info['cam_infos'].items():
if cam_info is None:
return None
image_path = self.data_root / cam_info['fpath']
image_paths.append(image_path)
image_raw_paths.append(cam_info['fpath'])
img_timestamp.append(cam_info['cam_timestamp_ns'])
city_SE3_ego_cam_t = cam_info['city_SE3_ego_cam_t']
ego_SE3_cam = cam_info['ego_SE3_cam']
ego_cam_t_SE3_ego_lidar_t = city_SE3_ego_cam_t.inverse().compose(city_SE3_ego_lidar_t) #ego2glo_lidar -> glo2ego_cam
cam_SE3_ego_cam_t = ego_SE3_cam.inverse().compose(ego_cam_t_SE3_ego_lidar_t) #ego -> cam
transform_matrix = np.eye(4)
transform_matrix[:3, :3] = cam_SE3_ego_cam_t.rotation
transform_matrix[:3, 3] = cam_SE3_ego_cam_t.translation
intrinsic = cam_info['intrinsics']
distotion = cam_info['cam_distortion']
viewpad = np.eye(4)
viewpad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic
ego2img = viewpad @ transform_matrix
intrinsics.append(viewpad)
extrinsics.append(transform_matrix)
lidar2img_rts.append(ego2img)
distotions.append(distotion)
input_dict.update(
dict(
img_timestamp=img_timestamp,
img_filename=image_paths,
lidar2img=lidar2img_rts,
distotion=distotions,
intrinsics=intrinsics,
extrinsics=extrinsics,
city_SE3_ego=city_SE3_ego_lidar_t,
))
if not self.test_mode:
annos = self.get_ann_info(index, input_dict)
annos.update(
dict(
bboxes=info['gt2d_infos']['gt_2dbboxes'],
labels=info['gt2d_infos']['gt_2dlabels'],
centers2d=info['gt2d_infos']['centers2d'],
depths=info['gt2d_infos']['depths'],)
)
input_dict['ann_info'] = annos
return input_dict
def get_ann_info(self, index, input_dict):
"""Get annotation info according to the given index.
Args:
index (int): Index of the annotation data to get.
Returns:
dict: Annotation information consists of the following keys:
- gt_bboxes_3d (:obj:`LiDARInstance3DBoxes`):
3D ground truth bboxes
- gt_labels_3d (np.ndarray): Labels of ground truths.
- gt_names (list[str]): Class names of ground truths.
"""
info = self.data_infos[index]['gt3d_infos']
# filter out bbox containing no points
if self.use_valid_flag:
mask = info['valid_flag']
else:
mask = info['num_interior_pts'] > 0
gt_bboxes_3d = info['gt_boxes'][mask]
gt_names_3d = np.array(info['gt_names'])[mask]
gt_labels_3d = []
for cat in gt_names_3d:
if cat in self.CLASSES:
gt_labels_3d.append(self.CLASSES.index(cat))
else:
gt_labels_3d.append(-1)
gt_labels_3d = np.array(gt_labels_3d)
gt_bboxes_3d = LiDARInstance3DBoxes(
gt_bboxes_3d, #xyzlwh+yaw
box_dim=gt_bboxes_3d.shape[-1],
origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)
anns_results = dict(
gt_bboxes_3d=gt_bboxes_3d,
gt_labels_3d=gt_labels_3d,
gt_names=gt_names_3d)
return anns_results
def evaluate(self,
results,
metric='waymo',
logger=None,
jsonfile_prefix=None,
submission_prefix=None,
show=False,
out_dir=None,
pipeline=None,
eval_range_m=None):
# from av2.evaluation.detection.utils import DetectionCfg
# from av2.evaluation.detection.eval import evaluate
# from av2.utils.io import read_all_annotations, read_feather
dts = self.format_results(results, jsonfile_prefix, submission_prefix)
val_anno_path = osp.join(self.data_root, 'val_anno.feather')
gts = read_feather(val_anno_path)
gts = gts.set_index(["log_id", "timestamp_ns"]).sort_values("category")
valid_uuids_gts = gts.index.tolist()
valid_uuids_dts = dts.index.tolist()
valid_uuids = set(valid_uuids_gts) & set(valid_uuids_dts)
gts = gts.loc[list(valid_uuids)].sort_index()
categories = set(x.value for x in CompetitionCategories)
categories &= set(gts["category"].unique().tolist()) # 交集
split_dir = Path(self.data_root) / self.split
cfg = DetectionCfg(
dataset_dir=split_dir,
categories=tuple(sorted(categories)),
eval_range_m=[0.0, 150.0] if eval_range_m is None else eval_range_m,
eval_only_roi_instances=True,
)
eval_dts, eval_gts, metrics, recall3d = evaluate(dts.reset_index(), gts.reset_index(), cfg)
valid_categories = sorted(categories) + ["AVERAGE_METRICS"]
print(metrics.loc[valid_categories])
ap_dict = {}
for index, row in metrics.iterrows():
ap_dict[index] = row.to_json()
return ap_dict
def format_results(self,
outputs,
pklfile_prefix=None,
submission_prefix=None,
):
"""Format the results to .feather file with argo2 format.
Args:
outputs (list[dict]): Testing results of the dataset.
pklfile_prefix (str | None): The prefix of pkl files. It includes
the file path and the prefix of filename, e.g., "a/b/prefix".
If not specified, a temp file will be created. Default: None.
submission_prefix (str | None): The prefix of submitted files. It
includes the file path and the prefix of filename, e.g.,
"a/b/prefix". If not specified, a temp file will be created.
Default: None.
Returns:
tuple: (result_files, tmp_dir), result_files is a dict containing
the json filepaths, tmp_dir is the temporal directory created
for saving json files when jsonfile_prefix is not specified.
"""
import pandas as pd
assert len(self.data_infos) == len(outputs)
num_samples = len(outputs)
print('\nGot {} samples'.format(num_samples))
serialized_dts_list = []
print('\nConvert predictions to Argoverse 2 format')
for i in mmcv.track_iter_progress(range(num_samples)):
out_i = outputs[i]
if 'pts_bbox' in out_i:
out_i = out_i['pts_bbox'] # for MVX-style detector
log_id = self.data_infos[i]['scene_id']
ts = self.data_infos[i]['lidar_timestamp_ns']
cat_id = out_i['labels_3d'].numpy().tolist()
category = [self.CLASSES[i].upper() for i in cat_id]
serialized_dts = pd.DataFrame(
self.box_to_av2(out_i['boxes_3d']).numpy(), columns=list(LABEL_ATTR)
)
serialized_dts["score"] = out_i['scores_3d'].numpy()
serialized_dts["log_id"] = log_id
serialized_dts["timestamp_ns"] = int(ts)
serialized_dts["category"] = category
serialized_dts_list.append(serialized_dts)
dts = (
pd.concat(serialized_dts_list)
.set_index(["log_id", "timestamp_ns"])
.sort_index()
)
dts = dts.sort_values("score", ascending=False).reset_index()
if pklfile_prefix is not None:
mmcv.mkdir_or_exist(pklfile_prefix)
if not pklfile_prefix.endswith(('.feather')):
pklfile_prefix = f'{pklfile_prefix}.feather'
dts.to_feather(pklfile_prefix)
print(f'Result is saved to {pklfile_prefix}.')
dts = dts.set_index(["log_id", "timestamp_ns"]).sort_index()
return dts
def box_to_av2(self, boxes):
cnt_xyz = boxes.gravity_center
lwh = boxes.tensor[:, [3, 4, 5]]
yaw = boxes.tensor[:, 6]
quat = yaw_to_quat(yaw)
argo_cuboid = torch.cat([cnt_xyz, lwh, quat], dim=1)
return argo_cuboid
================================================
FILE: projects/mmdet3d_plugin/datasets/argoverse2_dataset_t.py
================================================
import torch
import numpy as np
from mmdet.datasets import DATASETS
from av2.evaluation.detection.constants import CompetitionCategories
from pathlib import Path
from .argoverse2_dataset import Argoverse2Dataset
import math
from mmcv.parallel import DataContainer as DC
import random
LABEL_ATTR = (
"tx_m","ty_m","tz_m","length_m","width_m","height_m","qw","qx","qy","qz",
)
@DATASETS.register_module()
class Argoverse2DatasetT(Argoverse2Dataset):
CLASSES = tuple(x.value for x in CompetitionCategories)
def __init__(self, collect_keys, seq_mode=False, seq_split_num=1, num_frame_losses=1, queue_length=8, random_length=0, interval_test=False, *args, **kwargs):
super().__init__(*args, **kwargs)
self.queue_length = queue_length
self.collect_keys = collect_keys
self.random_length = random_length
self.num_frame_losses = num_frame_losses
self.seq_mode = seq_mode
if interval_test:
data_infos = self.data_infos
s1, s2, s3, s4, s5 = data_infos[::5], data_infos[1::5], data_infos[2::5], data_infos[3::5], data_infos[4::5]
data_infos = s1 + s2 + s3 + s4 + s5
self.data_infos = data_infos
if seq_mode:
self.num_frame_losses = 1
self.queue_length = 1
self.seq_split_num = seq_split_num
self.random_length = 0
self._set_sequence_group_flag() # Must be called after load_annotations b/c load_annotations does sorting.
def _set_sequence_group_flag(self):
"""
Set each sequence to be a different group
"""
res = []
scene_id = None
curr_sequence = -1
for idx in range(len(self.data_infos)):
if self.data_infos[idx]['scene_id'] != scene_id:
# Not first frame and # of sweeps is 0 -> new sequence
scene_id = self.data_infos[idx]['scene_id']
curr_sequence += 1
res.append(curr_sequence)
self.flag = np.array(res, dtype=np.int64)
if self.seq_split_num != 1:
if self.seq_split_num == 'all':
self.flag = np.array(range(len(self.data_infos)), dtype=np.int64)
else:
bin_counts = np.bincount(self.flag)
new_flags = []
curr_new_flag = 0
for curr_flag in range(len(bin_counts)):
curr_sequence_length = np.array(
list(range(0,
bin_counts[curr_flag],
math.ceil(bin_counts[curr_flag] / self.seq_split_num)))
+ [bin_counts[curr_flag]])
for sub_seq_idx in (curr_sequence_length[1:] - curr_sequence_length[:-1]):
for _ in range(sub_seq_idx):
new_flags.append(curr_new_flag)
curr_new_flag += 1
assert len(new_flags) == len(self.flag)
# assert len(np.bincount(new_flags)) == len(np.bincount(self.flag)) * self.seq_split_num
self.flag = np.array(new_flags, dtype=np.int64)
def prepare_train_data(self, index):
"""
Training data preparation.
Args:
index (int): Index for accessing the target data.
Returns:
dict: Training data dict of the corresponding index.
"""
queue = []
index_list = list(range(index-self.queue_length-self.random_length+1, index))
random.shuffle(index_list)
index_list = sorted(index_list[self.random_length:])
index_list.append(index)
prev_scene_token = None
for i in index_list:
i = max(0, i)
input_dict = self.get_data_info(i)
# print(len(np.bincount(self.flag)))
if input_dict is None:
return None
if not self.seq_mode:
if input_dict['scene_token'] != prev_scene_token:
input_dict.update(dict(prev_exists=False))
prev_scene_token = input_dict['scene_token']
else:
input_dict.update(dict(prev_exists=True))
self.pre_pipeline(input_dict)
example = self.pipeline(input_dict)
queue.append(example)
for k in range(self.num_frame_losses):
if self.filter_empty_gt and \
(queue[-k-1] is None or ~(queue[-k-1]['gt_labels_3d']._data != -1).any()):
return None
return self.union2one(queue)
def prepare_test_data(self, index):
"""Prepare data for testing.
Args:
index (int): Index for accessing the target data.
Returns:
dict: Testing data dict of the corresponding index.
"""
input_dict = self.get_data_info(index)
self.pre_pipeline(input_dict)
example = self.pipeline(input_dict)
return example
def union2one(self, queue):
for key in self.collect_keys:
if key != 'img_metas':
queue[-1][key] = DC(torch.stack([each[key].data for each in queue]), cpu_only=False, stack=True, pad_dims=None)
queue = queue[-1]
return queue
def get_data_info(self, index):
"""Get data info according to the given index.
Args:
index (int): Index of the sample data to get.
Returns:
dict: Data information that will be passed to the data \
preprocessing pipelines. It includes the following keys:
- sample_idx (str): Sample index.
- pts_filename (str): Filename of point clouds.
- sweeps (list[dict]): Infos of sweeps.
- timestamp (float): Sample timestamp.
- img_filename (str, optional): Image filename.
- lidar2img (list[np.ndarray], optional): Transformations \
from lidar to different cameras.
- ann_info (dict): Annotation info.
"""
info = self.data_infos[index]
# standard protocal modified from SECOND.Pytorch
city_SE3_ego = info['city_SE3_ego_lidar_t']
transform_matrix = np.eye(4)
transform_matrix[:3, :3] = city_SE3_ego.rotation
transform_matrix[:3, 3] = city_SE3_ego.translation
ego_pose = transform_matrix
ego_pose_inv = invert_matrix_egopose_numpy(ego_pose)
pts_filename = Path(self.split)/ info['scene_id'] / 'sensors' / 'lidar' / f"{info['lidar_timestamp_ns']}.feather"
input_dict = dict(
pts_filename=pts_filename,
ego_pose=ego_pose,
ego_pose_inv = ego_pose_inv,
scene_token=info['scene_id'],
timestamp=index,
lidar_timestamp=info['lidar_timestamp_ns'],
)
if self.modality['use_camera']:
image_paths = []
image_raw_paths = []
lidar2img_rts = []
intrinsics = []
extrinsics = []
img_timestamp = []
city_SE3_ego_lidar_t = info['city_SE3_ego_lidar_t']
for cam_type, cam_info in info['cam_infos'].items():
if cam_info is None:
return None
img_timestamp.append(cam_info['cam_timestamp_ns']/ 1e9)
image_path = self.data_root / cam_info['fpath']
image_paths.append(image_path)
image_raw_paths.append(cam_info['fpath'])
# obtain lidar to image transformation matrix
city_SE3_ego_cam_t = cam_info['city_SE3_ego_cam_t']
ego_SE3_cam = cam_info['ego_SE3_cam']
ego_cam_t_SE3_ego_lidar_t = city_SE3_ego_cam_t.inverse().compose(city_SE3_ego_lidar_t) #ego2glo_lidar -> glo2ego_cam
cam_SE3_ego_cam_t = ego_SE3_cam.inverse().compose(ego_cam_t_SE3_ego_lidar_t) #ego -> cam
transform_matrix = np.eye(4)
transform_matrix[:3, :3] = cam_SE3_ego_cam_t.rotation
transform_matrix[:3, 3] = cam_SE3_ego_cam_t.translation
intrinsic = cam_info['intrinsics']
viewpad = np.eye(4)
viewpad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic
lidar2img_rt = (viewpad @ transform_matrix)
intrinsics.append(viewpad)
extrinsics.append(transform_matrix)
lidar2img_rts.append(lidar2img_rt)
if not self.test_mode:
prev_exists = not (index == 0 or self.flag[index - 1] != self.flag[index])
else:
prev_exists = None
input_dict.update(
dict(
img_timestamp=img_timestamp,
img_filename=image_paths,
lidar2img=lidar2img_rts,
intrinsics=intrinsics,
extrinsics=extrinsics,
prev_exists=prev_exists,
))
if not self.test_mode:
annos = self.get_ann_info(index, input_dict)
annos.update(
dict(
bboxes=info['gt2d_infos']['gt_2dbboxes'],
labels=info['gt2d_infos']['gt_2dlabels'],
centers2d=info['gt2d_infos']['centers2d'],
depths=info['gt2d_infos']['depths'],
bboxes_ignore=None)
)
input_dict['ann_info'] = annos
return input_dict
def __getitem__(self, idx):
"""Get item from infos according to the given index.
Returns:
dict: Data dictionary of the corresponding index.
"""
if self.test_mode:
return self.prepare_test_data(idx)
while True:
data = self.prepare_train_data(idx)
if data is None:
idx = self._rand_another(idx)
continue
return data
def _rand_another(self, idx):
"""Randomly get another item with the same flag.
Returns:
int: Another index of item with the same flag.
"""
pool = np.where(self.flag != -1)[0]
return np.random.choice(pool)
def invert_matrix_egopose_numpy(egopose):
""" Compute the inverse transformation of a 4x4 egopose numpy matrix."""
inverse_matrix = np.zeros((4, 4), dtype=np.float32)
rotation = egopose[:3, :3]
translation = egopose[:3, 3]
inverse_matrix[:3, :3] = rotation.T
inverse_matrix[:3, 3] = -np.dot(rotation.T, translation)
inverse_matrix[3, 3] = 1.0
return inverse_matrix
def convert_egopose_to_matrix_numpy(rotation, translation):
transformation_matrix = np.zeros((4, 4), dtype=np.float32)
transformation_matrix[:3, :3] = rotation
transformation_matrix[:3, 3] = translation
transformation_matrix[3, 3] = 1.0
return transformation_matrix
================================================
FILE: projects/mmdet3d_plugin/datasets/av2_eval_util.py
================================================
'''
Overwrite some functions for adapting to our data loading scheme.
'''
import refile
import numpy as np
import pyarrow.feather as feather
import av2.utils.io as io_utils
import logging
import warnings
from multiprocessing import get_context
import numpy as np
import pandas as pd
from av2.utils.io import TimestampedCitySE3EgoPoses, read_city_SE3_ego
from av2.evaluation.detection.constants import NUM_DECIMALS, TruePositiveErrorNames
from av2.evaluation.detection.utils import (
compute_average_precision,
groupby,
)
from .av2_utils import (
DetectionCfg,
accumulate,
)
from av2.geometry.se3 import SE3
from av2.map.map_api import ArgoverseStaticMap
from av2.structures.cuboid import ORDERED_CUBOID_COL_NAMES
from av2.utils.io import TimestampedCitySE3EgoPoses
from av2.utils.typing import NDArrayBool, NDArrayFloat
import av2.geometry.geometry as geometry_utils
# from av2.evaluation.detection.eval import summarize_metrics
from .summarize_metrics_av2 import summarize_metrics
from typing import Dict, List, Optional, Tuple, Union, Final, Any
from joblib import Parallel, delayed
from pathlib import Path
# from upath import UPath
from io import BytesIO
from dataclasses import dataclass
import json
from av2.map.drivable_area import DrivableArea
from av2.map.lane_segment import LaneSegment
from av2.map.pedestrian_crossing import PedestrianCrossing
from av2.map.map_api import DrivableAreaMapLayer, RoiMapLayer, GroundHeightLayer
from av2.geometry.sim2 import Sim2
warnings.filterwarnings("ignore", module="google")
TP_ERROR_COLUMNS: Final[Tuple[str, ...]] = tuple(x.value for x in TruePositiveErrorNames)
DTS_COLUMN_NAMES: Final[Tuple[str, ...]] = tuple(ORDERED_CUBOID_COL_NAMES) + ("score",)
GTS_COLUMN_NAMES: Final[Tuple[str, ...]] = tuple(ORDERED_CUBOID_COL_NAMES) + ("num_interior_pts",)
UUID_COLUMN_NAMES: Final[Tuple[str, ...]] = (
"log_id",
"timestamp_ns",
"category",
)
logger = logging.getLogger(__name__)
def evaluate(
dts: pd.DataFrame,
gts: pd.DataFrame,
cfg: DetectionCfg,
n_jobs: int = 8,
) -> Tuple[pd.DataFrame, pd.DataFrame, pd.DataFrame]:
"""Evaluate a set of detections against the ground truth annotations.
Each sweep is processed independently, computing assignment between detections and ground truth annotations.
Args:
dts: (N,14) Table of detections.
gts: (M,15) Table of ground truth annotations.
cfg: Detection configuration.
n_jobs: Number of jobs running concurrently during evaluation.
Returns:
(C+1,K) Table of evaluation metrics where C is the number of classes. Plus a row for their means.
K refers to the number of evaluation metrics.
Raises:
RuntimeError: If accumulation fails.
ValueError: If ROI pruning is enabled but a dataset directory is not specified.
"""
if cfg.eval_only_roi_instances and cfg.dataset_dir is None:
raise ValueError(
"ROI pruning has been enabled, but the dataset directory has not be specified. "
"Please set `dataset_directory` to the split root, e.g. av2/sensor/val."
)
# Sort both the detections and annotations by lexicographic order for grouping.
dts = dts.sort_values(list(UUID_COLUMN_NAMES))
gts = gts.sort_values(list(UUID_COLUMN_NAMES))
dts_npy: NDArrayFloat = dts[list(DTS_COLUMN_NAMES)].to_numpy()
gts_npy: NDArrayFloat = gts[list(GTS_COLUMN_NAMES)].to_numpy()
dts_uuids: List[str] = dts[list(UUID_COLUMN_NAMES)].to_numpy().tolist()
gts_uuids: List[str] = gts[list(UUID_COLUMN_NAMES)].to_numpy().tolist()
# We merge the unique identifier -- the tuple of ("log_id", "timestamp_ns", "category")
# into a single string to optimize the subsequent grouping operation.
# `groupby_mapping` produces a mapping from the uuid to the group of detections / annotations
# which fall into that group.
uuid_to_dts = groupby([":".join(map(str, x)) for x in dts_uuids], dts_npy)
uuid_to_gts = groupby([":".join(map(str, x)) for x in gts_uuids], gts_npy)
log_id_to_avm: Optional[Dict[str, ArgoverseStaticMap]] = None
log_id_to_timestamped_poses: Optional[Dict[str, TimestampedCitySE3EgoPoses]] = None
# Load maps and egoposes if roi-pruning is enabled.
if cfg.eval_only_roi_instances and cfg.dataset_dir is not None:
logger.info("Loading maps and egoposes ...")
log_ids: List[str] = gts.loc[:, "log_id"].unique().tolist()
log_id_to_avm, log_id_to_timestamped_poses = load_mapped_avm_and_egoposes(log_ids, cfg.dataset_dir)
args_list: List[Tuple[NDArrayFloat, NDArrayFloat, DetectionCfg, Optional[ArgoverseStaticMap], Optional[SE3]]] = []
uuids = sorted(uuid_to_dts.keys() | uuid_to_gts.keys())
for uuid in uuids:
log_id, timestamp_ns, _ = uuid.split(":")
args: Tuple[NDArrayFloat, NDArrayFloat, DetectionCfg, Optional[ArgoverseStaticMap], Optional[SE3]]
sweep_dts: NDArrayFloat = np.zeros((0, 10))
sweep_gts: NDArrayFloat = np.zeros((0, 10))
if uuid in uuid_to_dts:
sweep_dts = uuid_to_dts[uuid]
if uuid in uuid_to_gts:
sweep_gts = uuid_to_gts[uuid]
args = sweep_dts, sweep_gts, cfg, None, None
if log_id_to_avm is not None and log_id_to_timestamped_poses is not None:
avm = log_id_to_avm[log_id]
city_SE3_ego = log_id_to_timestamped_poses[log_id][int(timestamp_ns)]
args = sweep_dts, sweep_gts, cfg, avm, city_SE3_ego
args_list.append(args)
logger.info("Starting evaluation ...")
with get_context("spawn").Pool(processes=n_jobs) as p:
outputs: Optional[List[Tuple[NDArrayFloat, NDArrayFloat]]] = p.starmap(accumulate, args_list)
if outputs is None:
raise RuntimeError("Accumulation has failed! Please check the integrity of your detections and annotations.")
dts_list, gts_list = zip(*outputs)
METRIC_COLUMN_NAMES = cfg.affinity_thresholds_m + TP_ERROR_COLUMNS + ("is_evaluated",)
dts_metrics: NDArrayFloat = np.concatenate(dts_list) # type: ignore
gts_metrics: NDArrayFloat = np.concatenate(gts_list) # type: ignore
dts.loc[:, METRIC_COLUMN_NAMES] = dts_metrics
gts.loc[:, METRIC_COLUMN_NAMES] = gts_metrics
# Compute summary metrics.
metrics, recall3d = summarize_metrics(dts, gts, cfg)
metrics.loc["AVERAGE_METRICS"] = metrics.mean()
recall3d.loc["AVERAGE_METRICS"] = recall3d.mean()
metrics = metrics.round(NUM_DECIMALS)
recall3d = recall3d.round(NUM_DECIMALS)
return dts, gts, metrics, recall3d
def load_mapped_avm_and_egoposes(log_ids: List[str], dataset_dir: Path
) -> Tuple[Dict[str, ArgoverseStaticMap], Dict[str, TimestampedCitySE3EgoPoses]]:
"""Load the maps and egoposes for each log in the dataset directory.
Args:
log_ids: List of the log_ids.
dataset_dir: Directory to the dataset.
Returns:
A tuple of mappings from log id to maps and timestamped-egoposes, respectively.
Raises:
RuntimeError: If the process for loading maps and timestamped egoposes fails.
"""
log_id_to_timestamped_poses = {log_id: read_city_SE3_ego(dataset_dir / log_id) for log_id in log_ids}
avms: Optional[List[ArgoverseStaticMap]] = Parallel(n_jobs=-1, backend="threading")(
delayed(ArgoverseStaticMapRemote.from_map_dir_remote)(dataset_dir / log_id / "map", build_raster=True) for log_id in log_ids)
if avms is None:
raise RuntimeError("Map and egopose loading has failed!")
log_id_to_avm = {log_ids[i]: avm for i, avm in enumerate(avms)}
return log_id_to_avm, log_id_to_timestamped_poses
def read_feather_remote(path: Path, columns: Optional[Tuple[str, ...]] = None) -> pd.DataFrame:
"""Read Apache Feather data from a .feather file.
AV2 uses .feather to serialize much of its data. This function handles the deserialization
process and returns a `pandas` DataFrame with rows corresponding to the records and the
columns corresponding to the record attributes.
Args:
path: Source data file (e.g., 'lidar.feather', 'calibration.feather', etc.)
columns: Tuple of columns to load for the given record. Defaults to None.
Returns:
(N,len(columns)) Apache Feather data represented as a `pandas` DataFrame.
"""
# with path.open("rb") as f:
with refile.smart_open(str(path), "rb") as f:
data: pd.DataFrame = feather.read_feather(f, columns=columns)
return data
@dataclass
class ArgoverseStaticMapRemote(ArgoverseStaticMap):
"""API to interact with a local map for a single log (within a single city).
"""
@classmethod
def from_json_remote(cls, static_map_path_s3, static_map_path: Path) -> ArgoverseStaticMap:
"""Instantiate an Argoverse static map object (without raster data) from a JSON file containing map data.
Args:
static_map_path: Path to the JSON file containing map data. The file name must match
the following pattern: "log_map_archive_{log_id}.json".
Returns:
An Argoverse HD map.
"""
vector_data = io_utils.read_json_file(static_map_path)
log_id = static_map_path.stem.split("log_map_archive_")[1]
# with refile.smart_open(static_map_path_s3, "rb") as f:
# vector_data: Dict[str, Any] = json.load(f)
vector_drivable_areas = {da["id"]: DrivableArea.from_dict(da) for da in vector_data["drivable_areas"].values()}
vector_lane_segments = {ls["id"]: LaneSegment.from_dict(ls) for ls in vector_data["lane_segments"].values()}
if "pedestrian_crossings" not in vector_data:
logger.error("Missing Pedestrian crossings!")
vector_pedestrian_crossings = {}
else:
vector_pedestrian_crossings = {
pc["id"]: PedestrianCrossing.from_dict(pc) for pc in vector_data["pedestrian_crossings"].values()
}
return cls(
log_id=log_id,
vector_drivable_areas=vector_drivable_areas,
vector_lane_segments=vector_lane_segments,
vector_pedestrian_crossings=vector_pedestrian_crossings,
raster_drivable_area_layer=None,
raster_roi_layer=None,
raster_ground_height_layer=None,
)
@classmethod
def from_map_dir_remote(cls, log_map_dirpath: Path, build_raster: bool = False, data_root='') -> ArgoverseStaticMap:
"""Instantiate an Argoverse map object from data stored within a map data directory.
Note: the ground height surface file and associated coordinate mapping is not provided for the
2.0 Motion Forecasting dataset, so `build_raster` defaults to False. If raster functionality is
desired, users should pass `build_raster` to True (e.g. for the Sensor Datasets and Map Change Datasets).
Args:
log_map_dirpath: Path to directory containing scenario-specific map data,
JSON file must follow this schema: "log_map_archive_{log_id}.json".
build_raster: Whether to rasterize drivable areas, compute region of interest BEV binary segmentation,
and to load raster ground height from disk (when available).
Returns:
The HD map.
Raises:
RuntimeError: If the vector map data JSON file is missing.
"""
# log_map_dirpath_s3 = str(log_map_dirpath).replace(data_root, 's3://argo/argo_data/')
# vector_data_fnames = sorted(refile.smart_glob(log_map_dirpath + "/log_map_archive_*.json"))
vector_data_fnames = sorted(log_map_dirpath.glob("log_map_archive_*.json"))
# "s3://argo/argo_data/val/02678d04-cc9f-3148-9f95-1ba66347dff9/map/log_map_archive_*.json"
# Load vector map data from JSON file
# vector_data_fnames = sorted(log_map_dirpath.glob("log_map_archive_*.json"))
if not len(vector_data_fnames) == 1:
raise RuntimeError(f"JSON file containing vector map data is missing (searched in {log_map_dirpath})")
vector_data_fname = vector_data_fnames[0]
vector_data_json_path = vector_data_fname
static_map = cls.from_json_remote(vector_data_json_path, Path(vector_data_json_path))
static_map.log_id = log_map_dirpath.parent.stem
# Avoid file I/O and polygon rasterization when not needed
if build_raster:
drivable_areas: List[DrivableArea] = list(static_map.vector_drivable_areas.values())
static_map.raster_drivable_area_layer = DrivableAreaMapLayer.from_vector_data(drivable_areas=drivable_areas)
static_map.raster_roi_layer = RoiMapLayer.from_drivable_area_layer(static_map.raster_drivable_area_layer)
static_map.raster_ground_height_layer = GroundHeightLayerRemote.from_file_remote(log_map_dirpath, log_map_dirpath)
# static_map.raster_ground_height_layer = GroundHeightLayerRemote.from_file_remote(log_map_dirpath, log_map_dirpath_s3)
return static_map
@dataclass(frozen=True)
class GroundHeightLayerRemote(GroundHeightLayer):
"""Rasterized ground height map layer.
Stores the "ground_height_matrix" and also the array_Sim2_city: Sim(2) that produces takes point in city
coordinates to numpy image/matrix coordinates, e.g. p_npyimage = array_Transformation_city * p_city
"""
@classmethod
def from_file_remote(cls, log_map_dirpath: Path, log_map_dirpath_s3) -> GroundHeightLayer:
"""Load ground height values (w/ values at 30 cm resolution) from .npy file, and associated Sim(2) mapping.
Note: ground height values are stored on disk as a float16 2d-array, but cast to float32 once loaded for
compatibility with matplotlib.
Args:
log_map_dirpath: path to directory which contains map files associated with one specific log/scenario.
Returns:
The ground height map layer.
Raises:
RuntimeError: If raster ground height layer file is missing or Sim(2) mapping from city to image coordinates
is missing.
"""
ground_height_npy_fpaths = sorted(log_map_dirpath.glob("*_ground_height_surface____*.npy"))
# ground_height_npy_fpaths = sorted(refile.smart_glob(log_map_dirpath_s3 + "/*_ground_height_surface____*.npy"))
if not len(ground_height_npy_fpaths) == 1:
raise RuntimeError("Raster ground height layer file is missing")
Sim2_json_fpaths = sorted(log_map_dirpath.glob("*___img_Sim2_city.json"))
# Sim2_json_fpaths = sorted(refile.smart_glob(log_map_dirpath_s3 + "/*___img_Sim2_city.json"))
if not len(Sim2_json_fpaths) == 1:
raise RuntimeError("Sim(2) mapping from city to image coordinates is missing")
# load the file with rasterized values
with ground_height_npy_fpaths[0].open("rb") as f:
# with refile.smart_open(ground_height_npy_fpaths[0], "rb") as f:
_bytes = f.read()
ground_height_array: NDArrayFloat = np.load(BytesIO(_bytes))
array_Sim2_city = Sim2.from_json(Sim2_json_fpaths[0])
# with refile.smart_open(Sim2_json_fpaths[0], "r") as f:
# json_data = json.load(f)
# R: NDArrayFloat = np.array(json_data["R"]).reshape(2, 2)
# t: NDArrayFloat = np.array(json_data["t"]).reshape(2)
# s = float(json_data["s"])
# array_Sim2_city = Sim2(R, t, s)
return cls(array=ground_height_array.astype(float), array_Sim2_city=array_Sim2_city)
================================================
FILE: projects/mmdet3d_plugin/datasets/av2_utils.py
================================================
import logging
from dataclasses import dataclass
from pathlib import Path
from typing import Optional, Tuple
import numpy as np
from scipy.spatial.distance import cdist
from av2.evaluation.detection.constants import (
MAX_NORMALIZED_ASE,
MAX_SCALE_ERROR,
MAX_YAW_RAD_ERROR,
MIN_AP,
MIN_CDS,
AffinityType,
CompetitionCategories,
DistanceType,
FilterMetricType,
)
from av2.geometry.geometry import mat_to_xyz, quat_to_mat, wrap_angles
from av2.geometry.iou import iou_3d_axis_aligned
from av2.geometry.se3 import SE3
from av2.map.map_api import ArgoverseStaticMap, RasterLayerType
from av2.structures.cuboid import Cuboid, CuboidList
from av2.utils.typing import NDArrayBool, NDArrayFloat, NDArrayInt
import kornia.geometry.conversions as C
import torch
from torch import Tensor
from math import pi as PI
logger = logging.getLogger(__name__)
@dataclass(frozen=True)
class DetectionCfg:
# affinity_thresholds_m: Tuple[float, ...] = (4.0,)
affinity_thresholds_m: Tuple[float, ...] = (0.5, 1.0, 2.0, 4.0)
affinity_type: AffinityType = AffinityType.CENTER
categories: Tuple[str, ...] = tuple(x.value for x in CompetitionCategories)
dataset_dir: Optional[Path] = None
eval_only_roi_instances: bool = True
filter_metric: FilterMetricType = FilterMetricType.EUCLIDEAN
max_num_dts_per_category: int = 100
eval_range_m: Tuple[float, ...] = (0.0, 150.0)
num_recall_samples: int = 100
tp_threshold_m: float = 2.0
@property
def metrics_defaults(self) -> Tuple[float, ...]:
"""Return the evaluation summary default values."""
return (
MIN_AP,
self.tp_threshold_m,
MAX_NORMALIZED_ASE,
MAX_YAW_RAD_ERROR,
MIN_CDS,
MIN_AP,
)
@property
def tp_normalization_terms(self) -> Tuple[float, ...]:
"""Return the normalization constants for ATE, ASE, and AOE."""
return (
self.tp_threshold_m,
MAX_SCALE_ERROR,
MAX_YAW_RAD_ERROR,
)
def accumulate(
dts: NDArrayFloat,
gts: NDArrayFloat,
cfg: DetectionCfg,
avm: Optional[ArgoverseStaticMap] = None,
city_SE3_ego: Optional[SE3] = None,
) -> Tuple[NDArrayFloat, NDArrayFloat]:
N, M = len(dts), len(gts)
T, E = len(cfg.affinity_thresholds_m), 3
# Sort the detections by score in _descending_ order.
scores: NDArrayFloat = dts[..., -1]
permutation: NDArrayInt = np.argsort(-scores).tolist()
dts = dts[permutation]
is_evaluated_dts: NDArrayBool = np.ones(N, dtype=bool)
is_evaluated_gts: NDArrayBool = np.ones(M, dtype=bool)
if avm is not None and city_SE3_ego is not None:
is_evaluated_dts &= compute_objects_in_roi_mask(dts, city_SE3_ego, avm)
is_evaluated_gts &= compute_objects_in_roi_mask(gts, city_SE3_ego, avm)
is_evaluated_dts &= compute_evaluated_dts_mask(dts[..., :3], cfg)
is_evaluated_gts &= compute_evaluated_gts_mask(gts[..., :3], gts[..., -1], cfg)
# Initialize results array.
dts_augmented: NDArrayFloat = np.zeros((N, T + E + 1))
gts_augmented: NDArrayFloat = np.zeros((M, T + E + 1))
# `is_evaluated` boolean flag is always the last column of the array.
dts_augmented[is_evaluated_dts, -1] = True
gts_augmented[is_evaluated_gts, -1] = True
if is_evaluated_dts.sum() > 0 and is_evaluated_gts.sum() > 0:
# Compute true positives by assigning detections and ground truths.
dts_assignments, gts_assignments = assign(dts[is_evaluated_dts], gts[is_evaluated_gts], cfg)
dts_augmented[is_evaluated_dts, :-1] = dts_assignments
gts_augmented[is_evaluated_gts, :-1] = gts_assignments
# Permute the detections according to the original ordering.
outputs: Tuple[NDArrayInt, NDArrayInt] = np.unique(permutation, return_index=True) # type: ignore
_, inverse_permutation = outputs
dts_augmented = dts_augmented[inverse_permutation]
return dts_augmented, gts_augmented
def assign(dts: NDArrayFloat, gts: NDArrayFloat, cfg: DetectionCfg) -> Tuple[NDArrayFloat, NDArrayFloat]:
affinity_matrix = compute_affinity_matrix(dts[..., :3], gts[..., :3], cfg.affinity_type)
# Get the GT label for each max-affinity GT label, detection pair.
idx_gts = affinity_matrix.argmax(axis=1)[None]
# The affinity matrix is an N by M matrix of the detections and ground truth labels respectively.
# We want to take the corresponding affinity for each of the initial assignments using `gt_matches`.
# The following line grabs the max affinity for each detection to a ground truth label.
affinities: NDArrayFloat = np.take_along_axis(affinity_matrix.transpose(), idx_gts, axis=0)[0] # type: ignore
# Find the indices of the _first_ detection assigned to each GT.
assignments: Tuple[NDArrayInt, NDArrayInt] = np.unique(idx_gts, return_index=True) # type: ignore
idx_gts, idx_dts = assignments
T, E = len(cfg.affinity_thresholds_m), 3
dts_metrics: NDArrayFloat = np.zeros((len(dts), T + E))
dts_metrics[:, T:] = cfg.metrics_defaults[1:4]
gts_metrics: NDArrayFloat = np.zeros((len(gts), T + E))
gts_metrics[:, T:] = cfg.metrics_defaults[1:4]
for i, threshold_m in enumerate(cfg.affinity_thresholds_m):
is_tp: NDArrayBool = affinities[idx_dts] > -threshold_m
dts_metrics[idx_dts[is_tp], i] = True
gts_metrics[idx_gts, i] = True
if threshold_m != cfg.tp_threshold_m:
continue # Skip if threshold isn't the true positive threshold.
if not np.any(is_tp):
continue # Skip if no true positives exist.
idx_tps_dts: NDArrayInt = idx_dts[is_tp]
idx_tps_gts: NDArrayInt = idx_gts[is_tp]
tps_dts = dts[idx_tps_dts]
tps_gts = gts[idx_tps_gts]
translation_errors = distance(tps_dts[:, :3], tps_gts[:, :3], DistanceType.TRANSLATION)
scale_errors = distance(tps_dts[:, 3:6], tps_gts[:, 3:6], DistanceType.SCALE)
orientation_errors = distance(tps_dts[:, 6:10], tps_gts[:, 6:10], DistanceType.ORIENTATION)
dts_metrics[idx_tps_dts, T:] = np.stack((translation_errors, scale_errors, orientation_errors), axis=-1)
return dts_metrics, gts_metrics
def distance(dts: NDArrayFloat, gts: NDArrayFloat, metric: DistanceType) -> NDArrayFloat:
if metric == DistanceType.TRANSLATION:
translation_errors: NDArrayFloat = np.linalg.norm(dts - gts, axis=1) # type: ignore
return translation_errors
elif metric == DistanceType.SCALE:
scale_errors: NDArrayFloat = 1 - iou_3d_axis_aligned(dts, gts)
return scale_errors
elif metric == DistanceType.ORIENTATION:
yaws_dts: NDArrayFloat = mat_to_xyz(quat_to_mat(dts))[..., 2]
yaws_gts: NDArrayFloat = mat_to_xyz(quat_to_mat(gts))[..., 2]
orientation_errors = wrap_angles(yaws_dts - yaws_gts)
return orientation_errors
else:
raise NotImplementedError("This distance metric is not implemented!")
def compute_affinity_matrix(dts: NDArrayFloat, gts: NDArrayFloat, metric: AffinityType) -> NDArrayFloat:
if metric == AffinityType.CENTER:
dts_xy_m = dts
gts_xy_m = gts
affinities: NDArrayFloat = -cdist(dts_xy_m, gts_xy_m)
else:
raise NotImplementedError("This affinity metric is not implemented!")
return affinities
def compute_evaluated_dts_mask(
xyz_m_ego: NDArrayFloat,
cfg: DetectionCfg,
) -> NDArrayBool:
is_evaluated: NDArrayBool
if len(xyz_m_ego) == 0:
is_evaluated = np.zeros((0,), dtype=bool)
return is_evaluated
norm: NDArrayFloat = np.linalg.norm(xyz_m_ego, axis=1) # type: ignore
# is_evaluated = norm < cfg.max_range_m
is_evaluated = np.logical_and(norm > cfg.eval_range_m[0], norm < cfg.eval_range_m[1])
cumsum: NDArrayInt = np.cumsum(is_evaluated)
max_idx_arr: NDArrayInt = np.where(cumsum > cfg.max_num_dts_per_category)[0]
if len(max_idx_arr) > 0:
max_idx = max_idx_arr[0]
is_evaluated[max_idx:] = False # type: ignore
return is_evaluated
def compute_evaluated_gts_mask(
xyz_m_ego: NDArrayFloat,
num_interior_pts: NDArrayInt,
cfg: DetectionCfg,
) -> NDArrayBool:
is_evaluated: NDArrayBool
if len(xyz_m_ego) == 0:
is_evaluated = np.zeros((0,), dtype=bool)
return is_evaluated
norm: NDArrayFloat = np.linalg.norm(xyz_m_ego, axis=1) # type: ignore
is_evaluated_range = np.logical_and(norm > cfg.eval_range_m[0], norm < cfg.eval_range_m[1])
is_evaluated = np.logical_and(is_evaluated_range, num_interior_pts > 0)
# is_evaluated = np.logical_and(norm < cfg.eval_range_m[1], num_interior_pts > 0)
return is_evaluated
def compute_objects_in_roi_mask(cuboids_ego: NDArrayFloat, city_SE3_ego: SE3, avm: ArgoverseStaticMap) -> NDArrayBool:
is_within_roi: NDArrayBool
if len(cuboids_ego) == 0:
is_within_roi = np.zeros((0,), dtype=bool)
return is_within_roi
cuboid_list_ego: CuboidList = CuboidList([Cuboid.from_numpy(params) for params in cuboids_ego])
cuboid_list_city = cuboid_list_ego.transform(city_SE3_ego)
cuboid_list_vertices_m_city = cuboid_list_city.vertices_m
is_within_roi = avm.get_raster_layer_points_boolean(
cuboid_list_vertices_m_city.reshape(-1, 3)[..., :2], RasterLayerType.ROI
)
is_within_roi = is_within_roi.reshape(-1, 8)
is_within_roi = is_within_roi.any(axis=1)
return is_within_roi
@torch.jit.script
def xyz_to_quat(xyz_rad: Tensor) -> Tensor:
"""Convert euler angles (xyz - pitch, roll, yaw) to scalar first quaternions.
Args:
xyz_rad: (...,3) Tensor of roll, pitch, and yaw in radians.
Returns:
(...,4) Scalar first quaternions (wxyz).
"""
x_rad = xyz_rad[..., 0]
y_rad = xyz_rad[..., 1]
z_rad = xyz_rad[..., 2]
cy = torch.cos(z_rad * 0.5)
sy = torch.sin(z_rad * 0.5)
cp = torch.cos(y_rad * 0.5)
sp = torch.sin(y_rad * 0.5)
cr = torch.cos(x_rad * 0.5)
sr = torch.sin(x_rad * 0.5)
qw = cr * cp * cy + sr * sp * sy
qx = sr * cp * cy - cr * sp * sy
qy = cr * sp * cy + sr * cp * sy
qz = cr * cp * sy - sr * sp * cy
quat_wxyz = torch.stack([qw, qx, qy, qz], dim=-1)
return quat_wxyz
@torch.jit.script
def yaw_to_quat(yaw_rad: Tensor) -> Tensor:
"""Convert yaw (rotation about the vertical axis) to scalar first quaternions.
Args:
yaw_rad: (...,1) Rotations about the z-axis.
Returns:
(...,4) scalar first quaternions (wxyz).
"""
xyz_rad = torch.zeros_like(yaw_rad)[..., None].repeat_interleave(3, dim=-1)
xyz_rad[..., -1] = yaw_rad
quat_wxyz: Tensor = xyz_to_quat(xyz_rad)
return quat_wxyz
================================================
FILE: projects/mmdet3d_plugin/datasets/builder.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Shihao Wang
# ---------------------------------------------
import copy
import platform
import random
from functools import partial
import numpy as np
from mmcv.parallel import collate
from mmcv.runner import get_dist_info
from mmcv.utils import Registry, build_from_cfg
from torch.utils.data import DataLoader
from mmdet.datasets.samplers import GroupSampler
from projects.mmdet3d_plugin.datasets.samplers.group_sampler import DistributedGroupSampler
from projects.mmdet3d_plugin.datasets.samplers.distributed_sampler import DistributedSampler
from projects.mmdet3d_plugin.datasets.samplers.group_sampler import InfiniteGroupEachSampleInBatchSampler
from projects.mmdet3d_plugin.datasets.samplers.sampler import build_sampler
def build_dataloader(dataset,
samples_per_gpu,
workers_per_gpu,
num_gpus=1,
dist=True,
shuffle=True,
seed=None,
shuffler_sampler=None,
nonshuffler_sampler=None,
runner_type=dict(type='EpochBasedRunner'),
**kwargs):
"""Build PyTorch DataLoader.
In distributed training, each GPU/process has a dataloader.
In non-distributed training, there is only one dataloader for all GPUs.
Args:
dataset (Dataset): A PyTorch dataset.
samples_per_gpu (int): Number of training samples on each GPU, i.e.,
batch size of each GPU.
workers_per_gpu (int): How many subprocesses to use for data loading
for each GPU.
num_gpus (int): Number of GPUs. Only used in non-distributed training.
dist (bool): Distributed training/test or not. Default: True.
shuffle (bool): Whether to shuffle the data at every epoch.
Default: True.
kwargs: any keyword argument to be used to initialize DataLoader
Returns:
DataLoader: A PyTorch dataloader.
"""
rank, world_size = get_dist_info()
if dist:
# DistributedGroupSampler will definitely shuffle the data to satisfy
# that images on each GPU are in the same group
if shuffle:
sampler = build_sampler(shuffler_sampler if shuffler_sampler is not None else dict(type='DistributedGroupSampler'),
dict(
dataset=dataset,
samples_per_gpu=samples_per_gpu,
num_replicas=world_size,
rank=rank,
seed=seed)
)
else:
sampler = build_sampler(nonshuffler_sampler if nonshuffler_sampler is not None else dict(type='DistributedSampler'),
dict(
dataset=dataset,
num_replicas=world_size,
rank=rank,
shuffle=shuffle,
seed=seed)
)
batch_size = samples_per_gpu
num_workers = workers_per_gpu
batch_sampler = None
else:
# assert False, 'not support in bevformer'
print('WARNING!!!!, Only can be used for obtain inference speed!!!!')
sampler = GroupSampler(dataset, samples_per_gpu) if shuffle else None
batch_size = num_gpus * samples_per_gpu
num_workers = num_gpus * workers_per_gpu
batch_sampler = None
if runner_type['type'] == 'IterBasedRunner' and shuffler_sampler['type'] =='InfiniteGroupEachSampleInBatchSampler':
# TODO: original has more options, but I'm not using them
# https://github.com/open-mmlab/mmdetection/blob/3b72b12fe9b14de906d1363982b9fba05e7d47c1/mmdet/datasets/builder.py#L145-L157
batch_sampler = InfiniteGroupEachSampleInBatchSampler(
dataset,
samples_per_gpu,
world_size,
rank,
seed=seed)
batch_size = 1
sampler = None
init_fn = partial(
worker_init_fn, num_workers=num_workers, rank=rank,
seed=seed) if seed is not None else None
data_loader = DataLoader(
dataset,
batch_size=batch_size,
sampler=sampler,
batch_sampler=batch_sampler,
num_workers=num_workers,
collate_fn=partial(collate, samples_per_gpu=samples_per_gpu),
pin_memory=False,
worker_init_fn=init_fn,
**kwargs)
return data_loader
def worker_init_fn(worker_id, num_workers, rank, seed):
# The seed of each worker equals to
# num_worker * rank + worker_id + user_seed
worker_seed = num_workers * rank + worker_id + seed
np.random.seed(worker_seed)
random.seed(worker_seed)
# Copyright (c) OpenMMLab. All rights reserved.
import platform
from mmcv.utils import Registry, build_from_cfg
from mmdet.datasets import DATASETS
from mmdet.datasets.builder import _concat_dataset
if platform.system() != 'Windows':
# https://github.com/pytorch/pytorch/issues/973
import resource
rlimit = resource.getrlimit(resource.RLIMIT_NOFILE)
base_soft_limit = rlimit[0]
hard_limit = rlimit[1]
soft_limit = min(max(4096, base_soft_limit), hard_limit)
resource.setrlimit(resource.RLIMIT_NOFILE, (soft_limit, hard_limit))
OBJECTSAMPLERS = Registry('Object sampler')
def custom_build_dataset(cfg, default_args=None):
from mmdet3d.datasets.dataset_wrappers import CBGSDataset
from mmdet.datasets.dataset_wrappers import (ClassBalancedDataset,
ConcatDataset, RepeatDataset)
if isinstance(cfg, (list, tuple)):
dataset = ConcatDataset([custom_build_dataset(c, default_args) for c in cfg])
elif cfg['type'] == 'ConcatDataset':
dataset = ConcatDataset(
[custom_build_dataset(c, default_args) for c in cfg['datasets']],
cfg.get('separate_eval', True))
elif cfg['type'] == 'RepeatDataset':
dataset = RepeatDataset(
custom_build_dataset(cfg['dataset'], default_args), cfg['times'])
elif cfg['type'] == 'ClassBalancedDataset':
dataset = ClassBalancedDataset(
custom_build_dataset(cfg['dataset'], default_args), cfg['oversample_thr'])
elif cfg['type'] == 'CBGSDataset':
dataset = CBGSDataset(custom_build_dataset(cfg['dataset'], default_args))
elif isinstance(cfg.get('ann_file'), (list, tuple)):
dataset = _concat_dataset(cfg, default_args)
else:
dataset = build_from_cfg(cfg, DATASETS, default_args)
return dataset
================================================
FILE: projects/mmdet3d_plugin/datasets/eval_recall.py
================================================
import mmcv
import torch
import torch.nn as nn
import numpy as np
from tqdm import tqdm
def bbox_cxcywh_to_xyxy(bbox):
"""Convert bbox coordinates from (cx, cy, w, h) to (x1, y1, x2, y2).
Args:
bbox (Tensor): Shape (n, 4) for bboxes.
Returns:
Tensor: Converted bboxes.
"""
# factor = [960, 640]
factor = [1, 1]
cx = bbox[:, 0:1] * factor[0]
cy = bbox[:, 1:2] * factor[1]
w = bbox[:, 2:3] * factor[0]
h = bbox[:, 3:4] * factor[1]
bbox_new = [(cx - 0.5 * w), (cy - 0.5 * h), (cx + 0.5 * w), (cy + 0.5 * h)]
return torch.cat(bbox_new, dim=-1)
def bbox_overlaps(bboxes1,
bboxes2,
mode='iou',
eps=1e-6,
use_legacy_coordinate=False):
"""Calculate the ious between each bbox of bboxes1 and bboxes2.
Args:
bboxes1 (ndarray): Shape (n, 4)
bboxes2 (ndarray): Shape (k, 4)
mode (str): IOU (intersection over union) or IOF (intersection
over foreground)
use_legacy_coordinate (bool): Whether to use coordinate system in
mmdet v1.x. which means width, height should be
calculated as 'x2 - x1 + 1` and 'y2 - y1 + 1' respectively.
Note when function is used in `VOCDataset`, it should be
True to align with the official implementation
`http://host.robots.ox.ac.uk/pascal/VOC/voc2012/VOCdevkit_18-May-2011.tar`
Default: False.
Returns:
ious (ndarray): Shape (n, k)
"""
assert mode in ['iou', 'iof']
if not use_legacy_coordinate:
extra_length = 0.
else:
extra_length = 1.
bboxes1 = bboxes1.to(torch.float32)
bboxes2 = bboxes2.to(torch.float32)
rows = bboxes1.shape[0]
cols = bboxes2.shape[0]
ious = torch.zeros((rows, cols), dtype=torch.float32)
if rows * cols == 0:
return ious
exchange = False
if bboxes1.shape[0] > bboxes2.shape[0]:
bboxes1, bboxes2 = bboxes2, bboxes1
ious = torch.zeros((cols, rows), dtype=torch.float32)
exchange = True
area1 = (bboxes1[:, 2] - bboxes1[:, 0] + extra_length) * (
bboxes1[:, 3] - bboxes1[:, 1] + extra_length)
area2 = (bboxes2[:, 2] - bboxes2[:, 0] + extra_length) * (
bboxes2[:, 3] - bboxes2[:, 1] + extra_length)
for i in range(bboxes1.shape[0]):
x_start = torch.maximum(bboxes1[i, 0], bboxes2[:, 0])
y_start = torch.maximum(bboxes1[i, 1], bboxes2[:, 1])
x_end = torch.minimum(bboxes1[i, 2], bboxes2[:, 2])
y_end = torch.minimum(bboxes1[i, 3], bboxes2[:, 3])
overlap = torch.maximum(x_end - x_start + extra_length, torch.zeros_like(x_end)) * torch.maximum(
y_end - y_start + extra_length, torch.zeros_like(y_end))
if mode == 'iou':
union = area1[i] + area2 - overlap
else:
union = area1[i] if not exchange else area2
union = torch.maximum(union, torch.ones_like(union) * eps)
ious[i, :] = overlap / union
if exchange:
ious = ious.T
return ious
def eval_recall(gt_2dbboxes, gt_2d_depth, pred_bboxes, thr, range_m = [0, 150]):
num_true_sample = 0
num_gt_sample = 0
num_pred_sample = 0
for i in range(len(gt_2dbboxes)):
pred_bbox = pred_bboxes[i]
if len(gt_2dbboxes[i]) == 0:
continue
valid_gt_2d_depth = np.logical_and(gt_2d_depth[i] >= range_m[0], gt_2d_depth[i] < range_m[1])
gt_bbox = gt_2dbboxes[i][valid_gt_2d_depth, :]
if len(gt_bbox) == 0:
continue
gt_bbox = gt_bbox.reshape(-1, 4)
if len(pred_bbox) == 0:
num_gt_sample = num_gt_sample + len(gt_bbox)
continue
gt_bbox = torch.tensor(gt_bbox, device=pred_bbox.device)
pred_bbox = bbox_cxcywh_to_xyxy(pred_bbox)
ious = bbox_overlaps(gt_bbox, pred_bbox)
gt_ious = torch.zeros((ious.shape[0]))
for j in range(ious.shape[0]):
gt_max_overlaps = ious.argmax(axis=1)
max_ious = ious[torch.arange(0, ious.shape[0]), gt_max_overlaps]
gt_idx = max_ious.argmax()
gt_ious[j] = max_ious[gt_idx]
box_idx = gt_max_overlaps[gt_idx]
ious[gt_idx, :] = -1
ious[:, box_idx] = -1
num_true_sample = num_true_sample + (gt_ious >= thr).sum()
num_gt_sample = num_gt_sample + len(gt_bbox)
num_pred_sample = num_pred_sample + len(pred_bbox)
return num_gt_sample, num_true_sample, num_pred_sample
def cal_recall_2d(results_2d):
thr_ious = [0.5, 0.3]
for thr_iou in thr_ious:
ranges_m = [[0, 50], [50, 100], [100, 150], [0, 150]]
# ranges_m = [[0, 25], [25,50], [50, 75], [75,100], [100, 150], [0, 150]]
for range_m in ranges_m:
num_gt_total = 0
num_true_total = 0
num_sample = 0
num_pred_total = 0
gt_2d = mmcv.load("data/av2/gt_2d_val_nopadding.pkl", file_format='pkl')
for token in tqdm(gt_2d.keys()):
if token in results_2d.keys():
pred_bboxes = results_2d[token]
gt_2d_bbox = gt_2d[token]['gt_bboxes']
gt_2d_depth = gt_2d[token]['depths']
num_gt_sample, num_true_sample, num_pred_sample = eval_recall(gt_2d_bbox, gt_2d_depth, pred_bboxes, thr_iou, range_m)
num_pred_total += num_pred_sample
num_gt_total = num_gt_total + num_gt_sample
num_true_total = num_true_total + num_true_sample
num_sample += 1
recall = num_true_total / num_gt_total
print("num_sample is {}".format(num_sample))
print("num_pred_total is {}".format(num_pred_total))
print("num_gt_total is {}".format(num_gt_total))
print("num_true_total is {}".format(num_true_total))
print("recall with iou {} in range {} is {}".format(thr_iou, range_m, recall))
return
================================================
FILE: projects/mmdet3d_plugin/datasets/nuscenes_dataset.py
================================================
# ------------------------------------------------------------------------
# Copyright (c) 2022 megvii-model. All Rights Reserved.
# ------------------------------------------------------------------------
# Modified from DETR3D (https://github.com/WangYueFt/detr3d)
# Copyright (c) 2021 Wang, Yue
# ------------------------------------------------------------------------
# Modified from mmdetection3d (https://github.com/open-mmlab/mmdetection3d)
# Copyright (c) OpenMMLab. All rights reserved.
# ------------------------------------------------------------------------
# Modified by Shihao Wang
# ------------------------------------------------------------------------
import numpy as np
from mmdet.datasets import DATASETS
from mmdet3d.datasets import NuScenesDataset
from mmdet.datasets import DATASETS
import torch
import numpy as np
from nuscenes.eval.common.utils import Quaternion
from mmcv.parallel import DataContainer as DC
import random
import math
@DATASETS.register_module()
class CustomNuScenesDataset(NuScenesDataset):
r"""NuScenes Dataset.
This datset only add camera intrinsics and extrinsics to the results.
"""
def __init__(self, collect_keys, seq_mode=False, seq_split_num=1, num_frame_losses=1, queue_length=8, random_length=0, *args, **kwargs):
super().__init__(*args, **kwargs)
self.queue_length = queue_length
self.collect_keys = collect_keys
self.random_length = random_length
self.num_frame_losses = num_frame_losses
self.seq_mode = seq_mode
if seq_mode:
self.num_frame_losses = 1
self.queue_length = 1
self.seq_split_num = seq_split_num
self.random_length = 0
self._set_sequence_group_flag() # Must be called after load_annotations b/c load_annotations does sorting.
def _set_sequence_group_flag(self):
"""
Set each sequence to be a different group
"""
res = []
curr_sequence = 0
for idx in range(len(self.data_infos)):
if idx != 0 and len(self.data_infos[idx]['sweeps']) == 0:
# Not first frame and # of sweeps is 0 -> new sequence
curr_sequence += 1
res.append(curr_sequence)
self.flag = np.array(res, dtype=np.int64)
if self.seq_split_num != 1:
if self.seq_split_num == 'all':
self.flag = np.array(range(len(self.data_infos)), dtype=np.int64)
else:
bin_counts = np.bincount(self.flag)
new_flags = []
curr_new_flag = 0
for curr_flag in range(len(bin_counts)):
curr_sequence_length = np.array(
list(range(0,
bin_counts[curr_flag],
math.ceil(bin_counts[curr_flag] / self.seq_split_num)))
+ [bin_counts[curr_flag]])
for sub_seq_idx in (curr_sequence_length[1:] - curr_sequence_length[:-1]):
for _ in range(sub_seq_idx):
new_flags.append(curr_new_flag)
curr_new_flag += 1
assert len(new_flags) == len(self.flag)
assert len(np.bincount(new_flags)) == len(np.bincount(self.flag)) * self.seq_split_num
self.flag = np.array(new_flags, dtype=np.int64)
def prepare_train_data(self, index):
"""
Training data preparation.
Args:
index (int): Index for accessing the target data.
Returns:
dict: Training data dict of the corresponding index.
"""
queue = []
index_list = list(range(index-self.queue_length-self.random_length+1, index))
random.shuffle(index_list)
index_list = sorted(index_list[self.random_length:])
index_list.append(index)
prev_scene_token = None
for i in index_list:
i = max(0, i)
input_dict = self.get_data_info(i)
if not self.seq_mode:
if input_dict['scene_token'] != prev_scene_token:
input_dict.update(dict(prev_exists=False))
prev_scene_token = input_dict['scene_token']
else:
input_dict.update(dict(prev_exists=True))
self.pre_pipeline(input_dict)
example = self.pipeline(input_dict)
queue.append(example)
for k in range(self.num_frame_losses):
if self.filter_empty_gt and \
(queue[-k-1] is None or ~(queue[-k-1]['gt_labels_3d']._data != -1).any()):
return None
return self.union2one(queue)
def prepare_test_data(self, index):
"""Prepare data for testing.
Args:
index (int): Index for accessing the target data.
Returns:
dict: Testing data dict of the corresponding index.
"""
input_dict = self.get_data_info(index)
self.pre_pipeline(input_dict)
example = self.pipeline(input_dict)
return example
def union2one(self, queue):
for key in self.collect_keys:
if key != 'img_metas':
queue[-1][key] = DC(torch.stack([each[key].data for each in queue]), cpu_only=False, stack=True, pad_dims=None)
else:
queue[-1][key] = DC([each[key].data for each in queue], cpu_only=True)
if not self.test_mode:
for key in ['gt_bboxes_3d', 'gt_labels_3d', 'gt_bboxes', 'gt_labels', 'centers2d', 'depths']:
if key == 'gt_bboxes_3d':
queue[-1][key] = DC([each[key].data for each in queue], cpu_only=True)
else:
queue[-1][key] = DC([each[key].data for each in queue], cpu_only=False)
queue = queue[-1]
return queue
def get_data_info(self, index):
"""Get data info according to the given index.
Args:
index (int): Index of the sample data to get.
Returns:
dict: Data information that will be passed to the data \
preprocessing pipelines. It includes the following keys:
- sample_idx (str): Sample index.
- pts_filename (str): Filename of point clouds.
- sweeps (list[dict]): Infos of sweeps.
- timestamp (float): Sample timestamp.
- img_filename (str, optional): Image filename.
- lidar2img (list[np.ndarray], optional): Transformations \
from lidar to different cameras.
- ann_info (dict): Annotation info.
"""
info = self.data_infos[index]
# standard protocal modified from SECOND.Pytorch
e2g_rotation = Quaternion(info['ego2global_rotation']).rotation_matrix
e2g_translation = info['ego2global_translation']
l2e_rotation = Quaternion(info['lidar2ego_rotation']).rotation_matrix
l2e_translation = info['lidar2ego_translation']
e2g_matrix = convert_egopose_to_matrix_numpy(e2g_rotation, e2g_translation)
l2e_matrix = convert_egopose_to_matrix_numpy(l2e_rotation, l2e_translation)
ego_pose = e2g_matrix @ l2e_matrix
ego_pose_inv = invert_matrix_egopose_numpy(ego_pose)
input_dict = dict(
sample_idx=info['token'],
pts_filename=info['lidar_path'],
sweeps=info['sweeps'],
ego_pose=ego_pose,
ego_pose_inv = ego_pose_inv,
prev_idx=info['prev'],
next_idx=info['next'],
scene_token=info['scene_token'],
frame_idx=info['frame_idx'],
timestamp=info['timestamp'] / 1e6,
)
if self.modality['use_camera']:
image_paths = []
lidar2img_rts = []
intrinsics = []
extrinsics = []
img_timestamp = []
for cam_type, cam_info in info['cams'].items():
img_timestamp.append(cam_info['timestamp'] / 1e6)
image_paths.append(cam_info['data_path'])
# obtain lidar to image transformation matrix
cam2lidar_r = cam_info['sensor2lidar_rotation']
cam2lidar_t = cam_info['sensor2lidar_translation']
cam2lidar_rt = convert_egopose_to_matrix_numpy(cam2lidar_r, cam2lidar_t)
lidar2cam_rt = invert_matrix_egopose_numpy(cam2lidar_rt)
intrinsic = cam_info['cam_intrinsic']
viewpad = np.eye(4)
viewpad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic
lidar2img_rt = (viewpad @ lidar2cam_rt)
intrinsics.append(viewpad)
extrinsics.append(lidar2cam_rt)
lidar2img_rts.append(lidar2img_rt)
if not self.test_mode:
prev_exists = not (index == 0 or self.flag[index - 1] != self.flag[index])
else:
prev_exists = None
input_dict.update(
dict(
img_timestamp=img_timestamp,
img_filename=image_paths,
lidar2img=lidar2img_rts,
intrinsics=intrinsics,
extrinsics=extrinsics,
prev_exists=prev_exists,
))
if not self.test_mode:
annos = self.get_ann_info(index)
annos.update(
dict(
bboxes=info['bboxes2d'],
labels=info['labels2d'],
centers2d=info['centers2d'],
depths=info['depths'],
bboxes_ignore=info['bboxes_ignore'])
)
input_dict['ann_info'] = annos
return input_dict
def __getitem__(self, idx):
"""Get item from infos according to the given index.
Returns:
dict: Data dictionary of the corresponding index.
"""
if self.test_mode:
return self.prepare_test_data(idx)
while True:
data = self.prepare_train_data(idx)
if data is None:
idx = self._rand_another(idx)
continue
return data
def invert_matrix_egopose_numpy(egopose):
""" Compute the inverse transformation of a 4x4 egopose numpy matrix."""
inverse_matrix = np.zeros((4, 4), dtype=np.float32)
rotation = egopose[:3, :3]
translation = egopose[:3, 3]
inverse_matrix[:3, :3] = rotation.T
inverse_matrix[:3, 3] = -np.dot(rotation.T, translation)
inverse_matrix[3, 3] = 1.0
return inverse_matrix
def convert_egopose_to_matrix_numpy(rotation, translation):
transformation_matrix = np.zeros((4, 4), dtype=np.float32)
transformation_matrix[:3, :3] = rotation
transformation_matrix[:3, 3] = translation
transformation_matrix[3, 3] = 1.0
return transformation_matrix
================================================
FILE: projects/mmdet3d_plugin/datasets/pipelines/__init__.py
================================================
from .transform_3d import NormalizeMultiviewImage
from .formating import *
from .custom_pipeline import *
================================================
FILE: projects/mmdet3d_plugin/datasets/pipelines/custom_pipeline.py
================================================
import mmcv
import copy
import torch
import numpy as np
from PIL import Image
from mmdet3d.datasets.builder import PIPELINES
from mmdet3d.core.points import BasePoints, get_points_type
import torch.nn.functional as F
import pickle
import refile
import numpy as np
from io import BytesIO
import pyarrow
import pyarrow.feather as feather
import pandas
@PIPELINES.register_module()
class AV2LoadMultiViewImageFromFiles(object):
def __init__(self, to_float32=False, color_type='unchanged'):
self.to_float32 = to_float32
self.color_type = color_type
def __call__(self, results):
filename = results['img_filename']
img = [mmcv.imread(name, self.color_type).astype(np.float32) for name in filename]
results['filename'] = [str(name) for name in filename]
results['img'] = img
results['img_shape'] = img[0].shape
results['ori_lidar2img'] = copy.deepcopy(results['lidar2img'])
results['scale_factor'] = 1.0
num_channels = 3
results['img_norm_cfg'] = dict(
mean=np.zeros(num_channels, dtype=np.float32),
std=np.ones(num_channels, dtype=np.float32),
to_rgb=False)
return results
def __repr__(self):
"""str: Return a string that describes the module."""
repr_str = self.__class__.__name__
repr_str += f'(to_float32={self.to_float32}, '
repr_str += f"color_type='{self.color_type}')"
return repr_str
@PIPELINES.register_module()
class AV2ResizeCropFlipRotImageV2():
def __init__(self, data_aug_conf=None, multi_stamps=False):
self.data_aug_conf = data_aug_conf
self.min_size = 2.0
self.multi_stamps = multi_stamps
def __call__(self, results):
imgs = results['img']
N = len(imgs) // 2 if self.multi_stamps else len(imgs)
new_imgs = []
new_gt_bboxes = []
new_centers2d = []
new_gt_labels = []
new_depths = []
ida_mats = []
with_depthmap = ('depthmap' in results.keys())
if with_depthmap:
new_depthmaps = []
assert self.data_aug_conf['rot_lim'] == (0.0, 0.0), "Rotation is not currently supported"
for i in range(N):
H, W = imgs[i].shape[:2]
if H > W:
resize, resize_dims, crop = self._sample_augmentation_f(imgs[i])
img = Image.fromarray(np.uint8(imgs[i]))
if with_depthmap:
depthmap_im = Image.fromarray(results['depthmap'][i])
else:
depthmap_im = None
img, ida_mat_f, depthmap = self._img_transform(img, resize=resize, resize_dims=resize_dims, crop=crop, depthmap=depthmap_im)
img_f = np.array(img).astype(np.float32)
if 'gt_bboxes' in results.keys() and len(results['gt_bboxes'])>0:
gt_bboxes = results['gt_bboxes'][i]
centers2d = results['centers2d'][i]
gt_labels = results['gt_labels'][i]
depths = results['depths'][i]
if len(gt_bboxes) != 0:
gt_bboxes, centers2d, gt_labels, depths = self._bboxes_transform(
img_f, gt_bboxes, centers2d, gt_labels, depths, resize=resize, crop=crop,
)
resize, resize_dims, crop, flip, rotate = self._sample_augmentation(img_f)
img = Image.fromarray(np.uint8(img_f))
img, ida_mat, depthmap = self._img_transform(img, resize=resize, resize_dims=resize_dims, crop=crop, flip=flip, rotate=rotate, depthmap=depthmap)
img = np.array(img).astype(np.float32)
if 'gt_bboxes' in results.keys() and len(results['gt_bboxes'])>0:
if len(gt_bboxes) != 0:
gt_bboxes, centers2d, gt_labels, depths = self._bboxes_transform(img, gt_bboxes, centers2d, gt_labels,depths, resize=resize, crop=crop, flip=flip,)
if len(gt_bboxes) != 0:
gt_bboxes, centers2d, gt_labels, depths = self._filter_invisible(img, gt_bboxes, centers2d, gt_labels, depths)
new_gt_bboxes.append(gt_bboxes)
new_centers2d.append(centers2d)
new_gt_labels.append(gt_labels)
new_depths.append(depths)
new_imgs.append(img)
results['intrinsics'][i][:3, :3] = ida_mat @ ida_mat_f @ results['intrinsics'][i][:3, :3]
ida_mats.append(np.array(ida_mat @ ida_mat_f))
if with_depthmap:
new_depthmaps.append(np.array(depthmap))
else:
resize, resize_dims, crop, flip, rotate = self._sample_augmentation(imgs[i])
img = Image.fromarray(np.uint8(imgs[i]))
if with_depthmap:
depthmap_im = Image.fromarray(results['depthmap'][i])
else:
depthmap_im = None
img, ida_mat, depthmap = self._img_transform(
img,
resize=resize,
resize_dims=resize_dims,
crop=crop,
flip=flip,
rotate=rotate,
depthmap=depthmap_im,
)
img = np.array(img).astype(np.float32)
if 'gt_bboxes' in results.keys() and len(results['gt_bboxes'])>0:
gt_bboxes = results['gt_bboxes'][i]
centers2d = results['centers2d'][i]
gt_labels = results['gt_labels'][i]
depths = results['depths'][i]
if len(gt_bboxes) != 0:
gt_bboxes, centers2d, gt_labels, depths = self._bboxes_transform(
img,
gt_bboxes,
centers2d,
gt_labels,
depths,
resize=resize,
crop=crop,
flip=flip,
)
if len(gt_bboxes) != 0:
gt_bboxes, centers2d, gt_labels, depths = self._filter_invisible(
img,
gt_bboxes,
centers2d,
gt_labels,
depths
)
new_gt_bboxes.append(gt_bboxes)
new_centers2d.append(centers2d)
new_gt_labels.append(gt_labels)
new_depths.append(depths)
new_imgs.append(img)
results['intrinsics'][i][:3, :3] = ida_mat @ results['intrinsics'][i][:3, :3]
ida_mats.append(np.array(ida_mat))
if with_depthmap:
new_depthmaps.append(np.array(depthmap))
results['gt_bboxes'] = new_gt_bboxes
results['centers2d'] = new_centers2d
results['gt_labels'] = new_gt_labels
results['depths'] = new_depths
results['img'] = new_imgs
results['cam2img'] = results['intrinsics']
results['lidar2img'] = [results['intrinsics'][i] @ results['extrinsics'][i] for i in
range(len(results['extrinsics']))]
results['img_shape'] = [img.shape for img in new_imgs]
results['pad_shape'] = [img.shape for img in new_imgs]
results['ida_mat'] = ida_mats # shape N * (3, 3)
if with_depthmap:
results['depthmap'] = new_depthmaps
return results
def _bboxes_transform(self, img, bboxes, centers2d, gt_labels, depths, resize, crop, flip=False):
assert len(bboxes) == len(centers2d) == len(gt_labels) == len(depths)
fH, fW = img.shape[:2]
bboxes = bboxes * resize
bboxes[:, 0] = bboxes[:, 0] - crop[0]
bboxes[:, 1] = bboxes[:, 1] - crop[1]
bboxes[:, 2] = bboxes[:, 2] - crop[0]
bboxes[:, 3] = bboxes[:, 3] - crop[1]
bboxes[:, 0] = np.clip(bboxes[:, 0], 0, fW)
bboxes[:, 2] = np.clip(bboxes[:, 2], 0, fW)
bboxes[:, 1] = np.clip(bboxes[:, 1], 0, fH)
bboxes[:, 3] = np.clip(bboxes[:, 3], 0, fH)
keep = ((bboxes[:, 2] - bboxes[:, 0]) >= self.min_size) & ((bboxes[:, 3] - bboxes[:, 1]) >= self.min_size)
if flip:
x0 = bboxes[:, 0].copy()
x1 = bboxes[:, 2].copy()
bboxes[:, 2] = fW - x0
bboxes[:, 0] = fW - x1
# normalize
bboxes = bboxes[keep]
centers2d = centers2d * resize
centers2d[:, 0] = centers2d[:, 0] - crop[0]
centers2d[:, 1] = centers2d[:, 1] - crop[1]
centers2d[:, 0] = np.clip(centers2d[:, 0], 0, fW)
centers2d[:, 1] = np.clip(centers2d[:, 1], 0, fH)
if flip:
centers2d[:, 0] = fW - centers2d[:, 0]
# normalize
centers2d = centers2d[keep]
gt_labels = gt_labels[keep]
depths = depths[keep]
return bboxes, centers2d, gt_labels, depths
def offline_2d_transform(self, img, bboxes, resize, crop, flip=False):
fH, fW = img.shape[:2]
bboxes = np.array(bboxes).reshape(-1, 6)
bboxes[..., :4] = bboxes[..., :4] * resize
bboxes[:, 0] = bboxes[:, 0] - crop[0]
bboxes[:, 1] = bboxes[:, 1] - crop[1]
bboxes[:, 2] = bboxes[:, 2] - crop[0]
bboxes[:, 3] = bboxes[:, 3] - crop[1]
bboxes[:, 0] = np.clip(bboxes[:, 0], 0, fW)
bboxes[:, 2] = np.clip(bboxes[:, 2], 0, fW)
bboxes[:, 1] = np.clip(bboxes[:, 1], 0, fH)
bboxes[:, 3] = np.clip(bboxes[:, 3], 0, fH)
if flip:
x0 = bboxes[:, 0].copy()
x1 = bboxes[:, 2].copy()
bboxes[:, 2] = fW - x0
bboxes[:, 0] = fW - x1
return bboxes
def _filter_invisible(self, img, bboxes, centers2d, gt_labels, depths):
assert len(bboxes) == len(centers2d) == len(gt_labels) == len(depths)
fH, fW = img.shape[:2]
indices_maps = np.zeros((fH, fW))
tmp_bboxes = np.zeros_like(bboxes)
tmp_bboxes[:, :2] = np.ceil(bboxes[:, :2])
tmp_bboxes[:, 2:] = np.floor(bboxes[:, 2:])
tmp_bboxes = tmp_bboxes.astype(np.int64)
sort_idx = np.argsort(-depths, axis=0, kind='stable')
tmp_bboxes = tmp_bboxes[sort_idx]
bboxes = bboxes[sort_idx]
depths = depths[sort_idx]
centers2d = centers2d[sort_idx]
gt_labels = gt_labels[sort_idx]
for i in range(bboxes.shape[0]):
u1, v1, u2, v2 = tmp_bboxes[i]
indices_maps[v1:v2, u1:u2] = i
indices_res = np.unique(indices_maps).astype(np.int64)
bboxes = bboxes[indices_res]
depths = depths[indices_res]
centers2d = centers2d[indices_res]
gt_labels = gt_labels[indices_res]
return bboxes, centers2d, gt_labels, depths
def _get_rot(self, h):
return torch.Tensor(
[
[np.cos(h), np.sin(h)],
[-np.sin(h), np.cos(h)],
]
)
def _img_transform(self, img, resize, resize_dims, crop, flip=False, rotate=0, depthmap=None):
ida_rot = torch.eye(2)
ida_tran = torch.zeros(2)
# adjust image
img = img.resize(resize_dims)
img = img.crop(crop)
if flip:
img = img.transpose(method=Image.FLIP_LEFT_RIGHT)
img = img.rotate(rotate)
# adjust depthmap (int32)
if depthmap is not None:
depthmap = depthmap.resize(resize_dims, resample=Image.NEAREST)
depthmap = depthmap.crop(crop)
if flip:
depthmap = depthmap.transpose(method=Image.FLIP_LEFT_RIGHT)
depthmap = depthmap.rotate(rotate, resample=Image.NEAREST)
# post-homography transformation
ida_rot *= resize
ida_tran -= torch.Tensor(crop[:2])
if flip:
A = torch.Tensor([[-1, 0], [0, 1]])
b = torch.Tensor([crop[2] - crop[0], 0])
ida_rot = A.matmul(ida_rot)
ida_tran = A.matmul(ida_tran) + b
A = self._get_rot(rotate / 180 * np.pi)
b = torch.Tensor([crop[2] - crop[0], crop[3] - crop[1]]) / 2
b = A.matmul(-b) + b
ida_rot = A.matmul(ida_rot)
ida_tran = A.matmul(ida_tran) + b
ida_mat = torch.eye(3)
ida_mat[:2, :2] = ida_rot
ida_mat[:2, 2] = ida_tran
return img, ida_mat, depthmap
def _sample_augmentation(self, img):
H, W = img.shape[:2]
fH, fW = self.data_aug_conf["final_dim"]
resize = np.random.uniform(*self.data_aug_conf["resize_lim"])
resize_dims = (int(W * resize), int(H * resize))
newW, newH = resize_dims
crop_h = int((1 - np.random.uniform(*self.data_aug_conf["bot_pct_lim"])) * newH) - fH
crop_w = int(np.random.uniform(0, max(0, newW - fW)))
crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)
flip = False
if self.data_aug_conf["rand_flip"] and np.random.choice([0, 1]):
flip = True
rotate = np.random.uniform(*self.data_aug_conf["rot_lim"])
return resize, resize_dims, crop, flip, rotate
def _sample_augmentation_f(self, img):
H, W = img.shape[:2]
fH, fW = W, H
resize = np.round(((H + 50) / W), 2)
resize_dims = (int(W * resize), int(H * resize))
newW, newH = resize_dims
crop_h = int((newH - fH) / 2)
crop_w = int((newW - fW) / 2)
crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)
return resize, resize_dims, crop
@PIPELINES.register_module()
class AV2PadMultiViewImage():
"""Pad the multi-view image.
There are two padding modes: (1) pad to a fixed size and (2) pad to the
minimum size that is divisible by some number.
Added keys are "pad_shape", "pad_fixed_size", "pad_size_divisor",
Args:
size (tuple, optional): Fixed padding size.
size_divisor (int, optional): The divisor of padded size.
pad_val (float, optional): Padding value, 0 by default.
"""
def __init__(self, size=None, size_divisor=None, pad_val=0):
self.size = size
self.size_divisor = size_divisor
self.pad_val = pad_val
assert size is not None or size_divisor is not None
assert size_divisor is None or size is None
def _pad_img(self, results):
"""Pad images according to ``self.size``."""
if self.size == 'same2max':
max_shape = max([img.shape for img in results['img']])[:2]
padded_img = [mmcv.impad(img, shape=max_shape, pad_val=self.pad_val) for img in results['img']]
with_depthmap = ('depthmap' in results.keys())
if with_depthmap:
results['depthmap'] = [mmcv.impad(depthmap, shape=max_shape, pad_val=self.pad_val) for depthmap in results['depthmap']]
elif self.size is not None:
padded_img = [mmcv.impad(img, shape=self.size, pad_val=self.pad_val) for img in results['img']]
elif self.size_divisor is not None:
padded_img = [
mmcv.impad_to_multiple(img, self.size_divisor, pad_val=self.pad_val) for img in results['img']
]
results['ori_shape'] = [img.shape for img in results['img']]
results['img'] = padded_img
results['img_shape'] = [img.shape for img in padded_img]
results['pad_shape'] = [img.shape for img in padded_img]
results['pad_fixed_size'] = self.size
results['pad_size_divisor'] = self.size_divisor
def __call__(self, results):
"""Call function to pad images, masks, semantic segmentation maps.
Args:
results (dict): Result dict from loading pipeline.
Returns:
dict: Updated result dict.
"""
self._pad_img(results)
return results
def __repr__(self):
repr_str = self.__class__.__name__
repr_str += f'(size={self.size}, '
repr_str += f'size_divisor={self.size_divisor}, '
repr_str += f'pad_val={self.pad_val})'
return repr_str
@PIPELINES.register_module()
class AV2DownsampleQuantizeDepthmap():
"""
Given downsample stride, downsample depthmap to (N, H, W), and make Quantization to return onehot format
Input depthmap in numpy array, Output in torch array.
"""
def __init__(self, downsample=16, grid_config=None):
'''
default: grid_config = [1, 150, 1]
'''
self.downsample = downsample
self.grid_config = grid_config
self.D = int(self.grid_config[1] / self.grid_config[2]) # D_max
def __call__(self, results):
"""
"""
depth_maps = torch.from_numpy(np.stack(results['depthmap'])) / 100.0 # (N, Hi, Wi)
gt_depths = self._get_downsampled_gt_depth(depth_maps) # (N, H/downsample, W/downsample)
gt_depths_ = self._quantize_gt_depth(gt_depths) # (N, Hd, Wd, self.D=150)
results['depthmap'] = gt_depths_
return results
def _get_downsampled_gt_depth(self, gt_depths):
"""
Input:
gt_depths: [B, N, H, W]
Output:
gt_depths: [B*N*h*w, d]
"""
N, H, W = gt_depths.shape
gt_depths = gt_depths.view(N, H // self.downsample, self.downsample, W // self.downsample, self.downsample, 1)
gt_depths = gt_depths.permute(0, 1, 3, 5, 2, 4).contiguous()
gt_depths = gt_depths.view(-1, self.downsample * self.downsample)
gt_depths_tmp = torch.where(gt_depths == 0.0, 1e5 * torch.ones_like(gt_depths), gt_depths)
gt_depths = torch.min(gt_depths_tmp, dim=-1).values
gt_depths = gt_depths.view(N, H // self.downsample, W // self.downsample)
gt_depths = torch.where(gt_depths == 1e5, torch.zeros_like(gt_depths), gt_depths)
return gt_depths
def _quantize_gt_depth(self, gt_depths):
gt_depths = (gt_depths - (self.grid_config[0] - self.grid_config[2])) / self.grid_config[2]
gt_depths = torch.where((gt_depths < self.D + 1) & (gt_depths >= 0.0), gt_depths, torch.zeros_like(gt_depths))
gt_depths = F.one_hot(gt_depths.long(), num_classes=self.D + 1)[..., 1:] # .view(-1, self.D + 1)
return gt_depths.float()
@PIPELINES.register_module()
class AV2DownsampleQuantizeInstanceDepthmap():
"""
Given downsample stride, downsample depthmap to (N, H, W), and make Quantization to return onehot format
Input depthmap in numpy array, Output in torch array.
"""
def __init__(self, downsample=8, depth_config={}):
'''
default: LID style
'''
self.downsample = downsample
self.depth_min, self.depth_max, self.num_bins = [depth_config.get(key) for key in
['depth_min', 'depth_max', 'num_depth_bins']]
def __call__(self, results):
"""
"""
# depth_maps = torch.from_numpy(np.stack(results['depthmap'])) / 100.0 # (N, Hi, Wi)
# gt_depths = self._get_downsampled_gt_depth(depth_maps) # (N, H/downsample, W/downsample)
# gt_depths_ = self._quantize_gt_depth(gt_depths) # (N, Hd, Wd, self.D=150)
# results['depthmap'] = gt_depths_
gt_boxes2d, gt_center_depth = results['gt_bboxes'], results['depths'] # np array, N*(M,4), N*(M)
H, W = results['img_shape'][0][:2]
H, W = int(H / self.downsample), int(W / self.downsample)
depth_maps, fg_mask = self.build_target_depth_from_3dcenter_argo(gt_boxes2d, gt_center_depth, (H, W))
depth_target = self.bin_depths(depth_maps, "LID", self.depth_min, self.depth_max, self.num_bins, target=True)
results['ins_depthmap'] = depth_target # (N, H, W)
results['ins_depthmap_mask'] = fg_mask # (N, H, W)
return results
def build_target_depth_from_3dcenter_argo(self, gt_boxes2d, gt_center_depth, HW):
H, W = HW
B = len(gt_boxes2d) # B is N indeed
depth_maps = torch.zeros((B, H, W), dtype=torch.float)
fg_mask = torch.zeros_like(depth_maps).bool()
for b in range(B):
center_depth_per_batch = torch.from_numpy(gt_center_depth[b])
# Set box corners
if gt_boxes2d[b].shape[0] > 0:
gt_boxes_per_batch = torch.from_numpy(gt_boxes2d[b])
gt_boxes_per_batch = gt_boxes_per_batch / self.downsample # downsample is necessary
gt_boxes_per_batch[:, :2] = torch.floor(gt_boxes_per_batch[:, :2])
gt_boxes_per_batch[:, 2:] = torch.ceil(gt_boxes_per_batch[:, 2:])
gt_boxes_per_batch = gt_boxes_per_batch.long()
for n in range(gt_boxes_per_batch.shape[0]):
u1, v1, u2, v2 = gt_boxes_per_batch[n]
depth_maps[b, v1:v2, u1:u2] = center_depth_per_batch[n]
fg_mask[b, v1:v2, u1:u2] = True
return depth_maps, fg_mask
def bin_depths(self, depth_map, mode="LID", depth_min=1e-3, depth_max=60, num_bins=80, target=False):
"""
Converts depth map into bin indices
Args:
depth_map [torch.Tensor(H, W)]: Depth Map
mode [string]: Discretiziation mode (See https://arxiv.org/pdf/2005.13423.pdf for more details)
UD: Uniform discretiziation
LID: Linear increasing discretiziation
SID: Spacing increasing discretiziation
depth_min [float]: Minimum depth value
depth_max [float]: Maximum depth value
num_bins [int]: Number of depth bins
target [bool]: Whether the depth bins indices will be used for a target tensor in loss comparison
Returns:
indices [torch.Tensor(H, W)]: Depth bin indices
"""
if mode == "UD":
bin_size = (depth_max - depth_min) / num_bins
indices = ((depth_map - depth_min) / bin_size)
elif mode == "LID":
bin_size = 2 * (depth_max - depth_min) / (num_bins * (1 + num_bins))
indices = -0.5 + 0.5 * torch.sqrt(1 + 8 * (depth_map - depth_min) / bin_size)
# elif mode == "SID":
# indices = num_bins * (torch.log(1 + depth_map) - math.log(1 + depth_min)) / \
# (math.log(1 + depth_max) - math.log(1 + depth_min))
else:
raise NotImplementedError
if target:
# Remove indicies outside of bounds
mask = (indices < 0) | (indices > num_bins) | (~torch.isfinite(indices))
indices[mask] = num_bins
# Convert to integer
indices = indices.type(torch.int64)
return indices
================================================
FILE: projects/mmdet3d_plugin/datasets/pipelines/formating.py
================================================
# ------------------------------------------------------------------------
# Modified from mmdetection3d (https://github.com/open-mmlab/mmdetection3d)
# Copyright (c) OpenMMLab. All rights reserved.
# ------------------------------------------------------------------------
# Modified by Shihao Wang
# ------------------------------------------------------------------------
import numpy as np
from mmdet.datasets.builder import PIPELINES
from mmcv.parallel import DataContainer as DC
from mmdet3d.core.points import BasePoints
from mmdet.datasets.pipelines import to_tensor
from mmdet3d.datasets.pipelines import DefaultFormatBundle
@PIPELINES.register_module()
class PETRFormatBundle3D(DefaultFormatBundle):
"""Default formatting bundle.
It simplifies the pipeline of formatting common fields for voxels,
including "proposals", "gt_bboxes", "gt_labels", "gt_masks" and
"gt_semantic_seg".
These fields are formatted as follows.
- img: (1)transpose, (2)to tensor, (3)to DataContainer (stack=True)
- proposals: (1)to tensor, (2)to DataContainer
- gt_bboxes: (1)to tensor, (2)to DataContainer
- gt_bboxes_ignore: (1)to tensor, (2)to DataContainer
- gt_labels: (1)to tensor, (2)to DataContainer
"""
def __init__(self, class_names, collect_keys, with_gt=True, with_label=True):
super(PETRFormatBundle3D, self).__init__()
self.class_names = class_names
self.with_gt = with_gt
self.with_label = with_label
self.collect_keys = collect_keys
def __call__(self, results):
"""Call function to transform and format common fields in results.
Args:
results (dict): Result dict contains the data to convert.
Returns:
dict: The result dict contains the data that is formatted with
default bundle.
"""
# Format 3D data
if 'points' in results:
assert isinstance(results['points'], BasePoints)
results['points'] = DC(results['points'].tensor)
for key in self.collect_keys:
if key in ['timestamp', 'img_timestamp']:
results[key] = DC(to_tensor(np.array(results[key], dtype=np.float64)))
else:
results[key] = DC(to_tensor(np.array(results[key], dtype=np.float32)))
for key in ['voxels', 'coors', 'voxel_centers', 'num_points']:
if key not in results:
continue
results[key] = DC(to_tensor(results[key]), stack=False)
if self.with_gt:
# Clean GT bboxes in the final
if 'gt_bboxes_3d_mask' in results:
gt_bboxes_3d_mask = results['gt_bboxes_3d_mask']
results['gt_bboxes_3d'] = results['gt_bboxes_3d'][
gt_bboxes_3d_mask]
if 'gt_names_3d' in results:
results['gt_names_3d'] = results['gt_names_3d'][
gt_bboxes_3d_mask]
if 'centers2d' in results:
results['centers2d'] = results['centers2d'][
gt_bboxes_3d_mask]
if 'depths' in results:
results['depths'] = results['depths'][gt_bboxes_3d_mask]
if 'gt_bboxes_mask' in results:
gt_bboxes_mask = results['gt_bboxes_mask']
if 'gt_bboxes' in results:
results['gt_bboxes'] = results['gt_bboxes'][gt_bboxes_mask]
results['gt_names'] = results['gt_names'][gt_bboxes_mask]
if self.with_label:
if 'gt_names' in results and len(results['gt_names']) == 0:
results['gt_labels'] = np.array([], dtype=np.int64)
results['attr_labels'] = np.array([], dtype=np.int64)
elif 'gt_names' in results and isinstance(
results['gt_names'][0], list):
# gt_labels might be a list of list in multi-view setting
results['gt_labels'] = [
np.array([self.class_names.index(n) for n in res],
dtype=np.int64) for res in results['gt_names']
]
elif 'gt_names' in results:
results['gt_labels'] = np.array([
self.class_names.index(n) for n in results['gt_names']
],
dtype=np.int64)
# we still assume one pipeline for one frame LiDAR
# thus, the 3D name is list[string]
if 'gt_names_3d' in results:
results['gt_labels_3d'] = np.array([
self.class_names.index(n)
for n in results['gt_names_3d']
],
dtype=np.int64)
results = super(PETRFormatBundle3D, self).__call__(results)
return results
def __repr__(self):
"""str: Return a string that describes the module."""
repr_str = self.__class__.__name__
repr_str += f'(class_names={self.class_names}, '
repr_str += f'collect_keys={self.collect_keys}, with_gt={self.with_gt}, with_label={self.with_label})'
return repr_str
================================================
FILE: projects/mmdet3d_plugin/datasets/pipelines/transform_3d.py
================================================
# ------------------------------------------------------------------------
# Copyright (c) 2022 megvii-model. All Rights Reserved.
# ------------------------------------------------------------------------
# Modified from DETR3D (https://github.com/WangYueFt/detr3d)
# Copyright (c) 2021 Wang, Yue
# ------------------------------------------------------------------------
# Modified from mmdetection3d (https://github.com/open-mmlab/mmdetection3d)
# Copyright (c) OpenMMLab. All rights reserved.
# ------------------------------------------------------------------------
# Modified by Shihao Wang
# ------------------------------------------------------------------------
import numpy as np
import mmcv
from mmdet.datasets.builder import PIPELINES
import torch
from PIL import Image
# import nori2 as nori
# import refile
# from skimage import io
@PIPELINES.register_module()
class PadMultiViewImage():
"""Pad the multi-view image.
There are two padding modes: (1) pad to a fixed size and (2) pad to the
minimum size that is divisible by some number.
Added keys are "pad_shape", "pad_fixed_size", "pad_size_divisor",
Args:
size (tuple, optional): Fixed padding size.
size_divisor (int, optional): The divisor of padded size.
pad_val (float, optional): Padding value, 0 by default.
"""
def __init__(self, size=None, size_divisor=None, pad_val=0):
self.size = size
self.size_divisor = size_divisor
self.pad_val = pad_val
assert size is not None or size_divisor is not None
assert size_divisor is None or size is None
def _pad_img(self, results):
"""Pad images according to ``self.size``."""
if self.size is not None:
padded_img = [mmcv.impad(img,
shape = self.size, pad_val=self.pad_val) for img in results['img']]
elif self.size_divisor is not None:
padded_img = [mmcv.impad_to_multiple(img,
self.size_divisor, pad_val=self.pad_val) for img in results['img']]
results['img_shape'] = [img.shape for img in results['img']]
results['img'] = padded_img
results['pad_shape'] = [img.shape for img in padded_img]
results['pad_fix_size'] = self.size
results['pad_size_divisor'] = self.size_divisor
def __call__(self, results):
"""Call function to pad images, masks, semantic segmentation maps.
Args:
results (dict): Result dict from loading pipeline.
Returns:
dict: Updated result dict.
"""
self._pad_img(results)
return results
def __repr__(self):
repr_str = self.__class__.__name__
repr_str += f'(size={self.size}, '
repr_str += f'size_divisor={self.size_divisor}, '
repr_str += f'pad_val={self.pad_val})'
return repr_str
@PIPELINES.register_module()
class NormalizeMultiviewImage(object):
"""Normalize the image.
Added key is "img_norm_cfg".
Args:
mean (sequence): Mean values of 3 channels.
std (sequence): Std values of 3 channels.
to_rgb (bool): Whether to convert the image from BGR to RGB,
default is true.
"""
def __init__(self, mean, std, to_rgb=True):
self.mean = np.array(mean, dtype=np.float32)
self.std = np.array(std, dtype=np.float32)
self.to_rgb = to_rgb
def __call__(self, results):
"""Call function to normalize images.
Args:
results (dict): Result dict from loading pipeline.
Returns:
dict: Normalized results, 'img_norm_cfg' key is added into
result dict.
"""
results['img'] = [mmcv.imnormalize(
img, self.mean, self.std, self.to_rgb) for img in results['img']]
results['img_norm_cfg'] = dict(
mean=self.mean, std=self.std, to_rgb=self.to_rgb)
return results
def __repr__(self):
repr_str = self.__class__.__name__
repr_str += f'(mean={self.mean}, std={self.std}, to_rgb={self.to_rgb})'
return repr_str
@PIPELINES.register_module()
class ResizeCropFlipRotImage():
def __init__(self, data_aug_conf=None, with_2d=True, filter_invisible=True, training=True):
self.data_aug_conf = data_aug_conf
self.training = training
self.min_size = 2.0
self.with_2d = with_2d
self.filter_invisible = filter_invisible
def __call__(self, results):
imgs = results['img']
N = len(imgs)
new_imgs = []
new_gt_bboxes = []
new_centers2d = []
new_gt_labels = []
new_depths = []
assert self.data_aug_conf['rot_lim'] == (0.0, 0.0), "Rotation is not currently supported"
resize, resize_dims, crop, flip, rotate = self._sample_augmentation()
for i in range(N):
img = Image.fromarray(np.uint8(imgs[i]))
img, ida_mat = self._img_transform(
img,
resize=resize,
resize_dims=resize_dims,
crop=crop,
flip=flip,
rotate=rotate,
)
if self.training and self.with_2d:
gt_bboxes = results['gt_bboxes'][i]
centers2d = results['centers2d'][i]
gt_labels = results['gt_labels'][i]
depths = results['depths'][i]
if len(gt_bboxes) != 0:
gt_bboxes, centers2d, gt_labels, depths = self._bboxes_transform(
gt_bboxes,
centers2d,
gt_labels,
depths,
resize=resize,
crop=crop,
flip=flip,
)
if len(gt_bboxes) != 0 and self.filter_invisible:
gt_bboxes, centers2d, gt_labels, depths = self._filter_invisible(gt_bboxes, centers2d, gt_labels, depths)
new_gt_bboxes.append(gt_bboxes)
new_centers2d.append(centers2d)
new_gt_labels.append(gt_labels)
new_depths.append(depths)
new_imgs.append(np.array(img).astype(np.float32))
results['intrinsics'][i][:3, :3] = ida_mat @ results['intrinsics'][i][:3, :3]
results['gt_bboxes'] = new_gt_bboxes
results['centers2d'] = new_centers2d
results['gt_labels'] = new_gt_labels
results['depths'] = new_depths
results['img'] = new_imgs
results['lidar2img'] = [results['intrinsics'][i] @ results['extrinsics'][i] for i in range(len(results['extrinsics']))]
return results
def _bboxes_transform(self, bboxes, centers2d, gt_labels, depths,resize, crop, flip):
assert len(bboxes) == len(centers2d) == len(gt_labels) == len(depths)
fH, fW = self.data_aug_conf["final_dim"]
bboxes = bboxes * resize
bboxes[:, 0] = bboxes[:, 0] - crop[0]
bboxes[:, 1] = bboxes[:, 1] - crop[1]
bboxes[:, 2] = bboxes[:, 2] - crop[0]
bboxes[:, 3] = bboxes[:, 3] - crop[1]
bboxes[:, 0] = np.clip(bboxes[:, 0], 0, fW)
bboxes[:, 2] = np.clip(bboxes[:, 2], 0, fW)
bboxes[:, 1] = np.clip(bboxes[:, 1], 0, fH)
bboxes[:, 3] = np.clip(bboxes[:, 3], 0, fH)
keep = ((bboxes[:, 2] - bboxes[:, 0]) >= self.min_size) & ((bboxes[:, 3] - bboxes[:, 1]) >= self.min_size)
if flip:
x0 = bboxes[:, 0].copy()
x1 = bboxes[:, 2].copy()
bboxes[:, 2] = fW - x0
bboxes[:, 0] = fW - x1
bboxes = bboxes[keep]
centers2d = centers2d * resize
centers2d[:, 0] = centers2d[:, 0] - crop[0]
centers2d[:, 1] = centers2d[:, 1] - crop[1]
centers2d[:, 0] = np.clip(centers2d[:, 0], 0, fW)
centers2d[:, 1] = np.clip(centers2d[:, 1], 0, fH)
if flip:
centers2d[:, 0] = fW - centers2d[:, 0]
centers2d = centers2d[keep]
gt_labels = gt_labels[keep]
depths = depths[keep]
return bboxes, centers2d, gt_labels, depths
def _filter_invisible(self, bboxes, centers2d, gt_labels, depths):
assert len(bboxes) == len(centers2d) == len(gt_labels) == len(depths)
fH, fW = self.data_aug_conf["final_dim"]
indices_maps = np.zeros((fH,fW))
tmp_bboxes = np.zeros_like(bboxes)
tmp_bboxes[:, :2] = np.ceil(bboxes[:, :2])
tmp_bboxes[:, 2:] = np.floor(bboxes[:, 2:])
tmp_bboxes = tmp_bboxes.astype(np.int64)
sort_idx = np.argsort(-depths, axis=0, kind='stable')
tmp_bboxes = tmp_bboxes[sort_idx]
bboxes = bboxes[sort_idx]
depths = depths[sort_idx]
centers2d = centers2d[sort_idx]
gt_labels = gt_labels[sort_idx]
for i in range(bboxes.shape[0]):
u1, v1, u2, v2 = tmp_bboxes[i]
indices_maps[v1:v2, u1:u2] = i
indices_res = np.unique(indices_maps).astype(np.int64)
bboxes = bboxes[indices_res]
depths = depths[indices_res]
centers2d = centers2d[indices_res]
gt_labels = gt_labels[indices_res]
return bboxes, centers2d, gt_labels, depths
def _get_rot(self, h):
return torch.Tensor(
[
[np.cos(h), np.sin(h)],
[-np.sin(h), np.cos(h)],
]
)
def _img_transform(self, img, resize, resize_dims, crop, flip, rotate):
ida_rot = torch.eye(2)
ida_tran = torch.zeros(2)
# adjust image
img = img.resize(resize_dims)
img = img.crop(crop)
if flip:
img = img.transpose(method=Image.FLIP_LEFT_RIGHT)
img = img.rotate(rotate)
# post-homography transformation
ida_rot *= resize
ida_tran -= torch.Tensor(crop[:2])
if flip:
A = torch.Tensor([[-1, 0], [0, 1]])
b = torch.Tensor([crop[2] - crop[0], 0])
ida_rot = A.matmul(ida_rot)
ida_tran = A.matmul(ida_tran) + b
A = self._get_rot(rotate / 180 * np.pi)
b = torch.Tensor([crop[2] - crop[0], crop[3] - crop[1]]) / 2
b = A.matmul(-b) + b
ida_rot = A.matmul(ida_rot)
ida_tran = A.matmul(ida_tran) + b
ida_mat = torch.eye(3)
ida_mat[:2, :2] = ida_rot
ida_mat[:2, 2] = ida_tran
return img, ida_mat
def _sample_augmentation(self):
H, W = self.data_aug_conf["H"], self.data_aug_conf["W"]
fH, fW = self.data_aug_conf["final_dim"]
if self.training:
resize = np.random.uniform(*self.data_aug_conf["resize_lim"])
resize_dims = (int(W * resize), int(H * resize))
newW, newH = resize_dims
crop_h = int((1 - np.random.uniform(*self.data_aug_conf["bot_pct_lim"])) * newH) - fH
crop_w = int(np.random.uniform(0, max(0, newW - fW)))
crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)
flip = False
if self.data_aug_conf["rand_flip"] and np.random.choice([0, 1]):
flip = True
rotate = np.random.uniform(*self.data_aug_conf["rot_lim"])
else:
resize = max(fH / H, fW / W)
resize_dims = (int(W * resize), int(H * resize))
newW, newH = resize_dims
crop_h = int((1 - np.mean(self.data_aug_conf["bot_pct_lim"])) * newH) - fH
crop_w = int(max(0, newW - fW) / 2)
crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)
flip = False
rotate = 0
return resize, resize_dims, crop, flip, rotate
# @PIPELINES.register_module()
# class GlobalRotScaleTransImage():
# def __init__(
# self,
# rot_range=[-0.3925, 0.3925],
# scale_ratio_range=[0.95, 1.05],
# translation_std=[0, 0, 0],
# reverse_angle=False,
# training=True,
# ):
# self.rot_range = rot_range
# self.scale_ratio_range = scale_ratio_range
# self.translation_std = translation_std
# self.reverse_angle = reverse_angle
# self.training = training
# def __call__(self, results):
# # random rotate
# translation_std = np.array(self.translation_std, dtype=np.float32)
# rot_angle = np.random.uniform(*self.rot_range)
# scale_ratio = np.random.uniform(*self.scale_ratio_range)
# trans = np.random.normal(scale=translation_std, size=3).T
# self._rotate_bev_along_z(results, rot_angle)
# if self.reverse_angle:
# rot_angle = rot_angle * -1
# results["gt_bboxes_3d"].rotate(
# np.array(rot_angle)
# )
# # random scale
# self._scale_xyz(results, scale_ratio)
# results["gt_bboxes_3d"].scale(scale_ratio)
# #random translate
# self._trans_xyz(results, trans)
# results["gt_bboxes_3d"].translate(trans)
# return results
# def _trans_xyz(self, results, trans):
# trans_mat = torch.eye(4, 4)
# trans_mat[:3, -1] = torch.from_numpy(trans).reshape(1, 3)
# trans_mat_inv = torch.inverse(trans_mat)
# num_view = len(results["lidar2img"])
# results['ego_pose'] = (torch.tensor(results["ego_pose"]).float() @ trans_mat_inv).numpy()
# results['ego_pose_inv'] = (trans_mat.float() @ torch.tensor(results["ego_pose_inv"])).numpy()
# for view in range(num_view):
# results["lidar2img"][view] = (torch.tensor(results["lidar2img"][view]).float() @ trans_mat_inv).numpy()
# def _rotate_bev_along_z(self, results, angle):
# rot_cos = torch.cos(torch.tensor(angle))
# rot_sin = torch.sin(torch.tensor(angle))
# rot_mat = torch.tensor([[rot_cos, rot_sin, 0, 0], [-rot_sin, rot_cos, 0, 0], [0, 0, 1, 0], [0, 0, 0, 1]])
# rot_mat_inv = torch.inverse(rot_mat)
# results['ego_pose'] = (torch.tensor(results["ego_pose"]).float() @ rot_mat_inv).numpy()
# results['ego_pose_inv'] = (rot_mat.float() @ torch.tensor(results["ego_pose_inv"])).numpy()
# num_view = len(results["lidar2img"])
# for view in range(num_view):
# results["lidar2img"][view] = (torch.tensor(results["lidar2img"][view]).float() @ rot_mat_inv).numpy()
# def _scale_xyz(self, results, scale_ratio):
# scale_mat = torch.tensor(
# [
# [scale_ratio, 0, 0, 0],
# [0, scale_ratio, 0, 0],
# [0, 0, scale_ratio, 0],
# [0, 0, 0, 1],
# ]
# )
# scale_mat_inv = torch.inverse(scale_mat)
# results['ego_pose'] = (torch.tensor(results["ego_pose"]).float() @ scale_mat_inv).numpy()
# results['ego_pose_inv'] = (scale_mat @ torch.tensor(results["ego_pose_inv"]).float()).numpy()
# num_view = len(results["lidar2img"])
# for view in range(num_view):
# results["lidar2img"][view] = (torch.tensor(results["lidar2img"][view]).float() @ scale_mat_inv).numpy()
# @PIPELINES.register_module()
# class LoadMultiViewImageFromNori(object):
# """Load multi channel images from a list of separate channel files.
# Expects results['img_filename'] to be a list of filenames.
# Args:
# to_float32 (bool): Whether to convert the img to float32.
# Defaults to False.
# color_type (str): Color type of the file. Defaults to 'unchanged'.
# """
# def __init__(self,
# nori_lists=None,
# to_float32=True,
# color_type='unchanged',
# data_prefix=None):
# self.nori_lists = nori_lists
# self.to_float32 = to_float32
# self.color_type = color_type
# self.fetcher = nori.Fetcher()
# self.data_prefix = data_prefix
# self.name2nori = self.decode_nori_list()
# def decode_nori_list(self):
# ret = {}
# for nori_list in self.nori_lists:
# with refile.smart_open(nori_list, "r") as f:
# for line in f:
# nori_id, filename = line.strip().split()
# ret[filename] = nori_
gitextract_puxntax1/
├── LICENSE
├── README.md
├── docs/
│ └── get_started.md
├── projects/
│ ├── configs/
│ │ └── far3d.py
│ └── mmdet3d_plugin/
│ ├── __init__.py
│ ├── core/
│ │ ├── apis/
│ │ │ ├── __init__.py
│ │ │ ├── mmdet_train.py
│ │ │ ├── test.py
│ │ │ └── train.py
│ │ ├── bbox/
│ │ │ ├── assigners/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── hungarian_assigner_2d.py
│ │ │ │ └── hungarian_assigner_3d.py
│ │ │ ├── coders/
│ │ │ │ ├── __init__.py
│ │ │ │ └── nms_free_coder.py
│ │ │ ├── match_costs/
│ │ │ │ ├── __init__.py
│ │ │ │ └── match_cost.py
│ │ │ └── util.py
│ │ └── evaluation/
│ │ ├── __init__.py
│ │ └── eval_hooks.py
│ ├── datasets/
│ │ ├── __init__.py
│ │ ├── argoverse2_dataset.py
│ │ ├── argoverse2_dataset_t.py
│ │ ├── av2_eval_util.py
│ │ ├── av2_utils.py
│ │ ├── builder.py
│ │ ├── eval_recall.py
│ │ ├── nuscenes_dataset.py
│ │ ├── pipelines/
│ │ │ ├── __init__.py
│ │ │ ├── custom_pipeline.py
│ │ │ ├── formating.py
│ │ │ └── transform_3d.py
│ │ ├── samplers/
│ │ │ ├── __init__.py
│ │ │ ├── distributed_sampler.py
│ │ │ ├── group_sampler.py
│ │ │ └── sampler.py
│ │ └── summarize_metrics_av2.py
│ └── models/
│ ├── backbones/
│ │ ├── __init__.py
│ │ ├── vovnet.py
│ │ └── vovnetcp.py
│ ├── dense_heads/
│ │ ├── __init__.py
│ │ ├── farhead.py
│ │ └── yolox_head.py
│ ├── depth_predictor/
│ │ ├── __init__.py
│ │ ├── ddn_loss/
│ │ │ ├── __init__.py
│ │ │ ├── balancer.py
│ │ │ ├── ddn_loss.py
│ │ │ └── focalloss.py
│ │ └── depth_predictor.py
│ ├── detectors/
│ │ ├── __init__.py
│ │ └── far3d.py
│ ├── necks/
│ │ ├── __init__.py
│ │ ├── cp_fpn.py
│ │ └── second_fpn.py
│ └── utils/
│ ├── __init__.py
│ ├── attention.py
│ ├── deformable_aggregation.py
│ ├── detr3d_transformer.py
│ ├── grid_mask.py
│ ├── hook.py
│ ├── layer_decay_optimizer_constructor.py
│ ├── misc.py
│ ├── petr_transformer.py
│ ├── positional_encoding.py
│ ├── sparse_blocks.py
│ └── warmup_fp16_optimizer.py
├── py38.yaml
└── tools/
├── analysis_tools/
│ └── benchmark.py
├── create_data_nusc.py
├── create_infos_av2/
│ ├── create_av2_infos.py
│ └── gather_argo2_anno_feather.py
├── data_converter/
│ ├── __init__.py
│ ├── info2coco.py
│ └── nuscenes_converter.py
├── dist_test.sh
├── dist_test_visualize.sh
├── dist_train.sh
├── filter_ckpt.py
├── multi_dist_train.sh
├── slurm_test.sh
├── slurm_train.sh
├── test.py
├── test_and_visualize.py
├── train.py
├── visual/
│ ├── __init__.py
│ ├── check_img_label.py
│ ├── vis_2d.ipynb
│ ├── vis_3dpred.py
│ ├── vis_3dpred_depth_stat.py
│ ├── vis_3dpred_depth_stat2.py
│ ├── vis_attention.py
│ ├── vis_av2.py
│ ├── vis_util.py
│ └── vis_yolox.py
├── visual_nuscenes.py
└── visualize.py
SYMBOL INDEX (528 symbols across 59 files)
FILE: projects/mmdet3d_plugin/core/apis/mmdet_train.py
function custom_train_detector (line 31) | def custom_train_detector(model,
FILE: projects/mmdet3d_plugin/core/apis/test.py
function custom_encode_mask_results (line 25) | def custom_encode_mask_results(mask_results):
function custom_multi_gpu_test (line 45) | def custom_multi_gpu_test(model, data_loader, tmpdir=None, gpu_collect=F...
function collect_results_cpu (line 116) | def collect_results_cpu(result_part, size, tmpdir=None):
function collect_results_gpu (line 163) | def collect_results_gpu(result_part, size):
FILE: projects/mmdet3d_plugin/core/apis/train.py
function custom_train_model (line 14) | def custom_train_model(model,
function train_model (line 41) | def train_model(model,
FILE: projects/mmdet3d_plugin/core/bbox/assigners/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: projects/mmdet3d_plugin/core/bbox/assigners/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,
class HungarianAssigner3DPolar (line 94) | class HungarianAssigner3DPolar(BaseAssigner):
method __init__ (line 95) | def __init__(self,
method assign (line 105) | def assign(self,
FILE: projects/mmdet3d_plugin/core/bbox/coders/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 93) | def decode(self, preds_dicts):
class NMSFreeCoderPolar (line 116) | class NMSFreeCoderPolar(BaseBBoxCoder):
method __init__ (line 128) | def __init__(self,
method encode (line 143) | def encode(self):
method decode_single (line 146) | def decode_single(self, cls_scores, bbox_preds):
method decode (line 199) | def decode(self, preds_dicts):
FILE: projects/mmdet3d_plugin/core/bbox/match_costs/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: projects/mmdet3d_plugin/core/bbox/util.py
function normalize_bbox (line 4) | def normalize_bbox(bboxes, pc_range):
function denormalize_bbox (line 25) | def denormalize_bbox(normalized_bboxes, pc_range):
function normalize_bbox_polar (line 54) | def normalize_bbox_polar(bboxes, pc_range):
function denormalize_bbox_polar (line 82) | def denormalize_bbox_polar(normalized_bboxes, pc_range):
FILE: projects/mmdet3d_plugin/core/evaluation/eval_hooks.py
function _calc_dynamic_intervals (line 17) | def _calc_dynamic_intervals(start_interval, dynamic_interval_list):
class CustomDistEvalHook (line 29) | class CustomDistEvalHook(BaseDistEvalHook):
method __init__ (line 31) | def __init__(self, *args, dynamic_intervals=None, **kwargs):
method _decide_interval (line 38) | def _decide_interval(self, runner):
method before_train_epoch (line 45) | def before_train_epoch(self, runner):
method before_train_iter (line 50) | def before_train_iter(self, runner):
method _do_evaluate (line 54) | def _do_evaluate(self, runner):
FILE: projects/mmdet3d_plugin/datasets/argoverse2_dataset.py
class Argoverse2Dataset (line 20) | class Argoverse2Dataset(Custom3DDataset):
method __init__ (line 23) | def __init__(self,
method get_cat_ids (line 61) | def get_cat_ids(self, idx):
method load_annotations (line 85) | def load_annotations(self, ann_file):
method get_data_info (line 99) | def get_data_info(self, index):
method get_ann_info (line 182) | def get_ann_info(self, index, input_dict):
method evaluate (line 224) | def evaluate(self,
method format_results (line 267) | def format_results(self,
method box_to_av2 (line 333) | def box_to_av2(self, boxes):
FILE: projects/mmdet3d_plugin/datasets/argoverse2_dataset_t.py
class Argoverse2DatasetT (line 16) | class Argoverse2DatasetT(Argoverse2Dataset):
method __init__ (line 19) | def __init__(self, collect_keys, seq_mode=False, seq_split_num=1, num_...
method _set_sequence_group_flag (line 40) | def _set_sequence_group_flag(self):
method prepare_train_data (line 82) | def prepare_train_data(self, index):
method prepare_test_data (line 122) | def prepare_test_data(self, index):
method union2one (line 136) | def union2one(self, queue):
method get_data_info (line 143) | def get_data_info(self, index):
method __getitem__ (line 243) | def __getitem__(self, idx):
method _rand_another (line 258) | def _rand_another(self, idx):
function invert_matrix_egopose_numpy (line 266) | def invert_matrix_egopose_numpy(egopose):
function convert_egopose_to_matrix_numpy (line 276) | def convert_egopose_to_matrix_numpy(rotation, translation):
FILE: projects/mmdet3d_plugin/datasets/av2_eval_util.py
function evaluate (line 60) | def evaluate(
function load_mapped_avm_and_egoposes (line 158) | def load_mapped_avm_and_egoposes(log_ids: List[str], dataset_dir: Path
function read_feather_remote (line 178) | def read_feather_remote(path: Path, columns: Optional[Tuple[str, ...]] =...
class ArgoverseStaticMapRemote (line 195) | class ArgoverseStaticMapRemote(ArgoverseStaticMap):
method from_json_remote (line 200) | def from_json_remote(cls, static_map_path_s3, static_map_path: Path) -...
method from_map_dir_remote (line 235) | def from_map_dir_remote(cls, log_map_dirpath: Path, build_raster: bool...
class GroundHeightLayerRemote (line 276) | class GroundHeightLayerRemote(GroundHeightLayer):
method from_file_remote (line 283) | def from_file_remote(cls, log_map_dirpath: Path, log_map_dirpath_s3) -...
FILE: projects/mmdet3d_plugin/datasets/av2_utils.py
class DetectionCfg (line 35) | class DetectionCfg:
method metrics_defaults (line 50) | def metrics_defaults(self) -> Tuple[float, ...]:
method tp_normalization_terms (line 62) | def tp_normalization_terms(self) -> Tuple[float, ...]:
function accumulate (line 70) | def accumulate(
function assign (line 115) | def assign(dts: NDArrayFloat, gts: NDArrayFloat, cfg: DetectionCfg) -> T...
function distance (line 159) | def distance(dts: NDArrayFloat, gts: NDArrayFloat, metric: DistanceType)...
function compute_affinity_matrix (line 175) | def compute_affinity_matrix(dts: NDArrayFloat, gts: NDArrayFloat, metric...
function compute_evaluated_dts_mask (line 185) | def compute_evaluated_dts_mask(
function compute_evaluated_gts_mask (line 205) | def compute_evaluated_gts_mask(
function compute_objects_in_roi_mask (line 222) | def compute_objects_in_roi_mask(cuboids_ego: NDArrayFloat, city_SE3_ego:...
function xyz_to_quat (line 241) | def xyz_to_quat(xyz_rad: Tensor) -> Tensor:
function yaw_to_quat (line 270) | def yaw_to_quat(yaw_rad: Tensor) -> Tensor:
FILE: projects/mmdet3d_plugin/datasets/builder.py
function build_dataloader (line 23) | def build_dataloader(dataset,
function worker_init_fn (line 121) | def worker_init_fn(worker_id, num_workers, rank, seed):
function custom_build_dataset (line 148) | def custom_build_dataset(cfg, default_args=None):
FILE: projects/mmdet3d_plugin/datasets/eval_recall.py
function bbox_cxcywh_to_xyxy (line 7) | def bbox_cxcywh_to_xyxy(bbox):
function bbox_overlaps (line 25) | def bbox_overlaps(bboxes1,
function eval_recall (line 86) | def eval_recall(gt_2dbboxes, gt_2d_depth, pred_bboxes, thr, range_m = [0...
function cal_recall_2d (line 121) | def cal_recall_2d(results_2d):
FILE: projects/mmdet3d_plugin/datasets/nuscenes_dataset.py
class CustomNuScenesDataset (line 23) | class CustomNuScenesDataset(NuScenesDataset):
method __init__ (line 29) | def __init__(self, collect_keys, seq_mode=False, seq_split_num=1, num_...
method _set_sequence_group_flag (line 43) | def _set_sequence_group_flag(self):
method prepare_train_data (line 82) | def prepare_train_data(self, index):
method prepare_test_data (line 118) | def prepare_test_data(self, index):
method union2one (line 132) | def union2one(self, queue):
method get_data_info (line 148) | def get_data_info(self, index):
method __getitem__ (line 243) | def __getitem__(self, idx):
function invert_matrix_egopose_numpy (line 258) | def invert_matrix_egopose_numpy(egopose):
function convert_egopose_to_matrix_numpy (line 268) | def convert_egopose_to_matrix_numpy(rotation, translation):
FILE: projects/mmdet3d_plugin/datasets/pipelines/custom_pipeline.py
class AV2LoadMultiViewImageFromFiles (line 18) | class AV2LoadMultiViewImageFromFiles(object):
method __init__ (line 20) | def __init__(self, to_float32=False, color_type='unchanged'):
method __call__ (line 24) | def __call__(self, results):
method __repr__ (line 40) | def __repr__(self):
class AV2ResizeCropFlipRotImageV2 (line 48) | class AV2ResizeCropFlipRotImageV2():
method __init__ (line 49) | def __init__(self, data_aug_conf=None, multi_stamps=False):
method __call__ (line 54) | def __call__(self, results):
method _bboxes_transform (line 186) | def _bboxes_transform(self, img, bboxes, centers2d, gt_labels, depths,...
method offline_2d_transform (line 224) | def offline_2d_transform(self, img, bboxes, resize, crop, flip=False):
method _filter_invisible (line 243) | def _filter_invisible(self, img, bboxes, centers2d, gt_labels, depths):
method _get_rot (line 269) | def _get_rot(self, h):
method _img_transform (line 277) | def _img_transform(self, img, resize, resize_dims, crop, flip=False, r...
method _sample_augmentation (line 313) | def _sample_augmentation(self, img):
method _sample_augmentation_f (line 328) | def _sample_augmentation_f(self, img):
class AV2PadMultiViewImage (line 341) | class AV2PadMultiViewImage():
method __init__ (line 351) | def __init__(self, size=None, size_divisor=None, pad_val=0):
method _pad_img (line 358) | def _pad_img(self, results):
method __call__ (line 380) | def __call__(self, results):
method __repr__ (line 390) | def __repr__(self):
class AV2DownsampleQuantizeDepthmap (line 398) | class AV2DownsampleQuantizeDepthmap():
method __init__ (line 404) | def __init__(self, downsample=16, grid_config=None):
method __call__ (line 412) | def __call__(self, results):
method _get_downsampled_gt_depth (line 422) | def _get_downsampled_gt_depth(self, gt_depths):
method _quantize_gt_depth (line 439) | def _quantize_gt_depth(self, gt_depths):
class AV2DownsampleQuantizeInstanceDepthmap (line 446) | class AV2DownsampleQuantizeInstanceDepthmap():
method __init__ (line 452) | def __init__(self, downsample=8, depth_config={}):
method __call__ (line 460) | def __call__(self, results):
method build_target_depth_from_3dcenter_argo (line 478) | def build_target_depth_from_3dcenter_argo(self, gt_boxes2d, gt_center_...
method bin_depths (line 501) | def bin_depths(self, depth_map, mode="LID", depth_min=1e-3, depth_max=...
FILE: projects/mmdet3d_plugin/datasets/pipelines/formating.py
class PETRFormatBundle3D (line 15) | class PETRFormatBundle3D(DefaultFormatBundle):
method __init__ (line 30) | def __init__(self, class_names, collect_keys, with_gt=True, with_label...
method __call__ (line 36) | def __call__(self, results):
method __repr__ (line 108) | def __repr__(self):
FILE: projects/mmdet3d_plugin/datasets/pipelines/transform_3d.py
class PadMultiViewImage (line 23) | class PadMultiViewImage():
method __init__ (line 33) | def __init__(self, size=None, size_divisor=None, pad_val=0):
method _pad_img (line 40) | def _pad_img(self, results):
method __call__ (line 54) | def __call__(self, results):
method __repr__ (line 65) | def __repr__(self):
class NormalizeMultiviewImage (line 74) | class NormalizeMultiviewImage(object):
method __init__ (line 84) | def __init__(self, mean, std, to_rgb=True):
method __call__ (line 89) | def __call__(self, results):
method __repr__ (line 103) | def __repr__(self):
class ResizeCropFlipRotImage (line 110) | class ResizeCropFlipRotImage():
method __init__ (line 111) | def __init__(self, data_aug_conf=None, with_2d=True, filter_invisible=...
method __call__ (line 118) | def __call__(self, results):
method _bboxes_transform (line 176) | def _bboxes_transform(self, bboxes, centers2d, gt_labels, depths,resiz...
method _filter_invisible (line 213) | def _filter_invisible(self, bboxes, centers2d, gt_labels, depths):
method _get_rot (line 240) | def _get_rot(self, h):
method _img_transform (line 248) | def _img_transform(self, img, resize, resize_dims, crop, flip, rotate):
method _sample_augmentation (line 276) | def _sample_augmentation(self):
FILE: projects/mmdet3d_plugin/datasets/samplers/distributed_sampler.py
class DistributedSampler (line 15) | class DistributedSampler(_DistributedSampler):
method __init__ (line 17) | def __init__(self,
method __iter__ (line 28) | def __iter__(self):
FILE: projects/mmdet3d_plugin/datasets/samplers/group_sampler.py
class DistributedGroupSampler (line 22) | class DistributedGroupSampler(Sampler):
method __init__ (line 40) | def __init__(self,
method __iter__ (line 69) | def __iter__(self):
method __len__ (line 112) | def __len__(self):
method set_epoch (line 115) | def set_epoch(self, epoch):
function sync_random_seed (line 119) | def sync_random_seed(seed=None, device='cuda'):
class InfiniteGroupEachSampleInBatchSampler (line 154) | class InfiniteGroupEachSampleInBatchSampler(Sampler):
method __init__ (line 162) | def __init__(self,
method _infinite_group_indices (line 204) | def _infinite_group_indices(self):
method _group_indices_per_global_sample_idx (line 210) | def _group_indices_per_global_sample_idx(self, global_sample_idx):
method __iter__ (line 216) | def __iter__(self):
method __len__ (line 231) | def __len__(self):
method set_epoch (line 235) | def set_epoch(self, epoch):
FILE: projects/mmdet3d_plugin/datasets/samplers/sampler.py
function build_sampler (line 13) | def build_sampler(cfg, default_args):
FILE: projects/mmdet3d_plugin/datasets/summarize_metrics_av2.py
class TruePositiveErrorNames (line 25) | class TruePositiveErrorNames(str, Enum):
class MetricNames (line 33) | class MetricNames(str, Enum):
function summarize_metrics (line 44) | def summarize_metrics(
function compute_average_precision (line 132) | def compute_average_precision(
function interpolate_precision (line 165) | def interpolate_precision(precision: NDArrayFloat, interpolation_method:...
FILE: projects/mmdet3d_plugin/models/backbones/vovnet.py
function dw_conv3x3 (line 100) | def dw_conv3x3(in_channels, out_channels, module_name, postfix, stride=1...
function conv3x3 (line 124) | def conv3x3(in_channels, out_channels, module_name, postfix, stride=1, g...
function conv1x1 (line 144) | def conv1x1(in_channels, out_channels, module_name, postfix, stride=1, g...
class Hsigmoid (line 164) | class Hsigmoid(nn.Module):
method __init__ (line 165) | def __init__(self, inplace=True):
method forward (line 169) | def forward(self, x):
class eSEModule (line 173) | class eSEModule(nn.Module):
method __init__ (line 174) | def __init__(self, channel, reduction=4):
method forward (line 180) | def forward(self, x):
class _OSA_module (line 188) | class _OSA_module(nn.Module):
method __init__ (line 189) | def __init__(
method forward (line 218) | def forward(self, x):
class _OSA_stage (line 241) | class _OSA_stage(nn.Sequential):
method __init__ (line 242) | def __init__(
class VoVNet (line 277) | class VoVNet(BaseModule):
method __init__ (line 278) | def __init__(self, spec_name, input_ch=3, out_features=None,
method _initialize_weights (line 344) | def _initialize_weights(self):
method forward (line 349) | def forward(self, x):
method _freeze_stages (line 362) | def _freeze_stages(self):
method train (line 375) | def train(self, mode=True):
FILE: projects/mmdet3d_plugin/models/backbones/vovnetcp.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 386) | def _freeze_stages(self):
method train (line 399) | def train(self, mode=True):
FILE: projects/mmdet3d_plugin/models/dense_heads/farhead.py
class FarHead (line 21) | class FarHead(AnchorFreeHead):
method __init__ (line 52) | def __init__(self,
method _init_layers (line 228) | def _init_layers(self):
method temporal_alignment (line 284) | def temporal_alignment(self, query_pos, tgt, reference_points):
method prepare_for_dn (line 315) | def prepare_for_dn(self, batch_size, reference_points, img_metas):
method init_weights (line 432) | def init_weights(self):
method reset_memory (line 446) | def reset_memory(self):
method pre_update_memory (line 453) | def pre_update_memory(self, data):
method post_update_memory (line 479) | def post_update_memory(self, data, rec_ego_pose, all_cls_scores, all_b...
method _get_gt_depth (line 510) | def _get_gt_depth(self, img_metas, device, BNHW):
method _convert_bin_depth_to_specific (line 521) | def _convert_bin_depth_to_specific(self, pred_indices, mode='LID', inv...
method forward (line 533) | def forward(self, img_metas, outs_roi=None, **data):
method split_offline_pred2d (line 695) | def split_offline_pred2d(self, pred_bbox_list, device):
method build_query2d_proposal (line 711) | def build_query2d_proposal(self, pred_bbox_list, pred_depth, data, bn,...
method prepare_for_loss (line 830) | def prepare_for_loss(self, mask_dict):
method _get_target_single (line 874) | def _get_target_single(self,
method get_targets (line 933) | def get_targets(self,
method loss_single (line 984) | def loss_single(self,
method dn_loss_single (line 1053) | def dn_loss_single(self,
method loss (line 1114) | def loss(self,
method get_bboxes (line 1225) | def get_bboxes(self, preds_dicts, img_metas, rescale=False):
FILE: projects/mmdet3d_plugin/models/dense_heads/yolox_head.py
class YOLOXHeadCustom (line 26) | class YOLOXHeadCustom(BaseDenseHead, BBoxTestMixin):
method __init__ (line 56) | def __init__(self,
method _init_layers (line 164) | def _init_layers(self):
method _build_stacked_convs (line 197) | def _build_stacked_convs(self):
method _build_predictor (line 221) | def _build_predictor(self):
method init_weights (line 229) | def init_weights(self):
method forward_single (line 241) | def forward_single(self, x, cls_convs, reg_convs, conv_cls, conv_reg,
method forward (line 261) | def forward(self, locations, **data):
method depth_func (line 343) | def depth_func(self, feat, net):
method get_2dpred_height (line 347) | def get_2dpred_height(self, bbox_preds, level_idx, HW):
method get_bboxes (line 356) | def get_bboxes(self, preds_dicts,
method _bbox_decode (line 491) | def _bbox_decode(self, priors, bbox_preds):
method _centers2d_decode (line 503) | def _centers2d_decode(self, priors, centers2d):
method _bboxes_nms (line 507) | def _bboxes_nms(self, cls_scores, bboxes, score_factor, cfg):
method loss (line 522) | def loss(self,
method _get_target_single (line 679) | def _get_target_single(self, cls_preds, objectness, priors, decoded_bb...
method _get_l1_target (line 751) | def _get_l1_target(self, l1_target, gt_bboxes, priors, eps=1e-8):
method _get_centers2d_target (line 758) | def _get_centers2d_target(self, centers2d_target, centers2d_labels, pr...
FILE: projects/mmdet3d_plugin/models/depth_predictor/ddn_loss/balancer.py
class Balancer (line 8) | class Balancer(nn.Module):
method __init__ (line 9) | def __init__(self, fg_weight, bg_weight, downsample_factor=1):
method forward (line 22) | def forward(self, loss, gt_boxes2d, num_gt_per_img, fg_mask=None):
function compute_fg_mask (line 55) | def compute_fg_mask(gt_boxes2d, shape, num_gt_per_img, downsample_factor...
FILE: projects/mmdet3d_plugin/models/depth_predictor/ddn_loss/ddn_loss.py
class DDNLoss (line 14) | class DDNLoss(nn.Module):
method __init__ (line 16) | def __init__(self,
method build_target_depth_from_3dcenter (line 48) | def build_target_depth_from_3dcenter(self, depth_logits, gt_boxes2d, g...
method build_target_depth_from_3dcenter_argo (line 71) | def build_target_depth_from_3dcenter_argo(self, depth_logits, gt_boxes...
method bin_depths (line 96) | def bin_depths(self, depth_map, mode="LID", depth_min=1e-3, depth_max=...
method forward (line 134) | def forward(self, depth_logits, gt_boxes2d, gt_center_depth, type='arg...
FILE: projects/mmdet3d_plugin/models/depth_predictor/ddn_loss/focalloss.py
function one_hot (line 12) | def one_hot(
function focal_loss (line 55) | def focal_loss(
class FocalLoss (line 138) | class FocalLoss(nn.Module):
method __init__ (line 169) | def __init__(self, alpha: float, gamma: float = 2.0, reduction: str = ...
method forward (line 176) | def forward(self, input: torch.Tensor, target: torch.Tensor) -> torch....
function binary_focal_loss_with_logits (line 180) | def binary_focal_loss_with_logits(
class BinaryFocalLossWithLogits (line 248) | class BinaryFocalLossWithLogits(nn.Module):
method __init__ (line 275) | def __init__(self, alpha: float, gamma: float = 2.0, reduction: str = ...
method forward (line 281) | def forward(self, input: torch.Tensor, target: torch.Tensor) -> torch....
FILE: projects/mmdet3d_plugin/models/depth_predictor/depth_predictor.py
class DepthPredictor (line 6) | class DepthPredictor(nn.Module):
method __init__ (line 8) | def __init__(self, model_cfg):
method forward (line 62) | def forward(self, feature):
FILE: projects/mmdet3d_plugin/models/detectors/far3d.py
class Far3D (line 22) | class Far3D(MVXTwoStageDetector):
method __init__ (line 25) | def __init__(self,
method extract_img_feat (line 64) | def extract_img_feat(self, img, return_depth=False):
method extract_feat (line 102) | def extract_feat(self, img, return_depth=False):
method prepare_location (line 111) | def prepare_location(self, img_metas, **data):
method forward_roi_head (line 122) | def forward_roi_head(self, location, **data):
method forward_pts_train (line 128) | def forward_pts_train(self,
method forward (line 167) | def forward(self, return_loss=True, **data):
method forward_train (line 182) | def forward_train(self,
method forward_test (line 232) | def forward_test(self, img_metas, rescale, **data):
method simple_test_pts (line 244) | def simple_test_pts(self, img_metas, **data):
method simple_test (line 268) | def simple_test(self, img_metas, **data):
FILE: projects/mmdet3d_plugin/models/necks/cp_fpn.py
class CPFPN (line 16) | class CPFPN(BaseModule):
method __init__ (line 67) | def __init__(self,
method forward (line 157) | def forward(self, inputs):
FILE: projects/mmdet3d_plugin/models/necks/second_fpn.py
class CustomSECONDFPN (line 12) | class CustomSECONDFPN(BaseModule):
method __init__ (line 26) | def __init__(self,
method forward (line 87) | def forward(self, x):
FILE: projects/mmdet3d_plugin/models/utils/attention.py
function _in_projection_packed (line 20) | def _in_projection_packed(q, k, v, w, b = None):
class FlashAttention (line 29) | class FlashAttention(nn.Module):
method __init__ (line 39) | def __init__(self, softmax_scale=None, attention_dropout=0.0, device=N...
method forward (line 46) | def forward(self, q, kv,
class FlashMHA (line 94) | class FlashMHA(nn.Module):
method __init__ (line 96) | def __init__(self, embed_dim, num_heads, bias=True, batch_first=True, ...
method _reset_parameters (line 119) | def _reset_parameters(self) -> None:
method forward (line 125) | def forward(self, q, k, v, key_padding_mask=None):
FILE: projects/mmdet3d_plugin/models/utils/deformable_aggregation.py
class DeformableAggregationFunction (line 7) | class DeformableAggregationFunction(Function):
method forward (line 9) | def forward(
method backward (line 41) | def backward(ctx, grad_output):
method feature_maps_format (line 78) | def feature_maps_format(feature_maps, inverse=False):
FILE: projects/mmdet3d_plugin/models/utils/detr3d_transformer.py
function get_global_pos (line 27) | def get_global_pos(points, pc_range):
class Detr3DTransformer (line 32) | class Detr3DTransformer(BaseModule):
method __init__ (line 43) | def __init__(self,
method init_weights (line 49) | def init_weights(self):
method forward (line 58) | def forward(self,
class Detr3DTransformerDecoder (line 127) | class Detr3DTransformerDecoder(TransformerLayerSequence):
method __init__ (line 135) | def __init__(self, embed_dims, *args, **kwargs):
method forward (line 138) | def forward(self,
class Detr3DTemporalDecoderLayer (line 193) | class Detr3DTemporalDecoderLayer(BaseModule):
method __init__ (line 229) | def __init__(self,
method _forward (line 311) | def _forward(self,
method forward (line 424) | def forward(self,
class DeformableFeatureAggregationCuda (line 484) | class DeformableFeatureAggregationCuda(BaseModule):
method __init__ (line 485) | def __init__(
method init_weight (line 517) | def init_weight(self):
method forward (line 522) | def forward(self, instance_feature, query_pos,feat_flatten, reference_...
method _get_weights (line 535) | def _get_weights(self, instance_feature, anchor_embed, lidar2img_mat):
method feature_sampling (line 544) | def feature_sampling(self, feat_flatten, spatial_flatten, level_start_...
FILE: projects/mmdet3d_plugin/models/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):
class CustomGridMask (line 125) | class CustomGridMask(nn.Module):
method __init__ (line 126) | def __init__(self, use_h, use_w, rotate=1, offset=False, ratio_range=(...
method set_prob (line 140) | def set_prob(self, epoch, max_epoch):
method forward (line 143) | def forward(self, x):
FILE: projects/mmdet3d_plugin/models/utils/hook.py
class UseGtDepthHook (line 5) | class UseGtDepthHook(Hook):
method __init__ (line 6) | def __init__(
method before_train_iter (line 14) | def before_train_iter(self, runner):
FILE: projects/mmdet3d_plugin/models/utils/layer_decay_optimizer_constructor.py
function get_vit_lr_decay_rate (line 17) | def get_vit_lr_decay_rate(name, backbone_lr_decay_rate=1.0, head_lr_deca...
function get_num_layer_layer_wise (line 38) | def get_num_layer_layer_wise(var_name, num_max_layer=12):
function get_num_layer_stage_wise (line 68) | def get_num_layer_stage_wise(var_name, num_max_layer):
class LearningRateDecayOptimizerConstructor (line 81) | class LearningRateDecayOptimizerConstructor(DefaultOptimizerConstructor):
method add_params (line 82) | def add_params(self, params, module, prefix='', is_dcn_module=None):
FILE: projects/mmdet3d_plugin/models/utils/misc.py
function memory_refresh (line 7) | def memory_refresh(memory, prev_exist):
function topk_gather (line 13) | def topk_gather(feat, topk_indexes):
function apply_ltrb (line 26) | def apply_ltrb(locations, pred_ltrb):
function apply_center_offset (line 44) | def apply_center_offset(locations, center_offset):
function locations (line 58) | def locations(features, stride, pad_h, pad_w):
function gaussian_2d (line 88) | def gaussian_2d(shape, sigma=1.0):
function draw_heatmap_gaussian (line 107) | def draw_heatmap_gaussian(heatmap, center, radius, k=1):
class SELayer_Linear (line 138) | class SELayer_Linear(nn.Module):
method __init__ (line 139) | def __init__(self, channels, act_layer=nn.ReLU, gate_layer=nn.Sigmoid):
method forward (line 146) | def forward(self, x, x_se):
class MLN (line 153) | class MLN(nn.Module):
method __init__ (line 160) | def __init__(self, c_dim, f_dim=256, use_ln=True):
method init_weight (line 176) | def init_weight(self):
method forward (line 182) | def forward(self, x, c):
function transform_reference_points (line 193) | def transform_reference_points(reference_points, egopose, reverse=False,...
FILE: projects/mmdet3d_plugin/models/utils/petr_transformer.py
class PETRMultiheadFlashAttention (line 24) | class PETRMultiheadFlashAttention(BaseModule):
method __init__ (line 44) | def __init__(self,
method forward (line 76) | def forward(self,
class MultiheadAttentionWrapper (line 165) | class MultiheadAttentionWrapper(nn.MultiheadAttention):
method __init__ (line 166) | def __init__(self, *args, **kwargs):
method forward_fp16 (line 171) | def forward_fp16(self, *args, **kwargs):
method forward_fp32 (line 174) | def forward_fp32(self, *args, **kwargs):
method forward (line 177) | def forward(self, *args, **kwargs):
class PETRMultiheadAttention (line 184) | class PETRMultiheadAttention(BaseModule):
method __init__ (line 204) | def __init__(self,
method forward (line 239) | def forward(self,
class PETRTransformerEncoder (line 331) | class PETRTransformerEncoder(TransformerLayerSequence):
method __init__ (line 338) | def __init__(self, *args, post_norm_cfg=dict(type='LN'), **kwargs):
method forward (line 349) | def forward(self, *args, **kwargs):
class PETRTransformerDecoder (line 361) | class PETRTransformerDecoder(TransformerLayerSequence):
method __init__ (line 369) | def __init__(self,
method forward (line 383) | def forward(self, query, *args, **kwargs):
class PETRTemporalTransformer (line 412) | class PETRTemporalTransformer(BaseModule):
method __init__ (line 430) | def __init__(self, encoder=None, decoder=None, init_cfg=None, cross=Fa...
method init_weights (line 440) | def init_weights(self):
method forward (line 448) | def forward(self, memory, tgt, query_pos, pos_embed, attn_masks, temp_...
class PETRTemporalDecoderLayer (line 502) | class PETRTemporalDecoderLayer(BaseModule):
method __init__ (line 538) | def __init__(self,
method _forward (line 634) | def _forward(self,
method forward (line 741) | def forward(self,
class PETRTransformer (line 789) | class PETRTransformer(BaseModule):
method __init__ (line 807) | def __init__(self, encoder=None, decoder=None, init_cfg=None, cross=Fa...
method init_weights (line 817) | def init_weights(self):
method forward (line 825) | def forward(self, x, mask, query_embed, pos_embed, reg_branch=None):
class PETRTransformerDecoderLayer (line 868) | class PETRTransformerDecoderLayer(BaseTransformerLayer):
method __init__ (line 889) | def __init__(self,
method _forward (line 913) | def _forward(self,
method forward (line 942) | def forward(self,
class FlattenMHSelfAttention (line 987) | class FlattenMHSelfAttention(MultiheadAttention):
method forward (line 989) | def forward(self,
FILE: projects/mmdet3d_plugin/models/utils/positional_encoding.py
function pos2posemb3d (line 13) | def pos2posemb3d(pos, num_pos_feats=128, temperature=10000):
function pos2posemb1d (line 27) | def pos2posemb1d(pos, num_pos_feats=256, temperature=10000):
function nerf_positional_encoding (line 38) | def nerf_positional_encoding(
class PE (line 82) | class PE(nn.Module):
method __init__ (line 83) | def __init__(self, positional_encoding, strides, position_range, depth...
method position_encoding (line 115) | def position_encoding(self, img_feats, img_metas, masks=None):
method forward (line 168) | def forward(self, mlvl_feats, img_metas):
class SELayer (line 202) | class SELayer(nn.Module):
method __init__ (line 203) | def __init__(self, channels, act_layer=nn.ReLU, gate_layer=nn.Sigmoid):
method forward (line 210) | def forward(self, x, x_se):
class SinePositionalEncoding3D (line 217) | class SinePositionalEncoding3D(BaseModule):
method __init__ (line 240) | def __init__(self,
method forward (line 260) | def forward(self, mask, stride=0):
method __repr__ (line 300) | def __repr__(self):
FILE: projects/mmdet3d_plugin/models/utils/sparse_blocks.py
class SparseBox3DRefinementModule (line 18) | class SparseBox3DRefinementModule(BaseModule):
method __init__ (line 19) | def __init__(
method init_weight (line 61) | def init_weight(self):
method forward (line 66) | def forward(self, instance_feature, reference_points, anchor_embed):
method cls_forward (line 73) | def cls_forward(self, instance_feature):
class DepthReweightModule (line 78) | class DepthReweightModule(BaseModule):
method __init__ (line 79) | def __init__(
method forward (line 109) | def forward(self, features, points_3d, output_conf=False):
class SparseBox3DKeyPointsGenerator (line 130) | class SparseBox3DKeyPointsGenerator(BaseModule):
method __init__ (line 131) | def __init__(
method init_weight (line 153) | def init_weight(self):
method forward (line 157) | def forward(self, anchor, instance_feature):
class DeformableFeatureAggregation (line 177) | class DeformableFeatureAggregation(BaseModule):
method __init__ (line 178) | def __init__(
method init_weight (line 200) | def init_weight(self):
method forward (line 206) | def forward(self, instance_feature, reference_points, anchor_embed, fe...
method _get_weights (line 223) | def _get_weights(self, instance_feature, anchor_embed):
method multi_view_level_fusion (line 228) | def multi_view_level_fusion(self, features, weights):
method feature_sampling (line 235) | def feature_sampling(feature_maps, key_points, lidar2img_mat, img_metas):
class DeformableFeatureAggregationCuda (line 258) | class DeformableFeatureAggregationCuda(BaseModule):
method __init__ (line 259) | def __init__(
method init_weight (line 283) | def init_weight(self):
method forward (line 288) | def forward(self, instance_feature, reference_points, anchor_embed, fe...
method _get_weights (line 299) | def _get_weights(self, instance_feature, anchor_embed):
method multi_view_level_fusion (line 305) | def multi_view_level_fusion(self, features, weights):
method feature_sampling (line 311) | def feature_sampling(self, feat_flatten, spatial_flatten, level_start_...
class SparseBox3DEncoder (line 343) | class SparseBox3DEncoder(BaseModule):
method __init__ (line 344) | def __init__(self, embed_dims=256, vel_dims=0):
method forward (line 363) | def forward(self, box_3d):
function get_global_pos (line 374) | def get_global_pos(points, pc_range):
FILE: projects/mmdet3d_plugin/models/utils/warmup_fp16_optimizer.py
class WarmupFp16OptimizerHook (line 19) | class WarmupFp16OptimizerHook(OptimizerHook):
method __init__ (line 44) | def __init__(self,
method before_run (line 72) | def before_run(self, runner) -> None:
method copy_grads_to_fp32 (line 81) | def copy_grads_to_fp32(self, fp16_net: nn.Module,
method copy_params_to_fp16 (line 92) | def copy_params_to_fp16(self, fp16_net: nn.Module,
method after_train_iter (line 99) | def after_train_iter(self, runner) -> None:
FILE: tools/analysis_tools/benchmark.py
function parse_args (line 18) | def parse_args():
function main (line 29) | def main():
FILE: tools/create_data_nusc.py
function nuscenes_data_prep (line 9) | def nuscenes_data_prep(root_path,
FILE: tools/create_infos_av2/create_av2_infos.py
function create_av2_infos (line 38) | def create_av2_infos(dataset_dir, split, out_dir):
function _load_annotations (line 116) | def _load_annotations(split, log_id, timestamp_ns):
function intrinsics_matrix (line 126) | def intrinsics_matrix(fx, fy, cx, cy):
function get_gt3d_data (line 134) | def get_gt3d_data(dataset_dir, split, log_id, timestamp_ns):
function get_gt2d_data (line 168) | def get_gt2d_data(synchronized_imagery, cam_infos, timestamp_city_SE3_eg...
function post_process_coords (line 260) | def post_process_coords(corner_coords, imsize = (2048, 1550)):
FILE: tools/data_converter/info2coco.py
function ref (line 8) | def ref():
function convert_info_to_coco (line 90) | def convert_info_to_coco(data_infos, name2nori, images, annotations):
FILE: tools/data_converter/nuscenes_converter.py
function create_nuscenes_infos (line 27) | def create_nuscenes_infos(root_path,
function get_available_scenes (line 106) | def get_available_scenes(nusc):
function _fill_trainval_infos (line 146) | def _fill_trainval_infos(nusc,
function obtain_sensor2top (line 355) | def obtain_sensor2top(nusc,
function export_2d_annotation (line 416) | def export_2d_annotation(root_path, info_path, version, mono3d=True):
function get_2d_boxes (line 481) | def get_2d_boxes(nusc,
function post_process_coords (line 613) | def post_process_coords(
function generate_record (line 646) | def generate_record(ann_rec: dict, x1: float, y1: float, x2: float, y2: ...
FILE: tools/filter_ckpt.py
function filter_params (line 4) | def filter_params(ckpt, left_prefix, inverse=False):
FILE: tools/test.py
function parse_args (line 27) | def parse_args():
function main (line 110) | def main():
FILE: tools/test_and_visualize.py
function parse_args (line 27) | def parse_args():
function main (line 110) | def main():
FILE: tools/train.py
function parse_args (line 30) | def parse_args():
function main (line 99) | def main():
FILE: tools/visual/check_img_label.py
function _bbox_decode (line 24) | def _bbox_decode(priors, bbox_preds):
function _centers2d_decode (line 34) | def _centers2d_decode(priors, pred_centers2d):
class NormalizeInverse (line 38) | class NormalizeInverse(torchvision.transforms.Normalize):
method __init__ (line 40) | def __init__(self, mean, std):
method __call__ (line 47) | def __call__(self, tensor):
FILE: tools/visual/vis_3dpred_depth_stat.py
function _convert_bin_depth_to_specific (line 118) | def _convert_bin_depth_to_specific(pred_indices):
FILE: tools/visual/vis_3dpred_depth_stat2.py
function _convert_bin_depth_to_specific (line 34) | def _convert_bin_depth_to_specific(pred_indices):
FILE: tools/visual/vis_util.py
function _bbox_decode (line 4) | def _bbox_decode(priors, bbox_preds):
function _centers2d_decode (line 15) | def _centers2d_decode(priors, pred_centers2d):
function bbox_xyxy_to_cxcywh (line 18) | def bbox_xyxy_to_cxcywh(bbox):
FILE: tools/visual_nuscenes.py
class NuScenes (line 59) | class NuScenes:
method __init__ (line 64) | def __init__(self,
method table_root (line 155) | def table_root(self) -> str:
method __load_table__ (line 159) | def __load_table__(self, table_name, pred=False) -> dict:
method load_lidarseg_cat_name_mapping (line 179) | def load_lidarseg_cat_name_mapping(self):
method __make_reverse_index__ (line 189) | def __make_reverse_index__(self, verbose: bool) -> None:
method get (line 248) | def get(self, table_name: str, token: str) -> dict:
method getind (line 259) | def getind(self, table_name: str, token: str) -> int:
method field2token (line 268) | def field2token(self, table_name: str, field: str, query) -> List[str]:
method get_sample_data_path (line 283) | def get_sample_data_path(self, sample_data_token: str) -> str:
method get_sample_data (line 289) | def get_sample_data(self, sample_data_token: str,
method get_box (line 351) | def get_box(self, sample_annotation_token: str) -> Box:
method get_boxes (line 360) | def get_boxes(self, sample_data_token: str) -> List[Box]:
method box_velocity (line 418) | def box_velocity(self, sample_annotation_token: str, max_time_diff: fl...
method get_sample_lidarseg_stats (line 465) | def get_sample_lidarseg_stats(self,
method list_categories (line 538) | def list_categories(self) -> None:
method list_lidarseg_categories (line 541) | def list_lidarseg_categories(self, sort_by: str = 'count', gt_from: st...
method list_panoptic_instances (line 544) | def list_panoptic_instances(self, sort_by: str = 'count', get_hist: bo...
method list_attributes (line 547) | def list_attributes(self) -> None:
method list_scenes (line 550) | def list_scenes(self) -> None:
method list_sample (line 553) | def list_sample(self, sample_token: str) -> None:
method render_pointcloud_in_image (line 556) | def render_pointcloud_in_image(self, sample_token: str, dot_size: int ...
method render_sample (line 575) | def render_sample(self, sample_token: str,
method render_sample_data (line 589) | def render_sample_data(self, sample_data_token: str, with_anns: bool =...
method render_annotation (line 609) | def render_annotation(self, sample_annotation_token: str, margin: floa...
method render_instance (line 614) | def render_instance(self, instance_token: str, margin: float = 10, vie...
method render_scene (line 619) | def render_scene(self, scene_token: str, freq: float = 10, imsize: Tup...
method render_scene_channel (line 623) | def render_scene_channel(self, scene_token: str, channel: str = 'CAM_F...
method render_egoposes_on_map (line 627) | def render_egoposes_on_map(self, log_location: str, scene_tokens: List...
method render_scene_channel_lidarseg (line 630) | def render_scene_channel_lidarseg(self, scene_token: str,
method render_scene_lidarseg (line 655) | def render_scene_lidarseg(self, scene_token: str,
class NuScenesExplorer (line 677) | class NuScenesExplorer:
method __init__ (line 681) | def __init__(self, nusc: NuScenes):
method get_color (line 684) | def get_color(self, category_name: str) -> Tuple[int, int, int]:
method list_categories (line 692) | def list_categories(self) -> None:
method list_lidarseg_categories (line 713) | def list_lidarseg_categories(self, sort_by: str = 'count', gt_from: st...
method list_panoptic_instances (line 766) | def list_panoptic_instances(self, sort_by: str = 'count', get_hist: bo...
method list_attributes (line 820) | def list_attributes(self) -> None:
method list_scenes (line 833) | def list_scenes(self) -> None:
method list_sample (line 861) | def list_sample(self, sample_token: str) -> None:
method map_pointcloud_to_image (line 875) | def map_pointcloud_to_image(self,
method render_pointcloud_in_image (line 1015) | def render_pointcloud_in_image(self,
method render_sample (line 1105) | def render_sample(self,
method render_ego_centric_map (line 1203) | def render_ego_centric_map(self,
method render_sample_data (line 1262) | def render_sample_data(self,
method render_annotation (line 1515) | def render_annotation(self,
method render_instance (line 1604) | def render_instance(self,
method render_scene (line 1634) | def render_scene(self,
method render_scene_channel (line 1748) | def render_scene_channel(self,
method render_egoposes_on_map (line 1825) | def render_egoposes_on_map(self,
method _plot_points_and_bboxes (line 1918) | def _plot_points_and_bboxes(self,
method render_scene_channel_lidarseg (line 1990) | def render_scene_channel_lidarseg(self,
method render_scene_lidarseg (line 2139) | def render_scene_lidarseg(self,
Condensed preview — 95 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (4,396K chars).
[
{
"path": "LICENSE",
"chars": 10787,
"preview": "Far3D\n\n Apache License\n Version 2.0, January 2004\n "
},
{
"path": "README.md",
"chars": 4069,
"preview": "<div align=\"center\">\n<h1>Far3D</h1>\n<h3> [AAAI2024] Expanding the Horizon for Surround-view 3D Object Detection </h3>\n</"
},
{
"path": "docs/get_started.md",
"chars": 2086,
"preview": "# Get Started\nNote our Far3D inherit from the repo of [StreamPETR](https://github.com/exiawsh/StreamPETR/), thus many pa"
},
{
"path": "projects/configs/far3d.py",
"chars": 10972,
"preview": "_base_ = [\n '../../../mmdetection3d/configs/_base_/default_runtime.py'\n]\nbackbone_norm_cfg = dict(type='LN', requires"
},
{
"path": "projects/mmdet3d_plugin/__init__.py",
"chars": 407,
"preview": "from .core.bbox.assigners.hungarian_assigner_3d import HungarianAssigner3D\nfrom .core.bbox.coders.nms_free_coder import "
},
{
"path": "projects/mmdet3d_plugin/core/apis/__init__.py",
"chars": 124,
"preview": "from .train import custom_train_model\nfrom .mmdet_train import custom_train_detector\nfrom .test import custom_multi_gpu_"
},
{
"path": "projects/mmdet3d_plugin/core/apis/mmdet_train.py",
"chars": 8115,
"preview": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ----------------------"
},
{
"path": "projects/mmdet3d_plugin/core/apis/test.py",
"chars": 6332,
"preview": "# ---------------------------------------------\r\n# Copyright (c) OpenMMLab. All rights reserved.\r\n# --------------------"
},
{
"path": "projects/mmdet3d_plugin/core/apis/train.py",
"chars": 2038,
"preview": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ----------------------"
},
{
"path": "projects/mmdet3d_plugin/core/bbox/assigners/__init__.py",
"chars": 169,
"preview": "from .hungarian_assigner_3d import HungarianAssigner3D\nfrom .hungarian_assigner_3d import HungarianAssigner3DPolar\nfrom "
},
{
"path": "projects/mmdet3d_plugin/core/bbox/assigners/hungarian_assigner_2d.py",
"chars": 7290,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\n# ---------------------------------------------\n# Modified by Shihao Wa"
},
{
"path": "projects/mmdet3d_plugin/core/bbox/assigners/hungarian_assigner_3d.py",
"chars": 7483,
"preview": "# ------------------------------------------------------------------------\n# Modified from DETR3D (https://github.com/Wa"
},
{
"path": "projects/mmdet3d_plugin/core/bbox/coders/__init__.py",
"chars": 60,
"preview": "from .nms_free_coder import NMSFreeCoder, NMSFreeCoderPolar\n"
},
{
"path": "projects/mmdet3d_plugin/core/bbox/coders/nms_free_coder.py",
"chars": 8250,
"preview": "import torch\n\nfrom mmdet.core.bbox import BaseBBoxCoder\nfrom mmdet.core.bbox.builder import BBOX_CODERS\nfrom projects.mm"
},
{
"path": "projects/mmdet3d_plugin/core/bbox/match_costs/__init__.py",
"chars": 141,
"preview": "from mmdet.core.bbox.match_costs import build_match_cost\nfrom .match_cost import BBox3DL1Cost\n\n__all__ = ['build_match_c"
},
{
"path": "projects/mmdet3d_plugin/core/bbox/match_costs/match_cost.py",
"chars": 853,
"preview": "import torch\nfrom mmdet.core.bbox.match_costs.builder import MATCH_COST\n\n@MATCH_COST.register_module()\nclass BBox3DL1Cos"
},
{
"path": "projects/mmdet3d_plugin/core/bbox/util.py",
"chars": 3216,
"preview": "import torch\nimport math\n\ndef normalize_bbox(bboxes, pc_range):\n cx = bboxes[..., 0:1]\n cy = bboxes[..., 1:2]\n "
},
{
"path": "projects/mmdet3d_plugin/core/evaluation/__init__.py",
"chars": 42,
"preview": "from .eval_hooks import CustomDistEvalHook"
},
{
"path": "projects/mmdet3d_plugin/core/evaluation/eval_hooks.py",
"chars": 3507,
"preview": "\n# Note: Considering that MMCV's EvalHook updated its interface in V1.3.16,\n# in order to avoid strong version dependenc"
},
{
"path": "projects/mmdet3d_plugin/datasets/__init__.py",
"chars": 240,
"preview": "from .nuscenes_dataset import CustomNuScenesDataset\nfrom .builder import custom_build_dataset\nfrom .argoverse2_dataset i"
},
{
"path": "projects/mmdet3d_plugin/datasets/argoverse2_dataset.py",
"chars": 12953,
"preview": "import mmcv\nimport torch\nimport numpy as np\nfrom .av2_utils import yaw_to_quat\nfrom mmdet3d.core.bbox import LiDARInstan"
},
{
"path": "projects/mmdet3d_plugin/datasets/argoverse2_dataset_t.py",
"chars": 11028,
"preview": "import torch\nimport numpy as np\nfrom mmdet.datasets import DATASETS\nfrom av2.evaluation.detection.constants import Compe"
},
{
"path": "projects/mmdet3d_plugin/datasets/av2_eval_util.py",
"chars": 15586,
"preview": "'''\nOverwrite some functions for adapting to our data loading scheme.\n'''\n\nimport refile\nimport numpy as np\nimport pyarr"
},
{
"path": "projects/mmdet3d_plugin/datasets/av2_utils.py",
"chars": 10767,
"preview": "import logging\nfrom dataclasses import dataclass\nfrom pathlib import Path\nfrom typing import Optional, Tuple\n\nimport num"
},
{
"path": "projects/mmdet3d_plugin/datasets/builder.py",
"chars": 6946,
"preview": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ----------------------"
},
{
"path": "projects/mmdet3d_plugin/datasets/eval_recall.py",
"chars": 6103,
"preview": "import mmcv\nimport torch\nimport torch.nn as nn\nimport numpy as np\nfrom tqdm import tqdm\n\ndef bbox_cxcywh_to_xyxy(bbox):\n"
},
{
"path": "projects/mmdet3d_plugin/datasets/nuscenes_dataset.py",
"chars": 11036,
"preview": "# ------------------------------------------------------------------------\n# Copyright (c) 2022 megvii-model. All Rights"
},
{
"path": "projects/mmdet3d_plugin/datasets/pipelines/__init__.py",
"chars": 107,
"preview": "from .transform_3d import NormalizeMultiviewImage\n\nfrom .formating import *\nfrom .custom_pipeline import *\n"
},
{
"path": "projects/mmdet3d_plugin/datasets/pipelines/custom_pipeline.py",
"chars": 22989,
"preview": "import mmcv\nimport copy\nimport torch\nimport numpy as np\nfrom PIL import Image\nfrom mmdet3d.datasets.builder import PIPEL"
},
{
"path": "projects/mmdet3d_plugin/datasets/pipelines/formating.py",
"chars": 5303,
"preview": "# ------------------------------------------------------------------------\n# Modified from mmdetection3d (https://github"
},
{
"path": "projects/mmdet3d_plugin/datasets/pipelines/transform_3d.py",
"chars": 19148,
"preview": "# ------------------------------------------------------------------------\n# Copyright (c) 2022 megvii-model. All Rights"
},
{
"path": "projects/mmdet3d_plugin/datasets/samplers/__init__.py",
"chars": 187,
"preview": "from .group_sampler import DistributedGroupSampler, InfiniteGroupEachSampleInBatchSampler\nfrom .distributed_sampler impo"
},
{
"path": "projects/mmdet3d_plugin/datasets/samplers/distributed_sampler.py",
"chars": 1661,
"preview": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ----------------------"
},
{
"path": "projects/mmdet3d_plugin/datasets/samplers/group_sampler.py",
"chars": 8922,
"preview": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ----------------------"
},
{
"path": "projects/mmdet3d_plugin/datasets/samplers/sampler.py",
"chars": 487,
"preview": "# ---------------------------------------------\r\n# Copyright (c) OpenMMLab. All rights reserved.\r\n# --------------------"
},
{
"path": "projects/mmdet3d_plugin/datasets/summarize_metrics_av2.py",
"chars": 7184,
"preview": "import logging\nfrom typing import Final, Tuple\n\nimport numpy as np\nimport pandas as pd\nfrom enum import Enum\nfrom av2.ev"
},
{
"path": "projects/mmdet3d_plugin/models/backbones/__init__.py",
"chars": 465,
"preview": "# ------------------------------------------------------------------------\n# Copyright (c) 2022 megvii-model. All Rights"
},
{
"path": "projects/mmdet3d_plugin/models/backbones/vovnet.py",
"chars": 12307,
"preview": "# ------------------------------------------------------------------------\n# Copyright (c) 2021 megvii-model. All Rights"
},
{
"path": "projects/mmdet3d_plugin/models/backbones/vovnetcp.py",
"chars": 12973,
"preview": "# ------------------------------------------------------------------------\n# Copyright (c) 2022 megvii-model. All Rights"
},
{
"path": "projects/mmdet3d_plugin/models/dense_heads/__init__.py",
"chars": 70,
"preview": "from .farhead import FarHead\nfrom .yolox_head import YOLOXHeadCustom\n\n"
},
{
"path": "projects/mmdet3d_plugin/models/dense_heads/farhead.py",
"chars": 64595,
"preview": "import torch\nimport torch.nn as nn \nfrom mmcv.cnn import Linear, bias_init_with_prob, Scale\n\nfrom mmcv.runner import for"
},
{
"path": "projects/mmdet3d_plugin/models/dense_heads/yolox_head.py",
"chars": 36929,
"preview": "import math\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.cnn import "
},
{
"path": "projects/mmdet3d_plugin/models/depth_predictor/__init__.py",
"chars": 44,
"preview": "from .depth_predictor import DepthPredictor\n"
},
{
"path": "projects/mmdet3d_plugin/models/depth_predictor/ddn_loss/__init__.py",
"chars": 68,
"preview": "from .ddn_loss import DDNLoss\n\n__all__ = {\n \"DDNLoss\": DDNLoss\n}\n"
},
{
"path": "projects/mmdet3d_plugin/models/depth_predictor/ddn_loss/balancer.py",
"chars": 2976,
"preview": "import torch\nimport torch.nn as nn\n\n# based on\n# https://github.com/TRAILab/CaDDN/blob/master/pcdet/models/backbones_3d/"
},
{
"path": "projects/mmdet3d_plugin/models/depth_predictor/ddn_loss/ddn_loss.py",
"chars": 7024,
"preview": "import pdb\n\nimport torch\nimport torch.nn as nn\nimport math\n\nfrom .balancer import Balancer\nfrom .focalloss import FocalL"
},
{
"path": "projects/mmdet3d_plugin/models/depth_predictor/ddn_loss/focalloss.py",
"chars": 11501,
"preview": "import warnings\nfrom typing import Optional\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\n# based"
},
{
"path": "projects/mmdet3d_plugin/models/depth_predictor/depth_predictor.py",
"chars": 3852,
"preview": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\n\nclass DepthPredictor(nn.Module):\n\n def __init__("
},
{
"path": "projects/mmdet3d_plugin/models/detectors/__init__.py",
"chars": 24,
"preview": "from .far3d import Far3D"
},
{
"path": "projects/mmdet3d_plugin/models/detectors/far3d.py",
"chars": 11750,
"preview": "# ------------------------------------------------------------------------\n# Copyright (c) 2022 megvii-model. All Rights"
},
{
"path": "projects/mmdet3d_plugin/models/necks/__init__.py",
"chars": 53,
"preview": "from .cp_fpn import CPFPN\nfrom .second_fpn import *\n\n"
},
{
"path": "projects/mmdet3d_plugin/models/necks/cp_fpn.py",
"chars": 9232,
"preview": "# ------------------------------------------------------------------------\n# Copyright (c) 2021 megvii-model. All Rights"
},
{
"path": "projects/mmdet3d_plugin/models/necks/second_fpn.py",
"chars": 4382,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport numpy as np\nimport torch\nfrom mmcv.cnn import build_conv_layer, b"
},
{
"path": "projects/mmdet3d_plugin/models/utils/__init__.py",
"chars": 703,
"preview": "# from .petr_transformer import PETRMultiheadAttention, PETRTransformerEncoder, PETRTemporalTransformer, \\\n# PETRTem"
},
{
"path": "projects/mmdet3d_plugin/models/utils/attention.py",
"chars": 6103,
"preview": "# flash-attention \nimport math\nimport torch\nimport torch.nn as nn\nfrom torch.nn.init import (\n xavier_uniform_,\n c"
},
{
"path": "projects/mmdet3d_plugin/models/utils/deformable_aggregation.py",
"chars": 3944,
"preview": "import torch\nfrom torch.autograd.function import Function, once_differentiable\n\nfrom . import deformable_aggregation_ext"
},
{
"path": "projects/mmdet3d_plugin/models/utils/detr3d_transformer.py",
"chars": 23153,
"preview": "import numpy as np\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom mmcv.cnn import xavier_init, "
},
{
"path": "projects/mmdet3d_plugin/models/utils/grid_mask.py",
"chars": 6441,
"preview": "import torch\nimport torch.nn as nn\nimport numpy as np\nfrom PIL import Image\n\nclass Grid(object):\n def __init__(self, "
},
{
"path": "projects/mmdet3d_plugin/models/utils/hook.py",
"chars": 718,
"preview": "from mmcv.parallel import is_module_wrapper\nfrom mmcv.runner.hooks import HOOKS, Hook\n\n@HOOKS.register_module()\nclass Us"
},
{
"path": "projects/mmdet3d_plugin/models/utils/layer_decay_optimizer_constructor.py",
"chars": 6039,
"preview": "# Copyright (c) ByteDance, Inc. and its affiliates.\n# All rights reserved.\n#\n# This source code is licensed under the li"
},
{
"path": "projects/mmdet3d_plugin/models/utils/misc.py",
"chars": 6586,
"preview": "import torch\nimport torch.nn as nn\nimport numpy as np\nfrom mmdet.core import bbox_xyxy_to_cxcywh\nfrom mmdet.models.utils"
},
{
"path": "projects/mmdet3d_plugin/models/utils/petr_transformer.py",
"chars": 42074,
"preview": "import warnings\nimport torch\nimport torch.nn as nn\nfrom mmcv.cnn.bricks.transformer import (BaseTransformerLayer,\n "
},
{
"path": "projects/mmdet3d_plugin/models/utils/positional_encoding.py",
"chars": 13629,
"preview": "import math\nimport torch\nimport torch.nn as nn \nimport numpy as np\nimport torch.nn as nn\nimport torch.nn.functional as F"
},
{
"path": "projects/mmdet3d_plugin/models/utils/sparse_blocks.py",
"chars": 15918,
"preview": "from typing import Optional\nimport torch.nn as nn\nimport torch\nfrom mmcv.runner.base_module import BaseModule\nfrom mmcv."
},
{
"path": "projects/mmdet3d_plugin/models/utils/warmup_fp16_optimizer.py",
"chars": 6061,
"preview": "import copy\nimport logging\nfrom collections import defaultdict\nfrom itertools import chain\nfrom typing import Optional, "
},
{
"path": "py38.yaml",
"chars": 6823,
"preview": "name: py38\nchannels:\n - https://mirrors.tuna.tsinghua.edu.cn/anaconda/cloud/conda-forge\n - https://mirrors.tuna.tsingh"
},
{
"path": "tools/analysis_tools/benchmark.py",
"chars": 4010,
"preview": "# ------------------------------------------------------------------------\n# Modified from mmdetection3d (https://github"
},
{
"path": "tools/create_data_nusc.py",
"chars": 2471,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport argparse\nfrom os import path as osp\n\nfrom data_converter import n"
},
{
"path": "tools/create_infos_av2/create_av2_infos.py",
"chars": 12657,
"preview": "from av2.datasets.sensor.sensor_dataloader import LIDAR_PATTERN\nfrom av2.datasets.sensor.utils import convert_path_to_na"
},
{
"path": "tools/create_infos_av2/gather_argo2_anno_feather.py",
"chars": 798,
"preview": "# \"create complete infos of gts for evaluation\"\nfrom av2.utils.io import read_feather\nimport pandas as pd \nfrom pathli"
},
{
"path": "tools/data_converter/__init__.py",
"chars": 48,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\n"
},
{
"path": "tools/data_converter/info2coco.py",
"chars": 6989,
"preview": "import json\nimport os\nimport pickle\nimport refile\nimport ipdb\nimport numpy as np\n\ndef ref():\n # Define the directory "
},
{
"path": "tools/data_converter/nuscenes_converter.py",
"chars": 28017,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport os\nfrom collections import OrderedDict\nfrom os import path as osp"
},
{
"path": "tools/dist_test.sh",
"chars": 494,
"preview": "#!/usr/bin/env bash\n\nCONFIG=$1\nCHECKPOINT=$2\nGPUS=$3\nNNODES=${NNODES:-1}\nNODE_RANK=${NODE_RANK:-0}\nPORT=${PORT:-29500}\nM"
},
{
"path": "tools/dist_test_visualize.sh",
"chars": 508,
"preview": "#!/usr/bin/env bash\n\nCONFIG=$1\nCHECKPOINT=$2\nGPUS=$3\nNNODES=${NNODES:-1}\nNODE_RANK=${NODE_RANK:-0}\nPORT=${PORT:-29500}\nM"
},
{
"path": "tools/dist_train.sh",
"chars": 472,
"preview": "#!/usr/bin/env bash\n\nCONFIG=$1\nGPUS=$2\nNNODES=${NNODES:-1}\nNODE_RANK=${NODE_RANK:-0}\nPORT=${PORT:-29500}\nMASTER_ADDR=${M"
},
{
"path": "tools/filter_ckpt.py",
"chars": 1091,
"preview": "import torch\nfrom collections import OrderedDict\n\ndef filter_params(ckpt, left_prefix, inverse=False):\n state_dict = "
},
{
"path": "tools/multi_dist_train.sh",
"chars": 1648,
"preview": "#!/usr/bin/env bash\n###\n### frist worker run: NNODES=2 NODE_RANK=0 rlaunch --cpu=20 --gpu=8 --max-wait-time=24h --memor"
},
{
"path": "tools/slurm_test.sh",
"chars": 566,
"preview": "#!/usr/bin/env bash\n\nset -x\n\nPARTITION=$1\nJOB_NAME=$2\nCONFIG=$3\nCHECKPOINT=$4\nGPUS=${GPUS:-8}\nGPUS_PER_NODE=${GPUS_PER_N"
},
{
"path": "tools/slurm_train.sh",
"chars": 574,
"preview": "#!/usr/bin/env bash\n\nset -x\n\nPARTITION=$1\nJOB_NAME=$2\nCONFIG=$3\nWORK_DIR=$4\nGPUS=${GPUS:-8}\nGPUS_PER_NODE=${GPUS_PER_NOD"
},
{
"path": "tools/test.py",
"chars": 10740,
"preview": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ----------------------"
},
{
"path": "tools/test_and_visualize.py",
"chars": 11261,
"preview": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ----------------------"
},
{
"path": "tools/train.py",
"chars": 10077,
"preview": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ----------------------"
},
{
"path": "tools/visual/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "tools/visual/check_img_label.py",
"chars": 9788,
"preview": "import torch\nfrom mmcv import Config\nfrom mmdet3d.datasets import build_dataloader, build_dataset\nimport os\nimport impor"
},
{
"path": "tools/visual/vis_2d.ipynb",
"chars": 3569891,
"preview": "{\n \"cells\": [\n {\n \"cell_type\": \"code\",\n \"execution_count\": 1,\n \"metadata\": {},\n \"outputs\": [\n {\n \"name\":"
},
{
"path": "tools/visual/vis_3dpred.py",
"chars": 6411,
"preview": "import torch\nfrom mmcv import Config\nfrom mmdet3d.datasets import build_dataloader, build_dataset\nimport os\nimport impor"
},
{
"path": "tools/visual/vis_3dpred_depth_stat.py",
"chars": 4696,
"preview": "import torch\nfrom mmcv import Config\nfrom mmdet3d.datasets import build_dataloader, build_dataset\nimport os\nimport impor"
},
{
"path": "tools/visual/vis_3dpred_depth_stat2.py",
"chars": 5244,
"preview": "import torch\nfrom mmcv import Config\nfrom mmdet3d.datasets import build_dataloader, build_dataset\nimport os\nimport impor"
},
{
"path": "tools/visual/vis_attention.py",
"chars": 5978,
"preview": "import numpy as np\nimport pandas as pd\nfrom av2.geometry.geometry import mat_to_xyz, quat_to_mat, wrap_angles\nfrom mmdet"
},
{
"path": "tools/visual/vis_av2.py",
"chars": 10134,
"preview": "import pandas as pd\nfrom av2.geometry.geometry import mat_to_xyz, quat_to_mat, wrap_angles\nfrom mmdet3d.core.bbox import"
},
{
"path": "tools/visual/vis_util.py",
"chars": 953,
"preview": "import torch\n\n\ndef _bbox_decode(priors, bbox_preds):\n xys = (bbox_preds[..., :2] * priors[:, 2:]) + priors[:, :2]\n "
},
{
"path": "tools/visual/vis_yolox.py",
"chars": 4243,
"preview": "import torch\nfrom mmcv import Config\nfrom mmdet3d.datasets import build_dataloader, build_dataset\nimport os\nimport impor"
},
{
"path": "tools/visual_nuscenes.py",
"chars": 121537,
"preview": "# nuScenes dev-kit.\n# Code written by Oscar Beijbom, Holger Caesar & Fong Whye Kit, 2020.\n\nimport json\nimport math\nimpor"
},
{
"path": "tools/visualize.py",
"chars": 904,
"preview": "import os\nimport tqdm\nimport json\nfrom visual_nuscenes import NuScenes\nuse_gt = False\nout_dir = './result_vis/'\nresult_j"
}
]
About this extraction
This page contains the full source code of the megvii-research/Far3D GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 95 files (4.2 MB), approximately 1.1M tokens, and a symbol index with 528 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.