【参考算法】地平线 Centerpoint 参考算法-V1.2.1

0 概述-


在自动驾驶应用中,除了在2D图像中检测目标之外,还必须在3D空间中检测某些目标的类别,如汽车、行人、自行车等。LiDAR通过构建3D空间的点云,可以提供一种精确、高空间维度、高分辨率的数据,可以弥补对3D空间的距离信息。随着深度学习架构的进步逐渐出现了许多基于LiDAR的3D目标检测器。本文在Nuscenes数据集下基于pillar-based的centerpoint算法的介绍和使用说明。-

该示例为参考算法,仅作为在J5上模型部署的设计参考,非量产算法

1 性能精度指标

数据集

NDS

infer

前处理耗时(ARM+DSP/ARM)

帧率(J5/双核)

Nuscenes

0.5753

24.51ms

20ms/77ms

98.72

infer耗时不包含pillar前处理、后处理-
前处理提供两种集成方式:纯ARM实现、通过ARM调取DSP实现

模型配置:-

点云数量

点云范围

Voxel 尺寸

最大点数

最大pillar数

检测类别

300000x5(注1)

[-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]

[0.2, 0.2, 8]

20

40000

10类(注2)

注-
1:维度为(x,y,z,r,t),即:3维坐标、强度和时间-
2:“car”,“truck”,“construction_vehicle”,“bus”,“trailer”,“barrier”,“motorcycle”,“bicycle”,“pedestrian”,“traffic_cone”,

2 模型介绍-


Centerpoint为在pointpillars基础上做优化的多类别3D检测模型,检测类别10类(见注1),模型实现上与pointpillars相同的,在VoxelNet中Voxel的基础上提出了一种改进版本的点云表征方法Pillar,可以将点云转换成伪图像,进而通过2D卷积实现多类别目标检测。由于nuscenes在二阶段模型中精度相比一阶段无明显提升,因此该Centerpoint为一阶段模型,框架可参考pointpillars。

Centerpoint整个网络结构分为三个部分:

  • 体素化(pillar 化):将输入的5维原始点云转换为稀疏的伪图像形式
  • Backbone:将PFN层后的特征提取高层语义特征
  • CenterPointHead:多类别的3D目标检测和回归3D框

2.1 模型改动点-

在网络结构上,相比于官方实现,我们做了如下更改:-

  • 前处理 point encoder部分,仅使用5维,并做归一化处理, 浮点相比官方几乎不掉点,对量化训练更友好;
  • PillarFeatutreNet 中的 PFNLayer 使用 Conv2d + BathNorm2d + ReLU,替换原有的 Linear + BatchNorm1d + ReLU,使该结构可在BPU上高效支持,性能提升;
  • PillarFeatutreNet 中的 PFNLayer 使用 MaxPool2d,替换原有的 torch.max,便于性能的提升;
  • Scatter过程使用horizon_plugin_pytorch实现的point_pillars_scatter,便于模型推理优化,逻辑与公版相同。
  • 对于耗时严重的OP,采用H W维度转换的方式,将大数据放到W维度,比如1x5x40000x20 转换为 1x5x20x40000

2.2 源码说明-

Config文件-

configs/detection/centerpoint/centerpoint_pointpillar_nuscenes.py 为 pointpillars 的配置文件,定义了模型结构、数据集加载,和整套训练流程,所需参数的说明在算子定义中会给出。配置文件主要内容包括:

batch_size_per_gpu = 4
device_ids = [0, 1, 2, 3, 4, 5, 6, 7]

# Voxelization cfg
point_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]
voxel_size = [0.2, 0.2, 8]
max_num_points = 20
max_voxels = (30000, 40000)
...

