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