WifiMapping/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"
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  camera_(camera),
59  odometryCorrection_(Transform::getIdentity()),
60  processingStatistics_(false),
61  lastOdometryProcessed_(true)
62  {
63  this->setWindowFlags(Qt::Dialog);
64  this->setWindowTitle(tr("3D Map"));
65  this->setMinimumWidth(800);
66  this->setMinimumHeight(600);
67 
68  cloudViewer_ = new CloudViewer(this);
69 
70  QVBoxLayout *layout = new QVBoxLayout();
71  layout->addWidget(cloudViewer_);
72  this->setLayout(layout);
73 
74  qRegisterMetaType<rtabmap::OdometryEvent>("rtabmap::OdometryEvent");
75  qRegisterMetaType<rtabmap::Statistics>("rtabmap::Statistics");
76 
77  QAction * pause = new QAction(this);
78  this->addAction(pause);
79  pause->setShortcut(Qt::Key_Space);
80  connect(pause, SIGNAL(triggered()), this, SLOT(pauseDetection()));
81  }
82 
83  virtual ~MapBuilder()
84  {
85  this->unregisterFromEventsManager();
86  }
87 
88 protected Q_SLOTS:
89  virtual void pauseDetection()
90  {
91  UWARN("");
92  if(camera_)
93  {
94  if(camera_->isCapturing())
95  {
96  camera_->join(true);
97  }
98  else
99  {
100  camera_->start();
101  }
102  }
103  }
104 
105  virtual void processOdometry(const rtabmap::OdometryEvent & odom)
106  {
107  if(!this->isVisible())
108  {
109  return;
110  }
111 
112  Transform pose = odom.pose();
113  if(pose.isNull())
114  {
115  //Odometry lost
116  cloudViewer_->setBackgroundColor(Qt::darkRed);
117 
118  pose = lastOdomPose_;
119  }
120  else
121  {
122  cloudViewer_->setBackgroundColor(cloudViewer_->getDefaultBackgroundColor());
123  }
124  if(!pose.isNull())
125  {
126  lastOdomPose_ = pose;
127 
128  // 3d cloud
129  if(odom.data().depthOrRightRaw().cols == odom.data().imageRaw().cols &&
130  odom.data().depthOrRightRaw().rows == odom.data().imageRaw().rows &&
131  !odom.data().depthOrRightRaw().empty() &&
132  (odom.data().stereoCameraModels().size() || odom.data().cameraModels().size()))
133  {
134  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = util3d::cloudRGBFromSensorData(
135  odom.data(),
136  2, // decimation
137  4.0f); // max depth
138  if(cloud->size())
139  {
140  if(!cloudViewer_->addCloud("cloudOdom", cloud, odometryCorrection_*pose))
141  {
142  UERROR("Adding cloudOdom to viewer failed!");
143  }
144  }
145  else
146  {
147  cloudViewer_->setCloudVisibility("cloudOdom", false);
148  UWARN("Empty cloudOdom!");
149  }
150  }
151 
152  if(!odom.pose().isNull())
153  {
154  // update camera position
155  cloudViewer_->updateCameraTargetPosition(odometryCorrection_*odom.pose());
156  }
157  }
158  cloudViewer_->update();
159  cloudViewer_->refreshView();
160 
161  lastOdometryProcessed_ = true;
162  }
163 
164 
165  virtual void processStatistics(const rtabmap::Statistics & stats)
166  {
167  processingStatistics_ = true;
168 
169  //============================
170  // Add RGB-D clouds
171  //============================
172  const std::map<int, Transform> & poses = stats.poses();
173  QMap<std::string, Transform> clouds = cloudViewer_->getAddedClouds();
174  for(std::map<int, Transform>::const_iterator iter = poses.lower_bound(1); iter!=poses.end(); ++iter)
175  {
176  if(!iter->second.isNull())
177  {
178  std::string cloudName = uFormat("cloud%d", iter->first);
179 
180  // 3d point cloud
181  if(clouds.contains(cloudName))
182  {
183  // Update only if the pose has changed
184  Transform tCloud;
185  cloudViewer_->getPose(cloudName, tCloud);
186  if(tCloud.isNull() || iter->second != tCloud)
187  {
188  if(!cloudViewer_->updateCloudPose(cloudName, iter->second))
189  {
190  UERROR("Updating pose cloud %d failed!", iter->first);
191  }
192  }
193  cloudViewer_->setCloudVisibility(cloudName, true);
194  }
195  else if(iter->first == stats.getLastSignatureData().id())
196  {
197  Signature s = stats.getLastSignatureData();
198  s.sensorData().uncompressData(); // make sure data is uncompressed
199  // Add the new cloud
200  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = util3d::cloudRGBFromSensorData(
201  s.sensorData(),
202  4, // decimation
203  4.0f); // max depth
204  if(cloud->size())
205  {
206  if(!cloudViewer_->addCloud(cloudName, cloud, iter->second))
207  {
208  UERROR("Adding cloud %d to viewer failed!", iter->first);
209  }
210  }
211  else
212  {
213  UWARN("Empty cloud %d!", iter->first);
214  }
215  }
216  }
217  else
218  {
219  UWARN("Null pose for %d ?!?", iter->first);
220  }
221  }
222 
223  //============================
224  // Add 3D graph (show all poses)
225  //============================
226  cloudViewer_->removeAllGraphs();
227  cloudViewer_->removeCloud("graph_nodes");
228  if(poses.size())
229  {
230  // Set graph
231  pcl::PointCloud<pcl::PointXYZ>::Ptr graph(new pcl::PointCloud<pcl::PointXYZ>);
232  pcl::PointCloud<pcl::PointXYZ>::Ptr graphNodes(new pcl::PointCloud<pcl::PointXYZ>);
233  for(std::map<int, Transform>::const_iterator iter=poses.lower_bound(1); iter!=poses.end(); ++iter)
234  {
235  graph->push_back(pcl::PointXYZ(iter->second.x(), iter->second.y(), iter->second.z()));
236  }
237  *graphNodes = *graph;
238 
239 
240  // add graph
241  cloudViewer_->addOrUpdateGraph("graph", graph, Qt::gray);
242  cloudViewer_->addCloud("graph_nodes", graphNodes, Transform::getIdentity(), Qt::green);
243  cloudViewer_->setCloudPointSize("graph_nodes", 5);
244  }
245 
246  odometryCorrection_ = stats.mapCorrection();
247 
248  cloudViewer_->update();
249  cloudViewer_->refreshView();
250 
251  processingStatistics_ = false;
252  }
253 
254  virtual bool handleEvent(UEvent * event)
255  {
256  if(event->getClassName().compare("RtabmapEvent") == 0)
257  {
258  RtabmapEvent * rtabmapEvent = (RtabmapEvent *)event;
259  const Statistics & stats = rtabmapEvent->getStats();
260  // Statistics must be processed in the Qt thread
261  if(this->isVisible())
262  {
263  QMetaObject::invokeMethod(this, "processStatistics", Q_ARG(rtabmap::Statistics, stats));
264  }
265  }
266  else if(event->getClassName().compare("OdometryEvent") == 0)
267  {
268  OdometryEvent * odomEvent = (OdometryEvent *)event;
269  // Odometry must be processed in the Qt thread
270  if(this->isVisible() &&
271  lastOdometryProcessed_ &&
272  !processingStatistics_)
273  {
274  lastOdometryProcessed_ = false; // if we receive too many odometry events!
275  QMetaObject::invokeMethod(this, "processOdometry", Q_ARG(rtabmap::OdometryEvent, *odomEvent));
276  }
277  }
278  return false;
279  }
280 
281 protected:
282  CloudViewer * cloudViewer_;
283  SensorCaptureThread * camera_;
284  Transform lastOdomPose_;
285  Transform odometryCorrection_;
286  bool processingStatistics_;
287  bool lastOdometryProcessed_;
288 };
289 
290 
291 #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: WifiMapping/MapBuilder.h:83
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: WifiMapping/MapBuilder.h:105
MapBuilder::MapBuilder
MapBuilder(SensorCaptureThread *camera=0)
Definition: WifiMapping/MapBuilder.h:57
rtabmap::RtabmapEvent
Definition: RtabmapEvent.h:42
MapBuilder::handleEvent
virtual bool handleEvent(UEvent *event)
Definition: WifiMapping/MapBuilder.h:254
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::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: WifiMapping/MapBuilder.h:165
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
util3d_transforms.h
UEvent::getClassName
virtual std::string getClassName() const =0
stats
bool stats
UConversion.h
Some conversion functions.
CloudViewer.h
util3d_filtering.h
OdometryEvent.h
graph
FactorGraph< FACTOR > * graph
MapBuilder::pauseDetection
virtual void pauseDetection()
Definition: WifiMapping/MapBuilder.h:89
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
rtabmap::SensorData::depthOrRightRaw
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:184
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