# 模型结构定义
model=dict(
    type="CenterPointDetector", 
    feature_map_shape=get_feature_map_size(point_cloud_range, voxel_size),
    pre_process=dict(
        type="CenterPointPreProcess",
        pc_range=point_cloud_range,
        voxel_size=voxel_size,
        max_voxels_num=max_voxels,
        max_points_in_voxel=max_num_points,
        norm_range=[-51.2, -51.2, -5.0, 0.0, 51.2, 51.2, 3.0, 255.0],
        norm_dims=[0, 1, 2, 3],
    ),
    reader=dict(
        type="PillarFeatureNet",
        num_input_features=5,
        ...
    ),
    backbone=dict(
        type="PointPillarScatter",
        use_horizon_pillar_scatter=True,
        ...
    ),
    neck=dict(
        type="SequentialBottleNeck",
        ...
    ),
    head=dict(
        type="CenterPointHead",
        ...
    ),
    targets=dict(
        type="CenterPointTargets",
        ...
    ),
    loss=dict(
        type="CenterPointLoss",
        num_classes=len(class_names),
        loss_cls=dict(type="GaussianFocalLoss", loss_weight=1.0),
        loss_bbox=dict(
            ...
        ),
    ),
    postprocess=dict(
        type="CenterPointPostProcess",
        ...
    ),
)
#deploy model and input
deploy_inputs = dict(
    features=torch.randn((1, 5, 40000, 20), dtype=torch.float32),
    coors=torch.zeros([40000, 4]).int(),
)
#train数据处理
train_set=dict(
    ...
)

# 数据加载相关定义
dataloader=dict(...)
val_data_loader=dict(...)
#callbacks 定义
stat_callback = dict(...)
ckpt_callback = dict(...)
val_callback = dict(...)
#训练策略配置
float_trainer=dict(...)
calibration_trainer=dict(...)
qat_trainer=dict(...)
int_infer_trainer=dict(...)
#编译设置
compile_cfg = dict(...)
# predictor
float_predictor = dict(...)
calibration_predictor= dict(...)
qat_predictor = dict(...)
int_infer_predictor= dict(...)

注: 如果需要复现精度,config中的训练策略最好不要修改。否则可能会有意外的训练情况出现。

Voxelization-
该接口是在horizon-plugin中实现,preprocess实现voxelization过程,主要是将点云数据根据预设size划分为一个个的网格。凡是落入到一个网格的点云数据被视为其处在一个 voxel里,或者理解为它们构成了一个 voxel。voxelization的实现流程见下图:

对应代码:/usr/local/lib/python3.8/dist-packages/horizon_plugin_pytorch/nn/quantized/functional_impl.py_voxelization

def _voxelization(
    points: Tensor,
    voxel_size: Tensor,
    pc_range: Tensor,
    max_voxels: int,
    max_points_per_voxel: int,
    use_max: bool,
) -> Tuple[Tensor, Tensor, Tensor]:
    "Convert points(N, >=3) to voxels."
    ndim = 3 #point xyz
    grid_size = (pc_range[3:] - pc_range[:3]) / voxel_size  # (x, y, z)
    voxel_map_shape = voxel_map_shape[::-1]  # (z, y, x)

    voxels = torch.zeros(...)    #(max_voxels, max_points_per_voxel, points.shape[-1])
    coors = torch.full(
        (max_voxels, 3),
        -1,
        dtype=torch.int32,
    )   #(max_voxels, 3)
    num_points_per_voxel = torch.zeros(...) #(max_voxels,)

    voxel_num = torch.zeros(1, dtype=torch.int64)
    voxel_num = torch.ops.horizon.voxelization(
        points.cpu(),
        voxel_size.cpu(),
        pc_range.cpu(),
        voxels.cpu(),
        coors.cpu(),
        num_points_per_voxel.cpu(),
        max_points_per_voxel,
        max_voxels,
        ndim,
    )

    if use_max:
        # for deploy, use max_voxels
        out_num = max_voxels
    else:
        out_num = voxel_num

    coors = coors[:out_num].to(points.device)
    voxels = voxels[:out_num].to(points.device)
    num_points_per_voxel = num_points_per_voxel[:out_num].to(points.device)
    return (voxels, coors, num_points_per_voxel)

