目录
- 前言
- 0. 简述
- 1. 案例运行
- 2. coordTrans
- 3. Precomputation
- 总结
- 下载链接
- 参考
前言
自动驾驶之心推出的 《CUDA与TensorRT部署实战课程》,链接。记录下个人学习笔记,仅供自己参考
本次课程我们来学习下课程第八章—实战:CUDA-BEVFusion部署分析,一起来学习 CUDA-BEVFusion 的坐标转换以及 bevpool 的 precomputation 的代码实现
课程大纲可以看下面的思维导图
0. 简述
这节课给大家去讲解 CUDA-BEVFusion 代码解析第二部分,第二部分涉及到的内容主要是两个,一个是坐标系的转换,我们去理解一下这里面的每个 tensor 它包含的信息是什么,以及第二部分 BEVPPool 的 precomputation 内部是如何实现的,这里面有几个核函数会跟大家讲解一下
下面我们开始本次课程的学习🤗
1. 案例运行
在 八. 实战:CUDA-BEVFusion部署分析-环境搭建 文章中博主有详细介绍 CUDA-BEVFusion 的环境配置,这里就不再赘述了,不过九个月过去了 CUDA-BEVFusion 有了一些更新(截止到 2024/9/22),主要有以下几个点需要大家注意:
- libprotobuf-dev==3.6.1 条件去除,目前要求 protobuf >= 3.12.0 即可,在
CUDA-BEVFusion/src/onnx/onnx-ml.pb.h
头文件有提到 - layernorm plugin 支持,在 head model 替换为
head.bbox.layernormplugin.plan
后 bbox 回归分类准确率大大提升,对比图如下 - TensorRT-10.x 支持
- spconv-1.1.10 版本发布
- CUDA-11.x 编译选项需设置为 -std=c++14,CUDA-12.x 编译选项需设置为 -std=c++17
Note:这里韩君老师分析的代码是 2023 年 12 中旬的代码,调试工具使用的是 vscode
head.bbox.plan
的推理结果如下:
head.bbox.layernormplugin.plan
的推理结果如下:
2. coordTrans
前面我们分析了 CUDA-BEVFusion 的初始化部分,也就是 create_core
函数,这里我们在 main 函数中接着往下看:
这里主要加载了四个 tensor,是 camera 到 lidar 以及 lidar 到 camera 所需要的坐标转换矩阵,shape 是 6x4x4,其中的 6 代表 nuScenes 中的六个相机,每个相机都有自己的转换矩阵,其中 4x4 矩阵主要包括 rotation 旋转矩阵以及 translation 平移矩阵两个部分
这里有个点需要注意,那就是 camera2lidar
这里的转换是直接通过加载一个 tensor 完成的,那大家如果学习过 nuScenes 数据集里面各个传感器的数据的话,就会知道 camera 坐标系到 lidar 坐标系的转换并不是那么简单,它里面其实需要做很多东西,之前杜老师有讲过,大家感兴趣的可以看看:AutoCV第十课:3D基础
我们可以这么理解,首先 camera 和 lidar 是两个传感器,它们相对于自车 ego 各自有一个坐标系,并且这两个传感器接收数据的频率也是不同的,那如果我们想要将这两个传感器之间的坐标做转换的话其实需要经过几个步骤:camera cord -> ego cord -> global cord -> ego cord -> lidar cord
我们首先需要把 camera 的坐标系给投影到 ego 自车的坐标系,之后我们需要把 ego 坐标系给投影到 global 坐标系,那么 global 坐标系其实是一个全局坐标系,它就是以 ego 自车在 T0 时刻为原点的一个坐标系,那接着我们要把 global 坐标系给映射到另一个 ego 坐标系,那这两个 ego 坐标系有什么不同呢,一个是 T0 时刻,一个是 T1 时刻,这么做的原因主要是因为 camera 和 lidar 传感器接收信息频率的差异,最后我们可以通过 T1 时刻的 ego 坐标系给映射到 lidar 坐标系,这样我们就可以得到从 camera 到 lidar 的投影
这里面每个坐标系之间的转换其实都是可以通过一个 4x4 的矩阵来实现的,所以 camera2lidar
这里的 4x4 矩阵其实是由多个坐标转换的 4x4 矩阵拼接得到的,有了 camera2lidar 的转换矩阵之后我们给它做一个逆变换可以得到 lidar2camera 的转换矩阵
camera_intrinsics
就是将相机的内参矩阵,将 3D 相机坐标系映射到 2D 像素坐标系,img_aug_matrix
代表的是图像的畸变矩阵,可以用于图像去畸变和图像校正
接下来我们来看这些 tensor 是如何加载的:
我们这里是通过 Tensor 结构体的 load 函数来完成加载的,我们主要是看 dims 和 shape 的变换,值得注意的是 .tensor 文件中的前几个字节会保存这个 tensor 的 dim 信息,接着 load 函数会根据数据的 dim 信息创建 shape,之后再按照 .tensor 存储的数据类型和 shape 保存成 Tensor 格式
我们可以看到 ndim 等于 4,意味着 dims 中的前四个数据是有效的,也就是说坐标转换类的 dim 是 1x6x4x4,也就是我们说的 shape 是 1x6x4x4,表示的是一共有 6 个 camera,每一个 camera 都有一个 4x4 的坐标转换矩阵
那 main 函数中还有一个 lidar points tensor 的 load:
我们来看看这个 tensor 的 shape 是多少:
我们可以看到 lidar points 这个 tensor 的 shape 是 242180x5,它代表当前帧中 lidar 传感器在场景中总共有 242180 个点,每一个点有 5 个 feature
这里我们再简单来分析下 nv::Tensor::load
函数:
Tensor Tensor::load(const std::string& file, bool device) {
FILE* f = fopen(file.c_str(), "rb");
if (f == nullptr) return Tensor();
int head[3];
if (fread(head, 1, sizeof(head), f) == 0) {
printf("This is invalid tensor file %s\n", file.c_str());
fclose(f);
return Tensor();
}
if (head[0] != 0x33ff1101) {
printf("This is invalid tensor file %s\n", file.c_str());
fclose(f);
return Tensor();
}
int ndim = head[1];
int dtypei = head[2];
int dims[16];
if (fread(dims, 1, ndim * sizeof(int), f) == 0) {
printf("This is invalid tensor file %s\n", file.c_str());
fclose(f);
return Tensor();
}
vector<int64_t> shape(ndim);
std::transform(dims, dims + ndim, shape.begin(), [](int x) { return x; });
int volumn = std::accumulate(dims, dims + ndim, 1, std::multiplies<int>());
DataType dtype = (DataType)dtypei;
size_t bytes = dtype_bytes(dtype) * volumn;
vector<unsigned char> host_data(bytes);
if (fread(host_data.data(), 1, bytes, f) == 0) {
printf("This is invalid tensor file %s\n", file.c_str());
fclose(f);
return Tensor();
}
fclose(f);
Tensor output = Tensor::create(shape, dtype, device);
if (device) {
checkRuntime(cudaMemcpy(output.ptr(), host_data.data(), bytes, cudaMemcpyHostToDevice));
} else {
checkRuntime(cudaMemcpy(output.ptr(), host_data.data(), bytes, cudaMemcpyHostToHost));
}
checkRuntime(cudaDeviceSynchronize());
return output;
}
Tensor::load
函数用于从文件中加载 Tensor,并根据 device
参数决定将数据加载到 device 还是 host 内存中,它从指定的文件中读取 tensor 的形状、数据类型和实际数据,以下是该函数的详细分析:(from ChatGPT)
1. 打开文件
FILE* f = fopen(file.c_str(), "rb");
if (f == nullptr) return Tensor();
函数首先尝试以二进制模式打开文件,如果文件打开失败(即 f == nullptr
),函数会立即返回一个默认的 Tensor
对象
2. 读取文件头
int head[3];
if (fread(head, 1, sizeof(head), f) == 0) {
printf("This is invalid tensor file %s\n", file.c_str());
fclose(f);
return Tensor();
}
文件头部包括三个整数:魔数(用于标识文件格式)、tensor 的维度数(ndim
)以及数据类型(dtype
)。fread
函数用于从文件中读取这三个整数。如果读取失败,函数返回一个无效的 Tensor
对象
3. 魔数校验
if (head[0] != 0x33ff1101) {
printf("This is invalid tensor file %s\n", file.c_str());
fclose(f);
return Tensor();
}
魔数 0x33ff1101
是一个用于验证文件是否为有效 tensor 文件的标识。如果魔数不匹配,文件就不是一个有效的 tensor 文件,函数返回无效 Tensor
4. 读取维度信息
int ndim = head[1];
int dtypei = head[2];
int dims[16];
if (fread(dims, 1, ndim * sizeof(int), f) == 0) {
printf("This is invalid tensor file %s\n", file.c_str());
fclose(f);
return Tensor();
}
在这里,ndim
表示 tensor 的维度数,dims
是一个包含维度信息的数组,最多支持 16 个维度。函数会根据 ndim
来读取相应数量的维度数据。如果读取失败,函数返回无效的 Tensor
5. 计算 tensor 的元素总数
vector<int64_t> shape(ndim);
std::transform(dims, dims + ndim, shape.begin(), [](int x) { return x; });
int volumn = std::accumulate(dims, dims + ndim, 1, std::multiplies<int>());
这段代码将维度信息转化为一个 shape
向量,并使用 std::accumulate
计算 tensor 的元素总数,即 volumn
6. 读取数据类型与字节大小
DataType dtype = (DataType)dtypei;
size_t bytes = dtype_bytes(dtype) * volumn;
vector<unsigned char> host_data(bytes);
dtype
是数据类型,通过 dtype_bytes(dtype)
来计算每个元素的字节数,并根据元素总数计算出整个 tensor 的字节大小(bytes
)
7. 读取 tensor 数据
if (fread(host_data.data(), 1, bytes, f) == 0) {
printf("This is invalid tensor file %s\n", file.c_str());
fclose(f);
return Tensor();
}
这里从文件中读取实际的 tensor 数据,并存储在 host_data
中,如果读取失败,函数返回无效 Tensor
8. 创建 tensor
Tensor output = Tensor::create(shape, dtype, device);
根据 tensor 的形状(shape
)、数据类型(dtype
)和目标设备(device
)来创建一个新的 Tensor
对象
9. 数据拷贝
if (device) {
checkRuntime(cudaMemcpy(output.ptr(), host_data.data(), bytes, cudaMemcpyHostToDevice));
} else {
checkRuntime(cudaMemcpy(output.ptr(), host_data.data(), bytes, cudaMemcpyHostToHost));
}
checkRuntime(cudaDeviceSynchronize());
如果目标是 device,则使用 cudaMemcpyHostToDevice
将数据从 host 复制到 device;否则使用 cudaMemcpyHostToHost
在 host 之间复制数据。最后调用 cudaDeviceSynchronize
确保设备操作同步完成
10. 返回 Tensor
return output;
最后返回加载并初始化完成的 Tensor
对象
那以上就是 CUDA-BEVFusion 加载的几个 tensor 的含义,下面我们来看 core->update
函数
3. Precomputation
我们前面讲过 core
是指向接口类 Core 的一个智能指针,它的接口中有一个 update 的方法:
它把前面读取的 tensor 都传入进行然后进行 update 更新,我们来看看它具体都做了哪些事情
update 有两个,一个是 camera_depth 的 update,另一个是 camera_geometry 的 update,前面 camera_depth 的 update 比较简单,我们一起来看下:
camera_depth 的 update 没有特别需要强调的地方,就是把我们读取到的 tensor 的数据给 memcpy 到 device 上面去,camera_depth 做的事情是 lidar 到 image 的坐标转换
我们重点来看下 geometry 的 update,这个比较重要:
camera geometry 的 update 主要是负责 BEVPool 的 precomputation,从而防止在 BEVPool 中做大量的计算。换句话说,如果 camera 位置固定不变,那么 BEVPool 中各个 grid 的点所对应的 camera 的坐标也是固定的,因此这里做个预计算提前知道这个关系
首先我们通过一个 for 循环将各个 camera 中的内参矩阵参数和畸变矩阵参数取出,接着 memcpy 将这些矩阵 tensor 从 host 拷贝到 device 上,然后我们会调用第一个 kernel 即 compute_geometry_kernel
我们在调用核函数时套了一个 cuda_linear_launch,它其实就是一个宏:
#define cuda_linear_launch(kernel, stream, num, ...) \
do { \
size_t __num__ = (size_t)(num); \
size_t __blocks__ = divup(__num__, LINEAR_LAUNCH_THREADS); \
kernel<<<__blocks__, LINEAR_LAUNCH_THREADS, 0, stream>>>(__num__, __VA_ARGS__); \
nv::check_runtime(cudaPeekAtLastError(), #kernel, __LINE__, __FILE__); \
} while (false)
这个宏其实就是调用一个 kernel,我们给它指定了 block size 之后把 stream 还有后面的参数放到 kernel 里面去就行了
compute_geometry_kernel
这个 kernel 其实负责的是计算 frustum 中的每一个点所对应的 BEV Grid 中的坐标,并存储到 geometry_
中,同时为每一个点都设置一个 rank,相同的 rank 的点会在同一个 interval 中
值得注意的是 frustum 中的每个点都有可能对应到 bev grid 中去,为什么说有可能呢,这是因为 bev grid 大小是固定的,就是 360x360,那 camera 中某些点通过坐标系转换后有可能不能投影到 360x360 大小的 grid 中去,也就是说越界了,那对于越界的点我们直接 skip 掉就行
另外关于 rank 的理解博主这边绘制了一个草图说明:
假设我们有 6 个点,每个点都投影到了不同的 bev grid 上,从上图中我们可以看到不同的 grid 中包含的 camera 投影的点的数量不同,grid0 包含 point0、point3 以及 point5 三个点,grid1 包含 point1 和 point4 两个点,grid2 仅包含 point2 一个点
我们在 八. 实战:CUDA-BEVFusion部署分析-学习BEVPool的优化方案 中有提到后续还要对每个 grid 还有做一个 inerval 规约计算,也就是说将 grid 中的所有点相加平均。当然我们从图中很清晰的可以看到 point0、point3、point5 在一个 grid 中,那在内存中我们该如何区分呢?这里就是通过设置 rank 来完成的,我们为每一个投影点设置一个 rank,相同 rank 的点通过排序和分区,被归类到同一个 interval 中,例如上面的 point0、point3、point5 属于同一个 rank,因此在一个 interval 中
总的来说在视锥的每个点投影到 bev grid 时我们都会为其设置一个 rank 用来标识它在哪一个 grid 中或者更准确的说用来标识哪些点处于同一个 interval 中,可以用来做规约计算
那这个就是博主关于 rank 的理解
compute_geometry_kernel
的实现如下:
static __global__ void compute_geometry_kernel(unsigned int numel_frustum, const float3* frustum, const float4* camera2lidar,
const float4* camera_intrins_inv, const float4* img_aug_matrix_inv,
nvtype::Float3 bx, nvtype::Float3 dx, nvtype::Int3 nx, unsigned int* keep_count,
int* ranks, nvtype::Int3 geometry_dim, unsigned int num_camera,
int* geometry_out) {
int tid = cuda_linear_index;
if (tid >= numel_frustum) return;
// 每一个线程负责frustum中的一个点。frustum中每一个元素有三个float(x, y, depth)
float3 point = frustum[tid];
// 在每一个相机中寻找这个点在BEV坐标系下的点
for (int icamerea = 0; icamerea < num_camera; ++icamerea) {
// 畸变的map
float3 projed = inverse_project(img_aug_matrix_inv, point);
projed.x *= projed.z;
projed.y *= projed.z;
// img->camera的map
projed = make_float3(
dot(camera_intrins_inv[4 * icamerea + 0], projed),
dot(camera_intrins_inv[4 * icamerea + 1], projed),
dot(camera_intrins_inv[4 * icamerea + 2], projed));
// camera->lidar的map
projed = make_float3(
project(camera2lidar[4 * icamerea + 0], projed),
project(camera2lidar[4 * icamerea + 1], projed),
project(camera2lidar[4 * icamerea + 2], projed));
int _pid = icamerea * numel_frustum + tid;
int3 coords;
// 这样我们就可以找到frustum的这个点,应该投影在BEVGrid上的点(x, y, z)了
coords.x = int((projed.x - (bx.x - dx.x / 2.0)) / dx.x);
coords.y = int((projed.y - (bx.y - dx.y / 2.0)) / dx.y);
coords.z = int((projed.z - (bx.z - dx.z / 2.0)) / dx.z);
// 这样我们可以把这个点在geometry中的offset与BEVGrid的坐标对应上了, 当我们再寻找img->BEVGrid的时候,直接可以通过这个geometry_out来找
geometry_out[_pid] = (coords.z * geometry_dim.z * geometry_dim.y + coords.x) * geometry_dim.x + coords.y;
bool kept = coords.x >= 0 && coords.y >= 0 && coords.z >= 0 && coords.x < nx.x && coords.y < nx.y && coords.z < nx.z;
if (!kept) {
ranks[_pid] = 0;
} else {
// 这个keep_count就是用来保留最终有多少个img上的点可以投影到BEVGrid上去的
atomicAdd(keep_count, 1);
ranks[_pid] = (coords.x * nx.y + coords.y) * nx.z + coords.z; //有些点的rank可能会一样,rank一样的点会在同一个interval中
}
}
}
该核函数通过一系列的坐标转换,将视锥中的点映射到 bev grid 中,并筛选出有效的点,为每个点分配 rank
,下面是该核函数的详细分析:(from ChatGPT)
static __global__ void compute_geometry_kernel(
unsigned int numel_frustum,
const float3* frustum,
const float4* camera2lidar,
const float4* camera_intrins_inv,
const float4* img_aug_matrix_inv,
nvtype::Float3 bx,
nvtype::Float3 dx,
nvtype::Int3 nx,
unsigned int* keep_count,
int* ranks,
nvtype::Int3 geometry_dim,
unsigned int num_camera,
int* geometry_out
) { ... }
该核函数参数如下:
numel_frustum
:视锥(frustum)中点的总数量,即处理的像素总数frustum
:包含视锥中每个点的坐标数组,每个元素是一个float3
类型,包含(x, y, depth)
camera2lidar
:camera 坐标系到 lidar 坐标系的转换矩阵数组,每个相机对应一个 4x4 矩阵camera_intrins_inv
:相机内参矩阵的逆矩阵数组,每个相机对应一个 4x4 矩阵img_aug_matrix_inv
:图像畸变矩阵的逆矩阵数组,每个相机对应一个 4x4 矩阵bx
:bev grid 的起始坐标,即最小坐标值,nvtype::Float3
类型dx
:bev grid 中每个体素(voxel)的尺寸,nvtype::Float3
类型nx
:bev grid 的尺寸,即在 x、y、z 方向上的 grid 数量,nvtype::Int3
类型keep_count
:用于统计有效点的计数器,位于 device 上,需要使用原子操作更新ranks
:用于存储每个点的 rank 值geometry_dim
:BEV 网格维度信息,nvtype::Int3
类型,大小为 360x360x80,用于计算geometry_out
中的索引num_camera
:相机的数量geometry_out
:用于输出每个点在 bev grid 中的索引
核心参数的具体数值如下图所示:
具体实现如下:
1. 线程索引获取
int tid = cuda_linear_index;
if (tid >= numel_frustum) return;
获取当前线程的全局索引 tid
,并判断是否超出处理范围。每个线程负责处理 frustum
中的一个点,cuda_linear_index
是一个宏,用于计算线程的全局线性索引,其定义如下:
#define cuda_linear_index (blockDim.x * blockIdx.x + threadIdx.x)
2. 获取当前处理的点
float3 point = frustum[tid];
从 frustum
数组中获取当前线程需要处理的点的坐标 (x, y, depth)
3. 遍历所有相机
for (int icamera = 0; icamera < num_camera; ++icamera) {
// 相机相关的处理
}
对每个相机进行处理,因为同一个点可能被多个相机观测到,需要在每个相机坐标系下计算
4. 图像畸变逆变换
float3 projed = inverse_project(img_aug_matrix_inv, point);
projed.x *= projed.z;
projed.y *= projed.z;
将 point
通过图像畸变矩阵的逆矩阵进行逆变换,得到去畸变的坐标,并将其从齐次坐标转换回非其次坐标
5. 从图像坐标系到相机坐标系
projed = make_float3(
dot(camera_intrins_inv[4 * icamera + 0], projed),
dot(camera_intrins_inv[4 * icamera + 1], projed),
dot(camera_intrins_inv[4 * icamera + 2], projed)
);
使用相机内参逆矩阵,将图像坐标转换到相机坐标系
6. 从相机坐标系到激光雷达坐标系
projed = make_float3(
project(camera2lidar[4 * icamera + 0], projed),
project(camera2lidar[4 * icamera + 1], projed),
project(camera2lidar[4 * icamera + 2], projed)
);
使用 camera 到 lidar 的转换矩阵,将点从相机坐标系转换到 lidar 坐标系
7. 计算全局索引 _pid
int _pid = icamera * numel_frustum + tid;
计算当前点在全局数组中的索引,用于在 geometry_out
和 ranks
中存储结果,每个相机都有 numel_frustum
个点,因此需要考虑相机索引 icamera
8. 计算 bev grid 坐标 coords
coords.x = int((projed.x - (bx.x - dx.x / 2.0)) / dx.x);
coords.y = int((projed.y - (bx.y - dx.y / 2.0)) / dx.y);
coords.z = int((projed.z - (bx.z - dx.z / 2.0)) / dx.z);
将点的物理坐标转换为 BEV 网格中的索引坐标,其中 bx
代表 BEV 网格的起始坐标,dx
代表 BEV 网格中每个体素的尺寸。先计算相对于起始坐标的偏移量,然后除以体素尺寸,得到对应的网格索引
这里…
9. 计算 geometry_out 中的索引
geometry_out[_pid] = (coords.z * geometry_dim.z * geometry_dim.y + coords.x) * geometry_dim.x + coords.y;
将三维的网格坐标转换为一维的数组索引,存储在 geometry_out
中,其中的 geometry
是 BEV 网格的尺寸,用于计算线程索引
10. 判断点是否在有效范围内
bool kept = coords.x >= 0 && coords.y >= 0 && coords.z >= 0 &&
coords.x < nx.x && coords.y < nx.y && coords.z < nx.z;
检查计算得到的网格坐标是否在 BEV 网格的有效范围内
11. 更新 ranks 和 keep_count
if (!kept) {
ranks[_pid] = 0;
} else {
atomicAdd(keep_count, 1);
ranks[_pid] = (coords.x * nx.y + coords.y) * nx.z + coords.z;
}
如果点不在有效范围内则将对应的 rank
设为 0,表示无效点,如果点在有效范围内,首先使用原子操作 atomic_Add
增加 keep_count
,统计有效点的数量,接着计算 rank
值,rank
的计算使得相同网格位置的点具有相同的 rank
以上就是 compute_geometry_kernel
核函数的总体分析了,不过这里博主自己还是有一些困惑的
问题一:
为什么在计算 BEV 网格坐标 coords
时,使用了如下公式:
coords.x = int((projed.x - (bx.x - dx.x / 2.0)) / dx.x);
coords.y = int((projed.y - (bx.y - dx.y / 2.0)) / dx.y);
coords.z = int((projed.z - (bx.z - dx.z / 2.0)) / dx.z);
而不是直接使用:
coords.x = int((projed.x - bx.x) / dx.x);
coords.y = int((projed.y - bx.y) / dx.y);
coords.z = int((projed.z - bx.z) / dx.z);
解答:
那 BEV 网格的起始位置需要明确,一般有两种常见的定义方式:
- 网格索引对应于体素的中心:在这种情况下,体素的中心坐标为
bx.x + (i + 0.5) * dx.x
,其中i
是网格索引 - 网格索引对应于体素的边界:这里,体素的左边界左边为
bx.x + i * dx
代码中的公式:
coords.x = int((projed.x - (bx.x - dx.x / 2.0)) / dx.x);
可以理解为将物理坐标 project.x
映射到以体素为基准的网格索引上。这里的调整 (bx.x - dx.x / 2.0)
是为了将物理坐标系中的起始点平移,使得第一个体素的中心与 bx.x
对齐
在实际计算中,浮点数取整会导致边界条件的变化,通过减去 dx.x / 2.0
可以确保边界点被正确地映射到期望的网格索引上,避免由于浮点数精度问题导致的偏差
因此总的来说调整的目的是确保物理空间中的点与 BEV 网格索引准确对应,避免由于取整或边界条件导致的错误。通过减去半个体素的尺寸,将网格的参考点从体素的左下角移动到体素的中心,使得映射更加准确
问题二:
geometry_out
中的索引计算公式:
geometry_out[_pid] = (coords.z * geometry_dim.z * geometry_dim.y + coords.x) * geometry_dim.x + coords.y;
这个公式是如何得出的?它代表什么含义?是否表示点投影到 3D 网格中的某个体素索引吗?如果是,是一个全局索引吗?
解答:
这个索引公式用于将三维 BEV 网格坐标映射到一维的线性索引中,也就是计算点在一维数组 geometry_out
中的全局索引,表示点在三维网格中的对应 voxel,这个索引的计算方式是从左下角开始,逐层(z
轴方向)展开,那具体的公式计算博主也没有理解
问题三:
rank
的计算公式:
ranks[_pid] = (coords.x * nx.y + coords.y) * nx.z + coords.z;
这个公式表示什么含义,为什么与 geometry_out
的计算不同呢?
解答:
rank
的计算是为了将位于同一 BEV 网格位置的点聚集在一起,它的作用是为每个点分配一个唯一的标识,便于按照空间位置排序,它得到的其实是 BEV 网格中某个 gird 的全局索引
我们可以稍微拆解下公式,首先是 coords.x * nx.y * nx.z
它得到的是 x 方向上的偏移,然后加上 coords.y * nx.z
即 y 方向上的偏移,最后加上 coords.z
即 z 方向上的偏移,最终得到的就是当前点在 BEV 网格中的全局位置索引,前面我们知道 nx.z
等于 1,它其实就是一个三维 BEV grid 按照高度维度拍扁后的二维网格
我们接着往下看:
下一个 kernel 即 arange_kernel
主要是用来更新 indices 的信息,可以暂时理解为 geometry 中每一个点的 index,内容为 [0, 1, 2, ..., numel_geometry_ - 1]
arange_kernel
的实现如下:
static __global__ void arange_kernel(unsigned int num, int32_t* p) {
int idx = cuda_linear_index;
if (idx < num) {
p[idx] = idx;
}
}
那它的实现也非常的简单,就是一个赋值,生成一个范围序列(arange),为后续排序和索引操作做准备
接着我们会使用 CUDA 中的 thrust 库中的 sort 来对 ranks_
里面的所有数据进行排序,同时 ranks 每一个点所对应的 indices_ 也会根据这个排序重新 arange
我们接着往下看:
这里调用的 kernel 是 interval_starts_kernel
,这个 kernel 负责寻找每一块 interval 的开始位置以及 interval 的总数
我们先回顾一下,我们在保存 interval 的时候它其实是一维的,每一个 interval 中有多个点,那么我们为了方便计算我们需要找到每一个 interval 它一开始的点即起始点的坐标是什么,以及它结尾点的坐标是什么,只有知道了这个我们才方便在后面的 BEVPool 中做索引
interval_starts_kernel
的实现如下:
static __global__ void interval_starts_kernel(unsigned int num, unsigned int remain, unsigned int total, const int32_t* ranks,
const int32_t* indices, int32_t* interval_starts, int32_t* interval_starts_size) {
int idx = cuda_linear_index;
if (idx >= num) return;
unsigned int i = remain + 1 + idx;
// 我们从这里可以看到,相同的rank的点的interval是一样的
if (ranks[i] != ranks[i - 1]) {
unsigned int offset = atomicAdd(interval_starts_size, 1);
interval_starts[offset] = idx + 1;
}
}
该核函数用于识别 ranks
数组中不同 rank
值的起始位置,并记录这些位置的索引,从而划分成不同的 interval,找到每一个 intervals 开始的索引之后,在 update
方法中又做了一个排序
我们继续往下看:
最后一个 kernel 即 collect_starts_kernel
,这个 kernel 负责寻找开始的 interval,并给存储到 intervals_ 里面,供 BEVPool 的时候使用
collect_starts_kernel
的具体实现如下:
/*
intervals[i]是由三个int(x, y, z)组成:
- x表示的是这个interval开始的点
- y表示的是这个interval结束的点
- z表示的是这个interval在BEVGrid上所对应的grid的id
在BEVPool的时候,对于每一个interval的计算,直接通过这个索引就好了
*/
static __global__ void collect_starts_kernel(unsigned int num, unsigned int remain, unsigned int numel_geometry,
const int32_t* indices, const int32_t* interval_starts, const int32_t* geometry,
int3* intervals) {
int i = cuda_linear_index;
if (i >= num) return;
int3 val;
val.x = interval_starts[i] + remain;
val.y = i < num - 1 ? interval_starts[i + 1] + remain : numel_geometry - interval_starts[i];
val.z = geometry[indices[interval_starts[i] + remain]];
intervals[i] = val;
}
该函数同于生成 intervals
数组,其中每个元素包含三个整数 (x, y, z)
,分别表示:
x
:当前 interval 的起始索引y
:当前 interval 的结束索引z
:当前 interval 对应的 BEV 网格的全局 ID
在 update
方法中,经过 interval_starts 的计算和排序后,需要将这些 intervals 的信息整理出来,以供 BEVPool 使用,collect_starts_kernel
通过生成 intervals
数组,将 interval 的起始和结束位置以及对应的 BEV 网格 ID 记录下来,方便后续的计算
geometry->update
方法的主要步骤可以概括为:
- 1. 矩阵求逆和数据拷贝:在 host 计算相机内参矩阵和图像畸变矩阵的你逆矩阵,然后将相关矩阵数据异步复制到 device 上
- 2. geometry 计算:调用
compute_geometry_kernel
核函数,计算视锥(frustum)中的每个点对应的 bev grid 坐标,存储在geometry_
中,同时为每个点设置一个rank
- 3. 更新索引信息:调用
arange_kernel
核函数,初始化indices_
数组,表示geometry_
中每个点的索引 - 4. 排 ranks_ 和 重排 indices_:使用 CUDA 的 Thrust 库,根据
ranks_
对数据进行稳定排序,同时调整indices_
,使其与排序后的ranks_
对应 - 5. 计算 interval 信息:调用
interval_starts_kernel
核函数,找到每个interval
的起始位置和总数,更新interval_starts_
和interval_starts_size_
- 6. 收集 interval:调用
collect_starts_kernel
核函数,收集所有 intervals 的起始位置,存储在intervals_
中,供 BEVPool 使用
以上就是 BEVPool 的 precomputation 的所有内容了,那这个部分没有放在 bevpool 中去写,而是放到了 camera_geometry 中去写,这个大家需要注意下
总结
本次课程我们学习了 CUDA-BEVFusion 中的坐标转换以及 BEVPool 预计算的代码实现,其中坐标转换主要是通过 load 函数加载变换矩阵的 tensor,预计算主要是在
geometry->update
函数中完成的,调用多个核函数来计算视锥中每个点对应的 grid 坐标并设置 rank 以及 interval_starts 的计算收集等等,那这里 rank 和 geometry_out 的计算博主没有理解,另外 rank 绘制的草图似乎有点问题,和后面的计算代码也对不上,这里可能还是需要大家自己结合代码来调试分析OK,以后就是第 10 小节有关 CUDA-BEVFusion 中坐标转换和预计算代码分析的全部内容了,下节我们讲 forward 部分,来看 BEVFusion 中每个模块的 forward 都做了哪些事情,敬请期待😄
下载链接
- 论文下载链接【提取码:6463】
- 数据集下载链接【提取码:data】
- 代码和安装包下载链接【提取码:cuda】
参考
- 八. 实战:CUDA-BEVFusion部署分析-环境搭建
- AutoCV第十课:3D基础
- 八. 实战:CUDA-BEVFusion部署分析-学习BEVPool的优化方案