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/CloudViewer.h"
00029
00030 #include <rtabmap/utilite/ULogger.h>
00031 #include <rtabmap/utilite/UTimer.h>
00032 #include <rtabmap/utilite/UConversion.h>
00033 #include <rtabmap/core/util3d.h>
00034 #include <pcl/visualization/pcl_visualizer.h>
00035 #include <pcl/filters/frustum_culling.h>
00036 #include <QMenu>
00037 #include <QAction>
00038 #include <QtGui/QContextMenuEvent>
00039 #include <QInputDialog>
00040 #include <QtGui/QWheelEvent>
00041 #include <QtGui/QKeyEvent>
00042 #include <QColorDialog>
00043 #include <QtGui/QVector3D>
00044 #include <set>
00045
00046 #include <vtkRenderWindow.h>
00047
00048 namespace rtabmap {
00049
00050 void CloudViewer::mouseEventOccurred (const pcl::visualization::MouseEvent &event, void* viewer_void)
00051 {
00052 if (event.getButton () == pcl::visualization::MouseEvent::LeftButton ||
00053 event.getButton () == pcl::visualization::MouseEvent::MiddleButton)
00054 {
00055 this->update();
00056 }
00057 }
00058
00059 CloudViewer::CloudViewer(QWidget *parent) :
00060 QVTKWidget(parent),
00061 _visualizer(new pcl::visualization::PCLVisualizer("PCLVisualizer", false)),
00062 _aLockCamera(0),
00063 _aFollowCamera(0),
00064 _aResetCamera(0),
00065 _aLockViewZ(0),
00066 _aShowTrajectory(0),
00067 _aSetTrajectorySize(0),
00068 _aClearTrajectory(0),
00069 _aShowGrid(0),
00070 _aSetGridCellCount(0),
00071 _aSetGridCellSize(0),
00072 _aSetBackgroundColor(0),
00073 _menu(0),
00074 _trajectory(new pcl::PointCloud<pcl::PointXYZ>),
00075 _maxTrajectorySize(100),
00076 _gridCellCount(50),
00077 _gridCellSize(1),
00078 _workingDirectory("."),
00079 _defaultBgColor(Qt::black),
00080 _currentBgColor(Qt::black)
00081 {
00082 this->setMinimumSize(200, 200);
00083
00084 this->SetRenderWindow(_visualizer->getRenderWindow());
00085
00086
00087
00088
00089 this->GetInteractor()->SetInteractorStyle (_visualizer->getInteractorStyle());
00090
00091 _visualizer->registerMouseCallback (&CloudViewer::mouseEventOccurred, *this, (void*)_visualizer);
00092 _visualizer->setCameraPosition(
00093 -1, 0, 0,
00094 0, 0, 0,
00095 0, 0, 1);
00096
00097
00098 createMenu();
00099
00100 setMouseTracking(false);
00101 }
00102
00103 CloudViewer::~CloudViewer()
00104 {
00105 UDEBUG("");
00106 this->removeAllClouds();
00107 this->removeAllGraphs();
00108 delete _visualizer;
00109 }
00110
00111 void CloudViewer::createMenu()
00112 {
00113 _aLockCamera = new QAction("Lock target", this);
00114 _aLockCamera->setCheckable(true);
00115 _aLockCamera->setChecked(false);
00116 _aFollowCamera = new QAction("Follow", this);
00117 _aFollowCamera->setCheckable(true);
00118 _aFollowCamera->setChecked(true);
00119 QAction * freeCamera = new QAction("Free", this);
00120 freeCamera->setCheckable(true);
00121 freeCamera->setChecked(false);
00122 _aLockViewZ = new QAction("Lock view Z", this);
00123 _aLockViewZ->setCheckable(true);
00124 _aLockViewZ->setChecked(true);
00125 _aResetCamera = new QAction("Reset position", this);
00126 _aShowTrajectory= new QAction("Show trajectory", this);
00127 _aShowTrajectory->setCheckable(true);
00128 _aShowTrajectory->setChecked(true);
00129 _aSetTrajectorySize = new QAction("Set trajectory size...", this);
00130 _aClearTrajectory = new QAction("Clear trajectory", this);
00131 _aShowGrid = new QAction("Show grid", this);
00132 _aShowGrid->setCheckable(true);
00133 _aSetGridCellCount = new QAction("Set cell count...", this);
00134 _aSetGridCellSize = new QAction("Set cell size...", this);
00135 _aSetBackgroundColor = new QAction("Set background color...", this);
00136
00137 QMenu * cameraMenu = new QMenu("Camera", this);
00138 cameraMenu->addAction(_aLockCamera);
00139 cameraMenu->addAction(_aFollowCamera);
00140 cameraMenu->addAction(freeCamera);
00141 cameraMenu->addSeparator();
00142 cameraMenu->addAction(_aLockViewZ);
00143 cameraMenu->addAction(_aResetCamera);
00144 QActionGroup * group = new QActionGroup(this);
00145 group->addAction(_aLockCamera);
00146 group->addAction(_aFollowCamera);
00147 group->addAction(freeCamera);
00148
00149 QMenu * trajectoryMenu = new QMenu("Trajectory", this);
00150 trajectoryMenu->addAction(_aShowTrajectory);
00151 trajectoryMenu->addAction(_aSetTrajectorySize);
00152 trajectoryMenu->addAction(_aClearTrajectory);
00153
00154 QMenu * gridMenu = new QMenu("Grid", this);
00155 gridMenu->addAction(_aShowGrid);
00156 gridMenu->addAction(_aSetGridCellCount);
00157 gridMenu->addAction(_aSetGridCellSize);
00158
00159
00160 _menu = new QMenu(this);
00161 _menu->addMenu(cameraMenu);
00162 _menu->addMenu(trajectoryMenu);
00163 _menu->addMenu(gridMenu);
00164 _menu->addAction(_aSetBackgroundColor);
00165 }
00166
00167 void CloudViewer::saveSettings(QSettings & settings, const QString & group) const
00168 {
00169 if(!group.isEmpty())
00170 {
00171 settings.beginGroup(group);
00172 }
00173
00174 float poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ;
00175 this->getCameraPosition(poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ);
00176 QVector3D pose(poseX, poseY, poseZ);
00177 QVector3D focal(focalX, focalY, focalZ);
00178 if(!this->isCameraFree())
00179 {
00180
00181 Transform T = this->getTargetPose();
00182 if(this->isCameraTargetLocked())
00183 {
00184 T = Transform(T.x(), T.y(), T.z(), 0,0,0);
00185 }
00186 Transform F(focalX, focalY, focalZ, 0,0,0);
00187 Transform P(poseX, poseY, poseZ, 0,0,0);
00188 Transform newFocal = T.inverse() * F;
00189 Transform newPose = newFocal * F.inverse() * P;
00190 pose = QVector3D(newPose.x(), newPose.y(), newPose.z());
00191 focal = QVector3D(newFocal.x(), newFocal.y(), newFocal.z());
00192 }
00193 settings.setValue("camera_pose", pose);
00194 settings.setValue("camera_focal", focal);
00195 settings.setValue("camera_up", QVector3D(upX, upY, upZ));
00196
00197 settings.setValue("grid", this->isGridShown());
00198 settings.setValue("grid_cell_count", this->getGridCellCount());
00199 settings.setValue("grid_cell_size", (double)this->getGridCellSize());
00200
00201 settings.setValue("trajectory_shown", this->isTrajectoryShown());
00202 settings.setValue("trajectory_size", this->getTrajectorySize());
00203
00204 settings.setValue("camera_target_locked", this->isCameraTargetLocked());
00205 settings.setValue("camera_target_follow", this->isCameraTargetFollow());
00206 settings.setValue("camera_free", this->isCameraFree());
00207 settings.setValue("camera_lockZ", this->isCameraLockZ());
00208
00209 settings.setValue("bg_color", this->getDefaultBackgroundColor());
00210 if(!group.isEmpty())
00211 {
00212 settings.endGroup();
00213 }
00214 }
00215
00216 void CloudViewer::loadSettings(QSettings & settings, const QString & group)
00217 {
00218 if(!group.isEmpty())
00219 {
00220 settings.beginGroup(group);
00221 }
00222
00223 float poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ;
00224 this->getCameraPosition(poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ);
00225 QVector3D pose(poseX, poseY, poseZ), focal(focalX, focalY, focalZ), up(upX, upY, upZ);
00226 pose = settings.value("camera_pose", pose).value<QVector3D>();
00227 focal = settings.value("camera_focal", focal).value<QVector3D>();
00228 up = settings.value("camera_up", up).value<QVector3D>();
00229 this->setCameraPosition(pose.x(),pose.y(),pose.z(), focal.x(),focal.y(),focal.z(), up.x(),up.y(),up.z());
00230
00231 this->setGridShown(settings.value("grid", this->isGridShown()).toBool());
00232 this->setGridCellCount(settings.value("grid_cell_count", this->getGridCellCount()).toUInt());
00233 this->setGridCellSize(settings.value("grid_cell_size", this->getGridCellSize()).toFloat());
00234
00235 this->setTrajectoryShown(settings.value("trajectory_shown", this->isTrajectoryShown()).toBool());
00236 this->setTrajectorySize(settings.value("trajectory_size", this->getTrajectorySize()).toUInt());
00237
00238 this->setCameraTargetLocked(settings.value("camera_target_locked", this->isCameraTargetLocked()).toBool());
00239 this->setCameraTargetFollow(settings.value("camera_target_follow", this->isCameraTargetFollow()).toBool());
00240 if(settings.value("camera_free", this->isCameraFree()).toBool())
00241 {
00242 this->setCameraFree();
00243 }
00244 this->setCameraLockZ(settings.value("camera_lockZ", this->isCameraLockZ()).toBool());
00245
00246 this->setDefaultBackgroundColor(settings.value("bg_color", this->getDefaultBackgroundColor()).value<QColor>());
00247 if(!group.isEmpty())
00248 {
00249 settings.endGroup();
00250 }
00251 }
00252
00253 bool CloudViewer::updateCloudPose(
00254 const std::string & id,
00255 const Transform & pose)
00256 {
00257 if(_addedClouds.contains(id))
00258 {
00259 UDEBUG("Updating pose %s to %s", id.c_str(), pose.prettyPrint().c_str());
00260 if(_addedClouds.find(id).value() == pose ||
00261 _visualizer->updatePointCloudPose(id, pose.toEigen3f()))
00262 {
00263 _addedClouds.find(id).value() = pose;
00264 return true;
00265 }
00266 }
00267 return false;
00268 }
00269
00270 bool CloudViewer::updateCloud(
00271 const std::string & id,
00272 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00273 const Transform & pose,
00274 const QColor & color)
00275 {
00276 if(_addedClouds.contains(id))
00277 {
00278 UDEBUG("Updating %s with %d points", id.c_str(), (int)cloud->size());
00279 int index = _visualizer->getColorHandlerIndex(id);
00280 this->removeCloud(id);
00281 if(this->addCloud(id, cloud, pose, color))
00282 {
00283 _visualizer->updateColorHandlerIndex(id, index);
00284 return true;
00285 }
00286 }
00287 return false;
00288 }
00289
00290 bool CloudViewer::updateCloud(
00291 const std::string & id,
00292 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00293 const Transform & pose,
00294 const QColor & color)
00295 {
00296 if(_addedClouds.contains(id))
00297 {
00298 UDEBUG("Updating %s with %d points", id.c_str(), (int)cloud->size());
00299 int index = _visualizer->getColorHandlerIndex(id);
00300 this->removeCloud(id);
00301 if(this->addCloud(id, cloud, pose, color))
00302 {
00303 _visualizer->updateColorHandlerIndex(id, index);
00304 return true;
00305 }
00306 }
00307 return false;
00308 }
00309
00310 bool CloudViewer::addOrUpdateCloud(
00311 const std::string & id,
00312 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00313 const Transform & pose,
00314 const QColor & color)
00315 {
00316 if(!updateCloud(id, cloud, pose, color))
00317 {
00318 return addCloud(id, cloud, pose, color);
00319 }
00320 return true;
00321 }
00322
00323 bool CloudViewer::addOrUpdateCloud(
00324 const std::string & id,
00325 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00326 const Transform & pose,
00327 const QColor & color)
00328 {
00329 if(!updateCloud(id, cloud, pose, color))
00330 {
00331 return addCloud(id, cloud, pose, color);
00332 }
00333 return true;
00334 }
00335
00336 bool CloudViewer::addCloud(
00337 const std::string & id,
00338 const pcl::PCLPointCloud2Ptr & binaryCloud,
00339 const Transform & pose,
00340 bool rgb,
00341 const QColor & color)
00342 {
00343 if(!_addedClouds.contains(id))
00344 {
00345 Eigen::Vector4f origin(pose.x(), pose.y(), pose.z(), 0.0f);
00346 Eigen::Quaternionf orientation = Eigen::Quaternionf(pose.toEigen3f().rotation());
00347
00348
00349 pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::Ptr colorHandler;
00350 colorHandler.reset (new pcl::visualization::PointCloudColorHandlerRandom<pcl::PCLPointCloud2> (binaryCloud));
00351 if(_visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id))
00352 {
00353 QColor c = Qt::gray;
00354 if(color.isValid())
00355 {
00356 c = color;
00357 }
00358 colorHandler.reset (new pcl::visualization::PointCloudColorHandlerCustom<pcl::PCLPointCloud2> (binaryCloud, c.red(), c.green(), c.blue()));
00359 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id);
00360
00361
00362 colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "x"));
00363 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id);
00364 colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "y"));
00365 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id);
00366 colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "z"));
00367 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id);
00368
00369 if(rgb)
00370 {
00371
00372 colorHandler.reset(new pcl::visualization::PointCloudColorHandlerRGBField<pcl::PCLPointCloud2>(binaryCloud));
00373 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id);
00374
00375 _visualizer->updateColorHandlerIndex(id, 5);
00376 }
00377 else if(color.isValid())
00378 {
00379 _visualizer->updateColorHandlerIndex(id, 1);
00380 }
00381
00382 _addedClouds.insert(id, pose);
00383 return true;
00384 }
00385 }
00386 return false;
00387 }
00388
00389 bool CloudViewer::addCloud(
00390 const std::string & id,
00391 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00392 const Transform & pose,
00393 const QColor & color)
00394 {
00395 if(!_addedClouds.contains(id))
00396 {
00397 UDEBUG("Adding %s with %d points", id.c_str(), (int)cloud->size());
00398
00399 pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
00400 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
00401 return addCloud(id, binaryCloud, pose, true, color);
00402 }
00403 return false;
00404 }
00405
00406 bool CloudViewer::addCloud(
00407 const std::string & id,
00408 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00409 const Transform & pose,
00410 const QColor & color)
00411 {
00412 if(!_addedClouds.contains(id))
00413 {
00414 UDEBUG("Adding %s with %d points", id.c_str(), (int)cloud->size());
00415
00416 pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
00417 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
00418 return addCloud(id, binaryCloud, pose, false, color);
00419 }
00420 return false;
00421 }
00422
00423 bool CloudViewer::addCloudMesh(
00424 const std::string & id,
00425 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00426 const std::vector<pcl::Vertices> & polygons,
00427 const Transform & pose)
00428 {
00429 if(!_addedClouds.contains(id))
00430 {
00431 UDEBUG("Adding %s with %d points and %d polygons", id.c_str(), (int)cloud->size(), (int)polygons.size());
00432 if(_visualizer->addPolygonMesh<pcl::PointXYZRGB>(cloud, polygons, id))
00433 {
00434 _visualizer->updatePointCloudPose(id, pose.toEigen3f());
00435 _addedClouds.insert(id, pose);
00436 return true;
00437 }
00438 }
00439 return false;
00440 }
00441
00442 bool CloudViewer::addCloudMesh(
00443 const std::string & id,
00444 const pcl::PolygonMesh::Ptr & mesh,
00445 const Transform & pose)
00446 {
00447 if(!_addedClouds.contains(id))
00448 {
00449 UDEBUG("Adding %s with %d polygons", id.c_str(), (int)mesh->polygons.size());
00450 if(_visualizer->addPolygonMesh(*mesh, id))
00451 {
00452 _visualizer->updatePointCloudPose(id, pose.toEigen3f());
00453 _addedClouds.insert(id, pose);
00454 return true;
00455 }
00456 }
00457 return false;
00458 }
00459
00460 bool CloudViewer::addOccupancyGridMap(
00461 const cv::Mat & map8U,
00462 float resolution,
00463 float xMin,
00464 float yMin,
00465 float opacity)
00466 {
00467 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
00468 UASSERT(map8U.channels() == 1 && map8U.type() == CV_8U);
00469
00470 float xSize = float(map8U.cols) * resolution;
00471 float ySize = float(map8U.rows) * resolution;
00472
00473 UDEBUG("resolution=%f, xSize=%f, ySize=%f, xMin=%f, yMin=%f", resolution, xSize, ySize, xMin, yMin);
00474 if(_visualizer->getShapeActorMap()->find("map") == _visualizer->getShapeActorMap()->end())
00475 {
00476 _visualizer->removeShape("map");
00477 }
00478
00479 if(xSize > 0.0f && ySize > 0.0f)
00480 {
00481 pcl::TextureMeshPtr mesh(new pcl::TextureMesh());
00482 pcl::PointCloud<pcl::PointXYZ> cloud;
00483 cloud.push_back(pcl::PointXYZ(xMin, yMin, 0));
00484 cloud.push_back(pcl::PointXYZ(xSize+xMin, yMin, 0));
00485 cloud.push_back(pcl::PointXYZ(xSize+xMin, ySize+yMin, 0));
00486 cloud.push_back(pcl::PointXYZ(xMin, ySize+yMin, 0));
00487 pcl::toPCLPointCloud2(cloud, mesh->cloud);
00488
00489 std::vector<pcl::Vertices> polygons(1);
00490 polygons[0].vertices.push_back(0);
00491 polygons[0].vertices.push_back(1);
00492 polygons[0].vertices.push_back(2);
00493 polygons[0].vertices.push_back(3);
00494 polygons[0].vertices.push_back(0);
00495 mesh->tex_polygons.push_back(polygons);
00496
00497
00498 pcl::TexMaterial material;
00499
00500 std::string tmpPath = (_workingDirectory+"/.tmp_map.png").toStdString();
00501 cv::imwrite(tmpPath, map8U);
00502 material.tex_file = tmpPath;
00503 mesh->tex_materials.push_back(material);
00504
00505 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
00506 std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > coordinates;
00507 #else
00508 std::vector<Eigen::Vector2f> coordinates;
00509 #endif
00510 coordinates.push_back(Eigen::Vector2f(0,1));
00511 coordinates.push_back(Eigen::Vector2f(1,1));
00512 coordinates.push_back(Eigen::Vector2f(1,0));
00513 coordinates.push_back(Eigen::Vector2f(0,0));
00514 mesh->tex_coordinates.push_back(coordinates);
00515
00516 _visualizer->addTextureMesh(*mesh, "map");
00517 _visualizer->getCloudActorMap()->find("map")->second.actor->GetProperty()->LightingOff();
00518 setCloudOpacity("map", 0.7);
00519
00520
00521 QFile::remove(tmpPath.c_str());
00522 }
00523 return true;
00524 #else
00525
00526 return false;
00527 #endif
00528 }
00529
00530 void CloudViewer::removeOccupancyGridMap()
00531 {
00532 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
00533 if(_visualizer->getShapeActorMap()->find("map") == _visualizer->getShapeActorMap()->end())
00534 {
00535 _visualizer->removeShape("map");
00536 }
00537 #endif
00538 }
00539
00540 void CloudViewer::addOrUpdateGraph(
00541 const std::string & id,
00542 const pcl::PointCloud<pcl::PointXYZ>::Ptr & graph,
00543 const QColor & color)
00544 {
00545 if(id.empty())
00546 {
00547 UERROR("id should not be empty!");
00548 return;
00549 }
00550
00551 removeGraph(id);
00552
00553 if(graph->size())
00554 {
00555 _graphes.insert(id);
00556
00557 pcl::PolygonMesh mesh;
00558 pcl::Vertices vertices;
00559 vertices.vertices.resize(graph->size());
00560 for(unsigned int i=0; i<vertices.vertices.size(); ++i)
00561 {
00562 vertices.vertices[i] = i;
00563 }
00564 pcl::toPCLPointCloud2(*graph, mesh.cloud);
00565 mesh.polygons.push_back(vertices);
00566 _visualizer->addPolylineFromPolygonMesh(mesh, id);
00567 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, color.redF(), color.greenF(), color.blueF(), id);
00568
00569 this->addOrUpdateCloud(id+"_nodes", graph, Transform::getIdentity(), color);
00570 this->setCloudPointSize(id+"_nodes", 5);
00571 }
00572 }
00573
00574 void CloudViewer::removeGraph(const std::string & id)
00575 {
00576 if(id.empty())
00577 {
00578 UERROR("id should not be empty!");
00579 return;
00580 }
00581
00582 if(_graphes.find(id) != _graphes.end())
00583 {
00584 _visualizer->removeShape(id);
00585 _graphes.erase(id);
00586 removeCloud(id+"_nodes");
00587 }
00588 }
00589
00590 void CloudViewer::removeAllGraphs()
00591 {
00592 std::set<std::string> graphes = _graphes;
00593 for(std::set<std::string>::iterator iter = graphes.begin(); iter!=graphes.end(); ++iter)
00594 {
00595 this->removeGraph(*iter);
00596 }
00597 UASSERT(_graphes.empty());
00598 }
00599
00600 bool CloudViewer::isTrajectoryShown() const
00601 {
00602 return _aShowTrajectory->isChecked();
00603 }
00604
00605 unsigned int CloudViewer::getTrajectorySize() const
00606 {
00607 return _maxTrajectorySize;
00608 }
00609
00610 void CloudViewer::setTrajectoryShown(bool shown)
00611 {
00612 _aShowTrajectory->setChecked(shown);
00613 }
00614
00615 void CloudViewer::setTrajectorySize(unsigned int value)
00616 {
00617 _maxTrajectorySize = value;
00618 }
00619
00620 void CloudViewer::clearTrajectory()
00621 {
00622 _trajectory->clear();
00623 _visualizer->removeShape("trajectory");
00624 this->update();
00625 }
00626
00627 void CloudViewer::removeAllClouds()
00628 {
00629 _addedClouds.clear();
00630 _visualizer->removeAllPointClouds();
00631 }
00632
00633
00634 bool CloudViewer::removeCloud(const std::string & id)
00635 {
00636 bool success = _visualizer->removePointCloud(id);
00637 _addedClouds.remove(id);
00638 return success;
00639 }
00640
00641 bool CloudViewer::getPose(const std::string & id, Transform & pose)
00642 {
00643 if(_addedClouds.contains(id))
00644 {
00645 pose = _addedClouds.value(id);
00646 return true;
00647 }
00648 return false;
00649 }
00650
00651 Transform CloudViewer::getTargetPose() const
00652 {
00653 if(_lastPose.isNull())
00654 {
00655 return Transform::getIdentity();
00656 }
00657 return _lastPose;
00658 }
00659
00660 void CloudViewer::getCameraPosition(
00661 float & x, float & y, float & z,
00662 float & focalX, float & focalY, float & focalZ,
00663 float & upX, float & upY, float & upZ) const
00664 {
00665 std::vector<pcl::visualization::Camera> cameras;
00666 _visualizer->getCameras(cameras);
00667 x = cameras.front().pos[0];
00668 y = cameras.front().pos[1];
00669 z = cameras.front().pos[2];
00670 focalX = cameras.front().focal[0];
00671 focalY = cameras.front().focal[1];
00672 focalZ = cameras.front().focal[2];
00673 upX = cameras.front().view[0];
00674 upY = cameras.front().view[1];
00675 upZ = cameras.front().view[2];
00676 }
00677
00678 void CloudViewer::setCameraPosition(
00679 float x, float y, float z,
00680 float focalX, float focalY, float focalZ,
00681 float upX, float upY, float upZ)
00682 {
00683 _visualizer->setCameraPosition(x,y,z, focalX,focalY,focalX, upX,upY,upZ);
00684 }
00685
00686 void CloudViewer::updateCameraTargetPosition(const Transform & pose)
00687 {
00688 if(!pose.isNull())
00689 {
00690 Eigen::Affine3f m = pose.toEigen3f();
00691 Eigen::Vector3f pos = m.translation();
00692
00693 Eigen::Vector3f lastPos(0,0,0);
00694 if(_trajectory->size())
00695 {
00696 lastPos[0]=_trajectory->back().x;
00697 lastPos[1]=_trajectory->back().y;
00698 lastPos[2]=_trajectory->back().z;
00699 }
00700
00701 _trajectory->push_back(pcl::PointXYZ(pos[0], pos[1], pos[2]));
00702 if(_maxTrajectorySize>0)
00703 {
00704 while(_trajectory->size() > _maxTrajectorySize)
00705 {
00706 _trajectory->erase(_trajectory->begin());
00707 }
00708 }
00709 if(_aShowTrajectory->isChecked())
00710 {
00711 _visualizer->removeShape("trajectory");
00712 pcl::PolygonMesh mesh;
00713 pcl::Vertices vertices;
00714 vertices.vertices.resize(_trajectory->size());
00715 for(unsigned int i=0; i<vertices.vertices.size(); ++i)
00716 {
00717 vertices.vertices[i] = i;
00718 }
00719 pcl::toPCLPointCloud2(*_trajectory, mesh.cloud);
00720 mesh.polygons.push_back(vertices);
00721 _visualizer->addPolylineFromPolygonMesh(mesh, "trajectory");
00722 }
00723
00724 if(pose != _lastPose || _lastPose.isNull())
00725 {
00726 if(_lastPose.isNull())
00727 {
00728 _lastPose.setIdentity();
00729 }
00730
00731 std::vector<pcl::visualization::Camera> cameras;
00732 _visualizer->getCameras(cameras);
00733
00734 if(_aLockCamera->isChecked())
00735 {
00736
00737 Eigen::Vector3f diff = pos - Eigen::Vector3f(_lastPose.x(), _lastPose.y(), _lastPose.z());
00738 cameras.front().pos[0] += diff[0];
00739 cameras.front().pos[1] += diff[1];
00740 cameras.front().pos[2] += diff[2];
00741 cameras.front().focal[0] += diff[0];
00742 cameras.front().focal[1] += diff[1];
00743 cameras.front().focal[2] += diff[2];
00744 }
00745 else if(_aFollowCamera->isChecked())
00746 {
00747 Eigen::Vector3f vPosToFocal = Eigen::Vector3f(cameras.front().focal[0] - cameras.front().pos[0],
00748 cameras.front().focal[1] - cameras.front().pos[1],
00749 cameras.front().focal[2] - cameras.front().pos[2]).normalized();
00750 Eigen::Vector3f zAxis(cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
00751 Eigen::Vector3f yAxis = zAxis.cross(vPosToFocal);
00752 Eigen::Vector3f xAxis = yAxis.cross(zAxis);
00753 Transform PR(xAxis[0], xAxis[1], xAxis[2],0,
00754 yAxis[0], yAxis[1], yAxis[2],0,
00755 zAxis[0], zAxis[1], zAxis[2],0);
00756
00757 Transform P(PR[0], PR[1], PR[2], cameras.front().pos[0],
00758 PR[4], PR[5], PR[6], cameras.front().pos[1],
00759 PR[8], PR[9], PR[10], cameras.front().pos[2]);
00760 Transform F(PR[0], PR[1], PR[2], cameras.front().focal[0],
00761 PR[4], PR[5], PR[6], cameras.front().focal[1],
00762 PR[8], PR[9], PR[10], cameras.front().focal[2]);
00763 Transform N = pose;
00764 Transform O = _lastPose;
00765 Transform O2N = O.inverse()*N;
00766 Transform F2O = F.inverse()*O;
00767 Transform T = F2O * O2N * F2O.inverse();
00768 Transform Fp = F * T;
00769 Transform P2F = P.inverse()*F;
00770 Transform Pp = P * P2F * T * P2F.inverse();
00771
00772 cameras.front().pos[0] = Pp.x();
00773 cameras.front().pos[1] = Pp.y();
00774 cameras.front().pos[2] = Pp.z();
00775 cameras.front().focal[0] = Fp.x();
00776 cameras.front().focal[1] = Fp.y();
00777 cameras.front().focal[2] = Fp.z();
00778
00779 cameras.front().view[0] = _aLockViewZ->isChecked()?0:Fp[8];
00780 cameras.front().view[1] = _aLockViewZ->isChecked()?0:Fp[9];
00781 cameras.front().view[2] = _aLockViewZ->isChecked()?1:Fp[10];
00782 }
00783
00784 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
00785 _visualizer->removeCoordinateSystem("reference", 0);
00786 _visualizer->addCoordinateSystem(0.2, m, "reference", 0);
00787 #else
00788 _visualizer->removeCoordinateSystem(0);
00789 _visualizer->addCoordinateSystem(0.2, m, 0);
00790 #endif
00791 _visualizer->setCameraPosition(
00792 cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
00793 cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
00794 cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
00795 }
00796 }
00797
00798 _lastPose = pose;
00799 }
00800
00801 const QColor & CloudViewer::getDefaultBackgroundColor() const
00802 {
00803 return _defaultBgColor;
00804 }
00805
00806 void CloudViewer::setDefaultBackgroundColor(const QColor & color)
00807 {
00808 if(_currentBgColor == _defaultBgColor)
00809 {
00810 setBackgroundColor(color);
00811 }
00812 _defaultBgColor = color;
00813 }
00814
00815 const QColor & CloudViewer::getBackgroundColor() const
00816 {
00817 return _currentBgColor;
00818 }
00819
00820 void CloudViewer::setBackgroundColor(const QColor & color)
00821 {
00822 _currentBgColor = color;
00823 _visualizer->setBackgroundColor(color.redF(), color.greenF(), color.blueF());
00824 }
00825
00826 void CloudViewer::setCloudVisibility(const std::string & id, bool isVisible)
00827 {
00828 pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
00829 pcl::visualization::CloudActorMap::iterator iter = cloudActorMap->find(id);
00830 if(iter != cloudActorMap->end())
00831 {
00832 iter->second.actor->SetVisibility(isVisible?1:0);
00833 }
00834 else
00835 {
00836 UERROR("Cannot find actor named \"%s\".", id.c_str());
00837 }
00838 }
00839
00840 bool CloudViewer::getCloudVisibility(const std::string & id)
00841 {
00842 pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
00843 pcl::visualization::CloudActorMap::iterator iter = cloudActorMap->find(id);
00844 if(iter != cloudActorMap->end())
00845 {
00846 return iter->second.actor->GetVisibility() != 0;
00847 }
00848 else
00849 {
00850 UERROR("Cannot find actor named \"%s\".", id.c_str());
00851 }
00852 return false;
00853 }
00854
00855 void CloudViewer::setCloudOpacity(const std::string & id, double opacity)
00856 {
00857 double lastOpacity;
00858 _visualizer->getPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, lastOpacity, id);
00859 if(lastOpacity != opacity)
00860 {
00861 _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, opacity, id);
00862 }
00863 }
00864
00865 void CloudViewer::setCloudPointSize(const std::string & id, int size)
00866 {
00867 double lastSize;
00868 _visualizer->getPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, lastSize, id);
00869 if((int)lastSize != size)
00870 {
00871 _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, (double)size, id);
00872 }
00873 }
00874
00875 void CloudViewer::setCameraTargetLocked(bool enabled)
00876 {
00877 _aLockCamera->setChecked(enabled);
00878 }
00879
00880 void CloudViewer::setCameraTargetFollow(bool enabled)
00881 {
00882 _aFollowCamera->setChecked(enabled);
00883 }
00884
00885 void CloudViewer::setCameraFree()
00886 {
00887 _aLockCamera->setChecked(false);
00888 _aFollowCamera->setChecked(false);
00889 }
00890
00891 void CloudViewer::setCameraLockZ(bool enabled)
00892 {
00893 _aLockViewZ->setChecked(enabled);
00894 }
00895
00896 void CloudViewer::setGridShown(bool shown)
00897 {
00898 _aShowGrid->setChecked(shown);
00899 if(shown)
00900 {
00901 this->addGrid();
00902 }
00903 else
00904 {
00905 this->removeGrid();
00906 }
00907 }
00908
00909 bool CloudViewer::isCameraTargetLocked() const
00910 {
00911 return _aLockCamera->isChecked();
00912 }
00913 bool CloudViewer::isCameraTargetFollow() const
00914 {
00915 return _aFollowCamera->isChecked();
00916 }
00917 bool CloudViewer::isCameraFree() const
00918 {
00919 return !_aFollowCamera->isChecked() && !_aLockCamera->isChecked();
00920 }
00921 bool CloudViewer::isCameraLockZ() const
00922 {
00923 return _aLockViewZ->isChecked();
00924 }
00925 bool CloudViewer::isGridShown() const
00926 {
00927 return _aShowGrid->isChecked();
00928 }
00929 unsigned int CloudViewer::getGridCellCount() const
00930 {
00931 return _gridCellCount;
00932 }
00933 float CloudViewer::getGridCellSize() const
00934 {
00935 return _gridCellSize;
00936 }
00937
00938 void CloudViewer::setGridCellCount(unsigned int count)
00939 {
00940 if(count > 0)
00941 {
00942 _gridCellCount = count;
00943 if(_aShowGrid->isChecked())
00944 {
00945 this->removeGrid();
00946 this->addGrid();
00947 }
00948 }
00949 else
00950 {
00951 UERROR("Cannot set grid cell count < 1, count=%d", count);
00952 }
00953 }
00954 void CloudViewer::setGridCellSize(float size)
00955 {
00956 if(size > 0)
00957 {
00958 _gridCellSize = size;
00959 if(_aShowGrid->isChecked())
00960 {
00961 this->removeGrid();
00962 this->addGrid();
00963 }
00964 }
00965 else
00966 {
00967 UERROR("Cannot set grid cell size <= 0, value=%f", size);
00968 }
00969 }
00970 void CloudViewer::addGrid()
00971 {
00972 if(_gridLines.empty())
00973 {
00974 float cellSize = _gridCellSize;
00975 int cellCount = _gridCellCount;
00976 double r=0.5;
00977 double g=0.5;
00978 double b=0.5;
00979 int id = 0;
00980 float min = -float(cellCount/2) * cellSize;
00981 float max = float(cellCount/2) * cellSize;
00982 std::string name;
00983 for(float i=min; i<=max; i += cellSize)
00984 {
00985
00986 name = uFormat("line%d", ++id);
00987 _visualizer->addLine(pcl::PointXYZ(i, min, 0.0f), pcl::PointXYZ(i, max, 0.0f), r, g, b, name);
00988 _gridLines.push_back(name);
00989
00990 name = uFormat("line%d", ++id);
00991 _visualizer->addLine(pcl::PointXYZ(min, i, 0.0f), pcl::PointXYZ(max, i, 0.0f), r, g, b, name);
00992 _gridLines.push_back(name);
00993 }
00994 }
00995 }
00996
00997 void CloudViewer::removeGrid()
00998 {
00999 for(std::list<std::string>::iterator iter = _gridLines.begin(); iter!=_gridLines.end(); ++iter)
01000 {
01001 _visualizer->removeShape(*iter);
01002 }
01003 _gridLines.clear();
01004 }
01005
01006 Eigen::Vector3f rotatePointAroundAxe(
01007 const Eigen::Vector3f & point,
01008 const Eigen::Vector3f & axis,
01009 float angle)
01010 {
01011 Eigen::Vector3f direction = point;
01012 Eigen::Vector3f zAxis = axis;
01013 float dotProdZ = zAxis.dot(direction);
01014 Eigen::Vector3f ptOnZaxis = zAxis * dotProdZ;
01015 direction -= ptOnZaxis;
01016 Eigen::Vector3f xAxis = direction.normalized();
01017 Eigen::Vector3f yAxis = zAxis.cross(xAxis);
01018
01019 Eigen::Matrix3f newFrame;
01020 newFrame << xAxis[0], yAxis[0], zAxis[0],
01021 xAxis[1], yAxis[1], zAxis[1],
01022 xAxis[2], yAxis[2], zAxis[2];
01023
01024
01025
01026 Eigen::Vector3f newDirection = newFrame.transpose() * direction;
01027
01028
01029 float cosTheta = cos(angle);
01030 float sinTheta = sin(angle);
01031 float magnitude = newDirection.norm();
01032 newDirection[0] = ( magnitude * cosTheta );
01033 newDirection[1] = ( magnitude * sinTheta );
01034
01035
01036 direction = newFrame * newDirection;
01037
01038 return direction + ptOnZaxis;
01039 }
01040
01041 void CloudViewer::keyReleaseEvent(QKeyEvent * event) {
01042 if(event->key() == Qt::Key_Up ||
01043 event->key() == Qt::Key_Down ||
01044 event->key() == Qt::Key_Left ||
01045 event->key() == Qt::Key_Right)
01046 {
01047 _keysPressed -= (Qt::Key)event->key();
01048 }
01049 else
01050 {
01051 QVTKWidget::keyPressEvent(event);
01052 }
01053 }
01054
01055 void CloudViewer::keyPressEvent(QKeyEvent * event)
01056 {
01057 if(event->key() == Qt::Key_Up ||
01058 event->key() == Qt::Key_Down ||
01059 event->key() == Qt::Key_Left ||
01060 event->key() == Qt::Key_Right)
01061 {
01062 _keysPressed += (Qt::Key)event->key();
01063
01064 std::vector<pcl::visualization::Camera> cameras;
01065 _visualizer->getCameras(cameras);
01066
01067
01068 Eigen::Vector3f pos(cameras.front().pos[0], cameras.front().pos[1], _aLockViewZ->isChecked()?0:cameras.front().pos[2]);
01069 Eigen::Vector3f focal(cameras.front().focal[0], cameras.front().focal[1], _aLockViewZ->isChecked()?0:cameras.front().focal[2]);
01070 Eigen::Vector3f viewUp(cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
01071 Eigen::Vector3f cummulatedDir(0,0,0);
01072 Eigen::Vector3f cummulatedFocalDir(0,0,0);
01073 float step = 0.2f;
01074 float stepRot = 0.02f;
01075 if(_keysPressed.contains(Qt::Key_Up))
01076 {
01077 Eigen::Vector3f dir;
01078 if(event->modifiers() & Qt::ShiftModifier)
01079 {
01080 dir = viewUp * step;
01081 }
01082 else
01083 {
01084 dir = (focal-pos).normalized() * step;
01085 }
01086 cummulatedDir += dir;
01087 }
01088 if(_keysPressed.contains(Qt::Key_Down))
01089 {
01090 Eigen::Vector3f dir;
01091 if(event->modifiers() & Qt::ShiftModifier)
01092 {
01093 dir = viewUp * -step;
01094 }
01095 else
01096 {
01097 dir = (focal-pos).normalized() * -step;
01098 }
01099 cummulatedDir += dir;
01100 }
01101 if(_keysPressed.contains(Qt::Key_Right))
01102 {
01103 if(event->modifiers() & Qt::ShiftModifier)
01104 {
01105
01106 Eigen::Vector3f point = (focal-pos);
01107 Eigen::Vector3f newPoint = rotatePointAroundAxe(point, viewUp, -stepRot);
01108 Eigen::Vector3f diff = newPoint - point;
01109 cummulatedFocalDir += diff;
01110 }
01111 else
01112 {
01113 Eigen::Vector3f dir = ((focal-pos).cross(viewUp)).normalized() * step;
01114 cummulatedDir += dir;
01115 }
01116 }
01117 if(_keysPressed.contains(Qt::Key_Left))
01118 {
01119 if(event->modifiers() & Qt::ShiftModifier)
01120 {
01121
01122 Eigen::Vector3f point = (focal-pos);
01123 Eigen::Vector3f newPoint = rotatePointAroundAxe(point, viewUp, stepRot);
01124 Eigen::Vector3f diff = newPoint - point;
01125 cummulatedFocalDir += diff;
01126 }
01127 else
01128 {
01129 Eigen::Vector3f dir = ((focal-pos).cross(viewUp)).normalized() * -step;
01130 cummulatedDir += dir;
01131 }
01132 }
01133
01134 cameras.front().pos[0] += cummulatedDir[0];
01135 cameras.front().pos[1] += cummulatedDir[1];
01136 cameras.front().pos[2] += cummulatedDir[2];
01137 cameras.front().focal[0] += cummulatedDir[0] + cummulatedFocalDir[0];
01138 cameras.front().focal[1] += cummulatedDir[1] + cummulatedFocalDir[1];
01139 cameras.front().focal[2] += cummulatedDir[2] + cummulatedFocalDir[2];
01140 _visualizer->setCameraPosition(
01141 cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
01142 cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
01143 cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
01144
01145 update();
01146
01147 emit configChanged();
01148 }
01149 else
01150 {
01151 QVTKWidget::keyPressEvent(event);
01152 }
01153 }
01154
01155 void CloudViewer::mousePressEvent(QMouseEvent * event)
01156 {
01157 if(event->button() == Qt::RightButton)
01158 {
01159 event->accept();
01160 }
01161 else
01162 {
01163 QVTKWidget::mousePressEvent(event);
01164 }
01165 }
01166
01167 void CloudViewer::mouseMoveEvent(QMouseEvent * event)
01168 {
01169 QVTKWidget::mouseMoveEvent(event);
01170
01171 if(_aLockViewZ->isChecked())
01172 {
01173 std::vector<pcl::visualization::Camera> cameras;
01174 _visualizer->getCameras(cameras);
01175
01176 cameras.front().view[0] = 0;
01177 cameras.front().view[1] = 0;
01178 cameras.front().view[2] = 1;
01179
01180 _visualizer->setCameraPosition(
01181 cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
01182 cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
01183 cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
01184
01185 }
01186 emit configChanged();
01187 }
01188
01189 void CloudViewer::contextMenuEvent(QContextMenuEvent * event)
01190 {
01191 QAction * a = _menu->exec(event->globalPos());
01192 if(a)
01193 {
01194 handleAction(a);
01195 emit configChanged();
01196 }
01197 }
01198
01199 void CloudViewer::handleAction(QAction * a)
01200 {
01201 if(a == _aSetTrajectorySize)
01202 {
01203 bool ok;
01204 int value = QInputDialog::getInt(this, tr("Set trajectory size"), tr("Size (0=infinite)"), _maxTrajectorySize, 0, 10000, 10, &ok);
01205 if(ok)
01206 {
01207 _maxTrajectorySize = value;
01208 }
01209 }
01210 else if(a == _aClearTrajectory)
01211 {
01212 this->clearTrajectory();
01213 }
01214 else if(a == _aResetCamera)
01215 {
01216 if((_aFollowCamera->isChecked() || _aLockCamera->isChecked()) && !_lastPose.isNull())
01217 {
01218
01219 if(_aLockViewZ->isChecked())
01220 {
01221 _visualizer->setCameraPosition(
01222 _lastPose.x()-1, _lastPose.y(), _lastPose.z(),
01223 _lastPose.x(), _lastPose.y(), _lastPose.z(),
01224 0, 0, 1);
01225 }
01226 else
01227 {
01228 _visualizer->setCameraPosition(
01229 _lastPose.x()-1, _lastPose.y(), _lastPose.z(),
01230 _lastPose.x(), _lastPose.y(), _lastPose.z(),
01231 _lastPose.r31(), _lastPose.r32(), _lastPose.r33());
01232 }
01233 }
01234 else
01235 {
01236 _visualizer->setCameraPosition(
01237 -1, 0, 0,
01238 0, 0, 0,
01239 0, 0, 1);
01240 }
01241 this->update();
01242 }
01243 else if(a == _aShowGrid)
01244 {
01245 if(_aShowGrid->isChecked())
01246 {
01247 this->addGrid();
01248 }
01249 else
01250 {
01251 this->removeGrid();
01252 }
01253
01254 this->update();
01255 }
01256 else if(a == _aSetGridCellCount)
01257 {
01258 bool ok;
01259 int value = QInputDialog::getInt(this, tr("Set grid cell count"), tr("Count"), _gridCellCount, 1, 10000, 10, &ok);
01260 if(ok)
01261 {
01262 this->setGridCellCount(value);
01263 }
01264 }
01265 else if(a == _aSetGridCellSize)
01266 {
01267 bool ok;
01268 double value = QInputDialog::getDouble(this, tr("Set grid cell size"), tr("Size (m)"), _gridCellSize, 0.01, 10, 2, &ok);
01269 if(ok)
01270 {
01271 this->setGridCellSize(value);
01272 }
01273 }
01274 else if(a == _aSetBackgroundColor)
01275 {
01276 QColor color = this->getDefaultBackgroundColor();
01277 color = QColorDialog::getColor(color, this);
01278 if(color.isValid())
01279 {
01280 this->setDefaultBackgroundColor(color);
01281 }
01282 }
01283 else if(a == _aLockViewZ)
01284 {
01285 if(_aLockViewZ->isChecked())
01286 {
01287 this->update();
01288 }
01289 }
01290 }
01291
01292 }