深度圖轉點雲原理


深度圖轉點雲的計算過程很簡潔,而里面的原理是根據內外參矩陣變換公式得到,下面來介紹其推導的過程。

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

 


免責聲明!

本站轉載的文章為個人學習借鑒使用,本站對版權不負任何法律責任。如果侵犯了您的隱私權益,請聯系本站郵箱yoyou2525@163.com刪除。



 
粵ICP備18138465號   © 2018-2025 CODEPRJ.COM