一、深度图像存储格式
基础数据结构
1. 像素值表示
- 物理含义:像素值代表相机到物体表面的距离(单位通常为毫米)
- 常见数值范围 :
- 消费级深度相机:0.3m~10m → 300~10000(16位可完整表示)
- 工业级相机:0.1m~50m → 100~50000(需16位或更高)
2. 数据类型选择
数据类型 | 位数 | 范围 | 应用场景 |
---|---|---|---|
uint8_t |
8位 | 0~255 | 近距离(<0.3m)或低精度场景 |
uint16_t |
16位 | 0~65535 | 主流(覆盖95%以上应用) |
float |
32位 | ±3.4×10^38 | 高精度计算(点云生成、SLAM) |
定点数(如Q16) | 16位 | 自定义小数精度 | 嵌入式设备优化(平衡精度与性能) |
3. 内存布局
-
行优先存储 (Row-major):主流格式,如OpenCV的
cv::Mat
[row0][row1]...[rowN] 每行:[pixel0][pixel1]...[pixelM]
-
交错存储 (Interleaved):深度与RGB数据交替存储(如RGBD格式)
[R0,G0,B0,D0][R1,G1,B1,D1]...
二、主流深度相机的输出格式
主流深度相机(如奥比中光、Intel RealSense、Kinect等)的深度图默认输出格式,本质上是由其硬件特性(传感器类型、量程)、应用场景(消费级/工业级)和数据效率(存储、传输、处理)共同决定的。
一、核心结论:主流默认格式的共性
所有主流深度相机的默认深度图格式,均以"单通道16位无符号整数(uint16)"为核心,单位通常为"毫米(mm)",像素格式表现为"单通道16位灰度值"(无RGB信息,仅深度维度)。这一选择的核心原因是:16位能覆盖大多数场景的量程(0-65535mm≈65米),且uint16兼顾精度(毫米级)和存储效率(单像素2字节,低于32位浮点的4字节),适合实时传输与处理。
二、分品牌解析(含具体型号与SDK定义)
1. 奥比中光(Orbbec):以"Y16"为标志的通用格式
奥比中光是消费级与工业级深度相机的主流厂商,核心型号包括Astra系列(Astra Pro)、Femto系列(Femto Mega)、Gemini系列等,其默认深度格式具有高度统一性:
- 默认格式 :单通道16位无符号整数(uint16),SDK中定义为
OB_FORMAT_Y16
(Y表示单通道,16表示位深)。 - 单位:毫米(mm),即每个像素值直接对应目标到相机的直线距离(如值为1000表示1米)。
- 无效值处理 :超出量程(如Astra Pro量程0.6-8米)或无法检测的像素,默认值为
0
(部分型号可能用65535
,需结合SDK文档确认)。 - 场景适配:该格式适用于体感交互、避障、3D扫描等场景,16位量程(65米)完全覆盖消费级与中短距工业场景。
2. Intel RealSense:以"Z16"为核心的多系列统一格式
Intel RealSense是PC端深度相机的标杆,核心系列包括D400(D435/D455)、L500(L515)、T265(已停产)等,其默认格式在不同系列中高度一致:
- 默认格式 :单通道16位无符号整数(uint16),SDK中定义为
RS2_FORMAT_Z16
(Z表示深度,16表示位深)。 - 单位:毫米(mm),与奥比中光一致,直接反映物理距离。
- 细分差异 :
- D400系列(结构光+立体匹配):量程0.1-10米,默认Z16,无效值为0;
- L515(LiDAR+ToF):量程0.25-9米,默认Z16,因LiDAR精度更高,有效深度值的噪声更低;
- 扩展格式 :RealSense支持压缩格式(如
RS2_FORMAT_Z16_COMPRESSED
)和浮点格式(RS2_FORMAT_DEPTH32F
,单位米),但默认输出必为Z16(平衡效率与兼容性)。
3. 微软Kinect:从V1到Azure的16位传承
微软Kinect是深度相机的"开山鼻祖",历经三代迭代(V1→V2→Azure Kinect DK),默认格式始终以16位为核心:
-
Kinect V1(Xbox 360/Windows) :
传感器类型为"结构光",量程0.8-4米。
- 默认格式:16位无符号整数(uint16),单位毫米,SDK中无明确格式名(早期OpenNI兼容格式)。
- 细节:实际有效深度值仅11-12位(0-4095,对应4米),但存储时扩展为16位(高位补0),便于统一处理。
-
Kinect V2(Windows) :
传感器类型为"飞行时间(ToF)",量程0.5-4.5米。
- 默认格式:16位无符号整数(uint16),单位毫米,SDK中输出为16位数组,无效值为0。
-
Azure Kinect DK(新一代) :
传感器类型为"多模式ToF",量程0.5-10米(宽模式)或0.2-3米(窄模式)。
- 默认格式:SDK中定义为
K4A_IMAGE_FORMAT_DEPTH16
(明确16位深度),单位毫米,无效值为0。 - 扩展:支持"深度+IR"联合输出,但深度通道默认仍为16位uint16。
- 默认格式:SDK中定义为
三、格式背后的"隐性规则"
-
有效位与存储的关系:部分相机的传感器实际精度低于16位(如Kinect V1为11位),但输出时会将有效位"填充"到16位(高位补0),避免处理时的位对齐问题(16位是CPU高效处理的基本单位)。
-
无效值的统一处理 :几乎所有相机默认用"0"表示无效深度(超出量程、遮挡、反光等),但部分工业级型号可能用"最大值65535"(需结合SDK文档确认,如奥比中光部分工业型号)。
-
格式转换的兼容性 :所有主流SDK均支持将16位深度图转换为32位浮点(单位米,如RealSense的
RS2_FORMAT_DEPTH32F
),但默认不启用(因浮点处理效率低)。
维度 | 核心内容 |
---|---|
通用格式 | 单通道16位无符号整数(uint16),单像素2字节,单通道(无色彩)。 |
单位 | 毫米(mm),直接对应物理距离,0-65535mm覆盖绝大多数场景。 |
奥比中光 | 默认OB_FORMAT_Y16 ,单位mm,无效值多为0,覆盖消费级/工业级中短距。 |
Intel RealSense | 默认RS2_FORMAT_Z16 ,D400/L500系列统一,无效值0,支持压缩/浮点扩展。 |
Kinect系列 | V1/V2/Azure均默认16位uint16,Azure定义为K4A_IMAGE_FORMAT_DEPTH16 。 |
隐性规则 | 低精度传感器填充至16位;无效值多为0;默认不启用浮点格式(效率低)。 |
三、OpenCV深度图像处理
OpenCV 作为计算机视觉领域的核心库,提供了完善的深度图像处理功能。
一、深度图像的存储格式
1.1 原始数据存储
深度图像通常以单通道16位无符号整数(CV_16U)格式存储,单位为毫米(mm)。
cpp
#include <opencv2/opencv.hpp>
// 创建/加载深度图像
cv::Mat depthImage(480, 640, CV_16U); // 480x640的深度图像
// 从文件加载深度图像(假设已保存为PNG格式)
cv::Mat loadedDepth = cv::imread("depth_image.png", cv::IMREAD_ANYDEPTH);
// 访问深度值(单位:毫米)
ushort depthValue = depthImage.at<ushort>(y, x); // (x,y)位置的深度值
// 保存深度图像
cv::imwrite("depth_output.png", depthImage); // 保存为PNG(无损格式)
1.2 浮点格式存储(高精度)
对于需要更高精度的应用,可以使用32位浮点数(CV_32F):
cpp
cv::Mat depthFloat(480, 640, CV_32F); // 浮点型深度图像
// 从16位转换为32位
depthImage.convertTo(depthFloat, CV_32F, 0.001); // 毫米转米(乘以0.001)
// 从32位转回16位
depthFloat.convertTo(depthImage, CV_16U, 1000.0); // 米转毫米
二、深度图像的基本处理
2.1 深度可视化
OpenCV显示深度图像一定要归一化(深度数据一般不在0~255范围之内)
将深度值映射到RGB颜色空间以便显示:
cpp
// 深度可视化函数
cv::Mat visualizeDepth(const cv::Mat& depth, double minDepth = 0, double maxDepth = 0) {
cv::Mat normalizedDepth;
// 自动计算深度范围
if (maxDepth <= minDepth) {
cv::minMaxLoc(depth, &minDepth, &maxDepth);
maxDepth = std::max(maxDepth, minDepth + 1); // 防止除零错误
}
// 归一化到[0,1]
cv::normalize(depth, normalizedDepth, 0.0, 1.0, cv::NORM_MINMAX, CV_32F);
// 转换为8位RGB图像
cv::Mat rgbDepth;
cv::applyColorMap(normalizedDepth * 255, rgbDepth, cv::COLORMAP_JET);
return rgbDepth;
}
// 使用示例
cv::Mat depthVisualization = visualizeDepth(depthImage);
cv::imshow("Depth Visualization", depthVisualization);
2.2 深度滤波
cpp
// 中值滤波(去除椒盐噪声)
cv::Mat filteredDepth;
cv::medianBlur(depthImage, filteredDepth, 5); // 5x5中值滤波
// 双边滤波(保留边缘的同时平滑)
cv::Mat depthFloat;
depthImage.convertTo(depthFloat, CV_32F, 0.001); // 转换为浮点数
cv::Mat filteredFloat;
cv::bilateralFilter(depthFloat, filteredFloat, 9, 0.1, 10); // 参数需根据场景调整
2.3 深度阈值处理
cpp
// 近景区域提取(保留2米内的物体)
cv::Mat foregroundMask;
cv::inRange(depthImage, 0, 2000, foregroundMask); // 0-2000mm范围内为前景
// 应用掩码提取前景
cv::Mat foregroundDepth;
depthImage.copyTo(foregroundDepth, foregroundMask);
三、深度图像与点云转换
3.1 深度图转点云(基于相机内参)
cpp
// 相机内参(示例值,需根据实际相机标定)
struct CameraIntrinsics {
float fx, fy; // 焦距
float cx, cy; // 主点
};
CameraIntrinsics intrinsics = {615.4f, 615.4f, 320.0f, 240.0f}; // 示例内参
// 深度图转点云
std::vector<cv::Point3f> depthToPointCloud(const cv::Mat& depth) {
std::vector<cv::Point3f> pointCloud;
pointCloud.reserve(depth.rows * depth.cols);
for (int y = 0; y < depth.rows; y++) {
for (int x = 0; x < depth.cols; x++) {
ushort d = depth.at<ushort>(y, x);
if (d == 0) continue; // 跳过无效深度
// 相机坐标系下的3D坐标
float z = static_cast<float>(d) / 1000.0f; // 毫米转米
float x3D = (x - intrinsics.cx) * z / intrinsics.fx;
float y3D = (y - intrinsics.cy) * z / intrinsics.fy;
pointCloud.push_back(cv::Point3f(x3D, y3D, z));
}
}
return pointCloud;
}
3.2 点云降采样(体素网格滤波)
cpp
// 体素网格滤波降采样(简化点云)
std::vector<cv::Point3f> voxelDownsample(const std::vector<cv::Point3f>& points, float voxelSize) {
// 计算体素网格索引
std::unordered_map<std::string, std::vector<cv::Point3f>> voxelMap;
for (const auto& p : points) {
int i = static_cast<int>(p.x / voxelSize);
int j = static_cast<int>(p.y / voxelSize);
int k = static_cast<int>(p.z / voxelSize);
std::string key = std::to_string(i) + "," + std::to_string(j) + "," + std::to_string(k);
voxelMap[key].push_back(p);
}
// 每个体素取平均值
std::vector<cv::Point3f> downsampledPoints;
for (const auto& pair : voxelMap) {
const auto& voxelPoints = pair.second;
if (voxelPoints.empty()) continue;
cv::Point3f sum(0, 0, 0);
for (const auto& p : voxelPoints) {
sum += p;
}
downsampledPoints.push_back(sum / static_cast<float>(voxelPoints.size()));
}
return downsampledPoints;
}
四、深度图像与RGB图像对齐
4.1 深度图对齐到RGB图像
cpp
// 假设已知深度相机到RGB相机的变换矩阵
cv::Mat depthToColorTransform = cv::Mat::eye(4, 4, CV_32F); // 示例变换矩阵
// 深度图对齐到RGB图像
cv::Mat alignDepthToColor(const cv::Mat& depth, const cv::Mat& rgb,
const CameraIntrinsics& depthIntrinsics,
const CameraIntrinsics& rgbIntrinsics,
const cv::Mat& transform) {
cv::Mat alignedDepth = cv::Mat::zeros(rgb.size(), CV_16U);
// 对每个RGB像素,找到对应的深度值
for (int y = 0; y < rgb.rows; y++) {
for (int x = 0; x < rgb.cols; x++) {
// RGB像素反投影到3D空间
float z = 1.0f; // 假设深度为1米
float x3D = (x - rgbIntrinsics.cx) * z / rgbIntrinsics.fx;
float y3D = (y - rgbIntrinsics.cy) * z / rgbIntrinsics.fy;
// 应用变换到深度相机坐标系
cv::Mat pointInDepth = transform * cv::Mat(cv::Vec4f(x3D, y3D, z, 1));
float xDepth = pointInDepth.at<float>(0, 0);
float yDepth = pointInDepth.at<float>(1, 0);
float zDepth = pointInDepth.at<float>(2, 0);
// 投影回深度图像平面
int u = static_cast<int>(xDepth * depthIntrinsics.fx / zDepth + depthIntrinsics.cx);
int v = static_cast<int>(yDepth * depthIntrinsics.fy / zDepth + depthIntrinsics.cy);
// 检查坐标是否在深度图像范围内
if (u >= 0 && u < depth.cols && v >= 0 && v < depth.rows) {
alignedDepth.at<ushort>(y, x) = depth.at<ushort>(v, u);
}
}
}
return alignedDepth;
}
五、高级应用:3D重建
5.1 基于深度图像的简单3D重建
cpp
// 3D重建类
class Simple3DReconstruction {
public:
Simple3DReconstruction(const CameraIntrinsics& intrinsics)
: intrinsics_(intrinsics) {}
// 添加新的深度帧进行重建
void addDepthFrame(const cv::Mat& depth, const cv::Mat& pose) {
std::vector<cv::Point3f> points = depthToPointCloud(depth);
// 应用相机位姿变换
for (auto& p : points) {
cv::Mat pointHomogeneous = cv::Mat(cv::Vec4f(p.x, p.y, p.z, 1));
cv::Mat transformedPoint = pose * pointHomogeneous;
p.x = transformedPoint.at<float>(0, 0);
p.y = transformedPoint.at<float>(1, 0);
p.z = transformedPoint.at<float>(2, 0);
}
// 合并到全局点云
globalPointCloud_.insert(globalPointCloud_.end(), points.begin(), points.end());
}
// 保存点云为PLY格式
void saveToPLY(const std::string& filename) const {
std::ofstream file(filename);
if (!file.is_open()) return;
// PLY文件头
file << "ply\n";
file << "format ascii 1.0\n";
file << "element vertex " << globalPointCloud_.size() << "\n";
file << "property float x\n";
file << "property float y\n";
file << "property float z\n";
file << "end_header\n";
// 写入点云数据
for (const auto& p : globalPointCloud_) {
file << p.x << " " << p.y << " " << p.z << "\n";
}
file.close();
}
private:
CameraIntrinsics intrinsics_;
std::vector<cv::Point3f> globalPointCloud_;
};
六、性能优化技巧
-
内存管理:
- 使用
cv::Mat::create()
预分配内存,避免频繁内存分配 - 批量处理时使用
cv::Mat::reshape()
减少内存拷贝
- 使用
-
并行计算:
cpp// 使用OpenMP并行处理深度图像 #pragma omp parallel for for (int y = 0; y < depth.rows; y++) { for (int x = 0; x < depth.cols; x++) { // 并行处理每个像素 } }
-
GPU加速:
cpp// 使用OpenCV的CUDA模块加速 cv::cuda::GpuMat d_depth, d_filtered; d_depth.upload(depthImage); cv::Ptr<cv::cuda::Filter> medianFilter = cv::cuda::createMedianFilter(CV_16U, 5); medianFilter->apply(d_depth, d_filtered); cv::Mat filteredHost; d_filtered.download(filteredHost);
七、注意事项
-
深度无效值处理:
- 多数深度相机使用0表示无效深度,处理时需特殊处理
- 使用
cv::Mat::setTo()
设置无效区域为特定值
-
坐标系约定:
- 相机坐标系通常为X右、Y下、Z前
- 转换时需注意单位一致性(通常为米或毫米)
-
精度损失:
- 16位深度图最大范围为65,535mm(约65米),超出范围会导致饱和
- 高精度场景建议使用32位浮点数存储