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 #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 9=Kinect for Azure SDK 10=MYNT EYE S\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 > 10)
68  {
69  UERROR("driver should be between 0 and 10.");
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  if(driver == 1)
81  {
83  {
84  UERROR("Not built with OpenNI2 support...");
85  exit(-1);
86  }
87  camera = new CameraOpenNI2();
88  }
89  else if(driver == 2)
90  {
92  {
93  UERROR("Not built with Freenect support...");
94  exit(-1);
95  }
96  camera = new CameraFreenect();
97  }
98  else if(driver == 3)
99  {
101  {
102  UERROR("Not built with OpenNI from OpenCV support...");
103  exit(-1);
104  }
105  camera = new CameraOpenNICV();
106  }
107  else if(driver == 4)
108  {
110  {
111  UERROR("Not built with OpenNI from OpenCV support...");
112  exit(-1);
113  }
114  camera = new CameraOpenNICV(true);
115  }
116  else if (driver == 5)
117  {
119  {
120  UERROR("Not built with Freenect2 support...");
121  exit(-1);
122  }
124  }
125  else if (driver == 6)
126  {
128  {
129  UERROR("Not built with ZED SDK support...");
130  exit(-1);
131  }
132  camera = new CameraStereoZed(0, 2, 1, 1, 100, false);
133  }
134  else if (driver == 7)
135  {
137  {
138  UERROR("Not built with RealSense support...");
139  exit(-1);
140  }
141  camera = new CameraRealSense();
142  }
143  else if (driver == 8)
144  {
146  {
147  UERROR("Not built with RealSense2 support...");
148  exit(-1);
149  }
150  camera = new CameraRealSense2();
151  }
152  else if (driver == 9)
153  {
155  {
156  UERROR("Not built with Kinect for Azure SDK support...");
157  exit(-1);
158  }
159  camera = new rtabmap::CameraK4A(1);
160  }
161  else if (driver == 10)
162  {
164  {
165  UERROR("Not built with Mynt Eye S support...");
166  exit(-1);
167  }
168  camera = new rtabmap::CameraMyntEye();
169  }
170  else
171  {
172  camera = new rtabmap::CameraOpenni();
173  }
174 
175  if(!camera->init())
176  {
177  UERROR("Camera init failed!");
178  }
179 
180  CameraThread cameraThread(camera);
181 
182 
183  // GUI stuff, there the handler will receive RtabmapEvent and construct the map
184  // We give it the camera so the GUI can pause/resume the camera
185  QApplication app(argc, argv);
186  MapBuilder mapBuilder(&cameraThread);
187 
188  // Create an odometry thread to process camera events, it will send OdometryEvent.
189  OdometryThread odomThread(Odometry::create());
190 
191 
192  ParametersMap params;
193  //param.insert(ParametersPair(Parameters::kRGBDCreateOccupancyGrid(), "true")); // uncomment to create local occupancy grids
194 
195  // Create RTAB-Map to process OdometryEvent
196  Rtabmap * rtabmap = new Rtabmap();
197  rtabmap->init(params);
198  RtabmapThread rtabmapThread(rtabmap); // ownership is transfered
199 
200  // Setup handlers
201  odomThread.registerToEventsManager();
202  rtabmapThread.registerToEventsManager();
203  mapBuilder.registerToEventsManager();
204 
205  // The RTAB-Map is subscribed by default to CameraEvent, but we want
206  // RTAB-Map to process OdometryEvent instead, ignoring the CameraEvent.
207  // We can do that by creating a "pipe" between the camera and odometry, then
208  // only the odometry will receive CameraEvent from that camera. RTAB-Map is
209  // also subscribed to OdometryEvent by default, so no need to create a pipe between
210  // odometry and RTAB-Map.
211  UEventsManager::createPipe(&cameraThread, &odomThread, "CameraEvent");
212 
213  // Let's start the threads
214  rtabmapThread.start();
215  odomThread.start();
216  cameraThread.start();
217 
218  mapBuilder.show();
219  app.exec(); // main loop
220 
221  // remove handlers
222  mapBuilder.unregisterFromEventsManager();
223  rtabmapThread.unregisterFromEventsManager();
224  odomThread.unregisterFromEventsManager();
225 
226  // Kill all threads
227  cameraThread.kill();
228  odomThread.join(true);
229  rtabmapThread.join(true);
230 
231  // Save 3D map
232  printf("Saving rtabmap_cloud.pcd...\n");
233  std::map<int, Signature> nodes;
234  std::map<int, Transform> optimizedPoses;
235  std::multimap<int, Link> links;
236  rtabmap->getGraph(optimizedPoses, links, true, true, &nodes, true, true, true, true);
237  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
238  for(std::map<int, Transform>::iterator iter=optimizedPoses.begin(); iter!=optimizedPoses.end(); ++iter)
239  {
240  Signature node = nodes.find(iter->first)->second;
241 
242  // uncompress data
243  node.sensorData().uncompressData();
244 
245  pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp = util3d::cloudRGBFromSensorData(
246  node.sensorData(),
247  4, // image decimation before creating the clouds
248  4.0f, // maximum depth of the cloud
249  0.0f);
250  pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmpNoNaN(new pcl::PointCloud<pcl::PointXYZRGB>);
251  std::vector<int> index;
252  pcl::removeNaNFromPointCloud(*tmp, *tmpNoNaN, index);
253  if(!tmpNoNaN->empty())
254  {
255  *cloud += *util3d::transformPointCloud(tmpNoNaN, iter->second); // transform the point cloud to its pose
256  }
257  }
258  if(cloud->size())
259  {
260  printf("Voxel grid filtering of the assembled cloud (voxel=%f, %d points)\n", 0.01f, (int)cloud->size());
261  cloud = util3d::voxelize(cloud, 0.01f);
262 
263  printf("Saving rtabmap_cloud.pcd... done! (%d points)\n", (int)cloud->size());
264  pcl::io::savePCDFile("rtabmap_cloud.pcd", *cloud);
265  //pcl::io::savePLYFile("rtabmap_cloud.ply", *cloud); // to save in PLY format
266  }
267  else
268  {
269  printf("Saving rtabmap_cloud.pcd... failed! The cloud is empty.\n");
270  }
271 
272  // Save trajectory
273  printf("Saving rtabmap_trajectory.txt ...\n");
274  if(optimizedPoses.size() && graph::exportPoses("rtabmap_trajectory.txt", 0, optimizedPoses, links))
275  {
276  printf("Saving rtabmap_trajectory.txt... done!\n");
277  }
278  else
279  {
280  printf("Saving rtabmap_trajectory.txt... failed!\n");
281  }
282 
283  rtabmap->close(false);
284 
285  return 0;
286 }
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:292
static void setLevel(ULogger::Level level)
Definition: ULogger.h:339
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:4543
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
void close(bool databaseSaved=true, const std::string &ouputDatabasePath="")
Definition: Rtabmap.cpp:392
static Odometry * create(const ParametersMap &parameters=ParametersMap())
Definition: Odometry.cpp:54
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[])
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(...)
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 Dec 14 2020 03:34:59