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 
28 #include <rtabmap/core/Odometry.h>
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 #ifdef RTABMAP_PYTHON
45 #endif
46 
47 #include "MapBuilder.h"
48 
49 void showUsage()
50 {
51  printf("\nUsage:\n"
52  "rtabmap-rgbd_mapping driver\n"
53  " 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 9=Kinect for Azure SDK 10=MYNT EYE S\n\n");
54  exit(1);
55 }
56 
57 using namespace rtabmap;
58 int main(int argc, char * argv[])
59 {
62 
63 #ifdef RTABMAP_PYTHON
64  PythonInterface python; // Make sure we initialize python in main thread
65 #endif
66 
67  int driver = 0;
68  if(argc < 2)
69  {
70  showUsage();
71  }
72  else
73  {
74  driver = atoi(argv[argc-1]);
75  if(driver < 0 || driver > 10)
76  {
77  UERROR("driver should be between 0 and 10.");
78  showUsage();
79  }
80  }
81 
82  // Here is the pipeline that we will use:
83  // CameraOpenni -> "CameraEvent" -> OdometryThread -> "OdometryEvent" -> RtabmapThread -> "RtabmapEvent"
84 
85  // Create the OpenNI camera, it will send a CameraEvent at the rate specified.
86  // Set transform to camera so z is up, y is left and x going forward
87  Camera * camera = 0;
88  if(driver == 1)
89  {
91  {
92  UERROR("Not built with OpenNI2 support...");
93  exit(-1);
94  }
95  camera = new CameraOpenNI2();
96  }
97  else if(driver == 2)
98  {
100  {
101  UERROR("Not built with Freenect support...");
102  exit(-1);
103  }
104  camera = new CameraFreenect();
105  }
106  else if(driver == 3)
107  {
109  {
110  UERROR("Not built with OpenNI from OpenCV support...");
111  exit(-1);
112  }
113  camera = new CameraOpenNICV();
114  }
115  else if(driver == 4)
116  {
118  {
119  UERROR("Not built with OpenNI from OpenCV support...");
120  exit(-1);
121  }
122  camera = new CameraOpenNICV(true);
123  }
124  else if (driver == 5)
125  {
127  {
128  UERROR("Not built with Freenect2 support...");
129  exit(-1);
130  }
132  }
133  else if (driver == 6)
134  {
136  {
137  UERROR("Not built with ZED SDK support...");
138  exit(-1);
139  }
140  camera = new CameraStereoZed(0, 2, 1, 1, 100, false);
141  }
142  else if (driver == 7)
143  {
145  {
146  UERROR("Not built with RealSense support...");
147  exit(-1);
148  }
149  camera = new CameraRealSense();
150  }
151  else if (driver == 8)
152  {
154  {
155  UERROR("Not built with RealSense2 support...");
156  exit(-1);
157  }
158  camera = new CameraRealSense2();
159  }
160  else if (driver == 9)
161  {
163  {
164  UERROR("Not built with Kinect for Azure SDK support...");
165  exit(-1);
166  }
167  camera = new rtabmap::CameraK4A(1);
168  }
169  else if (driver == 10)
170  {
172  {
173  UERROR("Not built with Mynt Eye S support...");
174  exit(-1);
175  }
176  camera = new rtabmap::CameraMyntEye();
177  }
178  else
179  {
180  camera = new rtabmap::CameraOpenni();
181  }
182 
183  if(!camera->init())
184  {
185  UERROR("Camera init failed!");
186  }
187 
188  CameraThread cameraThread(camera);
189 
190 
191  // GUI stuff, there the handler will receive RtabmapEvent and construct the map
192  // We give it the camera so the GUI can pause/resume the camera
193  QApplication app(argc, argv);
194  MapBuilder mapBuilder(&cameraThread);
195 
196  // Create an odometry thread to process camera events, it will send OdometryEvent.
197  OdometryThread odomThread(Odometry::create());
198 
199 
201  //param.insert(ParametersPair(Parameters::kRGBDCreateOccupancyGrid(), "true")); // uncomment to create local occupancy grids
202 
203  // Create RTAB-Map to process OdometryEvent
204  Rtabmap * rtabmap = new Rtabmap();
205  rtabmap->init(params);
206  RtabmapThread rtabmapThread(rtabmap); // ownership is transfered
207 
208  // Setup handlers
209  odomThread.registerToEventsManager();
210  rtabmapThread.registerToEventsManager();
211  mapBuilder.registerToEventsManager();
212 
213  // The RTAB-Map is subscribed by default to CameraEvent, but we want
214  // RTAB-Map to process OdometryEvent instead, ignoring the CameraEvent.
215  // We can do that by creating a "pipe" between the camera and odometry, then
216  // only the odometry will receive CameraEvent from that camera. RTAB-Map is
217  // also subscribed to OdometryEvent by default, so no need to create a pipe between
218  // odometry and RTAB-Map.
219  UEventsManager::createPipe(&cameraThread, &odomThread, "CameraEvent");
220 
221  // Let's start the threads
222  rtabmapThread.start();
223  odomThread.start();
224  cameraThread.start();
225 
226  mapBuilder.show();
227  app.exec(); // main loop
228 
229  // remove handlers
230  mapBuilder.unregisterFromEventsManager();
231  rtabmapThread.unregisterFromEventsManager();
232  odomThread.unregisterFromEventsManager();
233 
234  // Kill all threads
235  cameraThread.kill();
236  odomThread.join(true);
237  rtabmapThread.join(true);
238 
239  // Save 3D map
240  printf("Saving rtabmap_cloud.pcd...\n");
241  std::map<int, Signature> nodes;
242  std::map<int, Transform> optimizedPoses;
243  std::multimap<int, Link> links;
244  rtabmap->getGraph(optimizedPoses, links, true, true, &nodes, true, true, true, true);
245  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
246  for(std::map<int, Transform>::iterator iter=optimizedPoses.begin(); iter!=optimizedPoses.end(); ++iter)
247  {
248  Signature node = nodes.find(iter->first)->second;
249 
250  // uncompress data
251  node.sensorData().uncompressData();
252 
253  pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp = util3d::cloudRGBFromSensorData(
254  node.sensorData(),
255  4, // image decimation before creating the clouds
256  4.0f, // maximum depth of the cloud
257  0.0f);
258  pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmpNoNaN(new pcl::PointCloud<pcl::PointXYZRGB>);
259  std::vector<int> index;
260  pcl::removeNaNFromPointCloud(*tmp, *tmpNoNaN, index);
261  if(!tmpNoNaN->empty())
262  {
263  *cloud += *util3d::transformPointCloud(tmpNoNaN, iter->second); // transform the point cloud to its pose
264  }
265  }
266  if(cloud->size())
267  {
268  printf("Voxel grid filtering of the assembled cloud (voxel=%f, %d points)\n", 0.01f, (int)cloud->size());
269  cloud = util3d::voxelize(cloud, 0.01f);
270 
271  printf("Saving rtabmap_cloud.pcd... done! (%d points)\n", (int)cloud->size());
272  pcl::io::savePCDFile("rtabmap_cloud.pcd", *cloud);
273  //pcl::io::savePLYFile("rtabmap_cloud.ply", *cloud); // to save in PLY format
274  }
275  else
276  {
277  printf("Saving rtabmap_cloud.pcd... failed! The cloud is empty.\n");
278  }
279 
280  // Save trajectory
281  printf("Saving rtabmap_trajectory.txt ...\n");
282  if(optimizedPoses.size() && graph::exportPoses("rtabmap_trajectory.txt", 0, optimizedPoses, links))
283  {
284  printf("Saving rtabmap_trajectory.txt... done!\n");
285  }
286  else
287  {
288  printf("Saving rtabmap_trajectory.txt... failed!\n");
289  }
290 
291  rtabmap->close(false);
292 
293  return 0;
294 }
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:43
void showUsage()
void init(const ParametersMap &parameters, const std::string &databasePath="", bool loadDatabaseParameters=false)
Definition: Rtabmap.cpp:310
static void setLevel(ULogger::Level level)
Definition: ULogger.h:339
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
void close(bool databaseSaved=true, const std::string &ouputDatabasePath="")
Definition: Rtabmap.cpp:453
static Odometry * create(const ParametersMap &parameters=ParametersMap())
Definition: Odometry.cpp:57
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:1056
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
Definition: ULogger.cpp:176
int main(int argc, char *argv[])
params
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 >(), const ParametersMap &parameters=ParametersMap())
Definition: Graph.cpp:54
void registerToEventsManager()
QApplication * app
SensorData & sensorData()
Definition: Signature.h:137
#define UERROR(...)
void getGraph(std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global, std::map< int, Signature > *signatures=0, bool withImages=false, bool withScan=false, bool withUserData=false, bool withGrid=false, bool withWords=true, bool withGlobalDescriptors=true) const
Definition: Rtabmap.cpp:5189
static bool available()
Definition: CameraK4A.cpp:42
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 Mon Jan 23 2023 03:37:29