深度图转点云原理

深度图转点云的计算过程很简洁,而里面的原理是根据内外参矩阵变换公式得到,下面来介绍其推导的过程。

1. 原理

首先,要了解下世界坐标到图像的映射过程,考虑世界坐标点M(Xw,Yw,Zw)映射到图像点m(u,v)的过程,如下图所示:

详细原理请参考教程"相机标定(2)---摄像机标定原理",这里不做赘述。形式化表示如下:

\(z_{c}
\begin{pmatrix}
u\\
v\\
1
\end{pmatrix}
=\begin{bmatrix}
f/dx & 0 & u_{0}\\
0 & f/dy & v_{0}\\
0 & 0 & 1
\end{bmatrix}
\begin{bmatrix}
R & T\\
\end{bmatrix}
\begin{bmatrix}
x_{w}\\
y_{w}\\
z_{w}\\
1
\end{bmatrix}
\)

其中\(u,v\)为图像坐标系下的任意坐标点。\(u_{0},v_{0}\)分别为图像的中心坐标。\(x_{w},y_{w},z_{w}\)表示世界坐标系下的三维坐标点。\(z_{c}\)表示相机坐标的z轴值,即目标到相机的距离。\(R,T\)分别为外参矩阵的3x3旋转矩阵和3x1平移矩阵。

 对外参矩阵的设置:由于世界坐标原点和相机原点是重合的,即没有旋转和平移,所以:

\(R=\begin{bmatrix}
0 & 0 & 0\\
0 & 1& 0\\
0 & 0& 1
\end{bmatrix}
\),\(T=\begin{bmatrix}
0 \\ 
0 \\ 
0
\end{bmatrix}
\)

注意到,相机坐标系和世界坐标系的坐标原点重合,因此相机坐标和世界坐标下的同一个物体具有相同的深度,即\(z_{c}=z_{w}\).于是公式可进一步简化为:

\(z_{c}
\begin{pmatrix}
u\\
v\\
1
\end{pmatrix}=\begin{bmatrix}
f/dx & 0 & u_{0}\\
0 & f/dy & v_{0}\\
0 & 0& 1
\end{bmatrix}
\begin{bmatrix}
1&0&0& 0\\
0&1&0& 0\\
0&0&1& 0
\end{bmatrix}
\begin{bmatrix}
x_{w}\\
y_{w}\\
z_{c}\\
1
\end{bmatrix}
\)

 从以上的变换矩阵公式,可以计算得到图像点\(\begin{bmatrix}u, v \end{bmatrix}^{T}\) 到世界坐标点\(\begin{bmatrix}x_{w}, y_{w} ,z_{w}\end{bmatrix}^{T}\)的变换公式:

\(\left\{\begin{matrix}
x_{w}&=& z_{c} \cdot (u-u_{0})\cdot dx/f &\\
y_{w}&=& z_{c}\cdot (v-v_{0})\cdot dy/f &\\
z_{w}&=& z_{c}\qquad \qquad \qquad  &
\end{matrix}\right.\)

 

2. 代码

根据上述公式,再结合以下ROS给出的代码,就能理解其原理了。代码如下:

#ifndef DEPTH_IMAGE_PROC_DEPTH_CONVERSIONS
#define DEPTH_IMAGE_PROC_DEPTH_CONVERSIONS

#include <sensor_msgs/Image.h>
#include <sensor_msgs/point_cloud2_iterator.h>
#include <image_geometry/pinhole_camera_model.h>
#include "depth_traits.h"

#include <limits>

namespace depth_proc {

typedef sensor_msgs::PointCloud2 PointCloud;

// Handles float or uint16 depths
template<typename T>
void convert(
    const sensor_msgs::ImageConstPtr& depth_msg,
    PointCloud::Ptr& cloud_msg,
    const image_geometry::PinholeCameraModel& model,
    double range_max = 0.0)
{
  // Use correct principal point from calibration
  float center_x = model.cx();//内参矩阵中的图像中心的横坐标u0
  float center_y = model.cy();//内参矩阵中的图像中心的纵坐标v0

  // Combine unit conversion (if necessary) with scaling by focal length for computing (X,Y)
  double unit_scaling = DepthTraits<T>::toMeters( T(1) );//如果深度数据是毫米单位的,结果将会为0.001;如果深度数据是米单位的,结果将会为1;
  float constant_x = unit_scaling / model.fx();//内参矩阵中的 f/dx
  float constant_y = unit_scaling / model.fy();//内参矩阵中的 f/dy
  float bad_point = std::numeric_limits<float>::quiet_NaN();

  sensor_msgs::PointCloud2Iterator<float> iter_x(*cloud_msg, "x");
  sensor_msgs::PointCloud2Iterator<float> iter_y(*cloud_msg, "y");
  sensor_msgs::PointCloud2Iterator<float> iter_z(*cloud_msg, "z");
  const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
  int row_step = depth_msg->step / sizeof(T);
  for (int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step)
  {
    for (int u = 0; u < (int)cloud_msg->width; ++u, ++iter_x, ++iter_y, ++iter_z)
    {
      T depth = depth_row[u];

      // Missing points denoted by NaNs
      if (!DepthTraits<T>::valid(depth))
      {
        if (range_max != 0.0)
        {
          depth = DepthTraits<T>::fromMeters(range_max);
        }
        else
        {
          *iter_x = *iter_y = *iter_z = bad_point;
          continue;
        }
      }

      // Fill in XYZ
      *iter_x = (u - center_x) * depth * constant_x;//这句话计算的原理是什么,通过内外参数矩阵可以计算
      *iter_y = (v - center_y) * depth * constant_y;//这句话计算的原理是什么,通过内外参数矩阵可以计算
      *iter_z = DepthTraits<T>::toMeters(depth);
    }
  }
}

} // namespace depth_image_proc

#endif

 

posted @ 2016-07-29 18:10  horsetail  阅读(39202)  评论(2编辑  收藏  举报