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  cloudViewer_->refreshView();
163 
164  lastOdometryProcessed_ = true;
165  }
166 
167 
168  virtual void processStatistics(const rtabmap::Statistics & stats)
169  {
170  processingStatistics_ = true;
171 
172  //============================
173  // Add RGB-D clouds
174  //============================
175  const std::map<int, Transform> & poses = stats.poses();
176  QMap<std::string, Transform> clouds = cloudViewer_->getAddedClouds();
177  for(std::map<int, Transform>::const_iterator iter = poses.lower_bound(1); iter!=poses.end(); ++iter)
178  {
179  if(!iter->second.isNull())
180  {
181  std::string cloudName = uFormat("cloud%d", iter->first);
182 
183  // 3d point cloud
184  if(clouds.contains(cloudName))
185  {
186  // Update only if the pose has changed
187  Transform tCloud;
188  cloudViewer_->getPose(cloudName, tCloud);
189  if(tCloud.isNull() || iter->second != tCloud)
190  {
191  if(!cloudViewer_->updateCloudPose(cloudName, iter->second))
192  {
193  UERROR("Updating pose cloud %d failed!", iter->first);
194  }
195  }
196  cloudViewer_->setCloudVisibility(cloudName, true);
197  }
198  else if(iter->first == stats.getLastSignatureData().id())
199  {
200  Signature s = stats.getLastSignatureData();
201  s.sensorData().uncompressData(); // make sure data is uncompressed
202  // Add the new cloud
203  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = util3d::cloudRGBFromSensorData(
204  s.sensorData(),
205  4, // decimation
206  4.0f); // max depth
207  if(cloud->size())
208  {
209  if(!cloudViewer_->addCloud(cloudName, cloud, iter->second))
210  {
211  UERROR("Adding cloud %d to viewer failed!", iter->first);
212  }
213  }
214  else
215  {
216  UWARN("Empty cloud %d!", iter->first);
217  }
218  }
219  }
220  else
221  {
222  UWARN("Null pose for %d ?!?", iter->first);
223  }
224  }
225 
226  //============================
227  // Add 3D graph (show all poses)
228  //============================
229  cloudViewer_->removeAllGraphs();
230  cloudViewer_->removeCloud("graph_nodes");
231  if(poses.size())
232  {
233  // Set graph
234  pcl::PointCloud<pcl::PointXYZ>::Ptr graph(new pcl::PointCloud<pcl::PointXYZ>);
235  pcl::PointCloud<pcl::PointXYZ>::Ptr graphNodes(new pcl::PointCloud<pcl::PointXYZ>);
236  for(std::map<int, Transform>::const_iterator iter=poses.lower_bound(1); iter!=poses.end(); ++iter)
237  {
238  graph->push_back(pcl::PointXYZ(iter->second.x(), iter->second.y(), iter->second.z()));
239  }
240  *graphNodes = *graph;
241 
242 
243  // add graph
244  cloudViewer_->addOrUpdateGraph("graph", graph, Qt::gray);
245  cloudViewer_->addCloud("graph_nodes", graphNodes, Transform::getIdentity(), Qt::green);
246  cloudViewer_->setCloudPointSize("graph_nodes", 5);
247  }
248 
249  //============================
250  // Update/add occupancy grid (when RGBD/CreateOccupancyGrid is true)
251  //============================
252  if(grid_.addedNodes().find(stats.getLastSignatureData().id()) == grid_.addedNodes().end())
253  {
254  if(stats.getLastSignatureData().sensorData().gridCellSize() > 0.0f)
255  {
256  cv::Mat groundCells, obstacleCells, emptyCells;
257  stats.getLastSignatureData().sensorData().uncompressDataConst(0, 0, 0, 0, &groundCells, &obstacleCells, &emptyCells);
258  localGrids_.add(stats.getLastSignatureData().id(), groundCells, obstacleCells, emptyCells, stats.getLastSignatureData().sensorData().gridCellSize(), stats.getLastSignatureData().sensorData().gridViewPoint());
259  }
260  }
261 
262  if(grid_.addedNodes().size() || localGrids_.size())
263  {
264  grid_.update(stats.poses());
265  }
266  if(grid_.addedNodes().size())
267  {
268  float xMin, yMin;
269  cv::Mat map8S = grid_.getMap(xMin, yMin);
270  if(!map8S.empty())
271  {
272  //convert to gray scaled map
273  cv::Mat map8U = util3d::convertMap2Image8U(map8S);
274  cloudViewer_->addOccupancyGridMap(map8U, grid_.getCellSize(), xMin, yMin, 0.75);
275  }
276  }
277 
278  odometryCorrection_ = stats.mapCorrection();
279 
280  cloudViewer_->update();
281  cloudViewer_->refreshView();
282 
283  processingStatistics_ = false;
284  }
285 
286  virtual bool handleEvent(UEvent * event)
287  {
288  if(event->getClassName().compare("RtabmapEvent") == 0)
289  {
290  RtabmapEvent * rtabmapEvent = (RtabmapEvent *)event;
291  const Statistics & stats = rtabmapEvent->getStats();
292  // Statistics must be processed in the Qt thread
293  if(this->isVisible())
294  {
295  QMetaObject::invokeMethod(this, "processStatistics", Q_ARG(rtabmap::Statistics, stats));
296  }
297  }
298  else if(event->getClassName().compare("OdometryEvent") == 0)
299  {
300  OdometryEvent * odomEvent = (OdometryEvent *)event;
301  // Odometry must be processed in the Qt thread
302  if(this->isVisible() &&
303  lastOdometryProcessed_ &&
304  !processingStatistics_)
305  {
306  lastOdometryProcessed_ = false; // if we receive too many odometry events!
307  QMetaObject::invokeMethod(this, "processOdometry", Q_ARG(rtabmap::OdometryEvent, *odomEvent));
308  }
309  }
310  return false;
311  }
312 
313 protected:
314  CloudViewer * cloudViewer_;
316  Transform lastOdomPose_;
317  Transform odometryCorrection_;
318  bool processingStatistics_;
319  bool lastOdometryProcessed_;
322 };
323 
324 
325 #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:315
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:321
rtabmap::RtabmapEvent
Definition: RtabmapEvent.h:42
MapBuilder::handleEvent
virtual bool handleEvent(UEvent *event)
Definition: RGBDMapping/MapBuilder.h:286
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:168
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:320
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 Sun Dec 1 2024 03:42:48