对pillar特征归一化,可通过指定维度和范围值做归一化,有助于量化训练:

def _voxel_feature_encoder(
    norm_range: Tensor,
    norm_dims: List[int],
    ...
) -> Tensor:
    # normolize features
    for idx, dim in enumerate(norm_dims):
        start = norm_range[idx]
        norm = norm_range[idx + len(norm_range) // 2] - norm_range[idx]
        features[:, :, dim] = features[:, :, dim] - start
        features[:, :, dim] = features[:, :, dim] / norm

    # The feature decorations were calculated without regard to whether
    # pillar was empty. Need to ensure that empty pillars remain set to
    # zeros.
    mask = _get_paddings_indicator(num_points_in_voxel, voxel_count, axis=0)
    features *= mask
    features = features.unsqueeze(0).permute(0, 3, 2, 1).contiguous()  #对应改动5
    return features

PillarFeatureNet-
为了应用 2D 卷积架构,最终要实现将点云(P,N,5)转换为伪图像,整体步骤如下图:

伪图像处理包括三个步骤,stack pillars、learn features、pseudo image。PFN层主要完成learn features步骤,对应代码路径:/usr/local/lib/python3.8/dist-packages/hat/models/task_modules/lidar/pillar_encoder.py-
该算法主要实现将点云数据的shape (1,D,N,P)经过pfn_layers后变换为(1,C,1,P)–>(1,1,P,C)-
对应代码:/usr/local/lib/python3.8/dist-packages/hat/models/task_modules/lidar/pillar_encoder.py

class PillarFeatureNet(nn.Module):
    def __int__(
    ...
    ):
    ...
    def forward(
        self,
        features: torch.Tensor,
        coors: torch.Tensor,
        num_voxels: torch.Tensor = None,
        horizon_preprocess: bool = True,
    ):
        if horizon_preprocess:
            # used horizon preprocess, skip pre_process here.
            features = self._extract_feature(features) #PFNLayer
        else:
            # default preprocess
            assert num_voxels is not None, "`num_voxels` can not be None."
            features = self._extend_dim(features, num_voxels, coors)
            features = self._extract_feature(features) #PFNLayer
        return features


class PFNLayer(nn.Module):
    def __init__(
    ...
    )
    def forward(self, inputs: torch.Tensor):
        ...
        print('input:',inputs[0].size)
        x = self.linear(inputs)    #对应改动2
        x = self.norm(x)
        x = self.relu(x)
        x_max = self.max_pool(x)  # 对应改动3 
        ...

PointPillarScatter-
该层实现伪图像转换的最后一个步骤。为了获得伪图片特征,将 P 转化为(W, H),由于预先设定pillar最大值以及去除了一些空pillar,因此P<H*W,最终可以通过映射获得形如(C, H, W) 的伪图像。

对应代码: /usr/local/lib/python3.8/dist-packages/hat/models/task_modules/lidar/pillar_encoder.py

class PointPillarScatter(nn.Module):
    ...
    def forward(
        ...
        ):
         #input_shape=(coors_range[3:] - coors_range[:3]) / voxel_size 
         self.nx = input_shape[0]  
         self.ny = input_shape[1]
         if self.use_horizon_pillar_scatter: #对应改动4
             if len(voxel_features.shape) == 4:
                 P, C = voxel_features.size(2), voxel_features.size(3)
                 voxel_features = voxel_features.reshape(P, C)
             out_shape = (batch_size, self.nchannels, self.ny, self.nx)
             #(P, C)-->(batch,C,H,W)
             batch_canvas = point_pillars_scatter( 
                 voxel_features, coords, out_shape
             )
         else:
             ...
         return batch_canvas

Scatter实现代码在horizon_plugin_pytorch下实现,见代码:

def _point_pillars_scatter(
    voxel_features: Tensor, coords: Tensor, output_shape: List[int]
) -> Tensor:
    ...
    canvas = torch.zeros(
        batch_size * hight * width,
        channel_dim,
        dtype=voxel_features.dtype,
        device=voxel_features.device,
    )
    index = (
        coords[:, 0] * (hight * width) + coords[:, -2] * width + coords[:, -1]
    )
    canvas[index] = voxel_features
    return canvas.reshape(batch_size, hight, width, channel_dim).permute(
        0, 3, 1, 2
    )

SequentialBottleNeck-
该模型的backbone用是SequentialBottleNeck,使用多个 Conv2D + BN + ReLU 的结构将特征进行融合处理,通过多个卷积和反卷积的组合,最后在dim=1维做concat。RPN结构见下图:

对应代码:/usr/local/lib/python3.8/dist-packages/hat/models/necks/sequential_bottleneck.py

class SequentialBottleNeck(nn.Module):
    def __init__(
        self,
        ...
    ):
    ...
        for i, layer_num in enumerate(self._layer_nums):
            block, num_out_filters = make_layer(
            ...
            )
            blocks.append(block)
            if i - self._upsample_start_idx >= 0:
                ...
                    deblock = self._make_deblock(
                        num_out_filters, i, stride, True, use_tconv
                    )
                ...
                deblocks.append(deblock)
        self.blocks = nn.ModuleList(blocks)
        self.deblocks = nn.ModuleList(deblocks)
        ...
    
    def forward(self, x: torch.Tensor):
        ...
        for i in range(len(self.blocks)):
            x = self.blocks[i](x)
            if i - self._upsample_start_idx >= 0:
                ups.append(self.deblocks[i - self._upsample_start_idx](x))
        if len(ups) > 0:
            ...
            x = self.cat.cat(ups, dim=1)
        return x

CenterPointHead-

检测为多task检测,主要分为:

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"]),
]

