examples/RGBDMapping/main.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
29 #include "rtabmap/core/Rtabmap.h"
35 #include "rtabmap/core/Graph.h"
37 #include <QApplication>
38 #include <stdio.h>
39 #include <pcl/io/pcd_io.h>
40 #include <pcl/io/ply_io.h>
41 #include <pcl/filters/filter.h>
42 
43 #include "MapBuilder.h"
44 
45 void showUsage()
46 {
47  printf("\nUsage:\n"
48  "rtabmap-rgbd_mapping driver\n"
49  " 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");
50  exit(1);
51 }
52 
53 using namespace rtabmap;
54 int main(int argc, char * argv[])
55 {
58 
59  int driver = 0;
60  if(argc < 2)
61  {
62  showUsage();
63  }
64  else
65  {
66  driver = atoi(argv[argc-1]);
67  if(driver < 0 || driver > 8)
68  {
69  UERROR("driver should be between 0 and 8.");
70  showUsage();
71  }
72  }
73 
74  // Here is the pipeline that we will use:
75  // CameraOpenni -> "CameraEvent" -> OdometryThread -> "OdometryEvent" -> RtabmapThread -> "RtabmapEvent"
76 
77  // Create the OpenNI camera, it will send a CameraEvent at the rate specified.
78  // Set transform to camera so z is up, y is left and x going forward
79  Camera * camera = 0;
80  Transform opticalRotation(0,0,1,0, -1,0,0,0, 0,-1,0,0);
81  if(driver == 1)
82  {
84  {
85  UERROR("Not built with OpenNI2 support...");
86  exit(-1);
87  }
88  camera = new CameraOpenNI2("", CameraOpenNI2::kTypeColorDepth, 0, opticalRotation);
89  }
90  else if(driver == 2)
91  {
93  {
94  UERROR("Not built with Freenect support...");
95  exit(-1);
96  }
97  camera = new CameraFreenect(0, CameraFreenect::kTypeColorDepth, 0, opticalRotation);
98  }
99  else if(driver == 3)
100  {
102  {
103  UERROR("Not built with OpenNI from OpenCV support...");
104  exit(-1);
105  }
106  camera = new CameraOpenNICV(false, 0, opticalRotation);
107  }
108  else if(driver == 4)
109  {
111  {
112  UERROR("Not built with OpenNI from OpenCV support...");
113  exit(-1);
114  }
115  camera = new CameraOpenNICV(true, 0, opticalRotation);
116  }
117  else if (driver == 5)
118  {
120  {
121  UERROR("Not built with Freenect2 support...");
122  exit(-1);
123  }
124  camera = new CameraFreenect2(0, CameraFreenect2::kTypeColor2DepthSD, 0, opticalRotation);
125  }
126  else if (driver == 6)
127  {
129  {
130  UERROR("Not built with ZED SDK support...");
131  exit(-1);
132  }
133  camera = new CameraStereoZed(0, 2, 1, 1, 100, false, 0, opticalRotation);
134  }
135  else if (driver == 7)
136  {
138  {
139  UERROR("Not built with RealSense support...");
140  exit(-1);
141  }
142  camera = new CameraRealSense(0, 0, 0, false, 0, opticalRotation);
143  }
144  else if (driver == 8)
145  {
147  {
148  UERROR("Not built with RealSense2 support...");
149  exit(-1);
150  }
151  camera = new CameraRealSense2("", 0, opticalRotation);
152  }
153  else
154  {
155  camera = new rtabmap::CameraOpenni("", 0, opticalRotation);
156  }
157 
158  if(!camera->init())
159  {
160  UERROR("Camera init failed!");
161  }
162 
163  CameraThread cameraThread(camera);
164 
165 
166  // GUI stuff, there the handler will receive RtabmapEvent and construct the map
167  // We give it the camera so the GUI can pause/resume the camera
168  QApplication app(argc, argv);
169  MapBuilder mapBuilder(&cameraThread);
170 
171  // Create an odometry thread to process camera events, it will send OdometryEvent.
172  OdometryThread odomThread(new OdometryF2M());
173 
174 
175  ParametersMap params;
176  //param.insert(ParametersPair(Parameters::kRGBDCreateOccupancyGrid(), "true")); // uncomment to create local occupancy grids
177 
178  // Create RTAB-Map to process OdometryEvent
179  Rtabmap * rtabmap = new Rtabmap();
180  rtabmap->init(params);
181  RtabmapThread rtabmapThread(rtabmap); // ownership is transfered
182 
183  // Setup handlers
184  odomThread.registerToEventsManager();
185  rtabmapThread.registerToEventsManager();
186  mapBuilder.registerToEventsManager();
187 
188  // The RTAB-Map is subscribed by default to CameraEvent, but we want
189  // RTAB-Map to process OdometryEvent instead, ignoring the CameraEvent.
190  // We can do that by creating a "pipe" between the camera and odometry, then
191  // only the odometry will receive CameraEvent from that camera. RTAB-Map is
192  // also subscribed to OdometryEvent by default, so no need to create a pipe between
193  // odometry and RTAB-Map.
194  UEventsManager::createPipe(&cameraThread, &odomThread, "CameraEvent");
195 
196  // Let's start the threads
197  rtabmapThread.start();
198  odomThread.start();
199  cameraThread.start();
200 
201  mapBuilder.show();
202  app.exec(); // main loop
203 
204  // remove handlers
205  mapBuilder.unregisterFromEventsManager();
206  rtabmapThread.unregisterFromEventsManager();
207  odomThread.unregisterFromEventsManager();
208 
209  // Kill all threads
210  cameraThread.kill();
211  odomThread.join(true);
212  rtabmapThread.join(true);
213 
214  // Save 3D map
215  printf("Saving rtabmap_cloud.pcd...\n");
216  std::map<int, Signature> nodes;
217  std::map<int, Transform> optimizedPoses;
218  std::multimap<int, Link> links;
219  rtabmap->get3DMap(nodes, optimizedPoses, links, true, true);
220  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
221  for(std::map<int, Transform>::iterator iter=optimizedPoses.begin(); iter!=optimizedPoses.end(); ++iter)
222  {
223  Signature node = nodes.find(iter->first)->second;
224 
225  // uncompress data
226  node.sensorData().uncompressData();
227 
228  pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp = util3d::cloudRGBFromSensorData(
229  node.sensorData(),
230  4, // image decimation before creating the clouds
231  4.0f, // maximum depth of the cloud
232  0.0f);
233  pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmpNoNaN(new pcl::PointCloud<pcl::PointXYZRGB>);
234  std::vector<int> index;
235  pcl::removeNaNFromPointCloud(*tmp, *tmpNoNaN, index);
236  if(!tmpNoNaN->empty())
237  {
238  *cloud += *util3d::transformPointCloud(tmpNoNaN, iter->second); // transform the point cloud to its pose
239  }
240  }
241  if(cloud->size())
242  {
243  printf("Voxel grid filtering of the assembled cloud (voxel=%f, %d points)\n", 0.01f, (int)cloud->size());
244  cloud = util3d::voxelize(cloud, 0.01f);
245 
246  printf("Saving rtabmap_cloud.pcd... done! (%d points)\n", (int)cloud->size());
247  pcl::io::savePCDFile("rtabmap_cloud.pcd", *cloud);
248  //pcl::io::savePLYFile("rtabmap_cloud.ply", *cloud); // to save in PLY format
249  }
250  else
251  {
252  printf("Saving rtabmap_cloud.pcd... failed! The cloud is empty.\n");
253  }
254 
255  // Save trajectory
256  printf("Saving rtabmap_trajectory.txt ...\n");
257  if(optimizedPoses.size() && graph::exportPoses("rtabmap_trajectory.txt", 0, optimizedPoses, links))
258  {
259  printf("Saving rtabmap_trajectory.txt... done!\n");
260  }
261  else
262  {
263  printf("Saving rtabmap_trajectory.txt... failed!\n");
264  }
265 
266  rtabmap->close(false);
267 
268  return 0;
269 }
void get3DMap(std::map< int, Signature > &signatures, std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global) const
Definition: Rtabmap.cpp:3670
bool RTABMAP_EXP exportPoses(const std::string &filePath, int format, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints=std::multimap< int, Link >(), const std::map< int, double > &stamps=std::map< int, double >(), bool g2oRobust=false)
Definition: Graph.cpp:53
static void createPipe(const UEventsSender *sender, const UEventsHandler *receiver, const std::string &eventName)
void start()
Definition: UThread.cpp:122
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
f
void kill()
Definition: UThread.cpp:48
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
void showUsage()
static bool available()
Definition: CameraRGBD.cpp:382
static void setLevel(ULogger::Level level)
Definition: ULogger.h:339
static rtabmap::Transform opticalRotation(1.0f, 0.0f, 0.0f, 0.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f,-1.0f, 0.0f)
static bool available()
Definition: CameraRGBD.cpp:272
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
void close(bool databaseSaved=true, const std::string &ouputDatabasePath="")
Definition: Rtabmap.cpp:348
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
Definition: util3d.cpp:1031
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
Definition: ULogger.cpp:176
int main(int argc, char *argv[])
static RTABMapApp app
void init(const ParametersMap &parameters, const std::string &databasePath="")
Definition: Rtabmap.cpp:282
void registerToEventsManager()
SensorData & sensorData()
Definition: Signature.h:134
#define UERROR(...)
void unregisterFromEventsManager()
void join(bool killFirst=false)
Definition: UThread.cpp:85
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:31