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/OdometryF2M.h>
00029 #include "rtabmap/core/Rtabmap.h"
00030 #include "rtabmap/core/RtabmapThread.h"
00031 #include "rtabmap/core/CameraRGBD.h"
00032 #include "rtabmap/core/CameraStereo.h"
00033 #include "rtabmap/core/CameraThread.h"
00034 #include "rtabmap/core/OdometryThread.h"
00035 #include "rtabmap/core/Graph.h"
00036 #include "rtabmap/utilite/UEventsManager.h"
00037 #include <QApplication>
00038 #include <stdio.h>
00039 #include <pcl/io/pcd_io.h>
00040 #include <pcl/io/ply_io.h>
00041 #include <pcl/filters/filter.h>
00042
00043 #include "MapBuilder.h"
00044
00045 void showUsage()
00046 {
00047 printf("\nUsage:\n"
00048 "rtabmap-rgbd_mapping driver\n"
00049 " driver Driver number to use: 0=OpenNI-PCL, 1=OpenNI2, 2=Freenect, 3=OpenNI-CV, 4=OpenNI-CV-ASUS, 5=Freenect2, 6=ZED SDK, 7=RealSense, 8=RealSense2\n\n");
00050 exit(1);
00051 }
00052
00053 using namespace rtabmap;
00054 int main(int argc, char * argv[])
00055 {
00056 ULogger::setType(ULogger::kTypeConsole);
00057 ULogger::setLevel(ULogger::kWarning);
00058
00059 int driver = 0;
00060 if(argc < 2)
00061 {
00062 showUsage();
00063 }
00064 else
00065 {
00066 driver = atoi(argv[argc-1]);
00067 if(driver < 0 || driver > 8)
00068 {
00069 UERROR("driver should be between 0 and 8.");
00070 showUsage();
00071 }
00072 }
00073
00074
00075
00076
00077
00078
00079 Camera * camera = 0;
00080 Transform opticalRotation(0,0,1,0, -1,0,0,0, 0,-1,0,0);
00081 if(driver == 1)
00082 {
00083 if(!CameraOpenNI2::available())
00084 {
00085 UERROR("Not built with OpenNI2 support...");
00086 exit(-1);
00087 }
00088 camera = new CameraOpenNI2("", CameraOpenNI2::kTypeColorDepth, 0, opticalRotation);
00089 }
00090 else if(driver == 2)
00091 {
00092 if(!CameraFreenect::available())
00093 {
00094 UERROR("Not built with Freenect support...");
00095 exit(-1);
00096 }
00097 camera = new CameraFreenect(0, CameraFreenect::kTypeColorDepth, 0, opticalRotation);
00098 }
00099 else if(driver == 3)
00100 {
00101 if(!CameraOpenNICV::available())
00102 {
00103 UERROR("Not built with OpenNI from OpenCV support...");
00104 exit(-1);
00105 }
00106 camera = new CameraOpenNICV(false, 0, opticalRotation);
00107 }
00108 else if(driver == 4)
00109 {
00110 if(!CameraOpenNICV::available())
00111 {
00112 UERROR("Not built with OpenNI from OpenCV support...");
00113 exit(-1);
00114 }
00115 camera = new CameraOpenNICV(true, 0, opticalRotation);
00116 }
00117 else if (driver == 5)
00118 {
00119 if (!CameraFreenect2::available())
00120 {
00121 UERROR("Not built with Freenect2 support...");
00122 exit(-1);
00123 }
00124 camera = new CameraFreenect2(0, CameraFreenect2::kTypeColor2DepthSD, 0, opticalRotation);
00125 }
00126 else if (driver == 6)
00127 {
00128 if (!CameraStereoZed::available())
00129 {
00130 UERROR("Not built with ZED SDK support...");
00131 exit(-1);
00132 }
00133 camera = new CameraStereoZed(0, 2, 1, 1, 100, false, 0, opticalRotation);
00134 }
00135 else if (driver == 7)
00136 {
00137 if (!CameraRealSense::available())
00138 {
00139 UERROR("Not built with RealSense support...");
00140 exit(-1);
00141 }
00142 camera = new CameraRealSense(0, 0, 0, false, 0, opticalRotation);
00143 }
00144 else if (driver == 8)
00145 {
00146 if (!CameraRealSense2::available())
00147 {
00148 UERROR("Not built with RealSense2 support...");
00149 exit(-1);
00150 }
00151 camera = new CameraRealSense2("", 0, opticalRotation);
00152 }
00153 else
00154 {
00155 camera = new rtabmap::CameraOpenni("", 0, opticalRotation);
00156 }
00157
00158 if(!camera->init())
00159 {
00160 UERROR("Camera init failed!");
00161 }
00162
00163 CameraThread cameraThread(camera);
00164
00165
00166
00167
00168 QApplication app(argc, argv);
00169 MapBuilder mapBuilder(&cameraThread);
00170
00171
00172 OdometryThread odomThread(new OdometryF2M());
00173
00174
00175 ParametersMap params;
00176
00177
00178
00179 Rtabmap * rtabmap = new Rtabmap();
00180 rtabmap->init(params);
00181 RtabmapThread rtabmapThread(rtabmap);
00182
00183
00184 odomThread.registerToEventsManager();
00185 rtabmapThread.registerToEventsManager();
00186 mapBuilder.registerToEventsManager();
00187
00188
00189
00190
00191
00192
00193
00194 UEventsManager::createPipe(&cameraThread, &odomThread, "CameraEvent");
00195
00196
00197 rtabmapThread.start();
00198 odomThread.start();
00199 cameraThread.start();
00200
00201 mapBuilder.show();
00202 app.exec();
00203
00204
00205 mapBuilder.unregisterFromEventsManager();
00206 rtabmapThread.unregisterFromEventsManager();
00207 odomThread.unregisterFromEventsManager();
00208
00209
00210 cameraThread.kill();
00211 odomThread.join(true);
00212 rtabmapThread.join(true);
00213
00214
00215 printf("Saving rtabmap_cloud.pcd...\n");
00216 std::map<int, Signature> nodes;
00217 std::map<int, Transform> optimizedPoses;
00218 std::multimap<int, Link> links;
00219 rtabmap->get3DMap(nodes, optimizedPoses, links, true, true);
00220 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
00221 for(std::map<int, Transform>::iterator iter=optimizedPoses.begin(); iter!=optimizedPoses.end(); ++iter)
00222 {
00223 Signature node = nodes.find(iter->first)->second;
00224
00225
00226 node.sensorData().uncompressData();
00227
00228 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp = util3d::cloudRGBFromSensorData(
00229 node.sensorData(),
00230 4,
00231 4.0f,
00232 0.0f);
00233 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmpNoNaN(new pcl::PointCloud<pcl::PointXYZRGB>);
00234 std::vector<int> index;
00235 pcl::removeNaNFromPointCloud(*tmp, *tmpNoNaN, index);
00236 if(!tmpNoNaN->empty())
00237 {
00238 *cloud += *util3d::transformPointCloud(tmpNoNaN, iter->second);
00239 }
00240 }
00241 if(cloud->size())
00242 {
00243 printf("Voxel grid filtering of the assembled cloud (voxel=%f, %d points)\n", 0.01f, (int)cloud->size());
00244 cloud = util3d::voxelize(cloud, 0.01f);
00245
00246 printf("Saving rtabmap_cloud.pcd... done! (%d points)\n", (int)cloud->size());
00247 pcl::io::savePCDFile("rtabmap_cloud.pcd", *cloud);
00248
00249 }
00250 else
00251 {
00252 printf("Saving rtabmap_cloud.pcd... failed! The cloud is empty.\n");
00253 }
00254
00255
00256 printf("Saving rtabmap_trajectory.txt ...\n");
00257 if(optimizedPoses.size() && graph::exportPoses("rtabmap_trajectory.txt", 0, optimizedPoses, links))
00258 {
00259 printf("Saving rtabmap_trajectory.txt... done!\n");
00260 }
00261 else
00262 {
00263 printf("Saving rtabmap_trajectory.txt... failed!\n");
00264 }
00265
00266 rtabmap->close(false);
00267
00268 return 0;
00269 }