在nuscenes数据集中,目标的类别一共被分为了6个大类,网络给每一个类都分配了一个head,装在headlist中,而每个head内部都为预测的参数。-

对应代码:/usr/local/lib/python3.8/dist-packages/hat/models/task_modules/centerpoint/head.py

class CenterPointHead(nn.Module):
    def __init__(self,...):
        self.shared_conv = nn.Sequential(
            *(
                self._make_conv(
                    in_channels=in_channels if i == 0 else share_conv_channels,
                    ...
                )
                for i in range(share_conv_num)
            )
        )  
        #head module  
        for num_cls in num_classes:
            heads = copy.deepcopy(common_heads)
            heads.update({"heatmap": (num_cls, num_heatmap_convs)})
            task_head = self._make_task(
                ...,
            )
            self.task_heads.append(task_head)
 
    def forward(self, feats):
        rets = []
        feats = feats[0]
        feats = self.shared_conv(feats)
        for task in self.task_heads:
            rets.append(task(feats))

forward时,经过共享的Conv后,将feature再分别传入task_heads做task_pred。-

/usr/local/lib/python3.8/dist-packages/hat/models/task_modules/centerpoint/head.pyTaskHead对不同的task定义conv_layers:

class TaskHead(nn.Module):
    def __init__(...):
         ...    
         for head in self.heads:
            classes, num_conv = self.heads[head]
            ...
            #head_conv
            for _ in range(num_conv - 1):
                conv_layers.append(
                    self._make_conv(
                    ...
                    )
                )
                c_in = head_conv_channels
            #cls_layer
            conv_layers.append(
                ConvModule2d(
                    in_channels=head_conv_channels,
                    out_channels=classes,
                    ...
                )
            )
            conv_layers = nn.Sequential(*conv_layers)
    
    def forward(self, x):
        ret_dict = {}
        for head in self.heads:
            ret_dict[head] = self.dequant(self.__getattr__(head)(x))
        return ret_dict

Centerpoint Loss-

