31 #include <QVBoxLayout> 32 #include <QtCore/QMetaType> 35 #ifndef Q_MOC_RUN // Mac OS X issue 57 odometryCorrection_(
Transform::getIdentity()),
60 this->setWindowFlags(Qt::Dialog);
61 this->setWindowTitle(tr(
"3D Map"));
62 this->setMinimumWidth(800);
63 this->setMinimumHeight(600);
67 QVBoxLayout *layout =
new QVBoxLayout();
68 layout->addWidget(cloudViewer_);
69 this->setLayout(layout);
71 QAction * pause =
new QAction(
this);
72 this->addAction(pause);
73 pause->setShortcut(Qt::Key_Space);
74 connect(pause, SIGNAL(triggered()),
this, SLOT(pauseDetection()));
88 if(!this->isVisible())
96 cloudViewer_->setBackgroundColor(Qt::darkRed);
102 cloudViewer_->setBackgroundColor(cloudViewer_->getDefaultBackgroundColor());
106 lastOdomPose_ = pose;
120 if(!cloudViewer_->addCloud(
"cloudOdom", cloud, odometryCorrection_*pose))
122 UERROR(
"Adding cloudOdom to viewer failed!");
127 cloudViewer_->setCloudVisibility(
"cloudOdom",
false);
128 UWARN(
"Empty cloudOdom!");
135 cloudViewer_->updateCameraTargetPosition(odometryCorrection_*pose);
138 cloudViewer_->update();
148 const std::map<int, Transform> & poses = stats.
poses();
149 QMap<std::string, Transform> clouds = cloudViewer_->getAddedClouds();
150 for(std::map<int, Transform>::const_iterator iter = poses.lower_bound(1); iter!=poses.end(); ++iter)
152 if(!iter->second.isNull())
154 std::string cloudName =
uFormat(
"cloud%d", iter->first);
157 if(clouds.contains(cloudName))
161 cloudViewer_->getPose(cloudName, tCloud);
162 if(tCloud.
isNull() || iter->second != tCloud)
164 if(!cloudViewer_->updateCloudPose(cloudName, iter->second))
166 UERROR(
"Updating pose cloud %d failed!", iter->first);
169 cloudViewer_->setCloudVisibility(cloudName,
true);
182 if(!cloudViewer_->addCloud(cloudName, cloud, iter->second))
184 UERROR(
"Adding cloud %d to viewer failed!", iter->first);
189 UWARN(
"Empty cloud %d!", iter->first);
195 UWARN(
"Null pose for %d ?!?", iter->first);
202 cloudViewer_->removeAllGraphs();
203 cloudViewer_->removeCloud(
"graph_nodes");
207 pcl::PointCloud<pcl::PointXYZ>::Ptr graph(
new pcl::PointCloud<pcl::PointXYZ>);
208 pcl::PointCloud<pcl::PointXYZ>::Ptr graphNodes(
new pcl::PointCloud<pcl::PointXYZ>);
209 for(std::map<int, Transform>::const_iterator iter=poses.lower_bound(1); iter!=poses.end(); ++iter)
211 graph->push_back(pcl::PointXYZ(iter->second.x(), iter->second.y(), iter->second.z()));
213 *graphNodes = *graph;
217 cloudViewer_->addOrUpdateGraph(
"graph", graph, Qt::gray);
219 cloudViewer_->setCloudPointSize(
"graph_nodes", 5);
224 cloudViewer_->update();
void processStatistics(const rtabmap::Statistics &stats)
void processOdometry(const SensorData &data, Transform pose, const rtabmap::OdometryInfo &odom)
const Signature & getLastSignatureData() const
Some conversion functions.
const cv::Mat & imageRaw() const
Transform odometryCorrection_
Wrappers of STL for convenient functions.
bool isValidForProjection() const
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
const cv::Mat & depthOrRightRaw() const
CloudViewer * cloudViewer_
const std::map< int, Transform > & poses() const
const std::vector< CameraModel > & cameraModels() const
SensorData & sensorData()
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
const Transform & mapCorrection() const
std::string UTILITE_EXP uFormat(const char *fmt,...)