第二講 從圖像到點雲
本講中,我們將帶領讀者,編寫一個將圖像轉換爲點雲的程序。該程序是後期處理地圖的基礎。最簡單的點雲地圖即是把不同位置的點雲進行拼接得到的。
當我們使用RGB-D相機時,會從相機裏讀到兩種數據:彩色圖像和深度圖像。如果你有Kinect和ros,可以運行:
1 roslaunch openni_launch openni.launch
使Kinect工作。隨後,如果PC連接上了Kinect,彩色圖像與深度圖像就會發布在 /camera/rgb/image_color 和 /camera/depth_registered/image_raw 中。你可以通過:
1 rosrun image_view image_view image:=/camera/rgb/image_color
來顯示彩色圖像。或者,你也可以在Rviz裏看到圖像與點雲的可視化數據。
小蘿蔔:可是師兄!我現在手邊沒有Kinect,該怎麼辦啊!
師兄:沒關係!你可以下載我們給你提供的數據。實際上就是下面兩張圖片啦!
小蘿蔔:怎麼深度圖是一團黑的呀!
師兄:請睜大眼睛仔細看!怎麼可能是黑的!
小蘿蔔:呃……可是確實是黑的啊!
師兄:對!這是由於畫面裏的物體離我們比較近,所以看上去比較黑。但是你實際去讀的話可是有數據的哦!
重要的備註:
- 這兩張圖來自於nyuv2數據集:http://cs.nyu.edu/~silberman/datasets/ 原圖格式是ppm和pgm的,被我轉成了png格式(否則博客園不讓傳……)。
- 你可以直接另存爲這兩個圖,也可以到我的git裏面獲取這兩個圖。
- 實際Kinect裏(或其他rgb-d相機裏)直接採到的RGB圖和深度圖可能會有些小問題:
- 有一些時差(約幾到十幾個毫秒)。這個時差的存在,會產生“RGB圖已經向右轉了,怎麼深度圖還沒轉”的感覺哦。
- 光圈中心未對齊。因爲深度畢竟是靠另一個相機獲取的,所以深度傳感器和彩色傳感器參數可能不一致。
- 深度圖裏有很多“洞”。因爲RGB-D相機不是萬能的,它有一個探測距離的限制啦!太遠或太近的東西都是看不見的呢。關於這些“洞”,我們暫時睜一隻眼閉一隻眼,不去理它。以後我們也可以靠雙邊bayes濾波器去填這些洞。但是!這是RGB-D相機本身的侷限性。軟件算法頂多給它修修補補,並不能完全彌補它的缺陷。
不過請你放心,在我們給出的這兩個圖中,都進行了預處理。你可以認爲“深度圖就是彩色圖裏每個像素距傳感器的距離”啦!
師兄:現在,我們要把這兩個圖轉成點雲啦,因爲計算每個像素的空間點位置,可是後面配準、拼圖等一系列事情的基礎呢。比如,在配準時,必須知道特徵點的3D位置呢,這時候就要用到我們這裏講到的知識啦!
小蘿蔔:聽起來很重要的樣子!
師兄:對!所以請讀者朋友務必掌握好這部分的內容啦!
從2D到3D(數學部分)
上面兩個圖像給出了機器人外部世界的一個局部的信息。假設這個世界由一個點雲來描述:X={x1,…,xn}
對於常規相機,SLAM裏使用針孔相機模型(圖來自http://www.comp.nus.edu.sg/~cs4243/lecture/camera.pdf ):
其中,fx,fy指相機在x,y兩個軸上的焦距,cx,cy指相機的光圈中心,s指深度圖的縮放因子。
小蘿蔔:好暈啊!突然冒出這麼多個變量!
師兄:別急啊,這已經是很簡單的模型了,等你熟悉了就不覺得複雜了。
這個公式是從(x,y,z)推到(u,v,d)的。反之,我們也可以把它寫成已知(u,v,d),推導(x,y,z)的方式。請讀者自己推導一下。
不,還是我們來推導吧……公式是這樣的:
怎麼樣,是不是很簡單呢?事實上根據這個公式就可以構建點雲啦。
通常,我們會把fx,fy,cx,cy這四個參數定義爲相機的內參矩陣C,也就是相機做好之後就不會變的參數。相機的內參可以用很多方法來標定,詳細的步驟比較繁瑣,我們這裏就不提了。給定內參之後呢,每個點的空間位置與像素座標就可以用簡單的矩陣模型來描述了:
其中,R和t是相機的姿態。R代表旋轉矩陣,t代表位移矢量。因爲我們現在做的是單幅點雲,認爲相機沒有旋轉和平移。所以,把R設成單位矩陣I,把t設成了零。s是scaling factor,即深度圖裏給的數據與實際距離的比例。由於深度圖給的都是short (mm單位),s通常爲1000。
小蘿蔔:於是就有了上面那個(u,v,d)轉(x,y,z)的公式?
師兄:對!真聰明!如果相機發生了位移和旋轉,那麼只要對這些點進行位移和旋轉操作即可。
從2D到3D (編程部分)
下面,我們來實現一個程序,完成從圖像到點雲的轉換。請在上一節講到的 代碼根目錄/src/ 文件夾中新建一個generatePointCloud.cpp文件:
1 touch src/generatePointCloud.cpp
小蘿蔔:師兄!一個工程裏可以有好幾個main函數麼?
師兄:對呀,cmake允許你自己定義編譯的過程。我們會把這個cpp也編譯成一個可執行的二進制,只要在cmakelists.txt裏作相應的更改便行了。
接下來,請在剛建的文件裏輸入下面的代碼。爲保證行文的連貫性,我們先給出完整的代碼,然後在重要的地方加以解釋。建議新手逐字自己敲一遍,你會掌握得更牢固。
1 // C++ 標準庫 2 #include <iostream> 3 #include <string> 4 using namespace std; 5 6 // OpenCV 庫 7 #include <opencv2/core/core.hpp> 8 #include <opencv2/highgui/highgui.hpp> 9 10 // PCL 庫 11 #include <pcl/io/pcd_io.h> 12 #include <pcl/point_types.h> 13 14 // 定義點雲類型 15 typedef pcl::PointXYZRGBA PointT; 16 typedef pcl::PointCloud<PointT> PointCloud; 17 18 // 相機內參 19 const double camera_factor = 1000; 20 const double camera_cx = 325.5; 21 const double camera_cy = 253.5; 22 const double camera_fx = 518.0; 23 const double camera_fy = 519.0; 24 25 // 主函數 26 int main( int argc, char** argv ) 27 { 28 // 讀取./data/rgb.png和./data/depth.png,並轉化爲點雲 29 30 // 圖像矩陣 31 cv::Mat rgb, depth; 32 // 使用cv::imread()來讀取圖像 33 // API: http://docs.opencv.org/modules/highgui/doc/reading_and_writing_images_and_video.html?highlight=imread#cv2.imread 34 rgb = cv::imread( "./data/rgb.png" ); 35 // rgb 圖像是8UC3的彩色圖像 36 // depth 是16UC1的單通道圖像,注意flags設置-1,表示讀取原始數據不做任何修改 37 depth = cv::imread( "./data/depth.png", -1 ); 38 39 // 點雲變量 40 // 使用智能指針,創建一個空點雲。這種指針用完會自動釋放。 41 PointCloud::Ptr cloud ( new PointCloud ); 42 // 遍歷深度圖 43 for (int m = 0; m < depth.rows; m++) 44 for (int n=0; n < depth.cols; n++) 45 { 46 // 獲取深度圖中(m,n)處的值 47 ushort d = depth.ptr<ushort>(m)[n]; 48 // d 可能沒有值,若如此,跳過此點 49 if (d == 0) 50 continue; 51 // d 存在值,則向點雲增加一個點 52 PointT p; 53 54 // 計算這個點的空間座標 55 p.z = double(d) / camera_factor; 56 p.x = (n - camera_cx) * p.z / camera_fx; 57 p.y = (m - camera_cy) * p.z / camera_fy; 58 59 // 從rgb圖像中獲取它的顏色 60 // rgb是三通道的BGR格式圖,所以按下面的順序獲取顏色 61 p.b = rgb.ptr<uchar>(m)[n*3]; 62 p.g = rgb.ptr<uchar>(m)[n*3+1]; 63 p.r = rgb.ptr<uchar>(m)[n*3+2]; 64 65 // 把p加入到點雲中 66 cloud->points.push_back( p ); 67 } 68 // 設置並保存點雲 69 cloud->height = 1; 70 cloud->width = cloud->points.size(); 71 cout<<"point cloud size = "<<cloud->points.size()<<endl; 72 cloud->is_dense = false; 73 pcl::io::savePCDFile( "./data/pointcloud.pcd", *cloud ); 74 // 清除數據並退出 75 cloud->points.clear(); 76 cout<<"Point cloud saved."<<endl; 77 return 0; 78 }
程序運行需要數據。請把上面的那兩個圖存放在 代碼根目錄/data 下(沒有這個文件夾就新建一個)。
我們使用OpenCV的imread函數讀取圖片。在OpenCV2裏,圖像是以矩陣(cv::MAt)作爲基本的數據結構。Mat結構既可以幫你管理內存、像素信息,還支持一些常見的矩陣運算,是非常方便的結構。彩色圖像含有R,G,B三個通道,每個通道佔8個bit(也就是unsigned char),故稱爲8UC3(8位unsigend char, 3通道)結構。而深度圖則是單通道的圖像,每個像素由16個bit組成(也就是C++裏的unsigned short),像素的值代表該點離傳感器的距離。通常1000的值代表1米,所以我們把camera_factor設置成1000. 這樣,深度圖裏每個像素點的讀數除以1000,就是它離你的真實距離了。
接下來,我們按照“先列後行”的順序,遍歷了整張深度圖。在這個雙重循環中:
1 for (int m = 0; m < depth.rows; m++) 2 for (int n=0; n < depth.cols; n++)
m指圖像的行,n是圖像的列。它和空間點的座標系關係是這樣的:
深度圖第m行,第n行的數據可以使用depth.ptr<ushort>(m) [n]來獲取。其中,cv::Mat的ptr函數會返回指向該圖像第m行數據的頭指針。然後加上位移n後,這個指針指向的數據就是我們需要讀取的數據啦。
計算三維點座標的公式我們已經給出過了,代碼裏原封不動地實現了一遍。我們根據這個公式,新增了一個空間點,並放入了點雲中。最後,把整個點雲存儲爲 ./data/pointcloud.pcd 文件。
編譯並運行
最後,我們在src/CMakeLists.txt里加入幾行代碼,告訴編譯器我們希望編譯這個程序。請在此文件中加入以下幾行:
# 增加PCL庫的依賴
FIND_PACKAGE( PCL REQUIRED COMPONENTS common io )
然後,編譯新的工程:
1 cd build 2 cmake .. 3 make 4 cd ..
如果編譯通過,就可在bin目錄下找到新寫的二進制:generate_pointcloud 運行它:
bin/generate_pointcloud
即可在data目錄下生成點雲文件。現在,你肯定希望查看一下新生成的點雲了。如果已經安裝了pcl,就可以通過:
1 pcl_viewer data/pointcloud.pcd
來查看新生成的點雲。
課後作業
本講中,我們實現了一個從2D圖像到3D點雲的轉換程序。下一講,我們將探討圖像的特徵點提取與配準。配準過程中,我們需要計算2D圖像特徵點的空間位置。因此,請你編寫一個頭文件與一個源文件,實現一個point2dTo3d函數。請在頭文件裏寫這個函數的聲明,源文件裏給出它的實現,並在cmake中把它編譯成一個叫做slam_base的庫。(你需要考慮如何定義一個比較好的接口。)這樣一來,今後當我們需要計算它時,就只需調用這個函數就可以了。
小蘿蔔:師兄!這個作業看起來有些難度啊!
師兄:是呀,不能把讀者想的太簡單嘛。
最後呢,本節用到的源代碼仍然可以從我的Git裏下載到。如果您關於本文有什麼問題,也歡迎給我發郵件:[email protected] 讀者的鼓勵就是對我最好的支持!