由2部分构成:loss_cls+loss_reg。其中,loss_cls=GaussianFocalLoss;loss_bbox=L1Loss <br> 对应代码:/usr/local/lib/python3.8/dist-packages/hat/models/losses/centerpoint_losses.py`

class CenterPointLoss(nn.Module):
    def __init__(
        self,
        ...
    ):
    def forward(
    ...
    ):
        loss_dict = dict()
        for task_id, preds_dict in enumerate(preds_dicts):
            ...
            # heatmap focal loss
            loss_heatmap = self.loss_cls(
                preds_dict["heatmap"],
                heatmaps[task_id],
            )
            ...
            # Regression loss for dimension, offset, height, rotation
            loss_bbox = self.loss_bbox(
                pred, target_box, bbox_weights, avg_factor=(num + 1e-4)
            )
            
            loss_dict[f"task{task_id}.loss_heatmap"] = loss_heatmap
            loss_dict[f"task{task_id}.loss_bbox"] = loss_bbox

        return loss_dict

3 浮点模型训练-


3.1 Before Start-

3.1.1 环境部署-

Centerpoint示例集成在OE包中,获取方式见:J5芯片算法工具链OpenExplorer 版本发布

Centerpoint示例位于ddk/samples/ai_toolchain/horizon_model_train_sample下,其结构为:-

└── horizon_model_train_sample
    ├── scripts    
        ├── configs            #配置文件
        `── tools              #工具及运行脚本

release_models获取路径见:horizon_model_train_sample/scripts/configs/detection/centerpoint/README.md

拉取docker环境

docker pull openexplorer/ai_toolchain_ubuntu_20_j5_gpu: {version}
#启动容器,具体参数可根据实际需求配置
#-v 用于将本地的路径挂载到 docker 路径下
nvidia-docker run -it --shm-size="15g" -v `pwd`:/open_explorer openexplorer/ai_toolchain_ubuntu_20_j5_gpu: {version}

如需本地离线安装HAT,我们提供了训练环境的whl包,路径在ddk/package/host/ai_toolchain

3.1.2 数据下载-

在开始训练模型之前,第一步是需要准备好数据集,我们在 nuscenes 数据集 下载 下载Full dataset (v1.0)以及nuScenes-lidarseg。-
将下载的文件进行解压,lidar_seg/v1.0-trainval下的category.json 与 lidarseg.json 分别复制到nuscenes/v1.0-trainval 文件夹下,解压后的目录如下所示:

├──data   #原始数据集
    |--nuscenes
        |-- lidarseg
        |-- samples #v1.0-trainvalXX_blobs.tar解压后的目录
        |   |-- CAM_BACK
        |   |-- ...
        |   |-- CAM_FRONT_RIGHT
        |   |--  ...
        |   `-- RADAR_FRONT_RIGHT
        |-- sweeps
        |   |-- CAM_BACK
        |   |-- ...
        |   |-- CAM_FRONT_RIGHT
        |   |--  ...
        |   `-- RADAR_FRONT_RIGHT
        |-- v1.0-trainval #v1.0-trainval_meta.tar解压后的数据
            |-- attribute.json
            |-- lidarseg.json #来自lidar_seg/v1.0-trainval/
            |-- category.json #来自lidar_seg/v1.0-trainval/
            |-- ...
            `-- visibility.json

3.1.3 数据打包

#pack train_Set
python3 tools/datasets/nuscenes_packer.py --src-data-dir data/nuscenes/ --pack-type lmdb --target-data-dir tmp_data/nuscenes/lidar/v1.0-trainval --version v1.0-trainval --split-name train --only-lidar
#pack test_Set
python3 tools/datasets/nuscenes_packer.py --src-data-dir data/nuscenes/ --pack-type lmdb --target-data-dir tmp_data/nuscenes/lidar/v1.0-trainval --version v1.0-trainval --split-name val --only-lidar

--src-data-dir为解压后的nuscenes数据集目录;-
--target-data为打包后数据集的存储目录;-
--version 选项为[“v1.0-trainval”, “v1.0-test”, “v1.0-mini”],如果进行全量训练和验证设置为v1.0-trainval,如果仅想了解模型的训练和验证过程,则可以使用v1.0-mini数据集; v1.0-test数据集仅为测试场景,未提供注释

数据集打包命令执行完毕后会在target-data-dir下生成train_lmdbval_lmdbtrain_lmdbval_lmdb就是打包之后的训练数据集和验证数据集为config中的data_rootdir

|-- tmp_data 
|   |-- nuscenes 
|   |   |-- lidar
|   |   |   |-- v1.0-trainval
|   |   |   |   |-- train_lmdb  #打包后的train数据集
|   |   |   |   |   |-- data.mdb
|   |   |   |   |   `-- lock.mdb
|   |   |   |   `-- val_lmdb   #打包后的val数据集
|   |   |   |   |   |-- data.mdb
|   |   |   |   |   `-- lock.mdb

