30 #include <QVBoxLayout>
31 #include <QtCore/QMetaType>
34 #ifndef Q_MOC_RUN // Mac OS X issue
58 sensorCaptureThread_(
camera),
59 odometryCorrection_(
Transform::getIdentity()),
60 processingStatistics_(
false),
61 lastOdometryProcessed_(
true),
64 this->setWindowFlags(Qt::Dialog);
65 this->setWindowTitle(tr(
"3D Map"));
66 this->setMinimumWidth(800);
67 this->setMinimumHeight(600);
70 cloudViewer_->setCameraTargetLocked(
true);
72 QVBoxLayout *layout =
new QVBoxLayout();
73 layout->addWidget(cloudViewer_);
74 this->setLayout(layout);
76 qRegisterMetaType<rtabmap::OdometryEvent>(
"rtabmap::OdometryEvent");
77 qRegisterMetaType<rtabmap::Statistics>(
"rtabmap::Statistics");
79 QAction * pause =
new QAction(
this);
80 this->addAction(pause);
81 pause->setShortcut(Qt::Key_Space);
82 connect(pause, SIGNAL(triggered()),
this, SLOT(pauseDetection()));
84 QAction * visibility =
new QAction(
this);
85 this->addAction(visibility);
86 visibility->setShortcut(Qt::Key_Tab);
87 connect(visibility, SIGNAL(triggered()),
this, SLOT(rotateVisibility()));
92 this->unregisterFromEventsManager();
99 if(sensorCaptureThread_)
101 if(sensorCaptureThread_->isCapturing())
103 sensorCaptureThread_->join(
true);
107 sensorCaptureThread_->start();
114 visibility_ = (visibility_+1) % 3;
117 UWARN(
"Show both Odom and Map");
119 else if(visibility_ == 1)
121 UWARN(
"Show only Map");
123 else if(visibility_ == 2)
125 UWARN(
"Show only Odom");
131 if(!this->isVisible())
140 cloudViewer_->setBackgroundColor(Qt::darkRed);
142 pose = lastOdomPose_;
146 cloudViewer_->setBackgroundColor(cloudViewer_->getDefaultBackgroundColor());
150 lastOdomPose_ = pose;
156 if(cloud->size() && (visibility_ == 0 || visibility_ == 2))
158 if(!cloudViewer_->addCloud(
"cloudOdom", cloud, odometryCorrection_*pose, Qt::magenta))
160 UERROR(
"Adding cloudOdom to viewer failed!");
165 cloudViewer_->setCloudVisibility(
"cloudOdom",
false);
167 UWARN(
"Empty cloudOdom!");
174 if(cloud->size() && (visibility_ == 0 || visibility_ == 2))
176 if(!cloudViewer_->addCloud(
"cloudOdomLocalMap", cloud, odometryCorrection_, Qt::blue))
178 UERROR(
"Adding cloudOdomLocalMap to viewer failed!");
183 cloudViewer_->setCloudVisibility(
"cloudOdomLocalMap",
false);
185 UWARN(
"Empty cloudOdomLocalMap!");
192 cloudViewer_->updateCameraTargetPosition(odometryCorrection_*odom.
pose());
195 cloudViewer_->update();
197 lastOdometryProcessed_ =
true;
203 processingStatistics_ =
true;
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)
212 if(!
iter->second.isNull())
214 std::string cloudName =
uFormat(
"cloud_%d",
iter->first);
217 if(clouds.contains(cloudName))
221 cloudViewer_->getPose(cloudName, tCloud);
224 if(!cloudViewer_->updateCloudPose(cloudName,
iter->second))
226 UERROR(
"Updating pose cloud %d failed!",
iter->first);
230 else if(
iter->first ==
stats.getLastSignatureData().id())
233 s.sensorData().uncompressData();
236 s.sensorData().laserScanRaw(),
237 s.sensorData().laserScanRaw().localTransform());
240 if(!cloudViewer_->addCloud(cloudName, cloud,
iter->second))
242 UERROR(
"Adding cloud %d to viewer failed!",
iter->first);
251 cloudViewer_->setCloudVisibility(cloudName, visibility_ == 0 || visibility_ == 1);
255 UWARN(
"Null pose for %d ?!?",
iter->first);
260 for(QMap<std::string, Transform>::iterator
iter = clouds.begin();
iter!=clouds.end(); ++
iter)
265 if(poses.find(
id) == poses.end())
267 cloudViewer_->removeCloud(
iter.key());
275 cloudViewer_->removeAllGraphs();
276 cloudViewer_->removeCloud(
"graph_nodes");
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)
284 graph->push_back(pcl::PointXYZ(
iter->second.x(),
iter->second.y(),
iter->second.z()));
286 *graphNodes = *
graph;
290 cloudViewer_->addOrUpdateGraph(
"graph",
graph, Qt::gray);
292 cloudViewer_->setCloudPointSize(
"graph_nodes", 5);
295 odometryCorrection_ =
stats.mapCorrection();
297 cloudViewer_->update();
299 processingStatistics_ =
false;
309 if(this->isVisible())
314 else if(event->
getClassName().compare(
"OdometryEvent") == 0)
318 if(this->isVisible() &&
319 lastOdometryProcessed_ &&
320 !processingStatistics_)
322 lastOdometryProcessed_ =
false;