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 #include "rtabmap/gui/LoopClosureViewer.h"
00029 #include "ui_loopClosureViewer.h"
00030
00031 #include "rtabmap/core/Memory.h"
00032 #include "rtabmap/core/util3d.h"
00033 #include "rtabmap/core/Signature.h"
00034 #include "rtabmap/utilite/ULogger.h"
00035 #include "rtabmap/utilite/UStl.h"
00036
00037 #include <QtCore/QTimer>
00038
00039 namespace rtabmap {
00040
00041 LoopClosureViewer::LoopClosureViewer(QWidget * parent) :
00042 QWidget(parent),
00043 decimation_(1),
00044 maxDepth_(0),
00045 samples_(0)
00046 {
00047 ui_ = new Ui_loopClosureViewer();
00048 ui_->setupUi(this);
00049 ui_->cloudViewerTransform->setCameraLockZ(false);
00050
00051 connect(ui_->checkBox_rawCloud, SIGNAL(clicked()), this, SLOT(updateView()));
00052 }
00053
00054 LoopClosureViewer::~LoopClosureViewer() {
00055 delete ui_;
00056 }
00057
00058 void LoopClosureViewer::setData(const Signature & sA, const Signature & sB)
00059 {
00060 sA_ = sA;
00061 sB_ = sB;
00062 if(sA_.id()>0 && sB_.id()>0)
00063 {
00064 ui_->label_idA->setText(QString("[%1-%2]").arg(sA.id()).arg(sB.id()));
00065 }
00066 }
00067
00068 void LoopClosureViewer::updateView(const Transform & transform)
00069 {
00070 if(sA_.id()>0 && sB_.id()>0)
00071 {
00072 int decimation = 1;
00073 float maxDepth = 0;
00074 int samples = 0;
00075
00076 if(!ui_->checkBox_rawCloud->isChecked())
00077 {
00078 decimation = decimation_;
00079 maxDepth = maxDepth_;
00080 samples = samples_;
00081 }
00082
00083 UDEBUG("decimation = %d", decimation);
00084 UDEBUG("maxDepth = %f", maxDepth);
00085 UDEBUG("samples = %d", samples);
00086
00087 Transform t;
00088 if(!transform.isNull())
00089 {
00090 transform_ = transform;
00091 t = transform;
00092 }
00093 else if(!transform_.isNull())
00094 {
00095 t = transform_;
00096 }
00097 else
00098 {
00099 t = sB_.getPose();
00100 }
00101
00102 UDEBUG("t= %s", t.prettyPrint().c_str());
00103 ui_->label_transform->setText(QString("(%1)").arg(t.prettyPrint().c_str()));
00104 if(!t.isNull())
00105 {
00106
00107 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudA;
00108 if(sA_.getDepthRaw().type() == CV_8UC1)
00109 {
00110 cloudA = util3d::cloudFromStereoImages(
00111 sA_.getImageRaw(),
00112 sA_.getDepthRaw(),
00113 sA_.getCx(), sA_.getCy(),
00114 sA_.getFx(), sA_.getFy(),
00115 decimation);
00116 }
00117 else
00118 {
00119 cloudA = util3d::cloudFromDepthRGB(
00120 sA_.getImageRaw(),
00121 sA_.getDepthRaw(),
00122 sA_.getCx(), sA_.getCy(),
00123 sA_.getFx(), sA_.getFy(),
00124 decimation);
00125 }
00126
00127 cloudA = util3d::removeNaNFromPointCloud<pcl::PointXYZRGB>(cloudA);
00128
00129 if(maxDepth>0.0)
00130 {
00131 cloudA = util3d::passThrough<pcl::PointXYZRGB>(cloudA, "z", 0, maxDepth);
00132 }
00133 if(samples>0 && (int)cloudA->size() > samples)
00134 {
00135 cloudA = util3d::sampling<pcl::PointXYZRGB>(cloudA, samples);
00136 }
00137 cloudA = util3d::transformPointCloud<pcl::PointXYZRGB>(cloudA, sA_.getLocalTransform());
00138
00139 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudB;
00140 if(sB_.getDepthRaw().type() == CV_8UC1)
00141 {
00142 cloudB = util3d::cloudFromStereoImages(
00143 sB_.getImageRaw(),
00144 sB_.getDepthRaw(),
00145 sB_.getCx(), sB_.getCy(),
00146 sB_.getFx(), sB_.getFy(),
00147 decimation);
00148 }
00149 else
00150 {
00151 cloudB = util3d::cloudFromDepthRGB(
00152 sB_.getImageRaw(),
00153 sB_.getDepthRaw(),
00154 sB_.getCx(), sB_.getCy(),
00155 sB_.getFx(), sB_.getFy(),
00156 decimation);
00157 }
00158
00159 cloudB = util3d::removeNaNFromPointCloud<pcl::PointXYZRGB>(cloudB);
00160
00161 if(maxDepth>0.0)
00162 {
00163 cloudB = util3d::passThrough<pcl::PointXYZRGB>(cloudB, "z", 0, maxDepth);
00164 }
00165 if(samples>0 && (int)cloudB->size() > samples)
00166 {
00167 cloudB = util3d::sampling<pcl::PointXYZRGB>(cloudB, samples);
00168 }
00169 cloudB = util3d::transformPointCloud<pcl::PointXYZRGB>(cloudB, t*sB_.getLocalTransform());
00170
00171
00172 pcl::PointCloud<pcl::PointXYZ>::Ptr scanA, scanB;
00173 scanA = util3d::laserScanToPointCloud(sA_.getLaserScanRaw());
00174 scanB = util3d::laserScanToPointCloud(sB_.getLaserScanRaw());
00175 scanB = util3d::transformPointCloud<pcl::PointXYZ>(scanB, t);
00176
00177 ui_->label_idA->setText(QString("[%1 (%2) -> %3 (%4)]").arg(sB_.id()).arg(cloudB->size()).arg(sA_.id()).arg(cloudA->size()));
00178
00179 if(cloudA->size())
00180 {
00181 ui_->cloudViewerTransform->addOrUpdateCloud("cloud0", cloudA);
00182 }
00183 if(cloudB->size())
00184 {
00185 ui_->cloudViewerTransform->addOrUpdateCloud("cloud1", cloudB);
00186 }
00187 if(scanA->size())
00188 {
00189 ui_->cloudViewerTransform->addOrUpdateCloud("scan0", scanA);
00190 }
00191 if(scanB->size())
00192 {
00193 ui_->cloudViewerTransform->addOrUpdateCloud("scan1", scanB);
00194 }
00195 }
00196 else
00197 {
00198 UERROR("loop transform is null !?!?");
00199 ui_->cloudViewerTransform->removeAllClouds();
00200 }
00201 ui_->cloudViewerTransform->update();
00202 }
00203 }
00204
00205
00206 void LoopClosureViewer::showEvent(QShowEvent * event)
00207 {
00208 QWidget::showEvent( event );
00209 QTimer::singleShot(500, this, SLOT(updateView()));
00210 }
00211
00212 }