31 #include <QVBoxLayout>
32 #include <QtCore/QMetaType>
35 #ifndef Q_MOC_RUN // Mac OS X issue
61 odometryCorrection_(
Transform::getIdentity()),
62 processingStatistics_(
false),
63 lastOdometryProcessed_(
true),
66 this->setWindowFlags(Qt::Dialog);
67 this->setWindowTitle(tr(
"3D Map"));
68 this->setMinimumWidth(800);
69 this->setMinimumHeight(600);
73 QVBoxLayout *layout =
new QVBoxLayout();
74 layout->addWidget(cloudViewer_);
75 this->setLayout(layout);
77 qRegisterMetaType<rtabmap::OdometryEvent>(
"rtabmap::OdometryEvent");
78 qRegisterMetaType<rtabmap::Statistics>(
"rtabmap::Statistics");
80 QAction * pause =
new QAction(
this);
81 this->addAction(pause);
82 pause->setShortcut(Qt::Key_Space);
83 connect(pause, SIGNAL(triggered()),
this, SLOT(pauseDetection()));
88 this->unregisterFromEventsManager();
97 if(camera_->isCapturing())
110 if(!this->isVisible())
119 cloudViewer_->setBackgroundColor(Qt::darkRed);
121 pose = lastOdomPose_;
125 cloudViewer_->setBackgroundColor(cloudViewer_->getDefaultBackgroundColor());
129 lastOdomPose_ = pose;
143 if(!cloudViewer_->addCloud(
"cloudOdom", cloud, odometryCorrection_*pose))
145 UERROR(
"Adding cloudOdom to viewer failed!");
150 cloudViewer_->setCloudVisibility(
"cloudOdom",
false);
151 UWARN(
"Empty cloudOdom!");
158 cloudViewer_->updateCameraTargetPosition(odometryCorrection_*odom.
pose());
161 cloudViewer_->update();
163 lastOdometryProcessed_ =
true;
169 processingStatistics_ =
true;
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)
178 if(!
iter->second.isNull())
180 std::string cloudName =
uFormat(
"cloud%d",
iter->first);
183 if(clouds.contains(cloudName))
187 cloudViewer_->getPose(cloudName, tCloud);
190 if(!cloudViewer_->updateCloudPose(cloudName,
iter->second))
192 UERROR(
"Updating pose cloud %d failed!",
iter->first);
195 cloudViewer_->setCloudVisibility(cloudName,
true);
197 else if(
iter->first ==
stats.getLastSignatureData().id())
200 s.sensorData().uncompressData();
208 if(!cloudViewer_->addCloud(cloudName, cloud,
iter->second))
210 UERROR(
"Adding cloud %d to viewer failed!",
iter->first);
221 UWARN(
"Null pose for %d ?!?",
iter->first);
228 cloudViewer_->removeAllGraphs();
229 cloudViewer_->removeCloud(
"graph_nodes");
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)
237 graph->push_back(pcl::PointXYZ(
iter->second.x(),
iter->second.y(),
iter->second.z()));
239 *graphNodes = *
graph;
243 cloudViewer_->addOrUpdateGraph(
"graph",
graph, Qt::gray);
245 cloudViewer_->setCloudPointSize(
"graph_nodes", 5);
251 if(grid_.addedNodes().find(
stats.getLastSignatureData().id()) == grid_.addedNodes().end())
253 if(
stats.getLastSignatureData().sensorData().gridCellSize() > 0.0f)
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());
261 if(grid_.addedNodes().size() || localGrids_.size())
263 grid_.update(
stats.poses());
265 if(grid_.addedNodes().size())
268 cv::Mat map8S = grid_.getMap(xMin, yMin);
273 cloudViewer_->addOccupancyGridMap(map8U, grid_.getCellSize(), xMin, yMin, 0.75);
277 odometryCorrection_ =
stats.mapCorrection();
279 cloudViewer_->update();
281 processingStatistics_ =
false;
291 if(this->isVisible())
296 else if(event->
getClassName().compare(
"OdometryEvent") == 0)
300 if(this->isVisible() &&
301 lastOdometryProcessed_ &&
302 !processingStatistics_)
304 lastOdometryProcessed_ =
false;
316 bool processingStatistics_;
317 bool lastOdometryProcessed_;