3.1.4 meta文件夹构建-

tmp_data/nuscenes/下创建meta文件夹,将下载的nuScenes-map-expansion-v1.3.zipv1.0-trainval_meta.tar压缩包解压至meta文件夹下,当前的目录结构为:

|-- tmp_data 
|   |-- nuscenes 
|   |   |-- lidar
|   |   |   |-- v1.0-trainval 
|   |   |   |   |-- train_lmdb  #打包后的train数据集
|   |   |   |   |-- val_lmdb   #打包后的val数据集
|   |   |-- meta
|   |   |   |-- maps        #nuScenes-map-expansion-v1.3.zip解压后的目录
|   |   |   |   |-- 36092f0b03a857c6a3403e25b4b7aab3.png
                    ...
|   |   |   |   |-- 93406b464a165eaba6d9de76ca09f5da.png
|   |   |   |   |-- basemap
|   |   |   |   |-- expansion
|   |   |   |-- v1.0-trainval  #v1.0-trainval_meta.tar解压后的目录
|   |   |       |-- attribute.json
|   |   |       |-- lidarseg.json
|   |   |       |-- category.json
|   |   |       |-- ...
|   |   |       |-- visibility.json

3.1.5 数据生成-

为了训练 nuscenes 点云数据,还需为 nuscenes 数据集生成每个单独的训练目标的点云数据,以及需要为这部分数据生成 .pkl 格式的包含数据信息的文件。通过运行下面的命令来创建:

python3 tools/create_data.py --dataset nuscenes --root-dir ./tmp_data/nuscenes/lidar/v1.0-trainval/ --extra-tag nuscenes --out-dir tmp_nuscenes/lidar

执行上述命令后,生成的文件目录如下:

├── tmp_data
│   ├── nuscenes
│   │   ├── lidar
│   │   │   ├── v1.0-trainval #打包数据集
│   │   │   │   ├── train_lmdb  
│   │   │   │   ├── val_lmdb    
│   │   ├── meta
│   │   │   ├── maps        
│   │   │   ├── v1.0-trainval    

├── tmp_nuscenes
│   ├── lidar
│   │   ├── nuscenes_gt_database           # 新生成的 nuscenes_gt_database
│   │   ├── nuscenes_dbinfos_train.pkl     # 新生成的 nuscenes_dbinfos_train.pkl

其中 tmp_nuscenes/lidar/nuscenes_gt_database.bin 格式的文件为生成的gt_database;nuscenes_gt_databasenuscenes_dbinfos_train.pkl 是训练用于采样的样本;文件保存目录可通过--out-dir更改。

3.1.6 config配置-

在进行模型训练和验证之前,需要对configs文件中的部分参数进行配置,一般情况下,我们需要配置以下参数:

  • device_ids、batch_size_per_gpu:根据实际硬件配置进行device_ids和每个gpu的batchsize的配置;
  • ckpt_dir:浮点、calib、量化训练的权重路径配置,权重下载链接在config文件夹下的README中;
  • data_rootdir:打包的lmdb数据集路径配置;
  • meta_rootdir :meta文件夹的路径配置;
  • gt_data_root:nuscenes_gt_database的上一层路径
  • infer_cfg:input_points为点云输入,做结果可视化时需要配置

