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


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