**"**环境感知常用的传感器有激光雷达、单目相机、TOF、主动双目等感知传感器。本文主要阐述主动双目相机的深度图如何转换为3D点云数据,包括生成3D点云、彩色点云以及点云投影到图像"
01 深度图
目前接触的主动双目相机由左右侧2个IR相机、中间一个RGB相机以及一个结构光投射器组成。其中RGB相机提供纹理信息,为AI检测、识别所使用。左右IR相机基于投射器投射的结构光计算视差,基于三角测量原理,能够获得深度信息、深度图(像素保存的是深度值)。有了深度图,如何提取三维点云?
02 配置文件
配置文件如下:
python
depth_camera_intrinsic_params:
dfx: 301.27933
dfy: 301.27933
dcx: 319.20093
dcy: 235.68080
color_camera_intrinsic_params:
fx: 396.65051
fy: 396.72641
cx: 329.94049
cy: 233.1148
Coeffs: [-0.36969, 0.16313, -0.00015, -0.00001, -0.037709]
depthPC2RGB_params:
R_lidar2camera:
- 0.99999
- -0.00518
- 0.00063
- 0.00518
- 0.99999
- 0.00132
- -0.00064
- -0.00132
- 1.00000
T_lidar2camera:
- -0
- -1
- -0
- -0.03582
- 1
- 0
- 0
- -0.00005
- 0
- 0
- 1
- 0.00044
- 0
- 0
- 0
- 1
# path
depthImgPath: ~/rDepth/
rgbImgPath: ~/rColor/
ply_save_path: ~/ply/
colorPoints_save_path: ~/color-pc/
projectedRgb_save_path: ~/projected-img/
isDepthImg2PC: false
isDepthImg2ColorPC: true
isPcProject2Img: false
03 读取配置参数
配置参数包含rgb相机内参、畸变系数,深度相机内参、深度相机到rgb相机的转换矩阵(点云投影到图像使用)、以及深度图、彩色图、点云、彩色点云、点云到图像的投影结果路径,代码:
python
/ 读取相机参数配置文件(YAML格式)
bool Depth2PointCloud::readCameraParam(const std::string& t_cameraConfigFilePath, Depth2PointCloud& t_depth2pointCloud){
// 加载YAML配置文件
YAML::Node params_node = YAML::LoadFile(t_cameraConfigFilePath);
// 1. 读取RGB相机内参 & 畸变系数
// fx
if(params_node["color_camera_intrinsic_params"]["fx"].IsDefined()){
t_depth2pointCloud.cameraParams.fx = params_node["color_camera_intrinsic_params"]["fx"].as<double>();
}else{
std::cout << "fx is not exist" << std::endl;
return false;
}
// fy
if(params_node["color_camera_intrinsic_params"]["fy"].IsDefined()){
t_depth2pointCloud.cameraParams.fy = params_node["color_camera_intrinsic_params"]["fy"].as<double>();
}else{
std::cout << "fy is not exist" << std::endl;
return false;
}
// cx
if(params_node["color_camera_intrinsic_params"]["cx"].IsDefined()){
t_depth2pointCloud.cameraParams.cx = params_node["color_camera_intrinsic_params"]["cx"].as<double>();
}else{
std::cout << "cx is not exist" << std::endl;
return false;
}
// cy
if(params_node["color_camera_intrinsic_params"]["cy"].IsDefined()){
t_depth2pointCloud.cameraParams.cy = params_node["color_camera_intrinsic_params"]["cy"].as<double>();
}else{
std::cout << "cy is not exist" << std::endl;
return false;
}
// RGB畸变系数 (k1, k2, p1, p2, k3)
std::vector<double> rgbCoeffs(5, 0.0); // 修正变量名,移除非法空格
if(params_node["color_camera_intrinsic_params"]["Coeffs"].IsDefined()){
rgbCoeffs = params_node["color_camera_intrinsic_params"]["Coeffs"].as<std::vector<double>>();
// 赋值给结构体成员
t_depth2pointCloud.cameraParams.k1 = rgbCoeffs[0];
t_depth2pointCloud.cameraParams.k2 = rgbCoeffs[1];
t_depth2pointCloud.cameraParams.p1 = rgbCoeffs[2];
t_depth2pointCloud.cameraParams.p2 = rgbCoeffs[3];
t_depth2pointCloud.cameraParams.k3 = rgbCoeffs[4];
}else{
std::cout << "rgb Coeffs is not exist" << std::endl;
return false;
}
// 2. 读取深度相机内参
// dfx
if(params_node["depth_camera_intrinsic_params"]["dfx"].IsDefined()){
t_depth2pointCloud.cameraParams.dfx = params_node["depth_camera_intrinsic_params"]["dfx"].as<double>();
}else{
std::cout << "dfx is not exist" << std::endl;
return false;
}
// dfy
if(params_node["depth_camera_intrinsic_params"]["dfy"].IsDefined()){
t_depth2pointCloud.cameraParams.dfy = params_node["depth_camera_intrinsic_params"]["dfy"].as<double>();
}else{
std::cout << "dfy is not exist" << std::endl;
return false;
}
// dcx
if(params_node["depth_camera_intrinsic_params"]["dcx"].IsDefined()){
t_depth2pointCloud.cameraParams.dcx = params_node["depth_camera_intrinsic_params"]["dcx"].as<double>();
}else{
std::cout << "dcx is not exist" << std::endl;
return false;
}
// dcy
if(params_node["depth_camera_intrinsic_params"]["dcy"].IsDefined()){
t_depth2pointCloud.cameraParams.dcy = params_node["depth_camera_intrinsic_params"]["dcy"].as<double>();
}else{
std::cout << "dcy is not exist" << std::endl;
return false;
}
// 3. 读取路径配置
// depthImgPath
if(params_node["depthImgPath"].IsDefined()){
t_depth2pointCloud.depthImgPath = params_node["depthImgPath"].as<std::string>();
}else{
std::cout << "depthImgPath is not exist" << std::endl;
return false;
}
// rgbImgPath
if(params_node["rgbImgPath"].IsDefined()){
t_depth2pointCloud.rgbImgPath = params_node["rgbImgPath"].as<std::string>();
}else{
std::cout << "rgbImgPath is not exist" << std::endl;
return false;
}
// ply save path
if(params_node["ply_save_path"].IsDefined()){
t_depth2pointCloud.ply_save_path = params_node["ply_save_path"].as<std::string>();
// if directory not exist, create it
if(!boost::filesystem::exists(t_depth2pointCloud.ply_save_path)){
boost::filesystem::create_directories(t_depth2pointCloud.ply_save_path);
std::cout << "ply_save_path is created" << std::endl;
}else{
std::cout << "ply_save_path already exist !" << std::endl;
}
}else{
std::cout << "ply_save_path is not exist" << std::endl;
return false;
}
// colorPoints save path
if(params_node["colorPoints_save_path"].IsDefined()){
t_depth2pointCloud.colorPoints_save_path = params_node["colorPoints_save_path"].as<std::string>();
// if directory not exist, create it
if(!boost::filesystem::exists(t_depth2pointCloud.colorPoints_save_path)){
boost::filesystem::create_directories(t_depth2pointCloud.colorPoints_save_path);
std::cout << "colorPoints_save_path is created" << std::endl;
}else{
std::cout << "colorPoints_save_path already exist !" << std::endl;
}
}else{
std::cout << "colorPoints_save_path is not exist" << std::endl;
return false;
}
// projectedRgb_save_path
if(params_node["projectedRgb_save_path"].IsDefined()){
t_depth2pointCloud.projectedRgb_save_path = params_node["projectedRgb_save_path"].as<std::string>();
// if directory not exist, create it
if(!boost::filesystem::exists(t_depth2pointCloud.projectedRgb_save_path)){
boost::filesystem::create_directories(t_depth2pointCloud.projectedRgb_save_path);
std::cout << "projectedRgb_save_path is created" << std::endl;
}else{
std::cout << "projectedRgb_save_path already exist !" << std::endl;
}
}else{
std::cout << "projectedRgb_save_path is not exist" << std::endl;
return false;
}
// isDepthImg2PC
if(params_node["isDepthImg2PC"].IsDefined()){
t_depth2pointCloud.isDepthImg2PC = params_node["isDepthImg2PC"].as<bool>();
}else{
std::cout << "isDepthImg2PC is not exist" << std::endl;
return false;
}
// isDepthImg2ColorPC
if(params_node["isDepthImg2ColorPC"].IsDefined()){
t_depth2pointCloud.isDepthImg2ColorPC = params_node["isDepthImg2ColorPC"].as<bool>();
}else{
std::cout << "isDepthImg2ColorPC is not exist" << std::endl;
return false;
}
// isPcProject2Img
if(params_node["isPcProject2Img"].IsDefined()){
t_depth2pointCloud.isPcProject2Img = params_node["isPcProject2Img"].as<bool>();
}else{
std::cout << "isPcProject2Img is not exist" << std::endl;
return false;
}
// depthpc2img params
std::vector<double> depthpc2img_R_params(9, 0.0);
std::vector<double> depthpc2img_T_params(16, 0.0);
if(params_node["depthPC2RGB_params"].IsDefined()){
depthpc2img_R_params = params_node["depthPC2RGB_params"]["R_lidar2camera"].as<std::vector<double>>();
depthpc2img_T_params = params_node["depthPC2RGB_params"]["T_lidar2camera"].as<std::vector<double>>();
}else{
std::cout << "depthPC2RGB_params is not exist" << std::endl;
return false;
}
// 将读取的深度相机到彩色相机的旋转矩阵赋值给转换变量
t_depth2pointCloud.depthpc2img_RT.block<3,3>(0,0) = Eigen::Map<Eigen::Matrix3d>(depthpc2img_R_params.data());
t_depth2pointCloud.depthpc2img_RT(0,3) = depthpc2img_T_params[3];
t_depth2pointCloud.depthpc2img_RT(1,3) = depthpc2img_T_params[7];
t_depth2pointCloud.depthpc2img_RT(2,3) = depthpc2img_T_params[11];
return true;
}
04 深度图转换为点云
深度图转换为点云的转换代码如下:
python
bool Depth2PointCloud::depthImg2pointCloud(std::vector<std::string>& depthFileDirs, const Depth2PointCloud::cameraParam& t_cameraParams, const std::string& t_ply_save_path) {
std::sort(depthFileDirs.begin(), depthFileDirs.end());
for(auto depthFile: depthFileDirs){
std::string ply_stem = std::filesystem::path(depthFile).stem().string();
cv::Mat depthImage = cv::imread(depthFile,cv::IMREAD_UNCHANGED);
// 深度图转换点云
pcl::PointCloud<pcl::PointXYZ>::Ptr pointCloud(new pcl::PointCloud<pcl::PointXYZ>);
int imageWidth = depthImage.cols;
int imageHeight = depthImage.rows;
int bias_row = 0;
int bias_col = 0;
for (int index_row = 0; index_row < imageHeight; index_row += (2+bias_row)){
if (index_row > imageHeight * 0.9) {
bias_row = 3;
bias_col = 3;
} else if (index_row > imageHeight * 0.8) {
bias_row = 2;
bias_col = 2;
} else if (index_row > imageHeight * 0.7) { // 深度图越下方离车越近,降采样倍率越高 indY:108开始
bias_row = 1;
bias_col = 1;
}
for(int index_col = 0; index_col < imageWidth; index_col += (3+bias_col)){
pcl::PointXYZ point;
point.y = depthImage.at<uint16_t>(index_row,index_col) / 1000.0;
point.x = (index_col - t_cameraParams.dcx) * point.y / t_cameraParams.dfx;
point.z = -(index_row - t_cameraParams.dcy) * point.y / t_cameraParams.dfy;
pointCloud->push_back(point);
}
}
std::string save_plyFilePath = t_ply_save_path + ply_stem + ".ply";
pcl::io::savePLYFileBinary(save_plyFilePath, *pointCloud);
}
return true;
}
05 深度图转换为彩色点云
深度图转彩色点云代码如下:
python
// 彩色点云转换
bool Depth2PointCloud::depthImg2ColorPC(std::vector<std::string>& depthFileDirs,std::vector<std::string>& rgbFileDirs,const cameraParam& t_cameraParams,const std::string& t_colorPoints_save_path){
std::sort(depthFileDirs.begin(), depthFileDirs.end());
std::sort(rgbFileDirs.begin(), rgbFileDirs.end());
for(int img_index = 0; img_index < depthFileDirs.size(); img_index++){
std::string ply_stem = std::filesystem::path(depthFileDirs[img_index]).stem().string();
cv::Mat depthImage = cv::imread(depthFileDirs[img_index],cv::IMREAD_UNCHANGED);
cv::Mat rgbImage = cv::imread(rgbFileDirs[img_index],cv::IMREAD_UNCHANGED);
// 深度图转换点云
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointCloudRGB(new pcl::PointCloud<pcl::PointXYZRGB>);
int imageWidth = depthImage.cols;
int imageHeight = depthImage.rows;
int bias_row = 0;
int bias_col = 0;
for (int index_row = 0; index_row < imageHeight; index_row += (2+bias_row)){
if (index_row > imageHeight * 0.9) {
bias_row = 3;
bias_col = 3;
} else if (index_row > imageHeight * 0.8) {
bias_row = 2;
bias_col = 2;
} else if (index_row > imageHeight * 0.7) { // 深度图越下方离车越近,降采样倍率越高 indY:108开始
bias_row = 1;
bias_col = 1;
}
for(int index_col = 0; index_col < imageWidth; index_col += (3+bias_col)){
pcl::PointXYZRGB point;
point.y = depthImage.at<uint16_t>(index_row,index_col) / 1000.0;
point.x = (index_col - t_cameraParams.dcx) * point.y / t_cameraParams.dfx;
point.z = -(index_row - t_cameraParams.dcy) * point.y / t_cameraParams.dfy;
point.b = rgbImage.at<cv::Vec3b>(index_row, index_col)[0];
point.g = rgbImage.at<cv::Vec3b>(index_row, index_col)[1];
point.r = rgbImage.at<cv::Vec3b>(index_row, index_col)[2];
pointCloudRGB->push_back(point);
}
}
std::string save_plyFilePath = t_colorPoints_save_path + ply_stem + ".ply";
pcl::io::savePLYFileBinary(save_plyFilePath, *pointCloudRGB);
}
return true;
}
06 点云投影到图像
将生成的点云投影到图像,主要基于深度相机到rgb相机的转换矩阵以及rgb相机内参,同时考虑相机的畸变,将点云应用畸变关系转换到rgb相机坐标系下,即完成点云向rgb相机的投影,代码如下:
python
void Depth2PointCloud::depthImgProjetced2RgbImg(std::vector<std::string>& depthFileDirs,std::vector<std::string>& rgbFileDirs,const cameraParam& t_cameraParams,const std::string& t_projectedRgb_save_path,const Eigen::Matrix4d& t_depthpc2img_RT){
std::sort(depthFileDirs.begin(),depthFileDirs.end());
std::sort(rgbFileDirs.begin(),rgbFileDirs.end());
for(int img_index = 0; img_index < depthFileDirs.size(); img_index++){
std::string ply_stem = std::filesystem::path(depthFileDirs[img_index]).stem().string();
cv::Mat depthImage = cv::imread(depthFileDirs[img_index],cv::IMREAD_UNCHANGED);
cv::Mat rgbImage = cv::imread(rgbFileDirs[img_index],cv::IMREAD_UNCHANGED);
// 深度图转换点云
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointCloudRGB(new pcl::PointCloud<pcl::PointXYZRGB>);
int imageWidth = depthImage.cols;
int imageHeight = depthImage.rows;
int bias_row = 0;
int bias_col = 0;
for (int index_row = 0; index_row < imageHeight; index_row += (2+bias_row)){
if (index_row > imageHeight * 0.9) {
bias_row = 3;
bias_col = 3;
} else if (index_row > imageHeight * 0.8) {
bias_row = 2;
bias_col = 2;
} else if (index_row > imageHeight * 0.7) { // 深度图越下方离车越近,降采样倍率越高 indY:108开始
bias_row = 1;
bias_col = 1;
}
for(int index_col = 0; index_col < imageWidth; index_col += (3+bias_col)){
pcl::PointXYZRGB point;
point.y = depthImage.at<uint16_t>(index_row,index_col) / 1000.0;
point.x = (index_col - t_cameraParams.dcx) * point.y / t_cameraParams.dfx;
point.z = -(index_row - t_cameraParams.dcy) * point.y / t_cameraParams.dfy;
pcl::PointXYZRGB temp_point;
// 对x =x, y = -z, z = y进行坐标变换,转换到图像坐标系
temp_point.x = point.x;
temp_point.y = -point.z;
temp_point.z = point.y;
temp_point.b = rgbImage.at<cv::Vec3b>(index_row,index_col)[0];
temp_point.g = rgbImage.at<cv::Vec3b>(index_row,index_col)[1];
temp_point.r = rgbImage.at<cv::Vec3b>(index_row,index_col)[2];
pointCloudRGB->push_back(temp_point);
}
}
// 点云转换到相机坐标系
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointCloudRGB_cambase(new pcl::PointCloud<pcl::PointXYZRGB>);
pcl::transformPointCloud(*pointCloudRGB, *pointCloudRGB_cambase, t_depthpc2img_RT);
// 点云、图像对齐
for(auto point : *pointCloudRGB_cambase){
if(point.z < 0){
continue;
}else{
double X = point.x / point.z;
double Y = point.y / point.z;
double R2 = X * X + Y * Y;
double R4 = R2 * R2;
double R6 = R2 * R4;
// 径向畸变depthImage
double XR = X * (1 + t_cameraParams.k1 * R2 + t_cameraParams.k2 * R4 + t_cameraParams.k3 * R6);
double YR = Y * (1 + t_cameraParams.k1 * R2 + t_cameraParams.k2 * R4 + t_cameraParams.k3 * R6);
// 切向畸变
double XD = XR + 2 * t_cameraParams.p1 * X * Y + t_cameraParams.p2 * (R2 + 2 * X * X);
double YD = YR + t_cameraParams.p1 * (R2 + 2 * Y * Y) + 2 * t_cameraParams.p2 * X * Y;
// 像素坐标
// int u = std::round(t_cameraParams.fx * XD + t_cameraParams.cx);
// int v = std::round(t_cameraParams.fy * YD + t_cameraParams.cy);
int u = (t_cameraParams.fx * XD + t_cameraParams.cx);
int v = (t_cameraParams.fy * YD + t_cameraParams.cy);
// 像素是否在图像内
if(u >= 0 && u < rgbImage.cols && v >= 0 && v < rgbImage.rows){
cv::circle(rgbImage, cv::Point(u, v), 1, cv::Scalar(0, 0, 255), -1);
}
}
}
// 保存投影结果
std::string projected_rgb_name = t_projectedRgb_save_path + ply_stem + ".jpg";
cv::imwrite(projected_rgb_name, rgbImage);
}
return;
}
main.cpp
python
#include "depth2cloud.h"
// 提取目录下各个文件路径
void extractFilePath(const std::string& t_FileDir, std::vector<std::string>& t_FilePath){
for (const auto& entry : std::filesystem::directory_iterator(t_FileDir))
{
if (!entry.is_regular_file())
continue;
std::string ext = entry.path().extension().string();
std::transform(ext.begin(), ext.end(), ext.begin(), ::tolower);
if (ext == ".ply" || ext == ".pcd")
{
std::string full_path = std::filesystem::absolute(entry.path()).string();
t_FilePath.push_back(full_path);
}
}
return ;
}
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <chrono>
#include <thread>
// 显示点云
bool visPointcloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in){
// 显示数据
pcl::visualization::PCLVisualizer viewer;
// 3. 创建两个视口
int v1;
// 设置背景颜色
viewer.setBackgroundColor(0, 0, 0, v1);
// 4. 添加点云(不同颜色)
pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> color_in(cloud_in, 0, 255, 0); // 绿色
viewer.addPointCloud<pcl::PointXYZ>(cloud_in, color_in, "input_cloud", v1);
// 点大小
viewer.setPointCloudRenderingProperties(
pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 2, "input_cloud");
// 5. 添加文字
viewer.addText("Input Cloud", 10, 10, "v1 text", v1);
// while(!viewer.wasStopped()){
// viewer.spinOnce(100);
// }
viewer.spinOnce(20);
return true;
}
int main(){
Depth2PointCloud depth2pointCloud;
// 配置参数
std::string ConfigFilePath = "../config/config.yaml";
depth2pointCloud.readCameraParam(ConfigFilePath, depth2pointCloud);
// 读取深度图
std::vector<std::string> depthImgFiles = depth2pointCloud.readImage(depth2pointCloud.depthImgPath);
// 读取rgb图片
std::vector<std::string> rgbImgFiles = depth2pointCloud.readImage(depth2pointCloud.rgbImgPath);
// 生成点云并保存
if(depth2pointCloud.isDepthImg2PC){
bool depth2pc_finished = depth2pointCloud.depthImg2pointCloud(depthImgFiles, depth2pointCloud.cameraParams, depth2pointCloud.ply_save_path);
std::cout << "深度图转点云完成" << std::endl;
if(false){
// 读取文件路径
std::vector<std::string> filesPath;
extractFilePath(depth2pointCloud.ply_save_path, filesPath);
std::sort(filesPath.begin(), filesPath.end());
for(auto ply : filesPath){
pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud_in(new pcl::PointCloud<pcl::PointXYZ>);
pcl::io::loadPLYFile(ply, *pointcloud_in);
visPointcloud(pointcloud_in);
}
}
}else{
std::cout << "未开启深度图转点云功能" << std::endl;
}
// 生成彩色点云
if(depth2pointCloud.isDepthImg2ColorPC){
bool depthImg2ColorPC_finished = depth2pointCloud.depthImg2ColorPC(depthImgFiles, rgbImgFiles, depth2pointCloud.cameraParams, depth2pointCloud.colorPoints_save_path);
std::cout << "深度图转彩色点云完成" << std::endl;
std::vector<std::string> filesColorPCPath;
extractFilePath(depth2pointCloud.colorPoints_save_path, filesColorPCPath);
if(false){
// 读取文件路径
std::sort(filesColorPCPath.begin(), filesColorPCPath.end());
// 读取文件路径
std::sort(filesColorPCPath.begin(), filesColorPCPath.end());
for(auto ply : filesColorPCPath){
pcl::PointCloud<pcl::PointXYZ>::Ptr colorPC_in(new pcl::PointCloud<pcl::PointXYZ>);
pcl::io::loadPLYFile(ply, *colorPC_in);
visPointcloud(colorPC_in);
}
// system("pause");
}else{ // TODO:fixme
// 显示点云
///*
pcl::visualization::PCLVisualizer viewer("Point Cloud Viewer");
while(!viewer.wasStopped()){
for(auto file: filesColorPCPath){
PointCloud::Ptr cloud(new PointCloud);
if(pcl::io::loadPLYFile<DATA_TYPE>(file, *cloud) == -1){
PCL_ERROR("Couldn't read file %s \n", file.c_str());
return -1;
}
if(viewer.contains("VISCLOUD")){
viewer.removePointCloud("VISCLOUD");
}
viewer.addPointCloud(cloud, "VISCLOUD");
viewer.spinOnce(10);
std::this_thread::sleep_for(std::chrono::milliseconds(10));
}
}
}
}else{
std::cout << "未开启深度图转彩色点云功能" << std::endl;
}
// 生成点云并投影到图片
if(depth2pointCloud.isPcProject2Img){
depth2pointCloud.depthImgProjetced2RgbImg(depthImgFiles, rgbImgFiles, depth2pointCloud.cameraParams, depth2pointCloud.projectedRgb_save_path,
depth2pointCloud.depthpc2img_RT);
std::cout << "点云投影到图像完成" << std::endl;
}else{
std::cout << "未开启点云投影到图像功能" << std::endl;
}
return 0;
}
.h头文件
python
#ifndef DEPTH_2_POINTCLOUD_H
#define DEPTH_2_POINTCLOUD_H
#include <opencv2/opencv.hpp>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/io/ply_io.h>
#include <pcl/point_cloud.h>
#include <pcl/common/transforms.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <Eigen/Dense>
#include <iostream>
#include <string>
#include <vector>
#include <filesystem>
#include <algorithm>
#include <thread>
#define visColoredPoints 1
#if visColoredPoints
#define DATA_TYPE pcl::PointXYZRGB
typedef pcl::PointCloud<DATA_TYPE> PointCloud;
#else
#define DATA_TYPE pcl::PointXYZ
typedef pcl::PointCloud<DATA_TYPE> PointCloud;
#endif
class Depth2PointCloud
{
private:
public:
// 相机内参结构体(含深度/彩色相机内参 + 畸变系数)
struct cameraParam{
// depth camera intrinsic parameter
double dfx = 0.0;
double dfy = 0.0;
double dcx = 0.0;
double dcy = 0.0;
// rgb camera intrinsic parameter
double fx = 0.0;
double fy = 0.0;
double cx = 0.0;
double cy = 0.0;
// 相机畸变系数
double k1 = 0.0;
double k2 = 0.0;
double p1 = 0.0;
double p2 = 0.0;
double k3 = 0.0;
};
// 路径配置参数
std::string depthImgPath, rgbImgPath;
std::string ply_save_path;
std::string projectedRgb_save_path;
std::string colorPoints_save_path;
std::string ConfigFilePath;
// 核心参数对象
cameraParam cameraParams;
Eigen::Matrix4d depthpc2img_RT = Eigen::Matrix4d::Identity(); // 深度相机到RGB相机的外参变换矩阵
// 控制转换内容开关
bool isDepthImg2PC = false; // 深度图转普通点云
bool isDepthImg2ColorPC = false; // 深度图转彩色点云
bool isPcProject2Img = false; // 点云投影到图像
// 构造/析构函数
Depth2PointCloud(/* args */);
~Depth2PointCloud();
// 成员函数声明
bool readCameraParam(const std::string& t_cameraConfigFilePath, Depth2PointCloud& t_depth2pointCloud);
std::vector<std::string> readImage(const std::string& t_depthFileDirs);
// depth2pc 核心功能函数
bool depthImg2pointCloud(std::vector<std::string>& depthFileDirs, const cameraParam& t_cameraParams, const std::string& t_ply_save_path);
bool depthImg2ColorPC(std::vector<std::string>& depthFileDirs, std::vector<std::string>& rgbFileDirs, const cameraParam& t_cameraParams, const std::string& t_ply_save_path);
// pcProject2Img 点云投影功能函数
void depthImgProjetced2RgbImg(std::vector<std::string>& depthFileDirs, std::vector<std::string>& rgbFileDirs, const cameraParam& t_cameraParams, const std::string& t_projectedRgb_save_path, const Eigen::Matrix4d& t_depthpc2img_RT);
};
#endif
CMakeLists.txt
python
cmake_minimum_required(VERSION 3.10)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
project(depth2cloud)
# find_package(PCL 1.10 REQUIRED)
find_package(PCL 1.10 REQUIRED COMPONENTS common io visualization)
find_package(OpenCV REQUIRED)
# target_include_directories(depth2cloud ./include)
include_directories(${PCL_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS} ${OpenCV_LIBRARY_DIRS})
add_executable (depth2cloud main.cpp src/depth2cloud.cpp)
target_include_directories(depth2cloud PRIVATE ${PROJECT_SOURCE_DIR}/include)
target_link_libraries (depth2cloud ${PCL_LIBRARIES} ${OpenCV_LIBS})
target_link_libraries(depth2cloud yaml-cpp)