3.2 浮点模型训练-

configs/detection/centerpoint/centerpoint_pointpillar_nuscenes.py下配置参数,需要将相关硬件配置device_ids和权重路径ckpt_dir数据集路径data_rootdir配置修改后使用以下命令训练浮点模型:

python3 tools/train.py --stage float --config configs/detection/centerpoint/centerpoint_pointpillar_nuscenes.py

3.3 浮点模型精度验证-

通过指定训好的float_checkpoint_path,使用以下命令验证已经训练好的模型精度:

python3 tools/predict.py --stage float --config configs/detection/centerpoint/centerpoint_pointpillar_nuscenes.py

验证完成后,会在终端输出float模型在验证集上的检测精度。

4 模型量化和编译-


模型上板前需要将模型编译为.hbm文件, 可以使用compile的工具用来将量化模型编译成可以上板运行的hbm文件,因此首先需要将浮点模型量化,地平线对centerpoint模型的量化采用horizon_plugin框架,通过Calibration+QAT量化训练和转换最终获得定点模型。-

4.1 Calibration-

为加速QAT训练收敛和获得最优量化精度,建议在QAT之前做calibration,其过程为通过batchsize个样本初始化量化参数,为QAT的量化训练提供一个更好的初始化参数,和浮点训练的方式一样,将checkpoint_path指定为训好的浮点权重路径。通过运行下面的脚本就可以开启模型的Calibration:

python3 tools/train.py --stage calibration --config configs/detection/centerpoint/centerpoint_pointpillar_nuscenes.py

4.2 Calibration 模型精度验证-

calibration完成以后,可以使用以下命令验证经过calib后模型的精度:

python3 tools/predict.py --config configs/detection/centerpoint/centerpoint_pointpillar_nuscenes.py --stage calibration

验证完成后,会在终端输出calib模型在验证集上的检测精度。

4.3 量化模型训练-

Calibration完成后,就可以加载calib权重开启模型的量化训练。 量化训练其实是在浮点训练基础上的finetue,具体配置信息在config的qat_trainer中定义。量化训练的时候,初始学习率设置为浮点训练的十分之一,训练的epoch次数也大大减少。和浮点训练的方式一样,将checkpoint_path指定为训好的calibration权重路径。-
通过运行下面的脚本就可以开启模型的qat训练:

python3 tools/train.py --stage qat --config configs/detection/centerpoint/centerpoint_pointpillar_nuscenes.py

4.4 量化模型精度验证-

量化模型的精度验证,只需要运行以下命令:

#qat模型精度验证
python3 tools/predict.py --stage qat--config configs/detection/centerpoint/centerpoint_pointpillar_nuscenes.py
#quantize模型精度验证
python3 tools/predict.py --stage int_infer --config configs/detection/centerpoint/centerpoint_pointpillar_nuscenes.py

qat模型的精度验证对象为插入伪量化节点后的模型(float32);quantize模型的精度验证对象为定点模型(int8),验证的精度是最终的int8模型的真正精度,这两个精度应该是十分接近的。

4.5 仿真上板精度验证-

除了上述模型验证之外,我们还提供和上板完全一致的精度验证方法,可以通过下面的方式完成:

python3 tools/align_bpu_validation.py --config configs/detection/centerpoint/centerpoint_pointpillar_nuscenes.py

4.6 量化模型编译-

在训练完成之后,可以使用compile的工具用来将量化模型编译成可以上板运行的hbm文件,同时该工具也能预估在BPU上的运行性能,可以采用以下脚本:

python3 tools/compile_perf.py --config configs/detection/centerpoint/centerpoint_pointpillar_nuscenes.py --out-dir ./ --opt 3

