From be86bc74fd1708eddb0c532a71b6e940f214b48b Mon Sep 17 00:00:00 2001 From: VVsssssk <88368822+VVsssssk@users.noreply.github.com> Date: Fri, 1 Apr 2022 17:30:33 +0800 Subject: [PATCH] [Feature]Support centerpoint (#252) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * bump version to v0.4.0 * [Enhancement] Make rewriter more powerful (#150) * Finish function tests * lint * resolve comments * Fix tests * docstring & fix * Complement informations * lint * Add example * Fix version * Remove todo Co-authored-by: RunningLeon * Torchscript support (#159) * support torchscript * add nms * add torchscript configs and update deploy process and dump-info * typescript -> torchscript * add torchscript custom extension support * add ts custom ops again * support mmseg unet * [WIP] add optimizer for torchscript (#119) * add passes * add python api * Torchscript optimizer python api (#121) * add passes * add python api * use python api instead of executable * Merge Master, update optimizer (#151) * [Feature] add yolox ncnn (#29) * add yolox ncnn * add ncnn android performance of yolox * add ut * fix lint * fix None bugs for ncnn * test codecov * test codecov * add device * fix yapf * remove if-else for img shape * use channelshuffle optimize * change benchmark after channelshuffle * fix yapf * fix yapf * fuse continuous reshape * fix static shape deploy * fix code * drop pad * only static shape * fix static * fix docstring * Added mask overlay to output image, changed fprintf info messages to … (#55) * Added mask overlay to output image, changed fprintf info messages to stdout * Improved box filtering (filter area/score), make sure roi coordinates stay within bounds * clang-format * Support UNet in mmseg (#77) * Repeatdataset in train has no CLASSES & PALETTE * update result for unet * update docstring for mmdet * remove ppl for unet in docs * fix ort wrap about input type (#81) * Fix memleak (#86) * delete [] * fix build error when enble MMDEPLOY_ACTIVE_LEVEL * fix lint * [Doc] Nano benchmark and tutorial (#71) * add cls benchmark * add nano zh-cn benchmark and en tutorial * add device row * add doc path to index.rst * fix typo * [Fix] fix missing deploy_core (#80) * fix missing deploy_core * mv flag to demo * target link * [Docs] Fix links in Chinese doc (#84) * Fix docs in Chinese link * Fix links * Delete symbolic link and add links to html * delete files * Fix link * [Feature] Add docker files (#67) * add gpu and cpu dockerfile * fix lint * fix cpu docker and remove redundant * use pip instead * add build arg and readme * fix grammar * update readme * add chinese doc for dockerfile and add docker build to build.md * grammar * refine dockerfiles * add FAQs * update Dpplcv_DIR for SDK building * remove mmcls * add sdk demos * fix typo and lint * update FAQs * [Fix]fix check_env (#101) * fix check_env * update * Replace convert_syncbatchnorm in mmseg (#93) * replace convert_syncbatchnorm with revert_sync_batchnorm from mmcv * change logger * [Doc] Update FAQ for TensorRT (#96) * update FAQ * comment * [Docs]: Update doc for openvino installation (#102) * fix docs * fix docs * fix docs * fix mmcv version * fix docs * rm blank line * simplify non batch nms (#99) * [Enhacement] Allow test.py to save evaluation results (#108) * Add log file * Delete debug code * Rename logger * resolve comments * [Enhancement] Support mmocr v0.4+ (#115) * support mmocr v0.4+ * 0.4.0 -> 0.4.1 * fix onnxruntime wrapper for gpu inference (#123) * fix ncnn wrapper for ort-gpu * resolve comment * fix lint * Fix typo (#132) * lock mmcls version (#131) * [Enhancement] upgrade isort in pre-commit config (#141) * [Enhancement] upgrade isort in pre-commit config by refering to mmflow pr #87 * fix lint * remove .isort.cfg and put its known_third_party to setup.cfg * Fix ci for mmocr (#144) * fix mmocr unittests * remove useless * lock mmdet maximum version to 2.20 * pip install -U numpy * Fix capture_output (#125) Co-authored-by: hanrui1sensetime <83800577+hanrui1sensetime@users.noreply.github.com> Co-authored-by: Johannes L Co-authored-by: RunningLeon Co-authored-by: VVsssssk <88368822+VVsssssk@users.noreply.github.com> Co-authored-by: lvhan028 Co-authored-by: AllentDan <41138331+AllentDan@users.noreply.github.com> Co-authored-by: Yifan Zhou Co-authored-by: 杨培文 (Yang Peiwen) <915505626@qq.com> Co-authored-by: Semyon Bevzyuk * configs for all tasks * use torchvision roi align * remote unnecessary code * fix ut * fix ut * export * det dynamic * det dynamic * add ut * fix ut * add ut and docs * fix ut * skip torchscript ut if no ops available * add torchscript option to build.md * update benchmark and resolve comments * resolve conflicts * rename configs * fix mrcnn cuda test * remove useless * add version requirements to docs and comments to codes * enable empty image exporting for torchscript and accelerate ORT inference for MRCNN * rebase * update example for torchscript.md * update FAQs for torchscript.md * resolve comments * only use torchvision roi_align for torchscript * fix ut * use torchvision roi align when pool model is avg * resolve comments Co-authored-by: grimoire Co-authored-by: grimoire Co-authored-by: hanrui1sensetime <83800577+hanrui1sensetime@users.noreply.github.com> Co-authored-by: Johannes L Co-authored-by: RunningLeon Co-authored-by: VVsssssk <88368822+VVsssssk@users.noreply.github.com> Co-authored-by: lvhan028 Co-authored-by: Yifan Zhou Co-authored-by: 杨培文 (Yang Peiwen) <915505626@qq.com> Co-authored-by: Semyon Bevzyuk * Update supported mmseg models (#181) * fix ocrnet cascade decoder * update mmseg support models * update mmseg configs * support emanet and icnet * set max K of TopK for tensorrt * update supported models for mmseg in docs * add test for emamodule * add configs and update docs * Update docs * update benchmark * [Features]Support mmdet3d (#103) * add mmdet3d code * add code * update code * [log]This commit finish pointpillar export and evaluate on onnxruntime.The model is sample with nvidia repo model * add tensorrt config * fix config * update * support for tensorrt * add config * fix config` * fix apis about torch2onnx * update * mmdet3d deploy version1.0 * map is ok * fix code * version1.0 * fix code * fix visual * fix bug * tensorrt support success * add docstring * add docs * fix docs * fix comments * fix comment * fix comment * fix openvino wrapper * add unit test * fix device about cpu * fix comment * fix show_result * fix lint * fix requirments * remove ci about det3d * fix ut * add ut data * support for new version pointpillars * fix comment * fix support_list * fix comments * fix config name * [Enhancement] Update pad logic in detection heads (#168) * pad with register * fix lint Co-authored-by: AllentDan * [Enhancement] Additional arguments support for OpenVINO Model Optimizer (#178) * Add mo args. * [Docs]: update docs and argument descriptions (#196) * bump version to v0.4.0 * update docs and argument descriptions * revert version change * fix unnecessary change of config for dynamic exportation (#199) * fix mmcls get classes (#215) * fix mmcls get classes * resolve comment * resolve comment * Add ModelOptimizerOptions. * Fix merge bugs. * Update mmpose.md (#224) * [Dostring]add example in apis docstring (#214) * add example in apis docstring * add backend example in docstring * rm blank line * Fixed get_mo_options_from_cfg args * fix l2norm test Co-authored-by: RunningLeon Co-authored-by: Haofan Wang Co-authored-by: VVsssssk <88368822+VVsssssk@users.noreply.github.com> Co-authored-by: grimoire * [Enhancement] Switch to statically typed Value::Any (#209) * replace std::any with StaticAny * fix __compare_typeid * remove fallback id support * constraint on traits::TypeId::value * fix includes * support for centerpoint * [Enhancement] TensorRT DCN support (#205) * add tensorrt dcn support * fix lint * add docstring and dcn model support * add centerpoint ut and docs * add config and fix input rank * fix merge error * fix a bug * fix comment * [Doc] update benchmark add supported-model-list (#286) * update benchmark add supported-model-list * fix lint * fix lint * loc mmocr maximum version * fix ut Co-authored-by: maningsheng Co-authored-by: Yifan Zhou Co-authored-by: AllentDan <41138331+AllentDan@users.noreply.github.com> Co-authored-by: grimoire Co-authored-by: grimoire Co-authored-by: hanrui1sensetime <83800577+hanrui1sensetime@users.noreply.github.com> Co-authored-by: Johannes L Co-authored-by: lvhan028 Co-authored-by: 杨培文 (Yang Peiwen) <915505626@qq.com> Co-authored-by: Semyon Bevzyuk Co-authored-by: AllentDan Co-authored-by: Haofan Wang Co-authored-by: lzhangzz --- ...voxel-detection_openvino_dynamic_kitti.py} | 0 .../voxel-detection_openvino_dynamic_nus.py | 9 + .../voxel-detection_tensorrt_dynamic-nus.py | 18 ++ docs/en/benchmark.md | 8 +- docs/en/supported_models.md | 2 + docs/zh_cn/benchmark.md | 8 +- .../mmdet3d/deploy/voxel_detection_model.py | 31 ++- mmdeploy/codebase/mmdet3d/models/__init__.py | 2 + mmdeploy/codebase/mmdet3d/models/base.py | 2 +- .../codebase/mmdet3d/models/centerpoint.py | 189 ++++++++++++++++++ .../codebase/mmdet3d/models/mvx_two_stage.py | 54 +++++ mmdeploy/codebase/mmdet3d/models/voxelnet.py | 4 +- requirements/optional.txt | 2 +- .../test_mmdet3d/data/model_cfg.py | 87 ++++++++ .../test_mmdet3d/test_mmdet3d_models.py | 53 ++++- .../test_voxel_detection_model.py | 8 +- 16 files changed, 454 insertions(+), 23 deletions(-) rename configs/mmdet3d/voxel-detection/{voxel-detection_openvino_dynamic.py => voxel-detection_openvino_dynamic_kitti.py} (100%) create mode 100644 configs/mmdet3d/voxel-detection/voxel-detection_openvino_dynamic_nus.py create mode 100644 configs/mmdet3d/voxel-detection/voxel-detection_tensorrt_dynamic-nus.py create mode 100644 mmdeploy/codebase/mmdet3d/models/centerpoint.py create mode 100644 mmdeploy/codebase/mmdet3d/models/mvx_two_stage.py diff --git a/configs/mmdet3d/voxel-detection/voxel-detection_openvino_dynamic.py b/configs/mmdet3d/voxel-detection/voxel-detection_openvino_dynamic_kitti.py similarity index 100% rename from configs/mmdet3d/voxel-detection/voxel-detection_openvino_dynamic.py rename to configs/mmdet3d/voxel-detection/voxel-detection_openvino_dynamic_kitti.py diff --git a/configs/mmdet3d/voxel-detection/voxel-detection_openvino_dynamic_nus.py b/configs/mmdet3d/voxel-detection/voxel-detection_openvino_dynamic_nus.py new file mode 100644 index 0000000000..70ef925b6e --- /dev/null +++ b/configs/mmdet3d/voxel-detection/voxel-detection_openvino_dynamic_nus.py @@ -0,0 +1,9 @@ +_base_ = ['./voxel-detection_dynamic.py', '../../_base_/backends/openvino.py'] + +onnx_config = dict(input_shape=None) + +backend_config = dict(model_inputs=[ + dict( + opt_shapes=dict( + voxels=[20000, 20, 5], num_points=[20000], coors=[20000, 4])) +]) diff --git a/configs/mmdet3d/voxel-detection/voxel-detection_tensorrt_dynamic-nus.py b/configs/mmdet3d/voxel-detection/voxel-detection_tensorrt_dynamic-nus.py new file mode 100644 index 0000000000..7ab7ba8245 --- /dev/null +++ b/configs/mmdet3d/voxel-detection/voxel-detection_tensorrt_dynamic-nus.py @@ -0,0 +1,18 @@ +_base_ = ['./voxel-detection_dynamic.py', '../../_base_/backends/tensorrt.py'] +backend_config = dict( + common_config=dict(max_workspace_size=1 << 30), + model_inputs=[ + dict( + input_shapes=dict( + voxels=dict( + min_shape=[5000, 20, 5], + opt_shape=[20000, 20, 5], + max_shape=[30000, 20, 5]), + num_points=dict( + min_shape=[5000], opt_shape=[20000], max_shape=[30000]), + coors=dict( + min_shape=[5000, 4], + opt_shape=[20000, 4], + max_shape=[30000, 4]), + )) + ]) diff --git a/docs/en/benchmark.md b/docs/en/benchmark.md index 71268c0d8d..9e66f19b85 100644 --- a/docs/en/benchmark.md +++ b/docs/en/benchmark.md @@ -326,10 +326,10 @@ Users can directly test the speed through [how_to_measure_performance_of_models. Mask-RCNN COCO 1x3x800x1344 - 320.86 - 3.12 - 241.32 - 4.14 + 104.83 + 9.54 + 58.27 + 17.16 - - - diff --git a/docs/en/supported_models.md b/docs/en/supported_models.md index c5d251f8f9..27751e99bd 100644 --- a/docs/en/supported_models.md +++ b/docs/en/supported_models.md @@ -65,6 +65,8 @@ The table below lists the models that are guaranteed to be exportable to other b | MSPN | MMPose | ? | Y | Y | Y | N | Y | [config](https://mmpose.readthedocs.io/en/latest/papers/backbones.html#mspn-arxiv-2019) | | LiteHRNet | MMPose | ? | Y | Y | N | N | Y | [config](https://mmpose.readthedocs.io/en/latest/papers/backbones.html#litehrnet-cvpr-2021) | | PointPillars | MMDetection3d | ? | Y | Y | N | N | Y | [config](https://github.com/open-mmlab/mmdetection3d/blob/master/configs/pointpillars) | +| CenterPoint (pillar) | MMDetection3d | ? | Y | Y | N | N | Y | [config](https://github.com/open-mmlab/mmdetection3d/blob/master/configs/centerpoint) | + ### Note diff --git a/docs/zh_cn/benchmark.md b/docs/zh_cn/benchmark.md index ffece64617..3225c44fd8 100644 --- a/docs/zh_cn/benchmark.md +++ b/docs/zh_cn/benchmark.md @@ -327,10 +327,10 @@ GPU: ncnn, TensorRT, PPLNN Mask-RCNN COCO 1x3x800x1344 - 320.86 - 3.12 - 241.32 - 4.14 + 104.83 + 9.54 + 58.27 + 17.16 - - - diff --git a/mmdeploy/codebase/mmdet3d/deploy/voxel_detection_model.py b/mmdeploy/codebase/mmdet3d/deploy/voxel_detection_model.py index f33b8b60c8..c5696ef50a 100644 --- a/mmdeploy/codebase/mmdet3d/deploy/voxel_detection_model.py +++ b/mmdeploy/codebase/mmdet3d/deploy/voxel_detection_model.py @@ -7,6 +7,7 @@ from torch.nn import functional as F from mmdeploy.codebase.base import BaseBackendModel +from mmdeploy.core import RewriterContext from mmdeploy.utils import (Backend, get_backend, get_codebase_config, get_root_logger, load_config) @@ -92,7 +93,8 @@ def forward(self, 'coors': coors } outputs = self.wrapper(input_dict) - result = VoxelDetectionModel.post_process(self.model_cfg, outputs, + result = VoxelDetectionModel.post_process(self.model_cfg, + self.deploy_cfg, outputs, img_metas[i], self.device)[0] result_list.append(result) @@ -171,6 +173,7 @@ def voxelize(model_cfg: Union[str, mmcv.Config], points: torch.Tensor): @staticmethod def post_process(model_cfg: Union[str, mmcv.Config], + deploy_cfg: Union[str, mmcv.Config], outs: torch.Tensor, img_metas: Dict, device: str, @@ -179,6 +182,8 @@ def post_process(model_cfg: Union[str, mmcv.Config], Args: model_cfg (str | mmcv.Config): The model config. + deploy_cfg (str|mmcv.Config): Deployment config file or loaded + Config object. outs (torch.Tensor): Output of model's head. img_metas(Dict): Meta info for pcd. device (str): A string specifying device type. @@ -189,7 +194,13 @@ def post_process(model_cfg: Union[str, mmcv.Config], from mmdet3d.core import bbox3d2result from mmdet3d.models.builder import build_head model_cfg = load_config(model_cfg)[0] - head_cfg = dict(**model_cfg.model['bbox_head']) + deploy_cfg = load_config(deploy_cfg)[0] + if 'bbox_head' in model_cfg.model.keys(): + head_cfg = dict(**model_cfg.model['bbox_head']) + elif 'pts_bbox_head' in model_cfg.model.keys(): + head_cfg = dict(**model_cfg.model['pts_bbox_head']) + else: + raise NotImplementedError('Not supported model.') head_cfg['train_cfg'] = None head_cfg['test_cfg'] = model_cfg.model['test_cfg'] head = build_head(head_cfg) @@ -206,12 +217,16 @@ def post_process(model_cfg: Union[str, mmcv.Config], cls_scores = [outs['scores'].to(device)] bbox_preds = [outs['bbox_preds'].to(device)] dir_scores = [outs['dir_scores'].to(device)] - bbox_list = head.get_bboxes( - cls_scores, bbox_preds, dir_scores, img_metas, rescale=False) - bbox_results = [ - bbox3d2result(bboxes, scores, labels) - for bboxes, scores, labels in bbox_list - ] + with RewriterContext( + cfg=deploy_cfg, + backend=deploy_cfg.backend_config.type, + opset=deploy_cfg.onnx_config.opset_version): + bbox_list = head.get_bboxes( + cls_scores, bbox_preds, dir_scores, img_metas, rescale=False) + bbox_results = [ + bbox3d2result(bboxes, scores, labels) + for bboxes, scores, labels in bbox_list + ] return bbox_results diff --git a/mmdeploy/codebase/mmdet3d/models/__init__.py b/mmdeploy/codebase/mmdet3d/models/__init__.py index 47d3e08b57..8de0c41b3c 100644 --- a/mmdeploy/codebase/mmdet3d/models/__init__.py +++ b/mmdeploy/codebase/mmdet3d/models/__init__.py @@ -1,5 +1,7 @@ # Copyright (c) OpenMMLab. All rights reserved. from .base import * # noqa: F401,F403 +from .centerpoint import * # noqa: F401,F403 +from .mvx_two_stage import * # noqa: F401,F403 from .pillar_encode import * # noqa: F401,F403 from .pillar_scatter import * # noqa: F401,F403 from .voxelnet import * # noqa: F401,F403 diff --git a/mmdeploy/codebase/mmdet3d/models/base.py b/mmdeploy/codebase/mmdet3d/models/base.py index 4a1226e2b4..e8d7000e47 100644 --- a/mmdeploy/codebase/mmdet3d/models/base.py +++ b/mmdeploy/codebase/mmdet3d/models/base.py @@ -11,7 +11,7 @@ def base3ddetector__forward_test(ctx, coors, img_metas=None, img=None, - rescale=True): + rescale=False): """Rewrite this function to run simple_test directly.""" return self.simple_test(voxels, num_points, coors, img_metas, img) diff --git a/mmdeploy/codebase/mmdet3d/models/centerpoint.py b/mmdeploy/codebase/mmdet3d/models/centerpoint.py new file mode 100644 index 0000000000..6c9f5fc8c4 --- /dev/null +++ b/mmdeploy/codebase/mmdet3d/models/centerpoint.py @@ -0,0 +1,189 @@ +# Copyright (c) OpenMMLab. All rights reserved. +import torch +from mmdet3d.core import circle_nms + +from mmdeploy.core import FUNCTION_REWRITER + + +@FUNCTION_REWRITER.register_rewriter( + 'mmdet3d.models.detectors.centerpoint.CenterPoint.extract_pts_feat') +def centerpoint__extract_pts_feat(ctx, self, voxels, num_points, coors, + img_feats, img_metas): + """Extract features from points. Rewrite this func to remove voxelize op. + + Args: + voxels (torch.Tensor): Point features or raw points in shape (N, M, C). + num_points (torch.Tensor): Number of points in each voxel. + coors (torch.Tensor): Coordinates of each voxel. + img_feats (list[torch.Tensor], optional): Image features used for + multi-modality fusion. Defaults to None. + img_metas (list[dict]): Meta information of samples. + + Returns: + torch.Tensor: Points feature. + """ + if not self.with_pts_bbox: + return None + + voxel_features = self.pts_voxel_encoder(voxels, num_points, coors) + batch_size = coors[-1, 0] + 1 + x = self.pts_middle_encoder(voxel_features, coors, batch_size) + x = self.pts_backbone(x) + if self.with_pts_neck: + x = self.pts_neck(x) + return x + + +@FUNCTION_REWRITER.register_rewriter( + 'mmdet3d.models.detectors.centerpoint.CenterPoint.simple_test_pts') +def centerpoint__simple_test_pts(ctx, self, x, img_metas, rescale=False): + """Rewrite this func to format model outputs. + + Args: + x (torch.Tensor): Input points feature. + img_metas (list[dict]): Meta information of samples. + rescale (bool): Whether need rescale. + + Returns: + List: Result of model. + """ + outs = self.pts_bbox_head(x) + bbox_preds, scores, dir_scores = [], [], [] + for task_res in outs: + bbox_preds.append(task_res[0]['reg']) + bbox_preds.append(task_res[0]['height']) + bbox_preds.append(task_res[0]['dim']) + if 'vel' in task_res[0].keys(): + bbox_preds.append(task_res[0]['vel']) + scores.append(task_res[0]['heatmap']) + dir_scores.append(task_res[0]['rot']) + bbox_preds = torch.cat(bbox_preds, dim=1) + scores = torch.cat(scores, dim=1) + dir_scores = torch.cat(dir_scores, dim=1) + return scores, bbox_preds, dir_scores + + +@FUNCTION_REWRITER.register_rewriter( + 'mmdet3d.models.dense_heads.centerpoint_head.CenterHead.get_bboxes') +def centerpoint__get_bbox(ctx, + self, + cls_scores, + bbox_preds, + dir_scores, + img_metas, + img=None, + rescale=False): + """Rewrite this func to format func inputs. + + Args + cls_scores (list[torch.Tensor]): Classification predicts results. + bbox_preds (list[torch.Tensor]): Bbox predicts results. + dir_scores (list[torch.Tensor]): Dir predicts results. + img_metas (list[dict]): Point cloud and image's meta info. + img (torch.Tensor): Input image. + rescale (Bool): Whether need rescale. + + Returns: + list[dict]: Decoded bbox, scores and labels after nms. + """ + rets = [] + scores_range = [0] + bbox_range = [0] + dir_range = [0] + self.test_cfg = self.test_cfg['pts'] + for i, task_head in enumerate(self.task_heads): + scores_range.append(scores_range[i] + self.num_classes[i]) + bbox_range.append(bbox_range[i] + 8) + dir_range.append(dir_range[i] + 2) + for task_id in range(len(self.num_classes)): + num_class_with_bg = self.num_classes[task_id] + + batch_heatmap = cls_scores[ + 0][:, scores_range[task_id]:scores_range[task_id + 1], + ...].sigmoid() + + batch_reg = bbox_preds[0][:, + bbox_range[task_id]:bbox_range[task_id] + 2, + ...] + batch_hei = bbox_preds[0][:, bbox_range[task_id] + + 2:bbox_range[task_id] + 3, ...] + + if self.norm_bbox: + batch_dim = torch.exp(bbox_preds[0][:, bbox_range[task_id] + + 3:bbox_range[task_id] + 6, + ...]) + else: + batch_dim = bbox_preds[0][:, bbox_range[task_id] + + 3:bbox_range[task_id] + 6, ...] + + batch_vel = bbox_preds[0][:, bbox_range[task_id] + + 6:bbox_range[task_id + 1], ...] + + batch_rots = dir_scores[0][:, + dir_range[task_id]:dir_range[task_id + 1], + ...][:, 0].unsqueeze(1) + batch_rotc = dir_scores[0][:, + dir_range[task_id]:dir_range[task_id + 1], + ...][:, 1].unsqueeze(1) + + temp = self.bbox_coder.decode( + batch_heatmap, + batch_rots, + batch_rotc, + batch_hei, + batch_dim, + batch_vel, + reg=batch_reg, + task_id=task_id) + assert self.test_cfg['nms_type'] in ['circle', 'rotate'] + batch_reg_preds = [box['bboxes'] for box in temp] + batch_cls_preds = [box['scores'] for box in temp] + batch_cls_labels = [box['labels'] for box in temp] + if self.test_cfg['nms_type'] == 'circle': + + boxes3d = temp[0]['bboxes'] + scores = temp[0]['scores'] + labels = temp[0]['labels'] + centers = boxes3d[:, [0, 1]] + boxes = torch.cat([centers, scores.view(-1, 1)], dim=1) + keep = torch.tensor( + circle_nms( + boxes.detach().cpu().numpy(), + self.test_cfg['min_radius'][task_id], + post_max_size=self.test_cfg['post_max_size']), + dtype=torch.long, + device=boxes.device) + + boxes3d = boxes3d[keep] + scores = scores[keep] + labels = labels[keep] + ret = dict(bboxes=boxes3d, scores=scores, labels=labels) + ret_task = [ret] + rets.append(ret_task) + else: + rets.append( + self.get_task_detections(num_class_with_bg, batch_cls_preds, + batch_reg_preds, batch_cls_labels, + img_metas)) + + # Merge branches results + num_samples = len(rets[0]) + + ret_list = [] + for i in range(num_samples): + for k in rets[0][i].keys(): + if k == 'bboxes': + bboxes = torch.cat([ret[i][k] for ret in rets]) + bboxes[:, 2] = bboxes[:, 2] - bboxes[:, 5] * 0.5 + bboxes = img_metas[i]['box_type_3d'](bboxes, + self.bbox_coder.code_size) + elif k == 'scores': + scores = torch.cat([ret[i][k] for ret in rets]) + elif k == 'labels': + flag = 0 + for j, num_class in enumerate(self.num_classes): + rets[j][i][k] += flag + flag += num_class + labels = torch.cat([ret[i][k].int() for ret in rets]) + ret_list.append([bboxes, scores, labels]) + return ret_list diff --git a/mmdeploy/codebase/mmdet3d/models/mvx_two_stage.py b/mmdeploy/codebase/mmdet3d/models/mvx_two_stage.py new file mode 100644 index 0000000000..3018a2f732 --- /dev/null +++ b/mmdeploy/codebase/mmdet3d/models/mvx_two_stage.py @@ -0,0 +1,54 @@ +# Copyright (c) OpenMMLab. All rights reserved. +from mmdeploy.core import FUNCTION_REWRITER + + +@FUNCTION_REWRITER.register_rewriter( + 'mmdet3d.models.detectors.mvx_two_stage.MVXTwoStageDetector.simple_test') +def mvxtwostagedetector__simple_test(ctx, + self, + voxels, + num_points, + coors, + img_metas, + img=None, + rescale=False): + """Rewrite this func to remove voxelize op. + + Args: + voxels (torch.Tensor): Point features or raw points in shape (N, M, C). + num_points (torch.Tensor): Number of points in each voxel. + coors (torch.Tensor): Coordinates of each voxel. + img_metas (list[dict]): Meta information of samples. + img (torch.Tensor): Input image. + rescale (Bool): Whether need rescale. + + Returns: + list[dict]: Decoded bbox, scores and labels after nms. + """ + _, pts_feats = self.extract_feat( + voxels, num_points, coors, img=img, img_metas=img_metas) + if pts_feats and self.with_pts_bbox: + bbox_pts = self.simple_test_pts(pts_feats, img_metas, rescale=rescale) + return bbox_pts + + +@FUNCTION_REWRITER.register_rewriter( + 'mmdet3d.models.detectors.mvx_two_stage.MVXTwoStageDetector.extract_feat') +def mvxtwostagedetector__extract_feat(ctx, self, voxels, num_points, coors, + img, img_metas): + """Rewrite this func to remove voxelize op. + + Args: + voxels (torch.Tensor): Point features or raw points in shape (N, M, C). + num_points (torch.Tensor): Number of points in each voxel. + coors (torch.Tensor): Coordinates of each voxel. + img (torch.Tensor): Input image. + img_metas (list[dict]): Meta information of samples. + + Returns: + tuple(torch.Tensor) : image feature and points feather. + """ + img_feats = self.extract_img_feat(img, img_metas) + pts_feats = self.extract_pts_feat(voxels, num_points, coors, img_feats, + img_metas) + return (img_feats, pts_feats) diff --git a/mmdeploy/codebase/mmdet3d/models/voxelnet.py b/mmdeploy/codebase/mmdet3d/models/voxelnet.py index 6a47d20cae..e5d285bb2f 100644 --- a/mmdeploy/codebase/mmdet3d/models/voxelnet.py +++ b/mmdeploy/codebase/mmdet3d/models/voxelnet.py @@ -16,7 +16,7 @@ def voxelnet__simple_test(ctx, post process. Args: - voxels(torch.Tensor): Point features or raw points in shape (N, M, C). + voxels (torch.Tensor): Point features or raw points in shape (N, M, C). num_points (torch.Tensor): Number of points in each pillar. coors (torch.Tensor): Coordinates of each voxel. input_metas (list[dict]): Contain pcd meta info. @@ -40,7 +40,7 @@ def voxelnet__extract_feat(ctx, """Extract features from points. Rewrite this func to remove voxelize op. Args: - voxels(torch.Tensor): Point features or raw points in shape (N, M, C). + voxels (torch.Tensor): Point features or raw points in shape (N, M, C). num_points (torch.Tensor): Number of points in each pillar. coors (torch.Tensor): Coordinates of each voxel. input_metas (list[dict]): Contain pcd meta info. diff --git a/requirements/optional.txt b/requirements/optional.txt index 804f76f94b..8e52e01a66 100644 --- a/requirements/optional.txt +++ b/requirements/optional.txt @@ -1,7 +1,7 @@ mmcls>=0.15.0,<=0.19.0 mmdet>=2.19.0,<=2.20.0 mmedit -mmocr>=0.3.0 +mmocr>=0.3.0,<=0.4.1 mmpose>=0.24.0 mmsegmentation onnxruntime>=1.8.0 diff --git a/tests/test_codebase/test_mmdet3d/data/model_cfg.py b/tests/test_codebase/test_mmdet3d/data/model_cfg.py index b1934a2ca7..0c46aad4b8 100644 --- a/tests/test_codebase/test_mmdet3d/data/model_cfg.py +++ b/tests/test_codebase/test_mmdet3d/data/model_cfg.py @@ -141,3 +141,90 @@ classes=class_names, test_mode=True, box_type_3d='LiDAR')) + +point_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0] +centerpoint_model = dict( + pts_voxel_layer=dict( + max_num_points=20, + voxel_size=voxel_size, + max_voxels=(30000, 40000), + point_cloud_range=point_cloud_range), + pts_voxel_encoder=dict( + type='PillarFeatureNet', + in_channels=4, + feat_channels=[64], + with_distance=False, + voxel_size=(0.2, 0.2, 8), + norm_cfg=dict(type='BN1d', eps=1e-3, momentum=0.01), + legacy=False), + pts_middle_encoder=dict( + type='PointPillarsScatter', in_channels=64, output_shape=(512, 512)), + pts_backbone=dict( + type='SECOND', + in_channels=64, + out_channels=[64, 128, 256], + layer_nums=[3, 5, 5], + layer_strides=[2, 2, 2], + norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01), + conv_cfg=dict(type='Conv2d', bias=False)), + pts_neck=dict( + type='SECONDFPN', + in_channels=[64, 128, 256], + out_channels=[128, 128, 128], + upsample_strides=[0.5, 1, 2], + norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01), + upsample_cfg=dict(type='deconv', bias=False), + use_conv_for_no_stride=True), + pts_bbox_head=dict( + type='CenterHead', + in_channels=sum([128, 128, 128]), + tasks=[ + dict(num_class=1, class_names=['car']), + dict(num_class=2, class_names=['truck', 'construction_vehicle']), + dict(num_class=2, class_names=['bus', 'trailer']), + dict(num_class=1, class_names=['barrier']), + dict(num_class=2, class_names=['motorcycle', 'bicycle']), + dict(num_class=2, class_names=['pedestrian', 'traffic_cone']), + ], + common_heads=dict( + reg=(2, 2), height=(1, 2), dim=(3, 2), rot=(2, 2), vel=(2, 2)), + share_conv_channel=64, + bbox_coder=dict( + type='CenterPointBBoxCoder', + post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0], + pc_range=point_cloud_range[:2], + max_num=500, + score_threshold=0.1, + out_size_factor=4, + voxel_size=voxel_size[:2], + code_size=9), + separate_head=dict( + type='SeparateHead', init_bias=-2.19, final_kernel=3), + loss_cls=dict(type='GaussianFocalLoss', reduction='mean'), + loss_bbox=dict(type='L1Loss', reduction='mean', loss_weight=0.25), + norm_bbox=True), + # model training and testing settings + train_cfg=dict( + pts=dict( + grid_size=[512, 512, 1], + voxel_size=voxel_size, + out_size_factor=4, + dense_reg=1, + gaussian_overlap=0.1, + max_objs=500, + min_radius=2, + code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2])), + test_cfg=dict( + pts=dict( + post_center_limit_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0], + max_per_img=500, + max_pool_nms=False, + min_radius=[4, 12, 10, 1, 0.85, 0.175], + pc_range=point_cloud_range[:2], + score_threshold=0.1, + out_size_factor=4, + voxel_size=voxel_size[:2], + nms_type='circle', + pre_max_size=1000, + post_max_size=83, + nms_thr=0.2))) diff --git a/tests/test_codebase/test_mmdet3d/test_mmdet3d_models.py b/tests/test_codebase/test_mmdet3d/test_mmdet3d_models.py index 8b1b0039ed..afddebf1ab 100644 --- a/tests/test_codebase/test_mmdet3d/test_mmdet3d_models.py +++ b/tests/test_codebase/test_mmdet3d/test_mmdet3d_models.py @@ -5,7 +5,7 @@ import torch from mmdeploy.codebase import import_codebase -from mmdeploy.utils import Backend, Codebase, Task +from mmdeploy.utils import Backend, Codebase, Task, load_config from mmdeploy.utils.test import WrapModel, check_backend, get_rewrite_outputs try: @@ -13,6 +13,8 @@ except ImportError: pytest.skip( f'{Codebase.MMDET3D} is not installed.', allow_module_level=True) +model_cfg = load_config( + 'tests/test_codebase/test_mmdet3d/data/model_cfg.py')[0] def get_pillar_encoder(): @@ -107,3 +109,52 @@ def test_pointpillars_scatter(backend_type: Backend): rewrite_output = rewrite_output.cpu().numpy() assert np.allclose( model_output.shape, rewrite_output.shape, rtol=1e-03, atol=1e-03) + + +def get_centerpoint(): + from mmdet3d.models.detectors.centerpoint import CenterPoint + + model = CenterPoint(**model_cfg.centerpoint_model) + model.requires_grad_(False) + return model + + +def get_centerpoint_head(): + from mmdet3d.models import builder + model_cfg.centerpoint_model.pts_bbox_head.test_cfg = model_cfg.\ + centerpoint_model.test_cfg + head = builder.build_head(model_cfg.centerpoint_model.pts_bbox_head) + head.requires_grad_(False) + return head + + +@pytest.mark.parametrize('backend_type', [Backend.ONNXRUNTIME]) +def test_centerpoint(backend_type: Backend): + from mmdeploy.codebase.mmdet3d.deploy.voxel_detection import VoxelDetection + from mmdeploy.core import RewriterContext + check_backend(backend_type, True) + model = get_centerpoint() + model.cpu().eval() + deploy_cfg = mmcv.Config( + dict( + backend_config=dict(type=backend_type.value), + onnx_config=dict( + input_shape=None, + opset_version=11, + input_names=['voxels', 'num_points', 'coors'], + output_names=['outputs']), + codebase_config=dict( + type=Codebase.MMDET3D.value, task=Task.VOXEL_DETECTION.value))) + voxeldetection = VoxelDetection(model_cfg, deploy_cfg, 'cpu') + inputs, data = voxeldetection.create_input( + 'tests/test_codebase/test_mmdet3d/data/kitti/kitti_000008.bin') + + with RewriterContext( + cfg=deploy_cfg, + backend=deploy_cfg.backend_config.type, + opset=deploy_cfg.onnx_config.opset_version): + outputs = model.forward(*data) + head = get_centerpoint_head() + rewrite_outputs = head.get_bboxes(*[[i] for i in outputs], + inputs['img_metas'][0]) + assert rewrite_outputs is not None diff --git a/tests/test_codebase/test_mmdet3d/test_voxel_detection_model.py b/tests/test_codebase/test_mmdet3d/test_voxel_detection_model.py index 1959996d93..5946f7b762 100644 --- a/tests/test_codebase/test_mmdet3d/test_voxel_detection_model.py +++ b/tests/test_codebase/test_mmdet3d/test_voxel_detection_model.py @@ -41,7 +41,11 @@ def setup_class(cls): deploy_cfg = mmcv.Config({ 'onnx_config': { 'input_names': ['voxels', 'num_points', 'coors'], - 'output_names': ['scores', 'bbox_preds', 'dir_scores'] + 'output_names': ['scores', 'bbox_preds', 'dir_scores'], + 'opset_version': 11 + }, + 'backend_config': { + 'type': 'tensorrt' } }) @@ -71,7 +75,7 @@ def test_forward_and_show_result(self): @backend_checker(Backend.ONNXRUNTIME) -def test_build_pose_detection_model(): +def test_build_voxel_detection_model(): from mmdeploy.utils import load_config model_cfg_path = 'tests/test_codebase/test_mmdet3d/data/model_cfg.py' model_cfg = load_config(model_cfg_path)[0]