00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef MAPBUILDER_H_
00029 #define MAPBUILDER_H_
00030
00031 #include <QVBoxLayout>
00032 #include <QtCore/QMetaType>
00033 #include <QAction>
00034
00035 #ifndef Q_MOC_RUN // Mac OS X issue
00036 #include "rtabmap/gui/CloudViewer.h"
00037 #include "rtabmap/core/util3d.h"
00038 #include "rtabmap/core/RtabmapEvent.h"
00039 #endif
00040 #include "rtabmap/utilite/UStl.h"
00041 #include "rtabmap/utilite/UConversion.h"
00042 #include "rtabmap/utilite/UEventsHandler.h"
00043 #include "rtabmap/utilite/ULogger.h"
00044 #include "rtabmap/core/OdometryEvent.h"
00045 #include "rtabmap/core/CameraThread.h"
00046
00047 using namespace rtabmap;
00048
00049
00050 class MapBuilder : public QWidget, public UEventsHandler
00051 {
00052 Q_OBJECT
00053 public:
00054
00055 MapBuilder(CameraThread * camera = 0) :
00056 camera_(camera),
00057 odometryCorrection_(Transform::getIdentity()),
00058 processingStatistics_(false),
00059 lastOdometryProcessed_(true)
00060 {
00061 this->setWindowFlags(Qt::Dialog);
00062 this->setWindowTitle(tr("3D Map"));
00063 this->setMinimumWidth(800);
00064 this->setMinimumHeight(600);
00065
00066 cloudViewer_ = new CloudViewer(this);
00067
00068 QVBoxLayout *layout = new QVBoxLayout();
00069 layout->addWidget(cloudViewer_);
00070 this->setLayout(layout);
00071
00072 qRegisterMetaType<rtabmap::Statistics>("rtabmap::Statistics");
00073 qRegisterMetaType<rtabmap::SensorData>("rtabmap::SensorData");
00074
00075 QAction * pause = new QAction(this);
00076 this->addAction(pause);
00077 pause->setShortcut(Qt::Key_Space);
00078 connect(pause, SIGNAL(triggered()), this, SLOT(pauseDetection()));
00079 }
00080
00081 virtual ~MapBuilder()
00082 {
00083 this->unregisterFromEventsManager();
00084 }
00085
00086 protected slots:
00087 virtual void pauseDetection()
00088 {
00089 UWARN("");
00090 if(camera_)
00091 {
00092 if(camera_->isCapturing())
00093 {
00094 camera_->join(true);
00095 }
00096 else
00097 {
00098 camera_->start();
00099 }
00100 }
00101 }
00102
00103 virtual void processOdometry(const rtabmap::SensorData & data)
00104 {
00105 if(!this->isVisible())
00106 {
00107 return;
00108 }
00109
00110 Transform pose = data.pose();
00111 if(pose.isNull())
00112 {
00113
00114 cloudViewer_->setBackgroundColor(Qt::darkRed);
00115
00116 pose = lastOdomPose_;
00117 }
00118 else
00119 {
00120 cloudViewer_->setBackgroundColor(cloudViewer_->getDefaultBackgroundColor());
00121 }
00122 if(!pose.isNull())
00123 {
00124 lastOdomPose_ = pose;
00125
00126
00127 if(data.depth().cols == data.image().cols &&
00128 data.depth().rows == data.image().rows &&
00129 !data.depth().empty() &&
00130 data.fx() > 0.0f &&
00131 data.fy() > 0.0f)
00132 {
00133 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = util3d::cloudFromDepthRGB(
00134 data.image(),
00135 data.depth(),
00136 data.cx(),
00137 data.cy(),
00138 data.fx(),
00139 data.fy(),
00140 2);
00141 if(cloud->size())
00142 {
00143 cloud = util3d::passThrough<pcl::PointXYZRGB>(cloud, "z", 0, 4.0f);
00144 if(cloud->size())
00145 {
00146 cloud = util3d::transformPointCloud<pcl::PointXYZRGB>(cloud, data.localTransform());
00147 }
00148 }
00149 if(!cloudViewer_->addOrUpdateCloud("cloudOdom", cloud, odometryCorrection_*pose))
00150 {
00151 UERROR("Adding cloudOdom to viewer failed!");
00152 }
00153 }
00154
00155 if(!data.pose().isNull())
00156 {
00157
00158 cloudViewer_->updateCameraTargetPosition(odometryCorrection_*data.pose());
00159 }
00160 }
00161 cloudViewer_->update();
00162
00163 lastOdometryProcessed_ = true;
00164 }
00165
00166
00167 virtual void processStatistics(const rtabmap::Statistics & stats)
00168 {
00169 processingStatistics_ = true;
00170
00171
00172
00173
00174 const std::map<int, Transform> & poses = stats.poses();
00175 QMap<std::string, Transform> clouds = cloudViewer_->getAddedClouds();
00176 for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end(); ++iter)
00177 {
00178 if(!iter->second.isNull())
00179 {
00180 std::string cloudName = uFormat("cloud%d", iter->first);
00181
00182
00183 if(clouds.contains(cloudName))
00184 {
00185
00186 Transform tCloud;
00187 cloudViewer_->getPose(cloudName, tCloud);
00188 if(tCloud.isNull() || iter->second != tCloud)
00189 {
00190 if(!cloudViewer_->updateCloudPose(cloudName, iter->second))
00191 {
00192 UERROR("Updating pose cloud %d failed!", iter->first);
00193 }
00194 }
00195 cloudViewer_->setCloudVisibility(cloudName, true);
00196 }
00197 else if(iter->first == stats.refImageId() &&
00198 stats.getSignature().id() == iter->first)
00199 {
00200 Signature s = stats.getSignature();
00201 s.uncompressData();
00202
00203 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = util3d::cloudFromDepthRGB(
00204 s.getImageRaw(),
00205 s.getDepthRaw(),
00206 s.getCx(),
00207 s.getCy(),
00208 s.getFx(),
00209 s.getFy(),
00210 4);
00211
00212 if(cloud->size())
00213 {
00214 cloud = util3d::passThrough<pcl::PointXYZRGB>(cloud, "z", 0, 4.0f);
00215 if(cloud->size())
00216 {
00217 cloud = util3d::transformPointCloud<pcl::PointXYZRGB>(cloud, stats.getSignature().getLocalTransform());
00218 }
00219 }
00220 if(!cloudViewer_->addOrUpdateCloud(cloudName, cloud, iter->second))
00221 {
00222 UERROR("Adding cloud %d to viewer failed!", iter->first);
00223 }
00224 }
00225 }
00226 }
00227
00228
00229
00230
00231 cloudViewer_->removeAllGraphs();
00232 cloudViewer_->removeCloud("graph_nodes");
00233 if(poses.size())
00234 {
00235
00236 pcl::PointCloud<pcl::PointXYZ>::Ptr graph(new pcl::PointCloud<pcl::PointXYZ>);
00237 pcl::PointCloud<pcl::PointXYZ>::Ptr graphNodes(new pcl::PointCloud<pcl::PointXYZ>);
00238 for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
00239 {
00240 graph->push_back(pcl::PointXYZ(iter->second.x(), iter->second.y(), iter->second.z()));
00241 }
00242 *graphNodes = *graph;
00243
00244
00245
00246 cloudViewer_->addOrUpdateGraph("graph", graph, Qt::gray);
00247 cloudViewer_->addOrUpdateCloud("graph_nodes", graphNodes, Transform::getIdentity(), Qt::green);
00248 cloudViewer_->setCloudPointSize("graph_nodes", 5);
00249 }
00250
00251 odometryCorrection_ = stats.mapCorrection();
00252
00253 cloudViewer_->update();
00254
00255 processingStatistics_ = false;
00256 }
00257
00258 virtual void handleEvent(UEvent * event)
00259 {
00260 if(event->getClassName().compare("RtabmapEvent") == 0)
00261 {
00262 RtabmapEvent * rtabmapEvent = (RtabmapEvent *)event;
00263 const Statistics & stats = rtabmapEvent->getStats();
00264
00265 if(this->isVisible())
00266 {
00267 QMetaObject::invokeMethod(this, "processStatistics", Q_ARG(rtabmap::Statistics, stats));
00268 }
00269 }
00270 else if(event->getClassName().compare("OdometryEvent") == 0)
00271 {
00272 OdometryEvent * odomEvent = (OdometryEvent *)event;
00273
00274 if(this->isVisible() &&
00275 lastOdometryProcessed_ &&
00276 !processingStatistics_)
00277 {
00278 lastOdometryProcessed_ = false;
00279 QMetaObject::invokeMethod(this, "processOdometry", Q_ARG(rtabmap::SensorData, odomEvent->data()));
00280 }
00281 }
00282 }
00283
00284 protected:
00285 CloudViewer * cloudViewer_;
00286 CameraThread * camera_;
00287 Transform lastOdomPose_;
00288 Transform odometryCorrection_;
00289 bool processingStatistics_;
00290 bool lastOdometryProcessed_;
00291 };
00292
00293
00294 #endif