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/util3d_filtering.h"
00039 #include "rtabmap/core/util3d_transforms.h"
00040 #include "rtabmap/core/RtabmapEvent.h"
00041 #include "rtabmap/core/OccupancyGrid.h"
00042 #endif
00043 #include "rtabmap/utilite/UStl.h"
00044 #include "rtabmap/utilite/UConversion.h"
00045 #include "rtabmap/utilite/UEventsHandler.h"
00046 #include "rtabmap/utilite/ULogger.h"
00047 #include "rtabmap/core/OdometryEvent.h"
00048 #include "rtabmap/core/CameraThread.h"
00049
00050 using namespace rtabmap;
00051
00052
00053 class MapBuilder : public QWidget, public UEventsHandler
00054 {
00055 Q_OBJECT
00056 public:
00057
00058 MapBuilder(CameraThread * camera = 0) :
00059 camera_(camera),
00060 odometryCorrection_(Transform::getIdentity()),
00061 processingStatistics_(false),
00062 lastOdometryProcessed_(true)
00063 {
00064 this->setWindowFlags(Qt::Dialog);
00065 this->setWindowTitle(tr("3D Map"));
00066 this->setMinimumWidth(800);
00067 this->setMinimumHeight(600);
00068
00069 cloudViewer_ = new CloudViewer(this);
00070
00071 QVBoxLayout *layout = new QVBoxLayout();
00072 layout->addWidget(cloudViewer_);
00073 this->setLayout(layout);
00074
00075 qRegisterMetaType<rtabmap::OdometryEvent>("rtabmap::OdometryEvent");
00076 qRegisterMetaType<rtabmap::Statistics>("rtabmap::Statistics");
00077
00078 QAction * pause = new QAction(this);
00079 this->addAction(pause);
00080 pause->setShortcut(Qt::Key_Space);
00081 connect(pause, SIGNAL(triggered()), this, SLOT(pauseDetection()));
00082 }
00083
00084 virtual ~MapBuilder()
00085 {
00086 this->unregisterFromEventsManager();
00087 }
00088
00089 protected Q_SLOTS:
00090 virtual void pauseDetection()
00091 {
00092 UWARN("");
00093 if(camera_)
00094 {
00095 if(camera_->isCapturing())
00096 {
00097 camera_->join(true);
00098 }
00099 else
00100 {
00101 camera_->start();
00102 }
00103 }
00104 }
00105
00106 virtual void processOdometry(const rtabmap::OdometryEvent & odom)
00107 {
00108 if(!this->isVisible())
00109 {
00110 return;
00111 }
00112
00113 Transform pose = odom.pose();
00114 if(pose.isNull())
00115 {
00116
00117 cloudViewer_->setBackgroundColor(Qt::darkRed);
00118
00119 pose = lastOdomPose_;
00120 }
00121 else
00122 {
00123 cloudViewer_->setBackgroundColor(cloudViewer_->getDefaultBackgroundColor());
00124 }
00125 if(!pose.isNull())
00126 {
00127 lastOdomPose_ = pose;
00128
00129
00130 if(odom.data().depthOrRightRaw().cols == odom.data().imageRaw().cols &&
00131 odom.data().depthOrRightRaw().rows == odom.data().imageRaw().rows &&
00132 !odom.data().depthOrRightRaw().empty() &&
00133 (odom.data().stereoCameraModel().isValidForProjection() || odom.data().cameraModels().size()))
00134 {
00135 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = util3d::cloudRGBFromSensorData(
00136 odom.data(),
00137 2,
00138 4.0f);
00139 if(cloud->size())
00140 {
00141 if(!cloudViewer_->addCloud("cloudOdom", cloud, odometryCorrection_*pose))
00142 {
00143 UERROR("Adding cloudOdom to viewer failed!");
00144 }
00145 }
00146 else
00147 {
00148 cloudViewer_->setCloudVisibility("cloudOdom", false);
00149 UWARN("Empty cloudOdom!");
00150 }
00151 }
00152
00153 if(!odom.pose().isNull())
00154 {
00155
00156 cloudViewer_->updateCameraTargetPosition(odometryCorrection_*odom.pose());
00157 }
00158 }
00159 cloudViewer_->update();
00160
00161 lastOdometryProcessed_ = true;
00162 }
00163
00164
00165 virtual void processStatistics(const rtabmap::Statistics & stats)
00166 {
00167 processingStatistics_ = true;
00168
00169
00170
00171
00172 const std::map<int, Transform> & poses = stats.poses();
00173 QMap<std::string, Transform> clouds = cloudViewer_->getAddedClouds();
00174 for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end(); ++iter)
00175 {
00176 if(!iter->second.isNull())
00177 {
00178 std::string cloudName = uFormat("cloud%d", iter->first);
00179
00180
00181 if(clouds.contains(cloudName))
00182 {
00183
00184 Transform tCloud;
00185 cloudViewer_->getPose(cloudName, tCloud);
00186 if(tCloud.isNull() || iter->second != tCloud)
00187 {
00188 if(!cloudViewer_->updateCloudPose(cloudName, iter->second))
00189 {
00190 UERROR("Updating pose cloud %d failed!", iter->first);
00191 }
00192 }
00193 cloudViewer_->setCloudVisibility(cloudName, true);
00194 }
00195 else if(uContains(stats.getSignatures(), iter->first))
00196 {
00197 Signature s = stats.getSignatures().at(iter->first);
00198 s.sensorData().uncompressData();
00199
00200 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = util3d::cloudRGBFromSensorData(
00201 s.sensorData(),
00202 4,
00203 4.0f);
00204 if(cloud->size())
00205 {
00206 if(!cloudViewer_->addCloud(cloudName, cloud, iter->second))
00207 {
00208 UERROR("Adding cloud %d to viewer failed!", iter->first);
00209 }
00210 }
00211 else
00212 {
00213 UWARN("Empty cloud %d!", iter->first);
00214 }
00215 }
00216 }
00217 else
00218 {
00219 UWARN("Null pose for %d ?!?", iter->first);
00220 }
00221 }
00222
00223
00224
00225
00226 cloudViewer_->removeAllGraphs();
00227 cloudViewer_->removeCloud("graph_nodes");
00228 if(poses.size())
00229 {
00230
00231 pcl::PointCloud<pcl::PointXYZ>::Ptr graph(new pcl::PointCloud<pcl::PointXYZ>);
00232 pcl::PointCloud<pcl::PointXYZ>::Ptr graphNodes(new pcl::PointCloud<pcl::PointXYZ>);
00233 for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
00234 {
00235 graph->push_back(pcl::PointXYZ(iter->second.x(), iter->second.y(), iter->second.z()));
00236 }
00237 *graphNodes = *graph;
00238
00239
00240
00241 cloudViewer_->addOrUpdateGraph("graph", graph, Qt::gray);
00242 cloudViewer_->addCloud("graph_nodes", graphNodes, Transform::getIdentity(), Qt::green);
00243 cloudViewer_->setCloudPointSize("graph_nodes", 5);
00244 }
00245
00246
00247
00248
00249 for(std::map<int, Transform>::const_reverse_iterator iter = stats.poses().rbegin(); iter!=stats.poses().rend(); ++iter)
00250 {
00251 int id = iter->first;
00252 if(grid_.addedNodes().find(id) == grid_.addedNodes().end())
00253 {
00254 std::map<int, Signature>::const_iterator jter = stats.getSignatures().find(id);
00255 if(jter != stats.getSignatures().end() && jter->second.sensorData().gridCellSize() > 0.0f)
00256 {
00257 cv::Mat groundCells, obstacleCells, emptyCells;
00258 jter->second.sensorData().uncompressDataConst(0, 0, 0, 0, &groundCells, &obstacleCells, &emptyCells);
00259 grid_.addToCache(id, groundCells, obstacleCells, emptyCells);
00260 }
00261 }
00262 else
00263 {
00264
00265 break;
00266 }
00267 }
00268 if(grid_.addedNodes().size() || grid_.cacheSize())
00269 {
00270 grid_.update(stats.poses());
00271 }
00272 if(grid_.addedNodes().size())
00273 {
00274 float xMin, yMin;
00275 cv::Mat map8S = grid_.getMap(xMin, yMin);
00276 if(!map8S.empty())
00277 {
00278
00279 cv::Mat map8U = util3d::convertMap2Image8U(map8S);
00280 cloudViewer_->addOccupancyGridMap(map8U, grid_.getCellSize(), xMin, yMin, 0.75);
00281 }
00282 }
00283
00284 odometryCorrection_ = stats.mapCorrection();
00285
00286 cloudViewer_->update();
00287
00288 processingStatistics_ = false;
00289 }
00290
00291 virtual bool handleEvent(UEvent * event)
00292 {
00293 if(event->getClassName().compare("RtabmapEvent") == 0)
00294 {
00295 RtabmapEvent * rtabmapEvent = (RtabmapEvent *)event;
00296 const Statistics & stats = rtabmapEvent->getStats();
00297
00298 if(this->isVisible())
00299 {
00300 QMetaObject::invokeMethod(this, "processStatistics", Q_ARG(rtabmap::Statistics, stats));
00301 }
00302 }
00303 else if(event->getClassName().compare("OdometryEvent") == 0)
00304 {
00305 OdometryEvent * odomEvent = (OdometryEvent *)event;
00306
00307 if(this->isVisible() &&
00308 lastOdometryProcessed_ &&
00309 !processingStatistics_)
00310 {
00311 lastOdometryProcessed_ = false;
00312 QMetaObject::invokeMethod(this, "processOdometry", Q_ARG(rtabmap::OdometryEvent, *odomEvent));
00313 }
00314 }
00315 return false;
00316 }
00317
00318 protected:
00319 CloudViewer * cloudViewer_;
00320 CameraThread * camera_;
00321 Transform lastOdomPose_;
00322 Transform odometryCorrection_;
00323 bool processingStatistics_;
00324 bool lastOdometryProcessed_;
00325 OccupancyGrid grid_;
00326 };
00327
00328
00329 #endif