opt为优化等级,取值范围为0~3,数字越大优化等级越高,运行时间越长;-
compile_perf脚本将生成.html文件和.hbm文件(compile文件目录下),.html文件为BPU上的运行性能,.hbm文件为上板实测文件。

5 其他工具-


5.1 结果可视化-

如果你希望可以看到训练出来的模型对于雷达点云的检测效果,我们的tools文件夹下面同样提供了点云预测及可视化的脚本,你只需要运行以下脚本即可:

python3 tools/infer.py --config configs/detection/centerpoint/centerpoint_pointpillar_nuscenes.py --save-path ./
  1. --save-path:可视化结果保存路径;
  2. 可以通过修改config文件中infer_cfg字段的infer_inputs来配置输入数据路径。

可视化示例:

6 板端部署-


6.1 上板性能实测-

使用hrt_model_exec perf工具将生成的.hbm文件上板做BPU性能实测,hrt_model_exec perf参数如下:

hrt_model_exec perf --model_file {model}.hbm \
                    --input_file {lidar_data}.bin \
                    --thread_num 8 \
                    --frame_count 2000 \
                    --core_id 0 \
                    --profile_path '.'

6.2 AI Benchmark示例-

OE开发包中提供了Centerpoint的AI Benchmark示例,位于:ddk/samples/ai_benchmark/j5/qat/script/detection/centerpoint_pointpillar,具体使用可以参考开发者社区J5算法工具链产品手册-AIBenchmark评测示例-

可在板端使用以下命令执行做模型评测:

#性能数据
sh fps.sh
#单帧延迟数据
sh latency.sh

默认点云前处理为ARM实现,如需切换为DSP实现,可查看ddk/samples/ai_benchmark/j5/qat/script/detection/centerpoint_pointpillar/README.md-
DSP实现前处理的说明文档见:点云前处理介绍-
DSP实现前处理的源码见OE包ddk/samples/vdsp_rpc_sample/dsp/src/pointpillar_preprocess_ivp.cc

如果要进行精度评测,请参考开发者社区J5算法工具链产品手册-AIBenchmark示例精度评测进行数据的准备和模型的推理。-

相关链接:-

地平线pointpillars参考算法FAQ-

请问,3.1.2数据集组织形式是否使用于1.1.77版本的oe及docker

使用Centerpoint训练Kitti数据集时发现再postprocess部分缺少关键字gt_boxes和gt_classess。

在第6.2节中,运行sh fps.sh, 遇到错误fps.sh: line 16: ../../aarch64/bin/example: cannot execute binary file: Exec format error。-

请问如何解决?

文章里有一个错误,2.2节,**CenterPointHead节,**路径bev/models/task_modules/centerpoint/head.py :这里bev文件夹找不到,最终在`/usr/local/lib/python3.8/dist-packages/hat/models/task_modules/centerpoint/head.py`,找到了这段代码

想问一下如果centerpoint想用kitti类型的数据应该怎么修改呢?

最新OE包里出了densetnt的sample,请问后期会出类似本文一样的对densetnt的优化详解嘛~

有的,我们近期正在编写介绍文章。

【参考算法】地平线轨迹预测参考算法 DenseTNT-V1.2.1 (horizon.cc)

您好,kitti3d数据集的准备可以参考pointpillars,data_loader使用pointpillars的数据加载,model中将pre_process替换为pointpillars模型中的pre_process即可。

这个是要在开发板运行的

请问您解决了吗

不是lidar多任务模型,为什么需要下载lidarseg阿

好的,谢谢。我按照你的建议修改了相关参数,出现了RuntimeError: Given groups=1, weight of size [64, 5, 1, 1], expected input[1, 4, 20, 22681] to have 5 channels, but got 4 channels instead的报错,请问这个需要在哪里进行修改呢

kitti点云是4维,nuscenes点云是5维, reader=dict( type=“PillarFeatureNet”, num_input_features=5, … ), 模型配置要改下。

好的谢谢