LidarMapping/MapBuilder.h
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 #ifndef MAPBUILDER_H_
28 #define MAPBUILDER_H_
29 
30 #include <QVBoxLayout>
31 #include <QtCore/QMetaType>
32 #include <QAction>
33 
34 #ifndef Q_MOC_RUN // Mac OS X issue
36 #include "rtabmap/core/util3d.h"
41 #endif
42 #include "rtabmap/utilite/UStl.h"
48 
49 using namespace rtabmap;
50 
51 // This class receives RtabmapEvent and construct/update a 3D Map
52 class MapBuilder : public QWidget, public UEventsHandler
53 {
54  Q_OBJECT
55 public:
56  //Camera ownership is not transferred!
58  sensorCaptureThread_(camera),
59  odometryCorrection_(Transform::getIdentity()),
60  processingStatistics_(false),
61  lastOdometryProcessed_(true),
62  visibility_(0)
63  {
64  this->setWindowFlags(Qt::Dialog);
65  this->setWindowTitle(tr("3D Map"));
66  this->setMinimumWidth(800);
67  this->setMinimumHeight(600);
68 
69  cloudViewer_ = new CloudViewer(this);
70  cloudViewer_->setCameraTargetLocked(true);
71 
72  QVBoxLayout *layout = new QVBoxLayout();
73  layout->addWidget(cloudViewer_);
74  this->setLayout(layout);
75 
76  qRegisterMetaType<rtabmap::OdometryEvent>("rtabmap::OdometryEvent");
77  qRegisterMetaType<rtabmap::Statistics>("rtabmap::Statistics");
78 
79  QAction * pause = new QAction(this);
80  this->addAction(pause);
81  pause->setShortcut(Qt::Key_Space);
82  connect(pause, SIGNAL(triggered()), this, SLOT(pauseDetection()));
83 
84  QAction * visibility = new QAction(this);
85  this->addAction(visibility);
86  visibility->setShortcut(Qt::Key_Tab);
87  connect(visibility, SIGNAL(triggered()), this, SLOT(rotateVisibility()));
88  }
89 
90  virtual ~MapBuilder()
91  {
92  this->unregisterFromEventsManager();
93  }
94 
95 protected Q_SLOTS:
96  virtual void pauseDetection()
97  {
98  UWARN("");
99  if(sensorCaptureThread_)
100  {
101  if(sensorCaptureThread_->isCapturing())
102  {
103  sensorCaptureThread_->join(true);
104  }
105  else
106  {
107  sensorCaptureThread_->start();
108  }
109  }
110  }
111 
112  virtual void rotateVisibility()
113  {
114  visibility_ = (visibility_+1) % 3;
115  if(visibility_ == 0)
116  {
117  UWARN("Show both Odom and Map");
118  }
119  else if(visibility_ == 1)
120  {
121  UWARN("Show only Map");
122  }
123  else if(visibility_ == 2)
124  {
125  UWARN("Show only Odom");
126  }
127  }
128 
129  virtual void processOdometry(const rtabmap::OdometryEvent & odom)
130  {
131  if(!this->isVisible())
132  {
133  return;
134  }
135 
136  Transform pose = odom.pose();
137  if(pose.isNull())
138  {
139  //Odometry lost
140  cloudViewer_->setBackgroundColor(Qt::darkRed);
141 
142  pose = lastOdomPose_;
143  }
144  else
145  {
146  cloudViewer_->setBackgroundColor(cloudViewer_->getDefaultBackgroundColor());
147  }
148  if(!pose.isNull())
149  {
150  lastOdomPose_ = pose;
151 
152  // 3d cloud
153  if(!odom.data().laserScanRaw().empty())
154  {
155  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = util3d::laserScanToPointCloud(odom.data().laserScanRaw(), odom.data().laserScanRaw().localTransform());
156  if(cloud->size() && (visibility_ == 0 || visibility_ == 2))
157  {
158  if(!cloudViewer_->addCloud("cloudOdom", cloud, odometryCorrection_*pose, Qt::magenta))
159  {
160  UERROR("Adding cloudOdom to viewer failed!");
161  }
162  }
163  else
164  {
165  cloudViewer_->setCloudVisibility("cloudOdom", false);
166  if(cloud->empty())
167  UWARN("Empty cloudOdom!");
168  }
169  }
170 
171  if(!odom.info().localScanMap.empty())
172  {
173  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = util3d::laserScanToPointCloud(odom.info().localScanMap, odom.info().localScanMap.localTransform());
174  if(cloud->size() && (visibility_ == 0 || visibility_ == 2))
175  {
176  if(!cloudViewer_->addCloud("cloudOdomLocalMap", cloud, odometryCorrection_, Qt::blue))
177  {
178  UERROR("Adding cloudOdomLocalMap to viewer failed!");
179  }
180  }
181  else
182  {
183  cloudViewer_->setCloudVisibility("cloudOdomLocalMap", false);
184  if(cloud->empty())
185  UWARN("Empty cloudOdomLocalMap!");
186  }
187  }
188 
189  if(!odom.pose().isNull())
190  {
191  // update camera position
192  cloudViewer_->updateCameraTargetPosition(odometryCorrection_*odom.pose());
193  }
194  }
195  cloudViewer_->update();
196 
197  lastOdometryProcessed_ = true;
198  }
199 
200 
201  virtual void processStatistics(const rtabmap::Statistics & stats)
202  {
203  processingStatistics_ = true;
204 
205  //============================
206  // Add RGB-D clouds
207  //============================
208  const std::map<int, Transform> & poses = stats.poses();
209  QMap<std::string, Transform> clouds = cloudViewer_->getAddedClouds();
210  for(std::map<int, Transform>::const_iterator iter = poses.lower_bound(1); iter!=poses.end(); ++iter)
211  {
212  if(!iter->second.isNull())
213  {
214  std::string cloudName = uFormat("cloud_%d", iter->first);
215 
216  // 3d point cloud
217  if(clouds.contains(cloudName))
218  {
219  // Update only if the pose has changed
220  Transform tCloud;
221  cloudViewer_->getPose(cloudName, tCloud);
222  if(tCloud.isNull() || iter->second != tCloud)
223  {
224  if(!cloudViewer_->updateCloudPose(cloudName, iter->second))
225  {
226  UERROR("Updating pose cloud %d failed!", iter->first);
227  }
228  }
229  }
230  else if(iter->first == stats.getLastSignatureData().id())
231  {
232  Signature s = stats.getLastSignatureData();
233  s.sensorData().uncompressData(); // make sure data is uncompressed
234  // Add the new cloud
235  pcl::PointCloud<pcl::PointXYZI>::Ptr cloud = util3d::laserScanToPointCloudI(
236  s.sensorData().laserScanRaw(),
237  s.sensorData().laserScanRaw().localTransform());
238  if(cloud->size())
239  {
240  if(!cloudViewer_->addCloud(cloudName, cloud, iter->second))
241  {
242  UERROR("Adding cloud %d to viewer failed!", iter->first);
243  }
244  }
245  else
246  {
247  UWARN("Empty cloud %d!", iter->first);
248  }
249  }
250 
251  cloudViewer_->setCloudVisibility(cloudName, visibility_ == 0 || visibility_ == 1);
252  }
253  else
254  {
255  UWARN("Null pose for %d ?!?", iter->first);
256  }
257  }
258 
259  // cleanup
260  for(QMap<std::string, Transform>::iterator iter = clouds.begin(); iter!=clouds.end(); ++iter)
261  {
262  if(uStrContains(iter.key(), "cloud_"))
263  {
264  int id = uStr2Int(uSplitNumChar(iter.key()).back());
265  if(poses.find(id) == poses.end())
266  {
267  cloudViewer_->removeCloud(iter.key());
268  }
269  }
270  }
271 
272  //============================
273  // Add 3D graph (show all poses)
274  //============================
275  cloudViewer_->removeAllGraphs();
276  cloudViewer_->removeCloud("graph_nodes");
277  if(poses.size())
278  {
279  // Set graph
280  pcl::PointCloud<pcl::PointXYZ>::Ptr graph(new pcl::PointCloud<pcl::PointXYZ>);
281  pcl::PointCloud<pcl::PointXYZ>::Ptr graphNodes(new pcl::PointCloud<pcl::PointXYZ>);
282  for(std::map<int, Transform>::const_iterator iter=poses.lower_bound(1); iter!=poses.end(); ++iter)
283  {
284  graph->push_back(pcl::PointXYZ(iter->second.x(), iter->second.y(), iter->second.z()));
285  }
286  *graphNodes = *graph;
287 
288 
289  // add graph
290  cloudViewer_->addOrUpdateGraph("graph", graph, Qt::gray);
291  cloudViewer_->addCloud("graph_nodes", graphNodes, Transform::getIdentity(), Qt::green);
292  cloudViewer_->setCloudPointSize("graph_nodes", 5);
293  }
294 
295  odometryCorrection_ = stats.mapCorrection();
296 
297  cloudViewer_->update();
298 
299  processingStatistics_ = false;
300  }
301 
302  virtual bool handleEvent(UEvent * event)
303  {
304  if(event->getClassName().compare("RtabmapEvent") == 0)
305  {
306  RtabmapEvent * rtabmapEvent = (RtabmapEvent *)event;
307  const Statistics & stats = rtabmapEvent->getStats();
308  // Statistics must be processed in the Qt thread
309  if(this->isVisible())
310  {
311  QMetaObject::invokeMethod(this, "processStatistics", Q_ARG(rtabmap::Statistics, stats));
312  }
313  }
314  else if(event->getClassName().compare("OdometryEvent") == 0)
315  {
316  OdometryEvent * odomEvent = (OdometryEvent *)event;
317  // Odometry must be processed in the Qt thread
318  if(this->isVisible() &&
319  lastOdometryProcessed_ &&
320  !processingStatistics_)
321  {
322  lastOdometryProcessed_ = false; // if we receive too many odometry events!
323  QMetaObject::invokeMethod(this, "processOdometry", Q_ARG(rtabmap::OdometryEvent, *odomEvent));
324  }
325  }
326  return false;
327  }
328 
329 protected:
337 };
338 
339 
340 #endif /* MAPBUILDER_H_ */
UEventsHandler
Definition: UEventsHandler.h:128
rtabmap::SensorCaptureThread
Definition: SensorCaptureThread.h:58
rtabmap::LaserScan::localTransform
Transform localTransform() const
Definition: LaserScan.h:127
rtabmap::OdometryEvent
Definition: OdometryEvent.h:39
MapBuilder::~MapBuilder
virtual ~MapBuilder()
Definition: LidarMapping/MapBuilder.h:90
MapBuilder::sensorCaptureThread_
SensorCaptureThread * sensorCaptureThread_
Definition: LidarMapping/MapBuilder.h:331
rtabmap::Statistics
Definition: Statistics.h:53
SensorCaptureThread.h
rtabmap::OdometryEvent::pose
const Transform & pose() const
Definition: OdometryEvent.h:71
s
RealScalar s
rtabmap::Transform::getIdentity
static Transform getIdentity()
Definition: Transform.cpp:411
MapBuilder::processOdometry
virtual void processOdometry(const rtabmap::OdometryEvent &odom)
Definition: LidarMapping/MapBuilder.h:129
MapBuilder::MapBuilder
MapBuilder(SensorCaptureThread *camera=0)
Definition: LidarMapping/MapBuilder.h:57
MapBuilder::cloudViewer_
CloudViewer * cloudViewer_
Definition: LidarMapping/MapBuilder.h:330
MapBuilder::rotateVisibility
virtual void rotateVisibility()
Definition: LidarMapping/MapBuilder.h:112
rtabmap::RtabmapEvent
Definition: RtabmapEvent.h:42
MapBuilder::handleEvent
virtual bool handleEvent(UEvent *event)
Definition: LidarMapping/MapBuilder.h:302
true
#define true
Definition: ConvertUTF.c:57
util3d.h
rtabmap::Transform::isNull
bool isNull() const
Definition: Transform.cpp:107
uSplitNumChar
std::list< std::string > uSplitNumChar(const std::string &str)
Definition: UStl.h:670
UEvent
Definition: UEvent.h:57
rtabmap::CloudViewer
Definition: CloudViewer.h:79
MapBuilder::processStatistics
virtual void processStatistics(const rtabmap::Statistics &stats)
Definition: LidarMapping/MapBuilder.h:201
RtabmapEvent.h
MapBuilder::visibility_
int visibility_
Definition: LidarMapping/MapBuilder.h:336
rtabmap::SensorData::laserScanRaw
const LaserScan & laserScanRaw() const
Definition: SensorData.h:185
util3d_transforms.h
UEvent::getClassName
virtual std::string getClassName() const =0
stats
bool stats
UConversion.h
Some conversion functions.
CloudViewer.h
MapBuilder::processingStatistics_
bool processingStatistics_
Definition: LidarMapping/MapBuilder.h:334
util3d_filtering.h
OccupancyGrid.h
rtabmap::OdometryInfo::localScanMap
LaserScan localScanMap
Definition: OdometryInfo.h:130
rtabmap::OdometryEvent::info
const OdometryInfo & info() const
Definition: OdometryEvent.h:89
uStrContains
bool uStrContains(const std::string &string, const std::string &substring)
Definition: UStl.h:785
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
OdometryEvent.h
graph
FactorGraph< FACTOR > * graph
MapBuilder::pauseDetection
virtual void pauseDetection()
Definition: LidarMapping/MapBuilder.h:96
UWARN
#define UWARN(...)
uFormat
std::string UTILITE_EXPORT uFormat(const char *fmt,...)
Definition: UConversion.cpp:365
ULogger.h
ULogger class and convenient macros.
rtabmap::Transform
Definition: Transform.h:41
uStr2Int
int UTILITE_EXPORT uStr2Int(const std::string &str)
Definition: UConversion.cpp:125
UEventsHandler.h
iter
iterator iter(handle obj)
camera
Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)), Cal3Bundler0(1, 0, 0))
UStl.h
Wrappers of STL for convenient functions.
rtabmap::LaserScan::empty
bool empty() const
Definition: LaserScan.h:129
MapBuilder::odometryCorrection_
Transform odometryCorrection_
Definition: LidarMapping/MapBuilder.h:333
rtabmap::util3d::laserScanToPointCloud
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT laserScanToPointCloud(const LaserScan &laserScan, const Transform &transform=Transform())
Definition: util3d.cpp:2269
rtabmap::OdometryEvent::data
SensorData & data()
Definition: OdometryEvent.h:69
false
#define false
Definition: ConvertUTF.c:56
rtabmap
Definition: CameraARCore.cpp:35
UERROR
#define UERROR(...)
MapBuilder
Definition: LidarMapping/MapBuilder.h:52
MapBuilder::lastOdometryProcessed_
bool lastOdometryProcessed_
Definition: LidarMapping/MapBuilder.h:335
rtabmap::Signature
Definition: Signature.h:48
rtabmap::RtabmapEvent::getStats
const Statistics & getStats() const
Definition: RtabmapEvent.h:50
MapBuilder::lastOdomPose_
Transform lastOdomPose_
Definition: LidarMapping/MapBuilder.h:332


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