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"
34 #include "rtabmap/core/Graph.h"
36 #include <QApplication>
37 #include <stdio.h>
38 #include <pcl/io/pcd_io.h>
39 #include <pcl/io/ply_io.h>
40 #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 -> "SensorEvent" -> OdometryThread -> "OdometryEvent" -> RtabmapThread -> "RtabmapEvent"
84 
85  // Create the OpenNI camera, it will send a SensorEvent 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  }
177  }
178  else
179  {
181  }
182 
183  if(!camera->init())
184  {
185  UERROR("Camera init failed!");
186  }
187 
188  SensorCaptureThread 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 SensorEvent, but we want
214  // RTAB-Map to process OdometryEvent instead, ignoring the SensorEvent.
215  // We can do that by creating a "pipe" between the camera and odometry, then
216  // only the odometry will receive SensorEvent 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, "SensorEvent");
220 
221  // Let's start the threads
222  rtabmapThread.start();
223  odomThread.start();
224  cameraThread.start();
225 
226  printf("Press Space key to pause.\n");
227 
228  mapBuilder.show();
229  app.exec(); // main loop
230 
231  // remove handlers
232  mapBuilder.unregisterFromEventsManager();
233  rtabmapThread.unregisterFromEventsManager();
234  odomThread.unregisterFromEventsManager();
235 
236  // Kill all threads
237  cameraThread.kill();
238  odomThread.join(true);
239  rtabmapThread.join(true);
240 
241  // Save 3D map
242  printf("Saving rtabmap_cloud.pcd...\n");
243  std::map<int, Signature> nodes;
244  std::map<int, Transform> optimizedPoses;
245  std::multimap<int, Link> links;
246  rtabmap->getGraph(optimizedPoses, links, true, true, &nodes, true, true, true, true);
247  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
248  for(std::map<int, Transform>::iterator iter=optimizedPoses.begin(); iter!=optimizedPoses.end(); ++iter)
249  {
250  Signature node = nodes.find(iter->first)->second;
251 
252  // uncompress data
253  node.sensorData().uncompressData();
254 
255  pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp = util3d::cloudRGBFromSensorData(
256  node.sensorData(),
257  4, // image decimation before creating the clouds
258  4.0f, // maximum depth of the cloud
259  0.0f);
260  pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmpNoNaN(new pcl::PointCloud<pcl::PointXYZRGB>);
261  std::vector<int> index;
262  pcl::removeNaNFromPointCloud(*tmp, *tmpNoNaN, index);
263  if(!tmpNoNaN->empty())
264  {
265  *cloud += *util3d::transformPointCloud(tmpNoNaN, iter->second); // transform the point cloud to its pose
266  }
267  }
268  if(cloud->size())
269  {
270  printf("Voxel grid filtering of the assembled cloud (voxel=%f, %d points)\n", 0.01f, (int)cloud->size());
271  cloud = util3d::voxelize(cloud, 0.01f);
272 
273  printf("Saving rtabmap_cloud.pcd... done! (%d points)\n", (int)cloud->size());
274  pcl::io::savePCDFile("rtabmap_cloud.pcd", *cloud);
275  //pcl::io::savePLYFile("rtabmap_cloud.ply", *cloud); // to save in PLY format
276  }
277  else
278  {
279  printf("Saving rtabmap_cloud.pcd... failed! The cloud is empty.\n");
280  }
281 
282  // Save trajectory
283  printf("Saving rtabmap_trajectory.txt ...\n");
284  if(optimizedPoses.size() && graph::exportPoses("rtabmap_trajectory.txt", 0, optimizedPoses, links))
285  {
286  printf("Saving rtabmap_trajectory.txt... done!\n");
287  }
288  else
289  {
290  printf("Saving rtabmap_trajectory.txt... failed!\n");
291  }
292 
293  rtabmap->close(false);
294 
295  return 0;
296 }
rtabmap::SensorCaptureThread
Definition: SensorCaptureThread.h:58
rtabmap::Odometry::create
static Odometry * create(const ParametersMap &parameters=ParametersMap())
Definition: Odometry.cpp:58
rtabmap::SensorData::uncompressData
void uncompressData()
Definition: SensorData.cpp:528
SensorCaptureThread.h
main
int main(int argc, char *argv[])
Definition: examples/RGBDMapping/main.cpp:58
rtabmap::OdometryThread
Definition: OdometryThread.h:41
rtabmap::CameraFreenect::available
static bool available()
Definition: CameraFreenect.cpp:284
UEventsHandler::registerToEventsManager
void registerToEventsManager()
Definition: UEventsHandler.cpp:29
rtabmap::CameraRealSense::available
static bool available()
Definition: CameraRealSense.cpp:47
OdometryThread.h
ULogger::kTypeConsole
@ kTypeConsole
Definition: ULogger.h:244
rtabmap::graph::exportPoses
bool RTABMAP_CORE_EXPORT 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
ULogger::setLevel
static void setLevel(ULogger::Level level)
Definition: ULogger.h:339
rtabmap::util3d::voxelize
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
Definition: util3d_filtering.cpp:613
UThread::join
void join(bool killFirst=false)
Definition: UThread.cpp:85
rtabmap::CameraMyntEye
Definition: CameraMyntEye.h:47
CameraRGBD.h
CameraStereo.h
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
RtabmapThread.h
rtabmap::CameraFreenect2::available
static bool available()
Definition: CameraFreenect2.cpp:45
rtabmap::CameraK4A
Definition: CameraK4A.h:43
rtabmap::CameraFreenect
Definition: CameraFreenect.h:44
Odometry.h
rtabmap::SensorCapture::init
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
rtabmap::util3d::transformPointCloud
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
Definition: util3d_transforms.cpp:107
rtabmap::util3d::cloudRGBFromSensorData
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT 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:1268
app
QApplication * app
Definition: tools/DataRecorder/main.cpp:59
rtabmap::CameraFreenect2
Definition: CameraFreenect2.h:46
rtabmap::CameraOpenNI2
Definition: CameraOpenNI2.h:42
rtabmap::CameraRealSense2
Definition: CameraRealSense2.h:54
rtabmap::CameraFreenect2::kTypeColor2DepthSD
@ kTypeColor2DepthSD
Definition: CameraFreenect2.h:53
UEventsManager::createPipe
static void createPipe(const UEventsSender *sender, const UEventsHandler *receiver, const std::string &eventName)
Definition: UEventsManager.cpp:67
rtabmap::PythonInterface
Definition: PythonInterface.h:26
Rtabmap.h
ULogger::kWarning
@ kWarning
Definition: ULogger.h:252
MapBuilder.h
python
UThread::kill
void kill()
Definition: UThread.cpp:48
UEventsHandler::unregisterFromEventsManager
void unregisterFromEventsManager()
Definition: UEventsHandler.cpp:33
rtabmap_netvlad.argv
argv
Definition: rtabmap_netvlad.py:15
params
SmartProjectionParams params(gtsam::HESSIAN, gtsam::ZERO_ON_DEGENERACY)
UThread::start
void start()
Definition: UThread.cpp:122
ULogger::setType
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
Definition: ULogger.cpp:176
PythonInterface.h
rtabmap::CameraStereoZed::available
static bool available()
Definition: CameraStereoZed.cpp:235
rtabmap::Camera
Definition: Camera.h:43
rtabmap::CameraOpenNICV
Definition: CameraOpenNICV.h:36
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
nodes
KeyVector nodes
rtabmap::CameraStereoZed
Definition: CameraStereoZed.h:43
rtabmap::CameraOpenNICV::available
static bool available()
Definition: CameraOpenNICV.cpp:36
rtabmap::CameraMyntEye::available
static bool available()
Definition: CameraMyntEye.cpp:506
Graph.h
iter
iterator iter(handle obj)
rtabmap::CameraRealSense2::available
static bool available()
Definition: CameraRealSense2.cpp:45
rtabmap::CameraK4A::available
static bool available()
Definition: CameraK4A.cpp:42
camera
Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)), Cal3Bundler0(1, 0, 0))
rtabmap::util3d::removeNaNFromPointCloud
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
Definition: util3d_filtering.cpp:1002
rtabmap::CameraRealSense
Definition: CameraRealSense.h:49
rtabmap::CameraOpenNI2::available
static bool available()
Definition: CameraOpenNI2.cpp:42
rtabmap::Rtabmap
Definition: Rtabmap.h:54
rtabmap::Signature::sensorData
SensorData & sensorData()
Definition: Signature.h:138
rtabmap
Definition: CameraARCore.cpp:35
UEventsManager.h
UERROR
#define UERROR(...)
MapBuilder
Definition: LidarMapping/MapBuilder.h:52
rtabmap::CameraOpenni
Definition: CameraOpenni.h:55
showUsage
void showUsage()
Definition: examples/RGBDMapping/main.cpp:49
rtabmap::Signature
Definition: Signature.h:48
rtabmap::RtabmapThread
Definition: RtabmapThread.h:51


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:11