examples/LidarMapping/main.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2022, Mathieu Labbe
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 names of its contributors may be used to endorse or promote products
13  derived from this software without specific prior written permission.
14 
15 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
16 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
17 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
18 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
19 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
20 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
21 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
22 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
23 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
24 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
25 */
26 
27 // Should be first on windows to avoid "WinSock.h has already been included" error
29 
30 #include <rtabmap/core/Odometry.h>
31 #include "rtabmap/core/Rtabmap.h"
34 #include "rtabmap/core/Graph.h"
36 #include "rtabmap/utilite/UStl.h"
38 #include <QApplication>
39 #include <stdio.h>
40 #include <pcl/io/pcd_io.h>
41 #include <pcl/io/ply_io.h>
42 #include <pcl/filters/filter.h>
44 
45 #include "MapBuilder.h"
46 
47 void showUsage()
48 {
49  printf("\nUsage:\n"
50  "rtabmap-lidar_mapping IP PORT\n"
51  "rtabmap-lidar_mapping PCAP_FILEPATH\n"
52  "\n"
53  "Example:"
54  " rtabmap-lidar_mapping 192.168.1.201 2368\n\n");
55  exit(1);
56 }
57 
58 using namespace rtabmap;
59 int main(int argc, char * argv[])
60 {
63 
64  std::string filepath;
65  std::string ip;
66  int port = 2368;
67  if(argc < 2)
68  {
69  showUsage();
70  }
71  else if(argc == 2)
72  {
73  filepath = argv[1];
74  }
75  else
76  {
77  ip = argv[1];
78  port = uStr2Int(argv[2]);
79  }
80 
81  // Here is the pipeline that we will use:
82  // LidarVLP16 -> "SensorEvent" -> OdometryThread -> "OdometryEvent" -> RtabmapThread -> "RtabmapEvent"
83 
84  // Create the Lidar sensor, it will send a SensorEvent
85  LidarVLP16 * lidar;
86  if(!ip.empty())
87  {
88  printf("Using ip=%s port=%d\n", ip.c_str(), port);
89  lidar = new LidarVLP16(boost::asio::ip::address_v4::from_string(ip), port);
90  }
91  else
92  {
93  filepath = uReplaceChar(filepath, '~', UDirectory::homeDir());
94  printf("Using file=%s\n", filepath.c_str());
95  lidar = new LidarVLP16(filepath);
96  }
97  lidar->setOrganized(true); //faster deskewing
98 
99  if(!lidar->init())
100  {
101  UERROR("Lidar init failed!");
102  delete lidar;
103  return -1;
104  }
105 
106  SensorCaptureThread lidarThread(lidar);
107 
108  // GUI stuff, there the handler will receive RtabmapEvent and construct the map
109  // We give it the lidar so the GUI can pause/resume the lidar
110  QApplication app(argc, argv);
111  MapBuilder mapBuilder(&lidarThread);
112 
114 
115  float resolution = 0.05;
116 
117  // ICP parameters
118  params.insert(ParametersPair(Parameters::kRegStrategy(), "1"));
119  params.insert(ParametersPair(Parameters::kIcpFiltersEnabled(), "2"));
120  params.insert(ParametersPair(Parameters::kIcpPointToPlane(), "true"));
121  params.insert(ParametersPair(Parameters::kIcpPointToPlaneK(), "20"));
122  params.insert(ParametersPair(Parameters::kIcpPointToPlaneRadius(), "0"));
123  params.insert(ParametersPair(Parameters::kIcpIterations(), "10"));
124  params.insert(ParametersPair(Parameters::kIcpVoxelSize(), uNumber2Str(resolution)));
125  params.insert(ParametersPair(Parameters::kIcpEpsilon(), "0.001"));
126  params.insert(ParametersPair(Parameters::kIcpMaxCorrespondenceDistance(), uNumber2Str(resolution*10.0f)));
127  params.insert(ParametersPair(Parameters::kIcpMaxTranslation(), "2"));
128  params.insert(ParametersPair(Parameters::kIcpStrategy(), "1"));
129  params.insert(ParametersPair(Parameters::kIcpOutlierRatio(), "0.7"));
130  params.insert(ParametersPair(Parameters::kIcpCorrespondenceRatio(), "0.01"));
131  // Uncomment if lidar never pitch/roll (on a car or wheeled robot), for hand-held mapping, keep it commented
132  //params.insert(ParametersPair(Parameters::kIcpPointToPlaneGroundNormalsUp(), "0.8"));
133 
134  // Odom parameters
135  params.insert(ParametersPair(Parameters::kOdomStrategy(), "0")); // F2M
136  params.insert(ParametersPair(Parameters::kOdomScanKeyFrameThr(), "0.6"));
137  params.insert(ParametersPair(Parameters::kOdomF2MScanSubtractRadius(), uNumber2Str(resolution)));
138  params.insert(ParametersPair(Parameters::kOdomF2MScanMaxSize(), "15000"));
139  params.insert(ParametersPair(Parameters::kOdomGuessSmoothingDelay(), "0.3"));
140  params.insert(ParametersPair(Parameters::kOdomDeskewing(), "true"));
141 
142  // Create an odometry thread to process lidar events, it will send OdometryEvent.
144 
145  // Rtabmap params
146  params.insert(ParametersPair(Parameters::kRGBDProximityBySpace(), "true"));
147  params.insert(ParametersPair(Parameters::kRGBDProximityMaxGraphDepth(), "0"));
148  params.insert(ParametersPair(Parameters::kRGBDProximityPathMaxNeighbors(), "1"));
149  params.insert(ParametersPair(Parameters::kRGBDAngularUpdate(), "0.05"));
150  params.insert(ParametersPair(Parameters::kRGBDLinearUpdate(), "0.05"));
151  params.insert(ParametersPair(Parameters::kMemNotLinkedNodesKept(), "false"));
152  params.insert(ParametersPair(Parameters::kMemSTMSize(), "30"));
153  uInsert(params, ParametersPair(Parameters::kIcpCorrespondenceRatio(), "0.2")); // overwritten
154 
155 
156  // Create RTAB-Map to process OdometryEvent
157  Rtabmap * rtabmap = new Rtabmap();
158  rtabmap->init(params);
159  RtabmapThread rtabmapThread(rtabmap); // ownership is transfered
160 
161  // Setup handlers
162  odomThread.registerToEventsManager();
163  rtabmapThread.registerToEventsManager();
164  mapBuilder.registerToEventsManager();
165 
166  // The RTAB-Map is subscribed by default to SensorEvent, but we want
167  // RTAB-Map to process OdometryEvent instead, ignoring the SensorEvent.
168  // We can do that by creating a "pipe" between the lidar and odometry, then
169  // only the odometry will receive SensorEvent from that lidar. RTAB-Map is
170  // also subscribed to OdometryEvent by default, so no need to create a pipe between
171  // odometry and RTAB-Map.
172  UEventsManager::createPipe(&lidarThread, &odomThread, "SensorEvent");
173 
174  // Let's start the threads
175  rtabmapThread.start();
176  odomThread.start();
177  lidarThread.start();
178 
179  printf("Press Tab key to switch between map and odom views (or both).\n");
180  printf("Press Space key to pause.\n");
181 
182  mapBuilder.show();
183  app.exec(); // main loop
184 
185  // remove handlers
186  mapBuilder.unregisterFromEventsManager();
187  rtabmapThread.unregisterFromEventsManager();
188  odomThread.unregisterFromEventsManager();
189 
190  // Kill all threads
191  lidarThread.kill();
192  odomThread.join(true);
193  rtabmapThread.join(true);
194 
195  // Save 3D map
196  printf("Saving rtabmap_cloud.pcd...\n");
197  std::map<int, Signature> nodes;
198  std::map<int, Transform> optimizedPoses;
199  std::multimap<int, Link> links;
200  rtabmap->getGraph(optimizedPoses, links, true, true, &nodes, true, true, true, true);
201  pcl::PointCloud<pcl::PointXYZI>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZI>);
202  for(std::map<int, Transform>::iterator iter=optimizedPoses.begin(); iter!=optimizedPoses.end(); ++iter)
203  {
204  Signature node = nodes.find(iter->first)->second;
205 
206  // uncompress data
207  node.sensorData().uncompressData();
208 
209  pcl::PointCloud<pcl::PointXYZI>::Ptr tmp = util3d::laserScanToPointCloudI(node.sensorData().laserScanRaw(), node.sensorData().laserScanRaw().localTransform());
210  *cloud += *util3d::transformPointCloud(tmp, iter->second); // transform the point cloud to its pose
211  }
212  if(cloud->size())
213  {
214  printf("Voxel grid filtering of the assembled cloud (voxel=%f, %d points)\n", 0.01f, (int)cloud->size());
215  cloud = util3d::voxelize(cloud, 0.01f);
216 
217  printf("Saving rtabmap_cloud.pcd... done! (%d points)\n", (int)cloud->size());
218  pcl::io::savePCDFile("rtabmap_cloud.pcd", *cloud);
219  //pcl::io::savePLYFile("rtabmap_cloud.ply", *cloud); // to save in PLY format
220  }
221  else
222  {
223  printf("Saving rtabmap_cloud.pcd... failed! The cloud is empty.\n");
224  }
225 
226  // Save trajectory
227  printf("Saving rtabmap_trajectory.txt ...\n");
228  if(optimizedPoses.size() && graph::exportPoses("rtabmap_trajectory.txt", 0, optimizedPoses, links))
229  {
230  printf("Saving rtabmap_trajectory.txt... done!\n");
231  }
232  else
233  {
234  printf("Saving rtabmap_trajectory.txt... failed!\n");
235  }
236 
237  rtabmap->close(false);
238 
239  return 0;
240 }
rtabmap::SensorCaptureThread
Definition: SensorCaptureThread.h:58
rtabmap::ParametersPair
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:44
rtabmap::LaserScan::localTransform
Transform localTransform() const
Definition: LaserScan.h:127
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
rtabmap::OdometryThread
Definition: OdometryThread.h:41
UEventsHandler::registerToEventsManager
void registerToEventsManager()
Definition: UEventsHandler.cpp:29
LidarVLP16.h
OdometryThread.h
UDirectory.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::LidarVLP16::init
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="") override
Definition: LidarVLP16.cpp:132
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
RtabmapThread.h
Odometry.h
UDirectory::homeDir
static std::string homeDir()
Definition: UDirectory.cpp:355
uInsert
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)
Definition: UStl.h:441
rtabmap::LidarVLP16::setOrganized
void setOrganized(bool enable)
Definition: LidarVLP16.cpp:127
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::SensorData::laserScanRaw
const LaserScan & laserScanRaw() const
Definition: SensorData.h:185
app
QApplication * app
Definition: tools/DataRecorder/main.cpp:59
uNumber2Str
std::string UTILITE_EXPORT uNumber2Str(unsigned int number)
Definition: UConversion.cpp:91
UEventsManager::createPipe
static void createPipe(const UEventsSender *sender, const UEventsHandler *receiver, const std::string &eventName)
Definition: UEventsManager.cpp:67
MapBuilder.h
Rtabmap.h
ULogger::kWarning
@ kWarning
Definition: ULogger.h:252
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
rtabmap::util3d::laserScanToPointCloudI
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_CORE_EXPORT laserScanToPointCloudI(const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f)
Definition: util3d.cpp:2349
rtabmap::LidarVLP16
Definition: LidarVLP16.h:45
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
nodes
KeyVector nodes
uReplaceChar
std::string UTILITE_EXPORT uReplaceChar(const std::string &str, char before, char after)
Definition: UConversion.cpp:33
uStr2Int
int UTILITE_EXPORT uStr2Int(const std::string &str)
Definition: UConversion.cpp:125
Graph.h
iter
iterator iter(handle obj)
UStl.h
Wrappers of STL for convenient functions.
main
int main(int argc, char *argv[])
Definition: examples/LidarMapping/main.cpp:59
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
showUsage
void showUsage()
Definition: examples/LidarMapping/main.cpp:47
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