00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "rtabmap/core/CameraRGBD.h"
00029 #include "rtabmap/core/util3d.h"
00030 #include "rtabmap/utilite/ULogger.h"
00031 #include <opencv2/highgui/highgui.hpp>
00032 #include <opencv2/imgproc/imgproc.hpp>
00033 #include <pcl/visualization/cloud_viewer.h>
00034 #include <stdio.h>
00035
00036 void showUsage()
00037 {
00038 printf("\nUsage:\n"
00039 "rtabmap-rgbd_camera driver\n"
00040 " driver Driver number to use: 0=OpenNI-PCL (Kinect)\n"
00041 " 1=OpenNI2 (Kinect and Xtion PRO Live)\n"
00042 " 2=Freenect (Kinect)\n"
00043 " 3=OpenNI-CV (Kinect)\n"
00044 " 4=OpenNI-CV-ASUS (Xtion PRO Live)\n"
00045 " 5=Freenect2 (Kinect v2)\n"
00046 " 6=DC1394 (Bumblebee2)\n"
00047 " 7=FlyCapture2 (Bumblebee2)\n");
00048 exit(1);
00049 }
00050
00051 int main(int argc, char * argv[])
00052 {
00053 ULogger::setType(ULogger::kTypeConsole);
00054 ULogger::setLevel(ULogger::kInfo);
00055
00056
00057
00058 int driver = 0;
00059 if(argc < 2)
00060 {
00061 showUsage();
00062 }
00063 else
00064 {
00065 if(strcmp(argv[argc-1], "--help") == 0)
00066 {
00067 showUsage();
00068 }
00069 driver = atoi(argv[argc-1]);
00070 if(driver < 0 || driver > 7)
00071 {
00072 UERROR("driver should be between 0 and 6.");
00073 showUsage();
00074 }
00075 }
00076 UINFO("Using driver %d", driver);
00077
00078 rtabmap::CameraRGBD * camera = 0;
00079 if(driver == 0)
00080 {
00081 camera = new rtabmap::CameraOpenni();
00082 }
00083 else if(driver == 1)
00084 {
00085 if(!rtabmap::CameraOpenNI2::available())
00086 {
00087 UERROR("Not built with OpenNI2 support...");
00088 exit(-1);
00089 }
00090 camera = new rtabmap::CameraOpenNI2();
00091 }
00092 else if(driver == 2)
00093 {
00094 if(!rtabmap::CameraFreenect::available())
00095 {
00096 UERROR("Not built with Freenect support...");
00097 exit(-1);
00098 }
00099 camera = new rtabmap::CameraFreenect();
00100 }
00101 else if(driver == 3)
00102 {
00103 if(!rtabmap::CameraOpenNICV::available())
00104 {
00105 UERROR("Not built with OpenNI from OpenCV support...");
00106 exit(-1);
00107 }
00108 camera = new rtabmap::CameraOpenNICV(false);
00109 }
00110 else if(driver == 4)
00111 {
00112 if(!rtabmap::CameraOpenNICV::available())
00113 {
00114 UERROR("Not built with OpenNI from OpenCV support...");
00115 exit(-1);
00116 }
00117 camera = new rtabmap::CameraOpenNICV(true);
00118 }
00119 else if(driver == 5)
00120 {
00121 if(!rtabmap::CameraFreenect2::available())
00122 {
00123 UERROR("Not built with Freenect2 support...");
00124 exit(-1);
00125 }
00126 camera = new rtabmap::CameraFreenect2(0, rtabmap::CameraFreenect2::kTypeRGBDepthSD);
00127 }
00128 else if(driver == 6)
00129 {
00130 if(!rtabmap::CameraStereoDC1394::available())
00131 {
00132 UERROR("Not built with DC1394 support...");
00133 exit(-1);
00134 }
00135 camera = new rtabmap::CameraStereoDC1394();
00136 }
00137 else if(driver == 7)
00138 {
00139 if(!rtabmap::CameraStereoFlyCapture2::available())
00140 {
00141 UERROR("Not built with FlyCapture2/Triclops support...");
00142 exit(-1);
00143 }
00144 camera = new rtabmap::CameraStereoFlyCapture2();
00145 }
00146 else
00147 {
00148 UFATAL("");
00149 }
00150
00151 if(!camera->init())
00152 {
00153 printf("Camera init failed! Please select another driver (see \"--help\").\n");
00154 delete camera;
00155 exit(1);
00156 }
00157 cv::Mat rgb, depth;
00158 float fx, fy, cx, cy;
00159 camera->takeImage(rgb, depth, fx, fy, cx, cy);
00160 if(rgb.cols != depth.cols || rgb.rows != depth.rows)
00161 {
00162 UWARN("RGB (%d/%d) and depth (%d/%d) frames are not the same size! The registered cloud cannot be shown.",
00163 rgb.cols, rgb.rows, depth.cols, depth.rows);
00164 }
00165 if(!fx || !fy)
00166 {
00167 UWARN("fx and/or fy are not set! The registered cloud cannot be shown.");
00168 }
00169 pcl::visualization::CloudViewer viewer("cloud");
00170 rtabmap::Transform t(1, 0, 0, 0,
00171 0, -1, 0, 0,
00172 0, 0, -1, 0);
00173 while(!rgb.empty() && !viewer.wasStopped())
00174 {
00175 if(depth.type() == CV_16UC1 || depth.type() == CV_32FC1)
00176 {
00177
00178 if(depth.type() == CV_32FC1)
00179 {
00180 depth = rtabmap::util3d::cvtDepthFromFloat(depth);
00181 }
00182
00183 if(rgb.cols == depth.cols && rgb.rows == depth.rows && fx && fy)
00184 {
00185 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = rtabmap::util3d::cloudFromDepthRGB(rgb, depth, cx, cy, fx, fy);
00186 cloud = rtabmap::util3d::transformPointCloud<pcl::PointXYZRGB>(cloud, t);
00187 viewer.showCloud(cloud, "cloud");
00188 }
00189 else if(!depth.empty() && fx && fy)
00190 {
00191 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = rtabmap::util3d::cloudFromDepth(depth, cx, cy, fx, fy);
00192 cloud = rtabmap::util3d::transformPointCloud<pcl::PointXYZ>(cloud, t);
00193 viewer.showCloud(cloud, "cloud");
00194 }
00195
00196 cv::Mat tmp;
00197 unsigned short min=0, max = 2048;
00198 uMinMax((unsigned short*)depth.data, depth.rows*depth.cols, min, max);
00199 depth.convertTo(tmp, CV_8UC1, 255.0/max);
00200
00201 cv::imshow("Video", rgb);
00202 cv::imshow("Depth", tmp);
00203 }
00204 else
00205 {
00206
00207 cv::imshow("Left", rgb);
00208 cv::imshow("Right", depth);
00209
00210 if(rgb.cols == depth.cols && rgb.rows == depth.rows && fx && fy)
00211 {
00212 if(depth.channels() == 3)
00213 {
00214 cv::cvtColor(depth, depth, CV_BGR2GRAY);
00215 }
00216 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = rtabmap::util3d::cloudFromStereoImages(rgb, depth, cx, cy, fx, fy);
00217 cloud = rtabmap::util3d::transformPointCloud<pcl::PointXYZRGB>(cloud, t);
00218 viewer.showCloud(cloud, "cloud");
00219 }
00220 }
00221
00222 int c = cv::waitKey(10);
00223 if(c == 27)
00224 break;
00225
00226 rgb = cv::Mat();
00227 depth = cv::Mat();
00228 camera->takeImage(rgb, depth, fx, fy, cx, cy);
00229 }
00230 cv::destroyWindow("Video");
00231 cv::destroyWindow("Depth");
00232 delete camera;
00233 return 0;
00234 }