CloudViewer.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
30 
31 #include <rtabmap/core/Version.h>
34 #include <rtabmap/utilite/UTimer.h>
35 #include <rtabmap/utilite/UMath.h>
37 #include <rtabmap/utilite/UStl.h>
38 #include <pcl/visualization/pcl_visualizer.h>
39 #include <pcl/common/transforms.h>
40 #include <QMenu>
41 #include <QAction>
42 #include <QtGui/QContextMenuEvent>
43 #include <QInputDialog>
44 #include <QtGui/QWheelEvent>
45 #include <QtGui/QKeyEvent>
46 #include <QColorDialog>
47 #include <QtGui/QVector3D>
48 #include <QMainWindow>
49 #include <set>
50 
51 #include <vtkCamera.h>
52 #include <vtkRenderWindow.h>
53 #include <vtkCubeSource.h>
54 #include <vtkGlyph3D.h>
55 #include <vtkGlyph3DMapper.h>
56 #include <vtkSmartVolumeMapper.h>
57 #include <vtkVolumeProperty.h>
58 #include <vtkColorTransferFunction.h>
59 #include <vtkPiecewiseFunction.h>
60 #include <vtkImageData.h>
61 #include <vtkLookupTable.h>
62 #include <vtkTextureUnitManager.h>
63 #include <vtkJPEGReader.h>
64 #include <vtkBMPReader.h>
65 #include <vtkPNMReader.h>
66 #include <vtkPNGReader.h>
67 #include <vtkTIFFReader.h>
68 #include <vtkOpenGLRenderWindow.h>
69 #include <vtkPointPicker.h>
70 #include <vtkTextActor.h>
71 #include <vtkOBBTree.h>
72 #include <vtkObjectFactory.h>
73 #include <vtkQuad.h>
75 
76 #ifdef RTABMAP_OCTOMAP
77 #include <rtabmap/core/OctoMap.h>
78 #endif
79 
80 namespace rtabmap {
81 
83  QVTKWidget(parent),
84  _aLockCamera(0),
85  _aFollowCamera(0),
86  _aResetCamera(0),
87  _aLockViewZ(0),
88  _aCameraOrtho(0),
89  _aShowTrajectory(0),
90  _aSetTrajectorySize(0),
91  _aClearTrajectory(0),
92  _aShowFrustum(0),
93  _aSetFrustumScale(0),
94  _aSetFrustumColor(0),
95  _aShowGrid(0),
96  _aSetGridCellCount(0),
97  _aSetGridCellSize(0),
98  _aShowNormals(0),
99  _aSetNormalsStep(0),
100  _aSetNormalsScale(0),
101  _aSetBackgroundColor(0),
102  _aSetRenderingRate(0),
103  _aSetLighting(0),
104  _aSetFlatShading(0),
105  _aSetEdgeVisibility(0),
106  _aBackfaceCulling(0),
107  _menu(0),
108  _trajectory(new pcl::PointCloud<pcl::PointXYZ>),
109  _maxTrajectorySize(100),
110  _frustumScale(0.5f),
111  _frustumColor(Qt::gray),
112  _gridCellCount(50),
113  _gridCellSize(1),
114  _normalsStep(1),
115  _normalsScale(0.2),
116  _buildLocator(false),
117  _lastCameraOrientation(0,0,0),
118  _lastCameraPose(0,0,0),
119  _defaultBgColor(Qt::black),
120  _currentBgColor(Qt::black),
121  _frontfaceCulling(false),
122  _renderingRate(5.0),
123  _octomapActor(0)
124 {
125  UDEBUG("");
126  this->setMinimumSize(200, 200);
127 
128  int argc = 0;
129  UASSERT(style!=0);
130  style->setCloudViewer(this);
131  _visualizer = new pcl::visualization::PCLVisualizer(
132  argc,
133  0,
134  "PCLVisualizer",
135  style,
136  false);
137 
138  _visualizer->setShowFPS(false);
139 
140  int viewport;
141  _visualizer->createViewPort (0,0,1.0, 1.0, viewport); // all 3d objects here
142  _visualizer->createViewPort (0,0,1.0, 1.0, viewport); // text overlay
143  _visualizer->getRendererCollection()->InitTraversal ();
144  vtkRenderer* renderer = NULL;
145  int i =0;
146  while ((renderer = _visualizer->getRendererCollection()->GetNextItem ()) != NULL)
147  {
148  renderer->SetLayer(i);
149  if(i==1)
150  {
151  _visualizer->getInteractorStyle()->SetDefaultRenderer(renderer);
152  }
153  ++i;
154  }
155  _visualizer->getRenderWindow()->SetNumberOfLayers(3);
156 
157  this->SetRenderWindow(_visualizer->getRenderWindow());
158 
159  // Replaced by the second line, to avoid a crash in Mac OS X on close, as well as
160  // the "Invalid drawable" warning when the view is not visible.
161  //_visualizer->setupInteractor(this->GetInteractor(), this->GetRenderWindow());
162  this->GetInteractor()->SetInteractorStyle (_visualizer->getInteractorStyle());
163  // setup a simple point picker
165  UDEBUG("pick tolerance=%f", pp->GetTolerance());
166  pp->SetTolerance (pp->GetTolerance()/2.0);
167  this->GetInteractor()->SetPicker (pp);
168 
170 
171  _visualizer->setCameraPosition(
172  -1, 0, 0,
173  0, 0, 0,
174  0, 0, 1, 1);
175 #ifndef _WIN32
176  // Crash on startup on Windows (vtk issue)
177  this->addOrUpdateCoordinate("reference", Transform::getIdentity(), 0.2);
178 #endif
179 
180  //setup menu/actions
181  createMenu();
182 
183  setMouseTracking(false);
184 }
185 
187 {
188  UDEBUG("");
189  this->clear();
190  delete _visualizer;
191  UDEBUG("");
192 }
193 
195 {
196  this->removeAllClouds();
197  this->removeAllGraphs();
198  this->removeAllCoordinates();
199  this->removeAllLines();
200  this->removeAllFrustums();
201  this->removeAllTexts();
202  this->removeOccupancyGridMap();
203  this->removeOctomap();
204 
205  this->addOrUpdateCoordinate("reference", Transform::getIdentity(), 0.2);
206  _lastPose.setNull();
207  if(_aLockCamera->isChecked() || _aFollowCamera->isChecked())
208  {
209  resetCamera();
210  }
211  this->clearTrajectory();
212 }
213 
215 {
216  _aLockCamera = new QAction("Lock target", this);
217  _aLockCamera->setCheckable(true);
218  _aLockCamera->setChecked(false);
219  _aFollowCamera = new QAction("Follow", this);
220  _aFollowCamera->setCheckable(true);
221  _aFollowCamera->setChecked(true);
222  QAction * freeCamera = new QAction("Free", this);
223  freeCamera->setCheckable(true);
224  freeCamera->setChecked(false);
225  _aLockViewZ = new QAction("Lock view Z", this);
226  _aLockViewZ->setCheckable(true);
227  _aLockViewZ->setChecked(true);
228  _aCameraOrtho = new QAction("Ortho mode", this);
229  _aCameraOrtho->setCheckable(true);
230  _aCameraOrtho->setChecked(false);
231  _aResetCamera = new QAction("Reset position", this);
232  _aShowTrajectory= new QAction("Show trajectory", this);
233  _aShowTrajectory->setCheckable(true);
234  _aShowTrajectory->setChecked(true);
235  _aSetTrajectorySize = new QAction("Set trajectory size...", this);
236  _aClearTrajectory = new QAction("Clear trajectory", this);
237  _aShowFrustum= new QAction("Show frustum", this);
238  _aShowFrustum->setCheckable(true);
239  _aShowFrustum->setChecked(false);
240  _aSetFrustumScale = new QAction("Set frustum scale...", this);
241  _aSetFrustumColor = new QAction("Set frustum color...", this);
242  _aShowGrid = new QAction("Show grid", this);
243  _aShowGrid->setCheckable(true);
244  _aSetGridCellCount = new QAction("Set cell count...", this);
245  _aSetGridCellSize = new QAction("Set cell size...", this);
246  _aShowNormals = new QAction("Show normals", this);
247  _aShowNormals->setCheckable(true);
248  _aSetNormalsStep = new QAction("Set normals step...", this);
249  _aSetNormalsScale = new QAction("Set normals scale...", this);
250  _aSetBackgroundColor = new QAction("Set background color...", this);
251  _aSetRenderingRate = new QAction("Set rendering rate...", this);
252  _aSetLighting = new QAction("Lighting", this);
253  _aSetLighting->setCheckable(true);
254  _aSetLighting->setChecked(false);
255  _aSetFlatShading = new QAction("Flat Shading", this);
256  _aSetFlatShading->setCheckable(true);
257  _aSetFlatShading->setChecked(false);
258  _aSetEdgeVisibility = new QAction("Show edges", this);
259  _aSetEdgeVisibility->setCheckable(true);
260  _aSetEdgeVisibility->setChecked(false);
261  _aBackfaceCulling = new QAction("Backface culling", this);
262  _aBackfaceCulling->setCheckable(true);
263  _aBackfaceCulling->setChecked(true);
264  _aPolygonPicking = new QAction("Polygon picking", this);
265  _aPolygonPicking->setCheckable(true);
266  _aPolygonPicking->setChecked(false);
267 
268  QMenu * cameraMenu = new QMenu("Camera", this);
269  cameraMenu->addAction(_aLockCamera);
270  cameraMenu->addAction(_aFollowCamera);
271  cameraMenu->addAction(freeCamera);
272  cameraMenu->addSeparator();
273  cameraMenu->addAction(_aLockViewZ);
274  cameraMenu->addAction(_aCameraOrtho);
275  cameraMenu->addAction(_aResetCamera);
276  QActionGroup * group = new QActionGroup(this);
277  group->addAction(_aLockCamera);
278  group->addAction(_aFollowCamera);
279  group->addAction(freeCamera);
280 
281  QMenu * trajectoryMenu = new QMenu("Trajectory", this);
282  trajectoryMenu->addAction(_aShowTrajectory);
283  trajectoryMenu->addAction(_aSetTrajectorySize);
284  trajectoryMenu->addAction(_aClearTrajectory);
285 
286  QMenu * frustumMenu = new QMenu("Frustum", this);
287  frustumMenu->addAction(_aShowFrustum);
288  frustumMenu->addAction(_aSetFrustumScale);
289  frustumMenu->addAction(_aSetFrustumColor);
290 
291  QMenu * gridMenu = new QMenu("Grid", this);
292  gridMenu->addAction(_aShowGrid);
293  gridMenu->addAction(_aSetGridCellCount);
294  gridMenu->addAction(_aSetGridCellSize);
295 
296  QMenu * normalsMenu = new QMenu("Normals", this);
297  normalsMenu->addAction(_aShowNormals);
298  normalsMenu->addAction(_aSetNormalsStep);
299  normalsMenu->addAction(_aSetNormalsScale);
300 
301  //menus
302  _menu = new QMenu(this);
303  _menu->addMenu(cameraMenu);
304  _menu->addMenu(trajectoryMenu);
305  _menu->addMenu(frustumMenu);
306  _menu->addMenu(gridMenu);
307  _menu->addMenu(normalsMenu);
308  _menu->addAction(_aSetBackgroundColor);
309  _menu->addAction(_aSetRenderingRate);
310  _menu->addAction(_aSetLighting);
311  _menu->addAction(_aSetFlatShading);
312  _menu->addAction(_aSetEdgeVisibility);
313  _menu->addAction(_aBackfaceCulling);
314  _menu->addAction(_aPolygonPicking);
315 }
316 
317 void CloudViewer::saveSettings(QSettings & settings, const QString & group) const
318 {
319  if(!group.isEmpty())
320  {
321  settings.beginGroup(group);
322  }
323 
324  float poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ;
325  this->getCameraPosition(poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ);
326  QVector3D pose(poseX, poseY, poseZ);
327  QVector3D focal(focalX, focalY, focalZ);
328  if(!this->isCameraFree())
329  {
330  // make camera position relative to target
331  Transform T = this->getTargetPose();
332  if(this->isCameraTargetLocked())
333  {
334  T = Transform(T.x(), T.y(), T.z(), 0,0,0);
335  }
336  Transform F(focalX, focalY, focalZ, 0,0,0);
337  Transform P(poseX, poseY, poseZ, 0,0,0);
338  Transform newFocal = T.inverse() * F;
339  Transform newPose = newFocal * F.inverse() * P;
340  pose = QVector3D(newPose.x(), newPose.y(), newPose.z());
341  focal = QVector3D(newFocal.x(), newFocal.y(), newFocal.z());
342  }
343  settings.setValue("camera_pose", pose);
344  settings.setValue("camera_focal", focal);
345  settings.setValue("camera_up", QVector3D(upX, upY, upZ));
346 
347  settings.setValue("grid", this->isGridShown());
348  settings.setValue("grid_cell_count", this->getGridCellCount());
349  settings.setValue("grid_cell_size", (double)this->getGridCellSize());
350 
351  settings.setValue("normals", this->isNormalsShown());
352  settings.setValue("normals_step", this->getNormalsStep());
353  settings.setValue("normals_scale", (double)this->getNormalsScale());
354 
355  settings.setValue("trajectory_shown", this->isTrajectoryShown());
356  settings.setValue("trajectory_size", this->getTrajectorySize());
357 
358  settings.setValue("frustum_shown", this->isFrustumShown());
359  settings.setValue("frustum_scale", this->getFrustumScale());
360  settings.setValue("frustum_color", this->getFrustumColor());
361 
362  settings.setValue("camera_target_locked", this->isCameraTargetLocked());
363  settings.setValue("camera_target_follow", this->isCameraTargetFollow());
364  settings.setValue("camera_free", this->isCameraFree());
365  settings.setValue("camera_lockZ", this->isCameraLockZ());
366  settings.setValue("camera_ortho", this->isCameraOrtho());
367 
368  settings.setValue("bg_color", this->getDefaultBackgroundColor());
369  settings.setValue("rendering_rate", this->getRenderingRate());
370  if(!group.isEmpty())
371  {
372  settings.endGroup();
373  }
374 }
375 
376 void CloudViewer::loadSettings(QSettings & settings, const QString & group)
377 {
378  if(!group.isEmpty())
379  {
380  settings.beginGroup(group);
381  }
382 
383  float poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ;
384  this->getCameraPosition(poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ);
385  QVector3D pose(poseX, poseY, poseZ), focal(focalX, focalY, focalZ), up(upX, upY, upZ);
386  pose = settings.value("camera_pose", pose).value<QVector3D>();
387  focal = settings.value("camera_focal", focal).value<QVector3D>();
388  up = settings.value("camera_up", up).value<QVector3D>();
389  this->setCameraPosition(pose.x(),pose.y(),pose.z(), focal.x(),focal.y(),focal.z(), up.x(),up.y(),up.z());
390 
391  this->setGridShown(settings.value("grid", this->isGridShown()).toBool());
392  this->setGridCellCount(settings.value("grid_cell_count", this->getGridCellCount()).toUInt());
393  this->setGridCellSize(settings.value("grid_cell_size", this->getGridCellSize()).toFloat());
394 
395  this->setNormalsShown(settings.value("normals", this->isNormalsShown()).toBool());
396  this->setNormalsStep(settings.value("normals_step", this->getNormalsStep()).toInt());
397  this->setNormalsScale(settings.value("normals_scale", this->getNormalsScale()).toFloat());
398 
399  this->setTrajectoryShown(settings.value("trajectory_shown", this->isTrajectoryShown()).toBool());
400  this->setTrajectorySize(settings.value("trajectory_size", this->getTrajectorySize()).toUInt());
401 
402  this->setFrustumShown(settings.value("frustum_shown", this->isFrustumShown()).toBool());
403  this->setFrustumScale(settings.value("frustum_scale", this->getFrustumScale()).toDouble());
404  this->setFrustumColor(settings.value("frustum_color", this->getFrustumColor()).value<QColor>());
405 
406  this->setCameraTargetLocked(settings.value("camera_target_locked", this->isCameraTargetLocked()).toBool());
407  this->setCameraTargetFollow(settings.value("camera_target_follow", this->isCameraTargetFollow()).toBool());
408  if(settings.value("camera_free", this->isCameraFree()).toBool())
409  {
410  this->setCameraFree();
411  }
412  this->setCameraLockZ(settings.value("camera_lockZ", this->isCameraLockZ()).toBool());
413  this->setCameraOrtho(settings.value("camera_ortho", this->isCameraOrtho()).toBool());
414 
415  this->setDefaultBackgroundColor(settings.value("bg_color", this->getDefaultBackgroundColor()).value<QColor>());
416 
417  this->setRenderingRate(settings.value("rendering_rate", this->getRenderingRate()).toDouble());
418 
419  if(!group.isEmpty())
420  {
421  settings.endGroup();
422  }
423 
424  this->update();
425 }
426 
428  const std::string & id,
429  const Transform & pose)
430 {
431  if(_addedClouds.contains(id))
432  {
433  //UDEBUG("Updating pose %s to %s", id.c_str(), pose.prettyPrint().c_str());
434  bool samePose = _addedClouds.find(id).value() == pose;
435  Eigen::Affine3f posef = pose.toEigen3f();
436  if(samePose ||
437  _visualizer->updatePointCloudPose(id, posef))
438  {
439  _addedClouds.find(id).value() = pose;
440  if(!samePose)
441  {
442  std::string idNormals = id+"-normals";
443  if(_addedClouds.find(idNormals)!=_addedClouds.end())
444  {
445  _visualizer->updatePointCloudPose(idNormals, posef);
446  _addedClouds.find(idNormals).value() = pose;
447  }
448  }
449  return true;
450  }
451  }
452  return false;
453 }
454 
456  const std::string & id,
457  const pcl::PCLPointCloud2Ptr & binaryCloud,
458  const Transform & pose,
459  bool rgb,
460  bool hasNormals,
461  bool hasIntensity,
462  const QColor & color)
463 {
464  int previousColorIndex = -1;
465  if(_addedClouds.contains(id))
466  {
467  previousColorIndex = _visualizer->getColorHandlerIndex(id);
468  this->removeCloud(id);
469  }
470 
471  Eigen::Vector4f origin(pose.x(), pose.y(), pose.z(), 0.0f);
472  Eigen::Quaternionf orientation = Eigen::Quaternionf(pose.toEigen3f().linear());
473 
474  if(hasNormals && _aShowNormals->isChecked())
475  {
476  pcl::PointCloud<pcl::PointNormal>::Ptr cloud_xyz (new pcl::PointCloud<pcl::PointNormal>);
477  pcl::fromPCLPointCloud2 (*binaryCloud, *cloud_xyz);
478  std::string idNormals = id + "-normals";
479  if(_visualizer->addPointCloudNormals<pcl::PointNormal>(cloud_xyz, _normalsStep, _normalsScale, idNormals, 0))
480  {
481  _visualizer->updatePointCloudPose(idNormals, pose.toEigen3f());
482  _addedClouds.insert(idNormals, pose);
483  }
484  }
485 
486  // add random color channel
487  pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::Ptr colorHandler;
488  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerRandom<pcl::PCLPointCloud2> (binaryCloud));
489  if(_visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, 1))
490  {
491  QColor c = Qt::gray;
492  if(color.isValid())
493  {
494  c = color;
495  }
496  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerCustom<pcl::PCLPointCloud2> (binaryCloud, c.red(), c.green(), c.blue()));
497  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, 1);
498 
499  // x,y,z
500  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "x"));
501  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, 1);
502  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "y"));
503  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, 1);
504  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "z"));
505  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, 1);
506 
507  if(rgb)
508  {
509  //rgb
510  colorHandler.reset(new pcl::visualization::PointCloudColorHandlerRGBField<pcl::PCLPointCloud2>(binaryCloud));
511  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, 1);
512  }
513  else if(hasIntensity)
514  {
515  //rgb
516  colorHandler.reset(new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2>(binaryCloud, "intensity"));
517  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, 1);
518  }
519  else if(previousColorIndex == 5)
520  {
521  previousColorIndex = -1;
522  }
523 
524  if(hasNormals)
525  {
526  //normals
527  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "normal_x"));
528  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, 1);
529  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "normal_y"));
530  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, 1);
531  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "normal_z"));
532  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, 1);
533  }
534  else if(previousColorIndex > 5)
535  {
536  previousColorIndex = -1;
537  }
538 
539  if(previousColorIndex>=0)
540  {
541  _visualizer->updateColorHandlerIndex(id, previousColorIndex);
542  }
543  else if(rgb)
544  {
545  _visualizer->updateColorHandlerIndex(id, 5);
546  }
547  else if(hasNormals)
548  {
549  _visualizer->updateColorHandlerIndex(id, hasIntensity?8:7);
550  }
551  else if(hasIntensity)
552  {
553  _visualizer->updateColorHandlerIndex(id, 5);
554  }
555  else if(color.isValid())
556  {
557  _visualizer->updateColorHandlerIndex(id, 1);
558  }
559 
560  _addedClouds.insert(id, pose);
561  return true;
562  }
563  return false;
564 }
565 
567  const std::string & id,
568  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
569  const Transform & pose,
570  const QColor & color)
571 {
572  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
573  pcl::toPCLPointCloud2(*cloud, *binaryCloud);
574  return addCloud(id, binaryCloud, pose, true, true, false, color);
575 }
576 
578  const std::string & id,
579  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
580  const Transform & pose,
581  const QColor & color)
582 {
583  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
584  pcl::toPCLPointCloud2(*cloud, *binaryCloud);
585  return addCloud(id, binaryCloud, pose, true, false, false, color);
586 }
587 
589  const std::string & id,
590  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
591  const Transform & pose,
592  const QColor & color)
593 {
594  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
595  pcl::toPCLPointCloud2(*cloud, *binaryCloud);
596  return addCloud(id, binaryCloud, pose, false, true, true, color);
597 }
598 
600  const std::string & id,
601  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
602  const Transform & pose,
603  const QColor & color)
604 {
605  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
606  pcl::toPCLPointCloud2(*cloud, *binaryCloud);
607  return addCloud(id, binaryCloud, pose, false, false, true, color);
608 }
609 
611  const std::string & id,
612  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
613  const Transform & pose,
614  const QColor & color)
615 {
616  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
617  pcl::toPCLPointCloud2(*cloud, *binaryCloud);
618  return addCloud(id, binaryCloud, pose, false, true, false, color);
619 }
620 
622  const std::string & id,
623  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
624  const Transform & pose,
625  const QColor & color)
626 {
627  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
628  pcl::toPCLPointCloud2(*cloud, *binaryCloud);
629  return addCloud(id, binaryCloud, pose, false, false, false, color);
630 }
631 
633  const std::string & id,
634  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
635  const std::vector<pcl::Vertices> & polygons,
636  const Transform & pose)
637 {
638  if(_addedClouds.contains(id))
639  {
640  this->removeCloud(id);
641  }
642 
643  UDEBUG("Adding %s with %d points and %d polygons", id.c_str(), (int)cloud->size(), (int)polygons.size());
644  if(_visualizer->addPolygonMesh<pcl::PointXYZ>(cloud, polygons, id, 1))
645  {
646  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.5);
647  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
648  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetInterpolation(_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
649  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
650  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
651  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
652  _visualizer->updatePointCloudPose(id, pose.toEigen3f());
653  if(_buildLocator)
654  {
656  tree->SetDataSet(_visualizer->getCloudActorMap()->find(id)->second.actor->GetMapper()->GetInput());
657  tree->BuildLocator();
658  _locators.insert(std::make_pair(id, tree));
659  }
660  _addedClouds.insert(id, pose);
661  return true;
662  }
663  return false;
664 }
665 
667  const std::string & id,
668  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
669  const std::vector<pcl::Vertices> & polygons,
670  const Transform & pose)
671 {
672  if(_addedClouds.contains(id))
673  {
674  this->removeCloud(id);
675  }
676 
677  UDEBUG("Adding %s with %d points and %d polygons", id.c_str(), (int)cloud->size(), (int)polygons.size());
678  if(_visualizer->addPolygonMesh<pcl::PointXYZRGB>(cloud, polygons, id, 1))
679  {
680  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.5);
681  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
682  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetInterpolation(_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
683  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
684  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
685  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
686  _visualizer->updatePointCloudPose(id, pose.toEigen3f());
687  if(_buildLocator)
688  {
690  tree->SetDataSet(_visualizer->getCloudActorMap()->find(id)->second.actor->GetMapper()->GetInput());
691  tree->BuildLocator();
692  _locators.insert(std::make_pair(id, tree));
693  }
694  _addedClouds.insert(id, pose);
695  return true;
696  }
697  return false;
698 }
699 
701  const std::string & id,
702  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
703  const std::vector<pcl::Vertices> & polygons,
704  const Transform & pose)
705 {
706  if(_addedClouds.contains(id))
707  {
708  this->removeCloud(id);
709  }
710 
711  UDEBUG("Adding %s with %d points and %d polygons", id.c_str(), (int)cloud->size(), (int)polygons.size());
712  if(_visualizer->addPolygonMesh<pcl::PointXYZRGBNormal>(cloud, polygons, id, 1))
713  {
714  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.5);
715  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
716  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetInterpolation(_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
717  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
718  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
719  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
720  _visualizer->updatePointCloudPose(id, pose.toEigen3f());
721  if(_buildLocator)
722  {
724  tree->SetDataSet(_visualizer->getCloudActorMap()->find(id)->second.actor->GetMapper()->GetInput());
725  tree->BuildLocator();
726  _locators.insert(std::make_pair(id, tree));
727  }
728  _addedClouds.insert(id, pose);
729  return true;
730  }
731  return false;
732 }
733 
735  const std::string & id,
736  const pcl::PolygonMesh::Ptr & mesh,
737  const Transform & pose)
738 {
739  if(_addedClouds.contains(id))
740  {
741  this->removeCloud(id);
742  }
743 
744  UDEBUG("Adding %s with %d polygons", id.c_str(), (int)mesh->polygons.size());
745  if(_visualizer->addPolygonMesh(*mesh, id, 1))
746  {
747  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.5);
748  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
749  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
750  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
751  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
752  _visualizer->updatePointCloudPose(id, pose.toEigen3f());
753  if(_buildLocator)
754  {
756  tree->SetDataSet(_visualizer->getCloudActorMap()->find(id)->second.actor->GetMapper()->GetInput());
757  tree->BuildLocator();
758  _locators.insert(std::make_pair(id, tree));
759  }
760  _addedClouds.insert(id, pose);
761  return true;
762  }
763 
764  return false;
765 }
766 
768  const std::string & id,
769  const pcl::TextureMesh::Ptr & textureMesh,
770  const cv::Mat & texture,
771  const Transform & pose)
772 {
773  if(_addedClouds.contains(id))
774  {
775  this->removeCloud(id);
776  }
777 
778  UDEBUG("Adding %s", id.c_str());
779  if(this->addTextureMesh(*textureMesh, texture, id, 1))
780  {
781  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
782  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetInterpolation(_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
783  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
784  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
785  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
786  if(!textureMesh->cloud.is_dense)
787  {
788  _visualizer->getCloudActorMap()->find(id)->second.actor->GetTexture()->SetInterpolate(1);
789  _visualizer->getCloudActorMap()->find(id)->second.actor->GetTexture()->SetBlendingMode(vtkTexture::VTK_TEXTURE_BLENDING_MODE_REPLACE);
790  }
791  _visualizer->updatePointCloudPose(id, pose.toEigen3f());
792  if(_buildLocator)
793  {
795  tree->SetDataSet(_visualizer->getCloudActorMap()->find(id)->second.actor->GetMapper()->GetInput());
796  tree->BuildLocator();
797  _locators.insert(std::make_pair(id, tree));
798  }
799  _addedClouds.insert(id, pose);
800  return true;
801  }
802  return false;
803 }
804 
805 bool CloudViewer::addOctomap(const OctoMap * octomap, unsigned int treeDepth, bool volumeRepresentation)
806 {
807  UDEBUG("");
808 #ifdef RTABMAP_OCTOMAP
809  UASSERT(octomap!=0);
810 
811  pcl::IndicesPtr obstacles(new std::vector<int>);
812 
813  if(treeDepth == 0 || treeDepth > octomap->octree()->getTreeDepth())
814  {
815  if(treeDepth>0)
816  {
817  UWARN("Tree depth requested (%d) is deeper than the "
818  "actual maximum tree depth of %d. Using maximum depth.",
819  (int)treeDepth, (int)octomap->octree()->getTreeDepth());
820  }
821  treeDepth = octomap->octree()->getTreeDepth();
822  }
823 
824  removeOctomap();
825 
826  if(!volumeRepresentation)
827  {
828  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = octomap->createCloud(treeDepth, obstacles.get(), 0, 0, false);
829  if(obstacles->size())
830  {
831  //vtkSmartPointer<vtkUnsignedCharArray> colors = vtkSmartPointer<vtkUnsignedCharArray>::New();
832  //colors->SetName("colors");
833  //colors->SetNumberOfComponents(3);
835  colors->SetName("colors");
836  colors->SetNumberOfValues(obstacles->size());
837 
839  lut->SetNumberOfTableValues(obstacles->size());
840  lut->Build();
841 
842  // Create points
844  points->SetNumberOfPoints(obstacles->size());
845  double s = octomap->octree()->getNodeSize(treeDepth) / 2.0;
846  for (unsigned int i = 0; i < obstacles->size(); i++)
847  {
848  points->InsertPoint(i,
849  cloud->at(obstacles->at(i)).x,
850  cloud->at(obstacles->at(i)).y,
851  cloud->at(obstacles->at(i)).z);
852  colors->InsertValue(i,i);
853 
854  lut->SetTableValue(i,
855  double(cloud->at(obstacles->at(i)).r) / 255.0,
856  double(cloud->at(obstacles->at(i)).g) / 255.0,
857  double(cloud->at(obstacles->at(i)).b) / 255.0);
858  }
859 
860  // Combine into a polydata
862  polydata->SetPoints(points);
863  polydata->GetPointData()->SetScalars(colors);
864 
865  // Create anything you want here, we will use a cube for the demo.
867  cubeSource->SetBounds(-s, s, -s, s, -s, s);
868 
870  mapper->SetSourceConnection(cubeSource->GetOutputPort());
871  #if VTK_MAJOR_VERSION <= 5
872  mapper->SetInputConnection(polydata->GetProducerPort());
873  #else
874  mapper->SetInputData(polydata);
875  #endif
876  mapper->SetScalarRange(0, obstacles->size() - 1);
877  mapper->SetLookupTable(lut);
878  mapper->ScalingOff();
879  mapper->Update();
880 
882  octomapActor->SetMapper(mapper);
883 
884  octomapActor->GetProperty()->SetRepresentationToSurface();
885  octomapActor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
886  octomapActor->GetProperty()->SetLighting(_aSetLighting->isChecked());
887 
888  _visualizer->getRendererCollection()->InitTraversal ();
889  vtkRenderer* renderer = NULL;
890  renderer = _visualizer->getRendererCollection()->GetNextItem ();
891  renderer = _visualizer->getRendererCollection()->GetNextItem ();
892  UASSERT(renderer);
893  renderer->AddActor(octomapActor);
894 
895  _octomapActor = octomapActor.GetPointer();
896  return true;
897  }
898  }
899  else
900  {
901  if(octomap->octree()->size())
902  {
903  // Create an image data
906 
907  double sizeX, sizeY, sizeZ;
908  double minX, minY, minZ;
909  double maxX, maxY, maxZ;
910  octomap->getGridMin(minX, minY, minZ);
911  octomap->getGridMax(maxX, maxY, maxZ);
912  sizeX = maxX-minX;
913  sizeY = maxY-minY;
914  sizeZ = maxZ-minZ;
915  double cellSize = octomap->octree()->getNodeSize(treeDepth);
916 
917  UTimer t;
918  // Specify the size of the image data
919  imageData->SetExtent(0, int(sizeX/cellSize+0.5), 0, int(sizeY/cellSize+0.5), 0, int(sizeZ/cellSize+0.5)); // 3D image
920 #if VTK_MAJOR_VERSION <= 5
921  imageData->SetNumberOfScalarComponents(4);
922  imageData->SetScalarTypeToUnsignedChar();
923 #else
924  imageData->AllocateScalars(VTK_UNSIGNED_CHAR,4);
925 #endif
926 
927  int dims[3];
928  imageData->GetDimensions(dims);
929 
930  memset(imageData->GetScalarPointer(), 0, imageData->GetScalarSize()*imageData->GetNumberOfScalarComponents()*dims[0]*dims[1]*dims[2]);
931 
932  for (RtabmapColorOcTree::iterator it = octomap->octree()->begin(treeDepth); it != octomap->octree()->end(); ++it)
933  {
934  if(octomap->octree()->isNodeOccupied(*it))
935  {
936  octomap::point3d pt = octomap->octree()->keyToCoord(it.getKey());
937  int x = (pt.x()-minX) / cellSize;
938  int y = (pt.y()-minY) / cellSize;
939  int z = (pt.z()-minZ) / cellSize;
940  if(x>=0 && x<dims[0] && y>=0 && y<dims[1] && z>=0 && z<dims[2])
941  {
942  unsigned char* pixel = static_cast<unsigned char*>(imageData->GetScalarPointer(x,y,z));
943  if(octomap->octree()->getTreeDepth() == it.getDepth() && it->isColorSet())
944  {
945  pixel[0] = it->getColor().r;
946  pixel[1] = it->getColor().g;
947  pixel[2] = it->getColor().b;
948  }
949  else
950  {
951  // Gradiant color on z axis
952  float H = (maxZ - pt.z())*299.0f/(maxZ-minZ);
953  float r,g,b;
954  OctoMap::HSVtoRGB(&r, &g, &b, H, 1, 1);
955  pixel[0] = r*255.0f;
956  pixel[1] = g*255.0f;
957  pixel[2] = b*255.0f;
958  }
959  pixel[3] = 255;
960  }
961  }
962  }
965  volumeMapper->SetBlendModeToComposite(); // composite first
966 #if VTK_MAJOR_VERSION <= 5
967  volumeMapper->SetInputConnection(imageData->GetProducerPort());
968 #else
969  volumeMapper->SetInputData(imageData);
970 #endif
971  vtkSmartPointer<vtkVolumeProperty> volumeProperty =
973  volumeProperty->ShadeOff();
974  volumeProperty->IndependentComponentsOff();
975 
976  vtkSmartPointer<vtkPiecewiseFunction> compositeOpacity =
978  compositeOpacity->AddPoint(0.0,0.0);
979  compositeOpacity->AddPoint(255.0,1.0);
980  volumeProperty->SetScalarOpacity(0, compositeOpacity); // composite first.
981 
984  volume->SetMapper(volumeMapper);
985  volume->SetProperty(volumeProperty);
986  volume->SetScale(cellSize);
987  volume->SetPosition(minX, minY, minZ);
988 
989  _visualizer->getRendererCollection()->InitTraversal ();
990  vtkRenderer* renderer = NULL;
991  renderer = _visualizer->getRendererCollection()->GetNextItem ();
992  renderer = _visualizer->getRendererCollection()->GetNextItem ();
993  UASSERT(renderer);
994  renderer->AddViewProp(volume);
995 
996  // 3D texture mode. For coverage.
997 #if !defined(VTK_LEGACY_REMOVE) && !defined(VTK_OPENGL2)
998  volumeMapper->SetRequestedRenderModeToRayCastAndTexture();
999 #endif // VTK_LEGACY_REMOVE
1000 
1001  // Software mode, for coverage. It also makes sure we will get the same
1002  // regression image on all platforms.
1003  volumeMapper->SetRequestedRenderModeToRayCast();
1004  _octomapActor = volume.GetPointer();
1005 
1006  return true;
1007  }
1008  }
1009 #endif
1010  return false;
1011 }
1012 
1014 {
1015  UDEBUG("");
1016 #ifdef RTABMAP_OCTOMAP
1017  if(_octomapActor)
1018  {
1019  _visualizer->getRendererCollection()->InitTraversal ();
1020  vtkRenderer* renderer = NULL;
1021  renderer = _visualizer->getRendererCollection()->GetNextItem ();
1022  renderer = _visualizer->getRendererCollection()->GetNextItem ();
1023  UASSERT(renderer);
1024  renderer->RemoveActor(_octomapActor);
1025  _octomapActor = 0;
1026  }
1027 #endif
1028 }
1029 
1031  const pcl::TextureMesh &mesh,
1032  const cv::Mat & image,
1033  const std::string &id,
1034  int viewport)
1035 {
1036  // Copied from PCL 1.8, modified to ignore vertex color and accept only one material (loaded from memory instead of file)
1037 
1038  pcl::visualization::CloudActorMap::iterator am_it = _visualizer->getCloudActorMap()->find (id);
1039  if (am_it != _visualizer->getCloudActorMap()->end ())
1040  {
1041  PCL_ERROR ("[PCLVisualizer::addTextureMesh] A shape with id <%s> already exists!"
1042  " Please choose a different id and retry.\n",
1043  id.c_str ());
1044  return (false);
1045  }
1046  // no texture materials --> exit
1047  if (mesh.tex_materials.size () == 0)
1048  {
1049  PCL_ERROR("[PCLVisualizer::addTextureMesh] No textures found!\n");
1050  return (false);
1051  }
1052  else if (mesh.tex_materials.size() > 1)
1053  {
1054  PCL_ERROR("[PCLVisualizer::addTextureMesh] only one material per mesh is supported!\n");
1055  return (false);
1056  }
1057  // polygons are mapped to texture materials
1058  if (mesh.tex_materials.size () != mesh.tex_polygons.size ())
1059  {
1060  PCL_ERROR("[PCLVisualizer::addTextureMesh] Materials number %lu differs from polygons number %lu!\n",
1061  mesh.tex_materials.size (), mesh.tex_polygons.size ());
1062  return (false);
1063  }
1064  // each texture material should have its coordinates set
1065  if (mesh.tex_materials.size () != mesh.tex_coordinates.size ())
1066  {
1067  PCL_ERROR("[PCLVisualizer::addTextureMesh] Coordinates number %lu differs from materials number %lu!\n",
1068  mesh.tex_coordinates.size (), mesh.tex_materials.size ());
1069  return (false);
1070  }
1071  // total number of vertices
1072  std::size_t nb_vertices = 0;
1073  for (std::size_t i = 0; i < mesh.tex_polygons.size (); ++i)
1074  nb_vertices+= mesh.tex_polygons[i].size ();
1075  // no vertices --> exit
1076  if (nb_vertices == 0)
1077  {
1078  PCL_ERROR("[PCLVisualizer::addTextureMesh] No vertices found!\n");
1079  return (false);
1080  }
1081  // total number of coordinates
1082  std::size_t nb_coordinates = 0;
1083  for (std::size_t i = 0; i < mesh.tex_coordinates.size (); ++i)
1084  nb_coordinates+= mesh.tex_coordinates[i].size ();
1085  // no texture coordinates --> exit
1086  if (nb_coordinates == 0)
1087  {
1088  PCL_ERROR("[PCLVisualizer::addTextureMesh] No textures coordinates found!\n");
1089  return (false);
1090  }
1091 
1092  // Create points from mesh.cloud
1095  bool has_color = false;
1097 
1098  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ> ());
1099  pcl::fromPCLPointCloud2 (mesh.cloud, *cloud);
1100  // no points --> exit
1101  if (cloud->points.size () == 0)
1102  {
1103  PCL_ERROR("[PCLVisualizer::addTextureMesh] Cloud is empty!\n");
1104  return (false);
1105  }
1106  pcl::visualization::PCLVisualizer::convertToVtkMatrix (cloud->sensor_origin_, cloud->sensor_orientation_, transformation);
1107  poly_points->SetNumberOfPoints (cloud->points.size ());
1108  for (std::size_t i = 0; i < cloud->points.size (); ++i)
1109  {
1110  const pcl::PointXYZ &p = cloud->points[i];
1111  poly_points->InsertPoint (i, p.x, p.y, p.z);
1112  }
1113 
1114  //create polys from polyMesh.tex_polygons
1116  for (std::size_t i = 0; i < mesh.tex_polygons.size (); i++)
1117  {
1118  for (std::size_t j = 0; j < mesh.tex_polygons[i].size (); j++)
1119  {
1120  std::size_t n_points = mesh.tex_polygons[i][j].vertices.size ();
1121  polys->InsertNextCell (int (n_points));
1122  for (std::size_t k = 0; k < n_points; k++)
1123  polys->InsertCellPoint (mesh.tex_polygons[i][j].vertices[k]);
1124  }
1125  }
1126 
1128  polydata->SetPolys (polys);
1129  polydata->SetPoints (poly_points);
1130  if (has_color)
1131  polydata->GetPointData()->SetScalars(colors);
1132 
1134 #if VTK_MAJOR_VERSION < 6
1135  mapper->SetInput (polydata);
1136 #else
1137  mapper->SetInputData (polydata);
1138 #endif
1139 
1141  vtkTextureUnitManager* tex_manager = vtkOpenGLRenderWindow::SafeDownCast (_visualizer->getRenderWindow())->GetTextureUnitManager ();
1142  if (!tex_manager)
1143  return (false);
1144 
1146  // fill vtkTexture from pcl::TexMaterial structure
1148  cvImageToVtk->SetImage(image);
1149  cvImageToVtk->Update();
1150  texture->SetInputConnection(cvImageToVtk->GetOutputPort());
1151 
1152  // set texture coordinates
1154  coordinates->SetNumberOfComponents (2);
1155  coordinates->SetNumberOfTuples (mesh.tex_coordinates[0].size ());
1156  for (std::size_t tc = 0; tc < mesh.tex_coordinates[0].size (); ++tc)
1157  {
1158  const Eigen::Vector2f &uv = mesh.tex_coordinates[0][tc];
1159  coordinates->SetTuple2 (tc, (double)uv[0], (double)uv[1]);
1160  }
1161  coordinates->SetName ("TCoords");
1162  polydata->GetPointData ()->SetTCoords(coordinates);
1163  // apply texture
1164  actor->SetTexture (texture);
1165 
1166  // set mapper
1167  actor->SetMapper (mapper);
1168 
1169  //_visualizer->addActorToRenderer (actor, viewport);
1170  // Add it to all renderers
1171  _visualizer->getRendererCollection()->InitTraversal ();
1172  vtkRenderer* renderer = NULL;
1173  int i = 0;
1174  while ((renderer = _visualizer->getRendererCollection()->GetNextItem ()) != NULL)
1175  {
1176  // Should we add the actor to all renderers?
1177  if (viewport == 0)
1178  {
1179  renderer->AddActor (actor);
1180  }
1181  else if (viewport == i) // add the actor only to the specified viewport
1182  {
1183  renderer->AddActor (actor);
1184  }
1185  ++i;
1186  }
1187 
1188  // Save the pointer/ID pair to the global actor map
1189  (*_visualizer->getCloudActorMap())[id].actor = actor;
1190 
1191  // Save the viewpoint transformation matrix to the global actor map
1192  (*_visualizer->getCloudActorMap())[id].viewpoint_transformation_ = transformation;
1193 
1194  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.5);
1195  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
1196  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetInterpolation(_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
1197  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
1198  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
1199  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
1200  return true;
1201 }
1202 
1204  const cv::Mat & map8U,
1205  float resolution, // cell size
1206  float xMin,
1207  float yMin,
1208  float opacity)
1209 {
1210  UASSERT(map8U.channels() == 1 && map8U.type() == CV_8U);
1211 
1212  float xSize = float(map8U.cols) * resolution;
1213  float ySize = float(map8U.rows) * resolution;
1214 
1215  UDEBUG("resolution=%f, xSize=%f, ySize=%f, xMin=%f, yMin=%f", resolution, xSize, ySize, xMin, yMin);
1216  if(_visualizer->getCloudActorMap()->find("map") != _visualizer->getCloudActorMap()->end())
1217  {
1218  _visualizer->removePointCloud("map");
1219  }
1220 
1221  if(xSize > 0.0f && ySize > 0.0f)
1222  {
1223  pcl::TextureMeshPtr mesh(new pcl::TextureMesh());
1224  pcl::PointCloud<pcl::PointXYZ> cloud;
1225  cloud.push_back(pcl::PointXYZ(xMin, yMin, 0));
1226  cloud.push_back(pcl::PointXYZ(xSize+xMin, yMin, 0));
1227  cloud.push_back(pcl::PointXYZ(xSize+xMin, ySize+yMin, 0));
1228  cloud.push_back(pcl::PointXYZ(xMin, ySize+yMin, 0));
1229  pcl::toPCLPointCloud2(cloud, mesh->cloud);
1230 
1231  std::vector<pcl::Vertices> polygons(1);
1232  polygons[0].vertices.push_back(0);
1233  polygons[0].vertices.push_back(1);
1234  polygons[0].vertices.push_back(2);
1235  polygons[0].vertices.push_back(3);
1236  polygons[0].vertices.push_back(0);
1237  mesh->tex_polygons.push_back(polygons);
1238 
1239  // default texture materials parameters
1240  pcl::TexMaterial material;
1241  material.tex_file = "";
1242  mesh->tex_materials.push_back(material);
1243 
1244 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
1245  std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > coordinates;
1246 #else
1247  std::vector<Eigen::Vector2f> coordinates;
1248 #endif
1249  coordinates.push_back(Eigen::Vector2f(0,1));
1250  coordinates.push_back(Eigen::Vector2f(1,1));
1251  coordinates.push_back(Eigen::Vector2f(1,0));
1252  coordinates.push_back(Eigen::Vector2f(0,0));
1253  mesh->tex_coordinates.push_back(coordinates);
1254 
1255  this->addTextureMesh(*mesh, map8U, "map", 1);
1256  setCloudOpacity("map", opacity);
1257  }
1258  return true;
1259 }
1260 
1262 {
1263  if(_visualizer->getCloudActorMap()->find("map") != _visualizer->getCloudActorMap()->end())
1264  {
1265  _visualizer->removePointCloud("map");
1266  }
1267 }
1268 
1270  const std::string & id,
1271  const Transform & transform,
1272  double scale,
1273  bool foreground)
1274 {
1275  if(id.empty())
1276  {
1277  UERROR("id should not be empty!");
1278  return;
1279  }
1280 
1281  removeCoordinate(id);
1282 
1283  if(!transform.isNull())
1284  {
1285  _coordinates.insert(id);
1286 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
1287  _visualizer->addCoordinateSystem(scale, transform.toEigen3f(), id, foreground?2:1);
1288 #else
1289  // Well, on older versions, just update the main coordinate
1290  _visualizer->addCoordinateSystem(scale, transform.toEigen3f(), 0);
1291 #endif
1292  }
1293 }
1294 
1296  const std::string & id,
1297  const Transform & pose)
1298 {
1299 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
1300  if(_coordinates.find(id) != _coordinates.end() && !pose.isNull())
1301  {
1302  UDEBUG("Updating pose %s to %s", id.c_str(), pose.prettyPrint().c_str());
1303  return _visualizer->updateCoordinateSystemPose(id, pose.toEigen3f());
1304  }
1305 #else
1306  UERROR("CloudViewer::updateCoordinatePose() is not available on PCL < 1.7.2");
1307 #endif
1308  return false;
1309 }
1310 
1311 void CloudViewer::removeCoordinate(const std::string & id)
1312 {
1313  if(id.empty())
1314  {
1315  UERROR("id should not be empty!");
1316  return;
1317  }
1318 
1319  if(_coordinates.find(id) != _coordinates.end())
1320  {
1321 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
1322  _visualizer->removeCoordinateSystem(id);
1323 #else
1324  // Well, on older versions, just update the main coordinate
1325  _visualizer->removeCoordinateSystem(0);
1326 #endif
1327  _coordinates.erase(id);
1328  }
1329 }
1330 
1332 {
1333  std::set<std::string> coordinates = _coordinates;
1334  for(std::set<std::string>::iterator iter = coordinates.begin(); iter!=coordinates.end(); ++iter)
1335  {
1336  this->removeCoordinate(*iter);
1337  }
1338  UASSERT(_coordinates.empty());
1339 }
1340 
1342  const std::string & id,
1343  const Transform & from,
1344  const Transform & to,
1345  const QColor & color,
1346  bool arrow,
1347  bool foreground)
1348 {
1349  if(id.empty())
1350  {
1351  UERROR("id should not be empty!");
1352  return;
1353  }
1354 
1355  removeLine(id);
1356 
1357  if(!from.isNull() && !to.isNull())
1358  {
1359  _lines.insert(id);
1360 
1361  QColor c = Qt::gray;
1362  if(color.isValid())
1363  {
1364  c = color;
1365  }
1366 
1367  pcl::PointXYZ pt1(from.x(), from.y(), from.z());
1368  pcl::PointXYZ pt2(to.x(), to.y(), to.z());
1369 
1370  if(arrow)
1371  {
1372  _visualizer->addArrow(pt2, pt1, c.redF(), c.greenF(), c.blueF(), false, id, foreground?2:1);
1373  }
1374  else
1375  {
1376  _visualizer->addLine(pt2, pt1, c.redF(), c.greenF(), c.blueF(), id, foreground?2:1);
1377  }
1378  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1379  }
1380 }
1381 
1382 void CloudViewer::removeLine(const std::string & id)
1383 {
1384  if(id.empty())
1385  {
1386  UERROR("id should not be empty!");
1387  return;
1388  }
1389 
1390  if(_lines.find(id) != _lines.end())
1391  {
1392  _visualizer->removeShape(id);
1393  _lines.erase(id);
1394  }
1395 }
1396 
1398 {
1399  std::set<std::string> arrows = _lines;
1400  for(std::set<std::string>::iterator iter = arrows.begin(); iter!=arrows.end(); ++iter)
1401  {
1402  this->removeLine(*iter);
1403  }
1404  UASSERT(_lines.empty());
1405 }
1406 
1408  const std::string & id,
1409  const Transform & pose,
1410  float radius,
1411  const QColor & color,
1412  bool foreground)
1413 {
1414  if(id.empty())
1415  {
1416  UERROR("id should not be empty!");
1417  return;
1418  }
1419 
1420  removeSphere(id);
1421 
1422  if(!pose.isNull())
1423  {
1424  _spheres.insert(id);
1425 
1426  QColor c = Qt::gray;
1427  if(color.isValid())
1428  {
1429  c = color;
1430  }
1431 
1432  pcl::PointXYZ center(pose.x(), pose.y(), pose.z());
1433  _visualizer->addSphere(center, radius, c.redF(), c.greenF(), c.blueF(), id, foreground?2:1);
1434  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1435  }
1436 }
1437 
1438 void CloudViewer::removeSphere(const std::string & id)
1439 {
1440  if(id.empty())
1441  {
1442  UERROR("id should not be empty!");
1443  return;
1444  }
1445 
1446  if(_spheres.find(id) != _spheres.end())
1447  {
1448  _visualizer->removeShape(id);
1449  _spheres.erase(id);
1450  }
1451 }
1452 
1454 {
1455  std::set<std::string> spheres = _spheres;
1456  for(std::set<std::string>::iterator iter = spheres.begin(); iter!=spheres.end(); ++iter)
1457  {
1458  this->removeSphere(*iter);
1459  }
1460  UASSERT(_spheres.empty());
1461 }
1462 
1464  const std::string & id,
1465  const Transform & pose,
1466  float width,
1467  float height,
1468  float depth,
1469  const QColor & color,
1470  bool wireframe,
1471  bool foreground)
1472 {
1473  if(id.empty())
1474  {
1475  UERROR("id should not be empty!");
1476  return;
1477  }
1478 
1479  removeCube(id);
1480 
1481  if(!pose.isNull())
1482  {
1483  _cubes.insert(id);
1484 
1485  QColor c = Qt::gray;
1486  if(color.isValid())
1487  {
1488  c = color;
1489  }
1490  _visualizer->addCube(Eigen::Vector3f(pose.x(), pose.y(), pose.z()), pose.getQuaternionf(), width, height, depth, id, foreground?2:1);
1491  if(wireframe)
1492  {
1493  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_REPRESENTATION, pcl::visualization::PCL_VISUALIZER_REPRESENTATION_WIREFRAME, id);
1494  }
1495  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, c.redF(), c.greenF(), c.blueF(), id);
1496  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1497  }
1498 }
1499 
1500 void CloudViewer::removeCube(const std::string & id)
1501 {
1502  if(id.empty())
1503  {
1504  UERROR("id should not be empty!");
1505  return;
1506  }
1507 
1508  if(_cubes.find(id) != _cubes.end())
1509  {
1510  _visualizer->removeShape(id);
1511  _cubes.erase(id);
1512  }
1513 }
1514 
1516 {
1517  std::set<std::string> cubes = _cubes;
1518  for(std::set<std::string>::iterator iter = cubes.begin(); iter!=cubes.end(); ++iter)
1519  {
1520  this->removeCube(*iter);
1521  }
1522  UASSERT(_cubes.empty());
1523 }
1524 
1526  const std::string & id,
1527  const Transform & pose,
1528  float width,
1529  float height,
1530  const QColor & color,
1531  bool foreground)
1532 {
1533  addOrUpdateQuad(id, pose, width/2.0f, width/2.0f, height/2.0f, height/2.0f, color, foreground);
1534 }
1535 
1537  const std::string & id,
1538  const Transform & pose,
1539  float widthLeft,
1540  float widthRight,
1541  float heightBottom,
1542  float heightTop,
1543  const QColor & color,
1544  bool foreground)
1545 {
1546  if(id.empty())
1547  {
1548  UERROR("id should not be empty!");
1549  return;
1550  }
1551 
1552  removeQuad(id);
1553 
1554  if(!pose.isNull())
1555  {
1556  _quads.insert(id);
1557 
1558  QColor c = Qt::gray;
1559  if(color.isValid())
1560  {
1561  c = color;
1562  }
1563 
1564  // Create four points (must be in counter clockwise order)
1565  double p0[3] = {0.0, -widthLeft, heightTop};
1566  double p1[3] = {0.0, -widthLeft, -heightBottom};
1567  double p2[3] = {0.0, widthRight, -heightBottom};
1568  double p3[3] = {0.0, widthRight, heightTop};
1569 
1570  // Add the points to a vtkPoints object
1573  points->InsertNextPoint(p0);
1574  points->InsertNextPoint(p1);
1575  points->InsertNextPoint(p2);
1576  points->InsertNextPoint(p3);
1577 
1578  // Create a quad on the four points
1581  quad->GetPointIds()->SetId(0,0);
1582  quad->GetPointIds()->SetId(1,1);
1583  quad->GetPointIds()->SetId(2,2);
1584  quad->GetPointIds()->SetId(3,3);
1585 
1586  // Create a cell array to store the quad in
1589  quads->InsertNextCell(quad);
1590 
1591  // Create a polydata to store everything in
1592  vtkSmartPointer<vtkPolyData> polydata =
1594 
1595  // Add the points and quads to the dataset
1596  polydata->SetPoints(points);
1597  polydata->SetPolys(quads);
1598 
1599  // Setup actor and mapper
1602 #if VTK_MAJOR_VERSION <= 5
1603  mapper->SetInput(polydata);
1604 #else
1605  mapper->SetInputData(polydata);
1606 #endif
1607 
1610  actor->SetMapper(mapper);
1611  actor->GetProperty()->SetColor(c.redF(), c.greenF(), c.blueF());
1612 
1613  //_visualizer->addActorToRenderer (actor, viewport);
1614  // Add it to all renderers
1615  _visualizer->getRendererCollection()->InitTraversal ();
1616  vtkRenderer* renderer = NULL;
1617  int i = 0;
1618  while ((renderer = _visualizer->getRendererCollection()->GetNextItem ()) != NULL)
1619  {
1620  if ((foreground?2:1) == i) // add the actor only to the specified viewport
1621  {
1622  renderer->AddActor (actor);
1623  }
1624  ++i;
1625  }
1626 
1627  // Save the pointer/ID pair to the global actor map
1628  (*_visualizer->getCloudActorMap())[id].actor = actor;
1629 
1630  // Save the viewpoint transformation matrix to the global actor map
1632  pcl::visualization::PCLVisualizer::convertToVtkMatrix (pose.toEigen3f().matrix (), transformation);
1633  (*_visualizer->getCloudActorMap())[id].viewpoint_transformation_ = transformation;
1634  (*_visualizer->getCloudActorMap())[id].actor->SetUserMatrix (transformation);
1635  (*_visualizer->getCloudActorMap())[id].actor->Modified ();
1636 
1637  (*_visualizer->getCloudActorMap())[id].actor->GetProperty()->SetLighting(false);
1638  _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1639  }
1640 }
1641 
1642 void CloudViewer::removeQuad(const std::string & id)
1643 {
1644  if(id.empty())
1645  {
1646  UERROR("id should not be empty!");
1647  return;
1648  }
1649 
1650  if(_quads.find(id) != _quads.end())
1651  {
1652  _visualizer->removeShape(id);
1653  _quads.erase(id);
1654  }
1655 }
1656 
1658 {
1659  std::set<std::string> quads = _quads;
1660  for(std::set<std::string>::iterator iter = quads.begin(); iter!=quads.end(); ++iter)
1661  {
1662  this->removeQuad(*iter);
1663  }
1664  UASSERT(_quads.empty());
1665 }
1666 
1667 static const float frustum_vertices[] = {
1668  0.0f, 0.0f, 0.0f,
1669  1.0f, 1.0f, 1.0f,
1670  1.0f, -1.0f, 1.0f,
1671  1.0f, -1.0f, -1.0f,
1672  1.0f, 1.0f, -1.0f};
1673 
1674 static const int frustum_indices[] = {
1675  1, 2, 3, 4, 1, 0, 2, 0, 3, 0, 4};
1676 
1678  const std::string & id,
1679  const Transform & transform,
1680  const Transform & localTransform,
1681  double scale,
1682  const QColor & color)
1683 {
1684  if(id.empty())
1685  {
1686  UERROR("id should not be empty!");
1687  return;
1688  }
1689 
1690 #if PCL_VERSION_COMPARE(<, 1, 7, 2)
1691  this->removeFrustum(id);
1692 #endif
1693 
1694  if(!transform.isNull())
1695  {
1696  if(_frustums.find(id)==_frustums.end())
1697  {
1698  _frustums.insert(id, Transform());
1699 
1700  int frustumSize = sizeof(frustum_vertices)/sizeof(float);
1701  UASSERT(frustumSize>0 && frustumSize % 3 == 0);
1702  frustumSize/=3;
1703  pcl::PointCloud<pcl::PointXYZ> frustumPoints;
1704  frustumPoints.resize(frustumSize);
1705  float scaleX = 0.5f * scale;
1706  float scaleY = 0.4f * scale; //4x3 arbitrary ratio
1707  float scaleZ = 0.3f * scale;
1708  QColor c = Qt::gray;
1709  if(color.isValid())
1710  {
1711  c = color;
1712  }
1713  Transform opticalRotInv(0, -1, 0, 0, 0, 0, -1, 0, 1, 0, 0, 0);
1714 
1715 #if PCL_VERSION_COMPARE(<, 1, 7, 2)
1716  Eigen::Affine3f t = (transform*localTransform*opticalRotInv).toEigen3f();
1717 #else
1718  Eigen::Affine3f t = (localTransform*opticalRotInv).toEigen3f();
1719 #endif
1720  for(int i=0; i<frustumSize; ++i)
1721  {
1722  frustumPoints[i].x = frustum_vertices[i*3]*scaleX;
1723  frustumPoints[i].y = frustum_vertices[i*3+1]*scaleY;
1724  frustumPoints[i].z = frustum_vertices[i*3+2]*scaleZ;
1725  frustumPoints[i] = pcl::transformPoint(frustumPoints[i], t);
1726  }
1727 
1728  pcl::PolygonMesh mesh;
1729  pcl::Vertices vertices;
1730  vertices.vertices.resize(sizeof(frustum_indices)/sizeof(int));
1731  for(unsigned int i=0; i<vertices.vertices.size(); ++i)
1732  {
1733  vertices.vertices[i] = frustum_indices[i];
1734  }
1735  pcl::toPCLPointCloud2(frustumPoints, mesh.cloud);
1736  mesh.polygons.push_back(vertices);
1737  _visualizer->addPolylineFromPolygonMesh(mesh, id, 1);
1738  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, c.redF(), c.greenF(), c.blueF(), id);
1739  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1740  }
1741 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
1742  if(!this->updateFrustumPose(id, transform))
1743  {
1744  UERROR("Failed updating pose of frustum %s!?", id.c_str());
1745  }
1746 #endif
1747  }
1748  else
1749  {
1750  removeFrustum(id);
1751  }
1752 }
1753 
1755  const std::string & id,
1756  const Transform & pose)
1757 {
1758 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
1759  QMap<std::string, Transform>::iterator iter=_frustums.find(id);
1760  if(iter != _frustums.end() && !pose.isNull())
1761  {
1762  if(iter.value() == pose)
1763  {
1764  // same pose, just return
1765  return true;
1766  }
1767 
1768  pcl::visualization::ShapeActorMap::iterator am_it = _visualizer->getShapeActorMap()->find (id);
1769 
1770  vtkActor* actor;
1771 
1772  if (am_it == _visualizer->getShapeActorMap()->end ())
1773  return (false);
1774  else
1775  actor = vtkActor::SafeDownCast (am_it->second);
1776 
1777  if (!actor)
1778  return (false);
1779 
1781 
1782  pcl::visualization::PCLVisualizer::convertToVtkMatrix (pose.toEigen3f().matrix (), matrix);
1783 
1784  actor->SetUserMatrix (matrix);
1785  actor->Modified ();
1786 
1787  iter.value() = pose;
1788 
1789  return true;
1790  }
1791 #else
1792  UERROR("updateFrustumPose() cannot be used with PCL<1.7.2. Use addOrUpdateFrustum() instead.");
1793 #endif
1794  return false;
1795 }
1796 
1797 void CloudViewer::removeFrustum(const std::string & id)
1798 {
1799  if(id.empty())
1800  {
1801  UERROR("id should not be empty!");
1802  return;
1803  }
1804 
1805  if(_frustums.find(id) != _frustums.end())
1806  {
1807  _visualizer->removeShape(id);
1808  _frustums.remove(id);
1809  }
1810 }
1811 
1812 void CloudViewer::removeAllFrustums(bool exceptCameraReference)
1813 {
1814  QMap<std::string, Transform> frustums = _frustums;
1815  for(QMap<std::string, Transform>::iterator iter = frustums.begin(); iter!=frustums.end(); ++iter)
1816  {
1817  if(!exceptCameraReference || !uStrContains(iter.key(), "reference_frustum"))
1818  {
1819  this->removeFrustum(iter.key());
1820  }
1821  }
1822  UASSERT(exceptCameraReference || _frustums.empty());
1823 }
1824 
1826  const std::string & id,
1827  const pcl::PointCloud<pcl::PointXYZ>::Ptr & graph,
1828  const QColor & color)
1829 {
1830  if(id.empty())
1831  {
1832  UERROR("id should not be empty!");
1833  return;
1834  }
1835 
1836  removeGraph(id);
1837 
1838  if(graph->size())
1839  {
1840  _graphes.insert(id);
1841 
1842  pcl::PolygonMesh mesh;
1843  pcl::Vertices vertices;
1844  vertices.vertices.resize(graph->size());
1845  for(unsigned int i=0; i<vertices.vertices.size(); ++i)
1846  {
1847  vertices.vertices[i] = i;
1848  }
1849  pcl::toPCLPointCloud2(*graph, mesh.cloud);
1850  mesh.polygons.push_back(vertices);
1851  _visualizer->addPolylineFromPolygonMesh(mesh, id, 1);
1852  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, color.redF(), color.greenF(), color.blueF(), id);
1853  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, color.alphaF(), id);
1854 
1855  this->addCloud(id+"_nodes", graph, Transform::getIdentity(), color);
1856  this->setCloudPointSize(id+"_nodes", 5);
1857  }
1858 }
1859 
1860 void CloudViewer::removeGraph(const std::string & id)
1861 {
1862  if(id.empty())
1863  {
1864  UERROR("id should not be empty!");
1865  return;
1866  }
1867 
1868  if(_graphes.find(id) != _graphes.end())
1869  {
1870  _visualizer->removeShape(id);
1871  _graphes.erase(id);
1872  removeCloud(id+"_nodes");
1873  }
1874 }
1875 
1877 {
1878  std::set<std::string> graphes = _graphes;
1879  for(std::set<std::string>::iterator iter = graphes.begin(); iter!=graphes.end(); ++iter)
1880  {
1881  this->removeGraph(*iter);
1882  }
1883  UASSERT(_graphes.empty());
1884 }
1885 
1887  const std::string & id,
1888  const std::string & text,
1889  const Transform & position,
1890  double scale,
1891  const QColor & color,
1892  bool foreground)
1893 {
1894  if(id.empty())
1895  {
1896  UERROR("id should not be empty!");
1897  return;
1898  }
1899 
1900  removeText(id);
1901 
1902  if(!position.isNull())
1903  {
1904  _texts.insert(id);
1905  _visualizer->addText3D(
1906  text,
1907  pcl::PointXYZ(position.x(), position.y(), position.z()),
1908  scale,
1909  color.redF(),
1910  color.greenF(),
1911  color.blueF(),
1912  id,
1913  foreground?2:1);
1914  }
1915 }
1916 
1917 void CloudViewer::removeText(const std::string & id)
1918 {
1919  if(id.empty())
1920  {
1921  UERROR("id should not be empty!");
1922  return;
1923  }
1924 
1925  if(_texts.find(id) != _texts.end())
1926  {
1927  _visualizer->removeText3D(id);
1928  _texts.erase(id);
1929  }
1930 }
1931 
1933 {
1934  std::set<std::string> texts = _texts;
1935  for(std::set<std::string>::iterator iter = texts.begin(); iter!=texts.end(); ++iter)
1936  {
1937  this->removeText(*iter);
1938  }
1939  UASSERT(_texts.empty());
1940 }
1941 
1943 {
1944  return _aShowTrajectory->isChecked();
1945 }
1946 
1948 {
1949  return _maxTrajectorySize;
1950 }
1951 
1953 {
1954  _aShowTrajectory->setChecked(shown);
1955 }
1956 
1957 void CloudViewer::setTrajectorySize(unsigned int value)
1958 {
1959  _maxTrajectorySize = value;
1960 }
1961 
1963 {
1964  _trajectory->clear();
1965  _visualizer->removeShape("trajectory");
1966  this->update();
1967 }
1968 
1970 {
1971  return _aShowFrustum->isChecked();
1972 }
1973 
1975 {
1976  return _frustumScale;
1977 }
1978 
1980 {
1981  return _frustumColor;
1982 }
1983 
1985 {
1986  if(!shown)
1987  {
1988  QMap<std::string, Transform> frustumsCopy = _frustums;
1989  for(QMap<std::string, Transform>::iterator iter=frustumsCopy.begin(); iter!=frustumsCopy.end(); ++iter)
1990  {
1991  if(uStrContains(iter.key(), "reference_frustum"))
1992  {
1993  this->removeFrustum(iter.key());
1994  }
1995  }
1996  std::set<std::string> linesCopy = _lines;
1997  for(std::set<std::string>::iterator iter=linesCopy.begin(); iter!=linesCopy.end(); ++iter)
1998  {
1999  if(uStrContains(*iter, "reference_frustum_line"))
2000  {
2001  this->removeLine(*iter);
2002  }
2003  }
2004  this->update();
2005  }
2006  _aShowFrustum->setChecked(shown);
2007 }
2008 
2010 {
2011  _frustumScale = value;
2012 }
2013 
2015 {
2016  if(!value.isValid())
2017  {
2018  value = Qt::gray;
2019  }
2020  for(QMap<std::string, Transform>::iterator iter=_frustums.begin(); iter!=_frustums.end(); ++iter)
2021  {
2022  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, value.redF(), value.greenF(), value.blueF(), iter.key());
2023  }
2024  this->update();
2025  _frustumColor = value;
2026 }
2027 
2029 {
2030  _lastCameraOrientation= _lastCameraPose = cv::Vec3f(0,0,0);
2031  if((_aFollowCamera->isChecked() || _aLockCamera->isChecked()) && !_lastPose.isNull())
2032  {
2033  // reset relative to last current pose
2034  cv::Point3f pt = util3d::transformPoint(cv::Point3f(_lastPose.x(), _lastPose.y(), _lastPose.z()), ( _lastPose.rotation()*Transform(-1, 0, 0)).translation());
2035  if(_aCameraOrtho->isChecked())
2036  {
2037  _visualizer->setCameraPosition(
2038  _lastPose.x(), _lastPose.y(), _lastPose.z()+5,
2039  _lastPose.x(), _lastPose.y(), _lastPose.z(),
2040  1, 0, 0, 1);
2041  }
2042  else if(_aLockViewZ->isChecked())
2043  {
2044  _visualizer->setCameraPosition(
2045  pt.x, pt.y, pt.z,
2046  _lastPose.x(), _lastPose.y(), _lastPose.z(),
2047  0, 0, 1, 1);
2048  }
2049  else
2050  {
2051  _visualizer->setCameraPosition(
2052  pt.x, pt.y, pt.z,
2053  _lastPose.x(), _lastPose.y(), _lastPose.z(),
2054  _lastPose.r31(), _lastPose.r32(), _lastPose.r33(), 1);
2055  }
2056  }
2057  else if(_aCameraOrtho->isChecked())
2058  {
2059  _visualizer->setCameraPosition(
2060  0, 0, 5,
2061  0, 0, 0,
2062  1, 0, 0, 1);
2063  }
2064  else
2065  {
2066  _visualizer->setCameraPosition(
2067  -1, 0, 0,
2068  0, 0, 0,
2069  0, 0, 1, 1);
2070  }
2071  this->update();
2072 }
2073 
2075 {
2076  _addedClouds.clear();
2077  _locators.clear();
2078  _visualizer->removeAllPointClouds();
2079 }
2080 
2081 
2082 bool CloudViewer::removeCloud(const std::string & id)
2083 {
2084  bool success = _visualizer->removePointCloud(id);
2085  _visualizer->removePointCloud(id+"-normals");
2086  _addedClouds.remove(id); // remove after visualizer
2087  _addedClouds.remove(id+"-normals");
2088  _locators.erase(id);
2089  return success;
2090 }
2091 
2092 bool CloudViewer::getPose(const std::string & id, Transform & pose)
2093 {
2094  if(_addedClouds.contains(id))
2095  {
2096  pose = _addedClouds.value(id);
2097  return true;
2098  }
2099  return false;
2100 }
2101 
2103 {
2104  if(_lastPose.isNull())
2105  {
2106  return Transform::getIdentity();
2107  }
2108  return _lastPose;
2109 }
2110 
2111 std::string CloudViewer::getIdByActor(vtkProp * actor) const
2112 {
2113  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
2114  for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2115  {
2116  if(iter->second.actor.GetPointer() == actor)
2117  {
2118  return iter->first;
2119  }
2120  }
2121 
2122 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2123  // getShapeActorMap() not available in version < 1.7.2
2124  pcl::visualization::ShapeActorMapPtr shapeActorMap = _visualizer->getShapeActorMap();
2125  for(pcl::visualization::ShapeActorMap::iterator iter=shapeActorMap->begin(); iter!=shapeActorMap->end(); ++iter)
2126  {
2127  if(iter->second.GetPointer() == actor)
2128  {
2129  std::string id = iter->first;
2130  while(id.back() == '*')
2131  {
2132  id.erase(id.size()-1);
2133  }
2134 
2135  return id;
2136  }
2137  }
2138 #endif
2139  return std::string();
2140 }
2141 
2142 QColor CloudViewer::getColor(const std::string & id)
2143 {
2144  QColor color;
2145  pcl::visualization::CloudActorMap::iterator iter = _visualizer->getCloudActorMap()->find(id);
2146  if(iter != _visualizer->getCloudActorMap()->end())
2147  {
2148  double r,g,b,a;
2149  iter->second.actor->GetProperty()->GetColor(r,g,b);
2150  a = iter->second.actor->GetProperty()->GetOpacity();
2151  color.setRgbF(r, g, b, a);
2152  }
2153 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2154  // getShapeActorMap() not available in version < 1.7.2
2155  else
2156  {
2157  std::string idLayer1 = id+"*";
2158  std::string idLayer2 = id+"**";
2159  pcl::visualization::ShapeActorMap::iterator iter = _visualizer->getShapeActorMap()->find(id);
2160  if(iter == _visualizer->getShapeActorMap()->end())
2161  {
2162  iter = _visualizer->getShapeActorMap()->find(idLayer1);
2163  if(iter == _visualizer->getShapeActorMap()->end())
2164  {
2165  iter = _visualizer->getShapeActorMap()->find(idLayer2);
2166  }
2167  }
2168  if(iter != _visualizer->getShapeActorMap()->end())
2169  {
2170  vtkActor * actor = vtkActor::SafeDownCast(iter->second);
2171  if(actor)
2172  {
2173  double r,g,b,a;
2174  actor->GetProperty()->GetColor(r,g,b);
2175  a = actor->GetProperty()->GetOpacity();
2176  color.setRgbF(r, g, b, a);
2177  }
2178  }
2179  }
2180 #endif
2181  return color;
2182 }
2183 
2184 void CloudViewer::setColor(const std::string & id, const QColor & color)
2185 {
2186  pcl::visualization::CloudActorMap::iterator iter = _visualizer->getCloudActorMap()->find(id);
2187  if(iter != _visualizer->getCloudActorMap()->end())
2188  {
2189  iter->second.actor->GetProperty()->SetColor(color.redF(),color.greenF(),color.blueF());
2190  iter->second.actor->GetProperty()->SetOpacity(color.alphaF());
2191  }
2192 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2193  // getShapeActorMap() not available in version < 1.7.2
2194  else
2195  {
2196  std::string idLayer1 = id+"*";
2197  std::string idLayer2 = id+"**";
2198  pcl::visualization::ShapeActorMap::iterator iter = _visualizer->getShapeActorMap()->find(id);
2199  if(iter == _visualizer->getShapeActorMap()->end())
2200  {
2201  iter = _visualizer->getShapeActorMap()->find(idLayer1);
2202  if(iter == _visualizer->getShapeActorMap()->end())
2203  {
2204  iter = _visualizer->getShapeActorMap()->find(idLayer2);
2205  }
2206  }
2207  if(iter != _visualizer->getShapeActorMap()->end())
2208  {
2209  vtkActor * actor = vtkActor::SafeDownCast(iter->second);
2210  if(actor)
2211  {
2212  actor->GetProperty()->SetColor(color.redF(),color.greenF(),color.blueF());
2213  actor->GetProperty()->SetOpacity(color.alphaF());
2214  }
2215  }
2216  }
2217 #endif
2218 }
2219 
2220 void CloudViewer::setBackfaceCulling(bool enabled, bool frontfaceCulling)
2221 {
2222  _aBackfaceCulling->setChecked(enabled);
2223  _frontfaceCulling = frontfaceCulling;
2224 
2225  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
2226  for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2227  {
2228  iter->second.actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
2229  iter->second.actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
2230  }
2231  this->update();
2232 }
2233 
2235 {
2236  _aPolygonPicking->setChecked(enabled);
2237 
2238  if(!_aPolygonPicking->isChecked())
2239  {
2241  pp->SetTolerance (pp->GetTolerance());
2242  this->GetInteractor()->SetPicker (pp);
2243  setMouseTracking(false);
2244  }
2245  else
2246  {
2248  pp->SetTolerance (pp->GetTolerance());
2249  this->GetInteractor()->SetPicker (pp);
2250  setMouseTracking(true);
2251  }
2252 }
2253 
2254 
2255 
2257 {
2258  _renderingRate = rate;
2259  _visualizer->getInteractorStyle()->GetInteractor()->SetDesiredUpdateRate(_renderingRate);
2260 }
2261 
2263 {
2264  _aSetLighting->setChecked(on);
2265  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
2266  for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2267  {
2268  iter->second.actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
2269  }
2270  this->update();
2271 }
2272 
2274 {
2275  _aSetFlatShading->setChecked(on);
2276  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
2277  for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2278  {
2279  iter->second.actor->GetProperty()->SetInterpolation(_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG); // VTK_FLAT - VTK_GOURAUD - VTK_PHONG
2280  }
2281  this->update();
2282 }
2283 
2285 {
2286  _aSetEdgeVisibility->setChecked(visible);
2287  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
2288  for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2289  {
2290  iter->second.actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
2291  }
2292  this->update();
2293 }
2294 
2296 {
2297  _visualizer->getRendererCollection()->InitTraversal ();
2298  vtkRenderer* renderer = NULL;
2299  int i =0;
2300  while ((renderer = _visualizer->getRendererCollection()->GetNextItem ()) != NULL)
2301  {
2302  if(i==layer)
2303  {
2304  _visualizer->getInteractorStyle()->SetDefaultRenderer(renderer);
2305  _visualizer->getInteractorStyle()->SetCurrentRenderer(renderer);
2306  return;
2307  }
2308  ++i;
2309  }
2310  UWARN("Could not set layer %d to interactor (layers=%d).", layer, _visualizer->getRendererCollection()->GetNumberOfItems());
2311 }
2312 
2314  float & x, float & y, float & z,
2315  float & focalX, float & focalY, float & focalZ,
2316  float & upX, float & upY, float & upZ) const
2317 {
2318  std::vector<pcl::visualization::Camera> cameras;
2319  _visualizer->getCameras(cameras);
2320  if(cameras.size())
2321  {
2322  x = cameras.begin()->pos[0];
2323  y = cameras.begin()->pos[1];
2324  z = cameras.begin()->pos[2];
2325  focalX = cameras.begin()->focal[0];
2326  focalY = cameras.begin()->focal[1];
2327  focalZ = cameras.begin()->focal[2];
2328  upX = cameras.begin()->view[0];
2329  upY = cameras.begin()->view[1];
2330  upZ = cameras.begin()->view[2];
2331  }
2332  else
2333  {
2334  UERROR("No camera set!?");
2335  }
2336 }
2337 
2339  float x, float y, float z,
2340  float focalX, float focalY, float focalZ,
2341  float upX, float upY, float upZ)
2342 {
2343  _lastCameraOrientation= _lastCameraPose= cv::Vec3f(0,0,0);
2344  _visualizer->setCameraPosition(x,y,z, focalX,focalY,focalX, upX,upY,upZ, 1);
2345 }
2346 
2348 {
2349  if(!pose.isNull())
2350  {
2351  Eigen::Affine3f m = pose.toEigen3f();
2352  Eigen::Vector3f pos = m.translation();
2353 
2354  Eigen::Vector3f lastPos(0,0,0);
2355  if(_trajectory->size())
2356  {
2357  lastPos[0]=_trajectory->back().x;
2358  lastPos[1]=_trajectory->back().y;
2359  lastPos[2]=_trajectory->back().z;
2360  }
2361 
2362  _trajectory->push_back(pcl::PointXYZ(pos[0], pos[1], pos[2]));
2363  if(_maxTrajectorySize>0)
2364  {
2365  while(_trajectory->size() > _maxTrajectorySize)
2366  {
2367  _trajectory->erase(_trajectory->begin());
2368  }
2369  }
2370  if(_aShowTrajectory->isChecked())
2371  {
2372  _visualizer->removeShape("trajectory");
2373  pcl::PolygonMesh mesh;
2374  pcl::Vertices vertices;
2375  vertices.vertices.resize(_trajectory->size());
2376  for(unsigned int i=0; i<vertices.vertices.size(); ++i)
2377  {
2378  vertices.vertices[i] = i;
2379  }
2380  pcl::toPCLPointCloud2(*_trajectory, mesh.cloud);
2381  mesh.polygons.push_back(vertices);
2382  _visualizer->addPolylineFromPolygonMesh(mesh, "trajectory", 1);
2383  }
2384 
2385  if(pose != _lastPose || _lastPose.isNull())
2386  {
2387  if(_lastPose.isNull())
2388  {
2390  }
2391 
2392  std::vector<pcl::visualization::Camera> cameras;
2393  _visualizer->getCameras(cameras);
2394 
2395  if(_aLockCamera->isChecked() || _aCameraOrtho->isChecked())
2396  {
2397  //update camera position
2398  Eigen::Vector3f diff = pos - Eigen::Vector3f(_lastPose.x(), _lastPose.y(), _lastPose.z());
2399  cameras.front().pos[0] += diff[0];
2400  cameras.front().pos[1] += diff[1];
2401  cameras.front().pos[2] += diff[2];
2402  cameras.front().focal[0] += diff[0];
2403  cameras.front().focal[1] += diff[1];
2404  cameras.front().focal[2] += diff[2];
2405  }
2406  else if(_aFollowCamera->isChecked())
2407  {
2408  Eigen::Vector3f vPosToFocal = Eigen::Vector3f(cameras.front().focal[0] - cameras.front().pos[0],
2409  cameras.front().focal[1] - cameras.front().pos[1],
2410  cameras.front().focal[2] - cameras.front().pos[2]).normalized();
2411  Eigen::Vector3f zAxis(cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
2412  Eigen::Vector3f yAxis = zAxis.cross(vPosToFocal);
2413  Eigen::Vector3f xAxis = yAxis.cross(zAxis);
2414  Transform PR(xAxis[0], xAxis[1], xAxis[2],0,
2415  yAxis[0], yAxis[1], yAxis[2],0,
2416  zAxis[0], zAxis[1], zAxis[2],0);
2417 
2418  PR.normalizeRotation();
2419 
2420  Transform P(PR[0], PR[1], PR[2], cameras.front().pos[0],
2421  PR[4], PR[5], PR[6], cameras.front().pos[1],
2422  PR[8], PR[9], PR[10], cameras.front().pos[2]);
2423  Transform F(PR[0], PR[1], PR[2], cameras.front().focal[0],
2424  PR[4], PR[5], PR[6], cameras.front().focal[1],
2425  PR[8], PR[9], PR[10], cameras.front().focal[2]);
2426  Transform N = pose;
2427  Transform O = _lastPose;
2428  Transform O2N = O.inverse()*N;
2429  Transform F2O = F.inverse()*O;
2430  Transform T = F2O * O2N * F2O.inverse();
2431  Transform Fp = F * T;
2432  Transform P2F = P.inverse()*F;
2433  Transform Pp = P * P2F * T * P2F.inverse();
2434 
2435  cameras.front().pos[0] = Pp.x();
2436  cameras.front().pos[1] = Pp.y();
2437  cameras.front().pos[2] = Pp.z();
2438  cameras.front().focal[0] = Fp.x();
2439  cameras.front().focal[1] = Fp.y();
2440  cameras.front().focal[2] = Fp.z();
2441  //FIXME: the view up is not set properly...
2442  cameras.front().view[0] = _aLockViewZ->isChecked()?0:Fp[8];
2443  cameras.front().view[1] = _aLockViewZ->isChecked()?0:Fp[9];
2444  cameras.front().view[2] = _aLockViewZ->isChecked()?1:Fp[10];
2445  }
2446 
2447 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2448  if(_coordinates.find("reference") != _coordinates.end())
2449  {
2450  this->updateCoordinatePose("reference", pose);
2451  }
2452  else
2453 #endif
2454  {
2455  this->addOrUpdateCoordinate("reference", pose, 0.2);
2456  }
2457 
2458  _visualizer->setCameraPosition(
2459  cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
2460  cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
2461  cameras.front().view[0], cameras.front().view[1], cameras.front().view[2], 1);
2462  }
2463  }
2464 
2465  _lastPose = pose;
2466 }
2467 
2469 {
2470  std::vector<CameraModel> models;
2471  models.push_back(model.left());
2472  CameraModel right = model.right();
2473  if(!model.left().localTransform().isNull())
2474  {
2475  right.setLocalTransform(model.left().localTransform() * Transform(model.baseline(), 0, 0, 0, 0, 0));
2476  }
2477  models.push_back(right);
2478  updateCameraFrustums(pose, models);
2479 }
2480 
2481 void CloudViewer::updateCameraFrustum(const Transform & pose, const CameraModel & model)
2482 {
2483  std::vector<CameraModel> models;
2484  models.push_back(model);
2485  updateCameraFrustums(pose, models);
2486 }
2487 
2488 void CloudViewer::updateCameraFrustums(const Transform & pose, const std::vector<CameraModel> & models)
2489 {
2490  if(!pose.isNull())
2491  {
2492  if(_aShowFrustum->isChecked())
2493  {
2494  Transform baseToCamera;
2495  for(unsigned int i=0; i<models.size(); ++i)
2496  {
2497  baseToCamera = Transform::getIdentity();
2498  if(!models[i].localTransform().isNull() && !models[i].localTransform().isIdentity())
2499  {
2500  baseToCamera = models[i].localTransform();
2501  }
2502  std::string id = uFormat("reference_frustum_%d", i);
2503  this->removeFrustum(id);
2504  this->addOrUpdateFrustum(id, pose, baseToCamera, _frustumScale, _frustumColor);
2505  if(!baseToCamera.isIdentity())
2506  {
2507  this->addOrUpdateLine(uFormat("reference_frustum_line_%d", i), pose, pose * baseToCamera, _frustumColor);
2508  }
2509  }
2510  }
2511  }
2512 }
2513 
2515 {
2516  return _defaultBgColor;
2517 }
2518 
2519 void CloudViewer::setDefaultBackgroundColor(const QColor & color)
2520 {
2522  {
2523  setBackgroundColor(color);
2524  }
2525  _defaultBgColor = color;
2526 }
2527 
2528 const QColor & CloudViewer::getBackgroundColor() const
2529 {
2530  return _currentBgColor;
2531 }
2532 
2533 void CloudViewer::setBackgroundColor(const QColor & color)
2534 {
2535  _currentBgColor = color;
2536  _visualizer->setBackgroundColor(color.redF(), color.greenF(), color.blueF());
2537 }
2538 
2539 void CloudViewer::setCloudVisibility(const std::string & id, bool isVisible)
2540 {
2541  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
2542  pcl::visualization::CloudActorMap::iterator iter = cloudActorMap->find(id);
2543  if(iter != cloudActorMap->end())
2544  {
2545  iter->second.actor->SetVisibility(isVisible?1:0);
2546 
2547  iter = cloudActorMap->find(id+"-normals");
2548  if(iter != cloudActorMap->end())
2549  {
2550  iter->second.actor->SetVisibility(isVisible&&_aShowNormals->isChecked()?1:0);
2551  }
2552  }
2553  else
2554  {
2555  UERROR("Cannot find actor named \"%s\".", id.c_str());
2556  }
2557 }
2558 
2559 bool CloudViewer::getCloudVisibility(const std::string & id)
2560 {
2561  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
2562  pcl::visualization::CloudActorMap::iterator iter = cloudActorMap->find(id);
2563  if(iter != cloudActorMap->end())
2564  {
2565  return iter->second.actor->GetVisibility() != 0;
2566  }
2567  else
2568  {
2569  UERROR("Cannot find actor named \"%s\".", id.c_str());
2570  }
2571  return false;
2572 }
2573 
2574 void CloudViewer::setCloudColorIndex(const std::string & id, int index)
2575 {
2576  if(index>0)
2577  {
2578  _visualizer->updateColorHandlerIndex(id, index-1);
2579  }
2580 }
2581 
2582 void CloudViewer::setCloudOpacity(const std::string & id, double opacity)
2583 {
2584  double lastOpacity;
2585  _visualizer->getPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, lastOpacity, id);
2586  if(lastOpacity != opacity)
2587  {
2588  _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, opacity, id);
2589  }
2590 }
2591 
2592 void CloudViewer::setCloudPointSize(const std::string & id, int size)
2593 {
2594  double lastSize;
2595  _visualizer->getPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, lastSize, id);
2596  if((int)lastSize != size)
2597  {
2598  _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, (double)size, id);
2599  }
2600 }
2601 
2603 {
2604  _aLockCamera->setChecked(enabled);
2605 }
2606 
2608 {
2609  _aFollowCamera->setChecked(enabled);
2610 }
2611 
2613 {
2614  _aLockCamera->setChecked(false);
2615  _aFollowCamera->setChecked(false);
2616 }
2617 
2619 {
2620  _lastCameraOrientation= _lastCameraPose = cv::Vec3f(0,0,0);
2621  _aLockViewZ->setChecked(enabled);
2622 }
2624 {
2625  _lastCameraOrientation= _lastCameraPose = cv::Vec3f(0,0,0);
2626  CloudViewerInteractorStyle * interactor = CloudViewerInteractorStyle::SafeDownCast(this->GetInteractor()->GetInteractorStyle());
2627  if(interactor)
2628  {
2629  interactor->setOrthoMode(enabled);
2630  this->update();
2631  }
2632  _aCameraOrtho->setChecked(enabled);
2633 }
2635 {
2636  return _aLockCamera->isChecked();
2637 }
2639 {
2640  return _aFollowCamera->isChecked();
2641 }
2643 {
2644  return !_aFollowCamera->isChecked() && !_aLockCamera->isChecked();
2645 }
2647 {
2648  return _aLockViewZ->isChecked();
2649 }
2651 {
2652  return _aCameraOrtho->isChecked();
2653 }
2655 {
2656  return _renderingRate;
2657 }
2658 
2660 {
2661  _aShowGrid->setChecked(shown);
2662  if(shown)
2663  {
2664  this->addGrid();
2665  }
2666  else
2667  {
2668  this->removeGrid();
2669  }
2670 }
2672 {
2673  return _aShowGrid->isChecked();
2674 }
2675 unsigned int CloudViewer::getGridCellCount() const
2676 {
2677  return _gridCellCount;
2678 }
2680 {
2681  return _gridCellSize;
2682 }
2683 void CloudViewer::setGridCellCount(unsigned int count)
2684 {
2685  if(count > 0)
2686  {
2687  _gridCellCount = count;
2688  if(_aShowGrid->isChecked())
2689  {
2690  this->removeGrid();
2691  this->addGrid();
2692  }
2693  }
2694  else
2695  {
2696  UERROR("Cannot set grid cell count < 1, count=%d", count);
2697  }
2698 }
2700 {
2701  if(size > 0)
2702  {
2703  _gridCellSize = size;
2704  if(_aShowGrid->isChecked())
2705  {
2706  this->removeGrid();
2707  this->addGrid();
2708  }
2709  }
2710  else
2711  {
2712  UERROR("Cannot set grid cell size <= 0, value=%f", size);
2713  }
2714 }
2716 {
2717  if(_gridLines.empty())
2718  {
2719  float cellSize = _gridCellSize;
2720  int cellCount = _gridCellCount;
2721  double r=0.5;
2722  double g=0.5;
2723  double b=0.5;
2724  int id = 0;
2725  float min = -float(cellCount/2) * cellSize;
2726  float max = float(cellCount/2) * cellSize;
2727  std::string name;
2728  for(float i=min; i<=max; i += cellSize)
2729  {
2730  //over x
2731  name = uFormat("line%d", ++id);
2732  _visualizer->addLine(pcl::PointXYZ(i, min, 0.0f), pcl::PointXYZ(i, max, 0.0f), r, g, b, name, 1);
2733  _gridLines.push_back(name);
2734  //over y or z
2735  name = uFormat("line%d", ++id);
2736  _visualizer->addLine(
2737  pcl::PointXYZ(min, i, 0),
2738  pcl::PointXYZ(max, i, 0),
2739  r, g, b, name, 1);
2740  _gridLines.push_back(name);
2741  }
2742  }
2743 }
2744 
2746 {
2747  for(std::list<std::string>::iterator iter = _gridLines.begin(); iter!=_gridLines.end(); ++iter)
2748  {
2749  _visualizer->removeShape(*iter);
2750  }
2751  _gridLines.clear();
2752 }
2753 
2755 {
2756  _aShowNormals->setChecked(shown);
2757  QList<std::string> ids = _addedClouds.keys();
2758  for(QList<std::string>::iterator iter = ids.begin(); iter!=ids.end(); ++iter)
2759  {
2760  std::string idNormals = *iter + "-normals";
2761  if(_addedClouds.find(idNormals) != _addedClouds.end())
2762  {
2763  this->setCloudVisibility(idNormals, this->getCloudVisibility(*iter) && shown);
2764  }
2765  }
2766 }
2768 {
2769  return _aShowNormals->isChecked();
2770 }
2772 {
2773  return _normalsStep;
2774 }
2776 {
2777  return _normalsScale;
2778 }
2780 {
2781  if(step > 0)
2782  {
2783  _normalsStep = step;
2784  }
2785  else
2786  {
2787  UERROR("Cannot set normals step <= 0, step=%d", step);
2788  }
2789 }
2791 {
2792  if(scale > 0)
2793  {
2795  }
2796  else
2797  {
2798  UERROR("Cannot set normals scale <= 0, value=%f", scale);
2799  }
2800 }
2801 
2803 {
2804  _buildLocator = enable;
2805 }
2806 
2807 Eigen::Vector3f rotatePointAroundAxe(
2808  const Eigen::Vector3f & point,
2809  const Eigen::Vector3f & axis,
2810  float angle)
2811 {
2812  Eigen::Vector3f direction = point;
2813  Eigen::Vector3f zAxis = axis;
2814  float dotProdZ = zAxis.dot(direction);
2815  Eigen::Vector3f ptOnZaxis = zAxis * dotProdZ;
2816  direction -= ptOnZaxis;
2817  Eigen::Vector3f xAxis = direction.normalized();
2818  Eigen::Vector3f yAxis = zAxis.cross(xAxis);
2819 
2820  Eigen::Matrix3f newFrame;
2821  newFrame << xAxis[0], yAxis[0], zAxis[0],
2822  xAxis[1], yAxis[1], zAxis[1],
2823  xAxis[2], yAxis[2], zAxis[2];
2824 
2825  // transform to axe frame
2826  // transpose=inverse for orthogonal matrices
2827  Eigen::Vector3f newDirection = newFrame.transpose() * direction;
2828 
2829  // rotate about z
2830  float cosTheta = cos(angle);
2831  float sinTheta = sin(angle);
2832  float magnitude = newDirection.norm();
2833  newDirection[0] = ( magnitude * cosTheta );
2834  newDirection[1] = ( magnitude * sinTheta );
2835 
2836  // transform back to global frame
2837  direction = newFrame * newDirection;
2838 
2839  return direction + ptOnZaxis;
2840 }
2841 
2842 void CloudViewer::keyReleaseEvent(QKeyEvent * event) {
2843  if(event->key() == Qt::Key_Up ||
2844  event->key() == Qt::Key_Down ||
2845  event->key() == Qt::Key_Left ||
2846  event->key() == Qt::Key_Right)
2847  {
2848  _keysPressed -= (Qt::Key)event->key();
2849  }
2850  else
2851  {
2852  QVTKWidget::keyPressEvent(event);
2853  }
2854 }
2855 
2856 void CloudViewer::keyPressEvent(QKeyEvent * event)
2857 {
2858  if(event->key() == Qt::Key_Up ||
2859  event->key() == Qt::Key_Down ||
2860  event->key() == Qt::Key_Left ||
2861  event->key() == Qt::Key_Right)
2862  {
2863  _keysPressed += (Qt::Key)event->key();
2864 
2865  std::vector<pcl::visualization::Camera> cameras;
2866  _visualizer->getCameras(cameras);
2867 
2868  //update camera position
2869  Eigen::Vector3f pos(cameras.front().pos[0], cameras.front().pos[1], _aLockViewZ->isChecked()?0:cameras.front().pos[2]);
2870  Eigen::Vector3f focal(cameras.front().focal[0], cameras.front().focal[1], _aLockViewZ->isChecked()?0:cameras.front().focal[2]);
2871  Eigen::Vector3f viewUp(cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
2872  Eigen::Vector3f cummulatedDir(0,0,0);
2873  Eigen::Vector3f cummulatedFocalDir(0,0,0);
2874  float step = 0.2f;
2875  float stepRot = 0.02f; // radian
2876  if(_keysPressed.contains(Qt::Key_Up))
2877  {
2878  Eigen::Vector3f dir;
2879  if(event->modifiers() & Qt::ShiftModifier)
2880  {
2881  dir = viewUp * step;// up
2882  }
2883  else
2884  {
2885  dir = (focal-pos).normalized() * step; // forward
2886  }
2887  cummulatedDir += dir;
2888  }
2889  if(_keysPressed.contains(Qt::Key_Down))
2890  {
2891  Eigen::Vector3f dir;
2892  if(event->modifiers() & Qt::ShiftModifier)
2893  {
2894  dir = viewUp * -step;// down
2895  }
2896  else
2897  {
2898  dir = (focal-pos).normalized() * -step; // backward
2899  }
2900  cummulatedDir += dir;
2901  }
2902  if(_keysPressed.contains(Qt::Key_Right))
2903  {
2904  if(event->modifiers() & Qt::ShiftModifier)
2905  {
2906  // rotate right
2907  Eigen::Vector3f point = (focal-pos);
2908  Eigen::Vector3f newPoint = rotatePointAroundAxe(point, viewUp, -stepRot);
2909  Eigen::Vector3f diff = newPoint - point;
2910  cummulatedFocalDir += diff;
2911  }
2912  else
2913  {
2914  Eigen::Vector3f dir = ((focal-pos).cross(viewUp)).normalized() * step; // strafing right
2915  cummulatedDir += dir;
2916  }
2917  }
2918  if(_keysPressed.contains(Qt::Key_Left))
2919  {
2920  if(event->modifiers() & Qt::ShiftModifier)
2921  {
2922  // rotate left
2923  Eigen::Vector3f point = (focal-pos);
2924  Eigen::Vector3f newPoint = rotatePointAroundAxe(point, viewUp, stepRot);
2925  Eigen::Vector3f diff = newPoint - point;
2926  cummulatedFocalDir += diff;
2927  }
2928  else
2929  {
2930  Eigen::Vector3f dir = ((focal-pos).cross(viewUp)).normalized() * -step; // strafing left
2931  cummulatedDir += dir;
2932  }
2933  }
2934 
2935  cameras.front().pos[0] += cummulatedDir[0];
2936  cameras.front().pos[1] += cummulatedDir[1];
2937  cameras.front().pos[2] += cummulatedDir[2];
2938  cameras.front().focal[0] += cummulatedDir[0] + cummulatedFocalDir[0];
2939  cameras.front().focal[1] += cummulatedDir[1] + cummulatedFocalDir[1];
2940  cameras.front().focal[2] += cummulatedDir[2] + cummulatedFocalDir[2];
2941  _visualizer->setCameraPosition(
2942  cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
2943  cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
2944  cameras.front().view[0], cameras.front().view[1], cameras.front().view[2], 1);
2945 
2946  update();
2947 
2948  Q_EMIT configChanged();
2949  }
2950  else
2951  {
2952  QVTKWidget::keyPressEvent(event);
2953  }
2954 }
2955 
2956 void CloudViewer::mousePressEvent(QMouseEvent * event)
2957 {
2958  if(event->button() == Qt::RightButton)
2959  {
2960  event->accept();
2961  }
2962  else
2963  {
2964  QVTKWidget::mousePressEvent(event);
2965  }
2966 }
2967 
2968 void CloudViewer::mouseMoveEvent(QMouseEvent * event)
2969 {
2970  QVTKWidget::mouseMoveEvent(event);
2971 
2972  // camera view up z locked?
2973  if(_aLockViewZ->isChecked() && !_aCameraOrtho->isChecked())
2974  {
2975  std::vector<pcl::visualization::Camera> cameras;
2976  _visualizer->getCameras(cameras);
2977 
2978  cv::Vec3d newCameraOrientation = cv::Vec3d(0,0,1).cross(cv::Vec3d(cameras.front().pos)-cv::Vec3d(cameras.front().focal));
2979 
2980  if( _lastCameraOrientation!=cv::Vec3d(0,0,0) &&
2981  _lastCameraPose!=cv::Vec3d(0,0,0) &&
2982  (uSign(_lastCameraOrientation[0]) != uSign(newCameraOrientation[0]) &&
2983  uSign(_lastCameraOrientation[1]) != uSign(newCameraOrientation[1])))
2984  {
2985  cameras.front().pos[0] = _lastCameraPose[0];
2986  cameras.front().pos[1] = _lastCameraPose[1];
2987  cameras.front().pos[2] = _lastCameraPose[2];
2988  }
2989  else if(newCameraOrientation != cv::Vec3d(0,0,0))
2990  {
2991  _lastCameraOrientation = newCameraOrientation;
2992  _lastCameraPose = cv::Vec3d(cameras.front().pos);
2993  }
2994  else
2995  {
2996  if(cameras.front().view[2] == 0)
2997  {
2998  cameras.front().pos[0] -= 0.00001*cameras.front().view[0];
2999  cameras.front().pos[1] -= 0.00001*cameras.front().view[1];
3000  }
3001  else
3002  {
3003  cameras.front().pos[0] -= 0.00001;
3004  }
3005  }
3006  cameras.front().view[0] = 0;
3007  cameras.front().view[1] = 0;
3008  cameras.front().view[2] = 1;
3009 
3010  _visualizer->setCameraPosition(
3011  cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
3012  cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
3013  cameras.front().view[0], cameras.front().view[1], cameras.front().view[2], 1);
3014 
3015  }
3016  this->update();
3017 
3018  Q_EMIT configChanged();
3019 }
3020 
3021 void CloudViewer::wheelEvent(QWheelEvent * event)
3022 {
3023  QVTKWidget::wheelEvent(event);
3024  if(_aLockViewZ->isChecked() && !_aCameraOrtho->isChecked())
3025  {
3026  std::vector<pcl::visualization::Camera> cameras;
3027  _visualizer->getCameras(cameras);
3028  _lastCameraPose = cv::Vec3d(cameras.front().pos);
3029  }
3030  Q_EMIT configChanged();
3031 }
3032 
3033 void CloudViewer::contextMenuEvent(QContextMenuEvent * event)
3034 {
3035  QAction * a = _menu->exec(event->globalPos());
3036  if(a)
3037  {
3038  handleAction(a);
3039  Q_EMIT configChanged();
3040  }
3041 }
3042 
3043 void CloudViewer::handleAction(QAction * a)
3044 {
3045  if(a == _aSetTrajectorySize)
3046  {
3047  bool ok;
3048  int value = QInputDialog::getInt(this, tr("Set trajectory size"), tr("Size (0=infinite)"), _maxTrajectorySize, 0, 10000, 10, &ok);
3049  if(ok)
3050  {
3051  _maxTrajectorySize = value;
3052  }
3053  }
3054  else if(a == _aClearTrajectory)
3055  {
3056  this->clearTrajectory();
3057  }
3058  else if(a == _aShowFrustum)
3059  {
3060  this->setFrustumShown(a->isChecked());
3061  }
3062  else if(a == _aSetFrustumScale)
3063  {
3064  bool ok;
3065  double value = QInputDialog::getDouble(this, tr("Set frustum scale"), tr("Scale"), _frustumScale, 0.0, 999.0, 1, &ok);
3066  if(ok)
3067  {
3068  this->setFrustumScale(value);
3069  }
3070  }
3071  else if(a == _aSetFrustumColor)
3072  {
3073  QColor value = QColorDialog::getColor(_frustumColor, this);
3074  if(value.isValid())
3075  {
3076  this->setFrustumColor(value);
3077  }
3078  }
3079  else if(a == _aResetCamera)
3080  {
3081  this->resetCamera();
3082  }
3083  else if(a == _aShowGrid)
3084  {
3085  if(_aShowGrid->isChecked())
3086  {
3087  this->addGrid();
3088  }
3089  else
3090  {
3091  this->removeGrid();
3092  }
3093 
3094  this->update();
3095  }
3096  else if(a == _aSetGridCellCount)
3097  {
3098  bool ok;
3099  int value = QInputDialog::getInt(this, tr("Set grid cell count"), tr("Count"), _gridCellCount, 1, 10000, 10, &ok);
3100  if(ok)
3101  {
3102  this->setGridCellCount(value);
3103  }
3104  }
3105  else if(a == _aSetGridCellSize)
3106  {
3107  bool ok;
3108  double value = QInputDialog::getDouble(this, tr("Set grid cell size"), tr("Size (m)"), _gridCellSize, 0.01, 10, 2, &ok);
3109  if(ok)
3110  {
3111  this->setGridCellSize(value);
3112  }
3113  }
3114  else if(a == _aShowNormals)
3115  {
3116  this->setNormalsShown(_aShowNormals->isChecked());
3117  this->update();
3118  }
3119  else if(a == _aSetNormalsStep)
3120  {
3121  bool ok;
3122  int value = QInputDialog::getInt(this, tr("Set normals step"), tr("Step"), _normalsStep, 1, 10000, 1, &ok);
3123  if(ok)
3124  {
3125  this->setNormalsStep(value);
3126  }
3127  }
3128  else if(a == _aSetNormalsScale)
3129  {
3130  bool ok;
3131  double value = QInputDialog::getDouble(this, tr("Set normals scale"), tr("Scale (m)"), _normalsScale, 0.01, 10, 2, &ok);
3132  if(ok)
3133  {
3134  this->setNormalsScale(value);
3135  }
3136  }
3137  else if(a == _aSetBackgroundColor)
3138  {
3139  QColor color = this->getDefaultBackgroundColor();
3140  color = QColorDialog::getColor(color, this);
3141  if(color.isValid())
3142  {
3143  this->setDefaultBackgroundColor(color);
3144  this->update();
3145  }
3146  }
3147  else if(a == _aSetRenderingRate)
3148  {
3149  bool ok;
3150  double value = QInputDialog::getDouble(this, tr("Rendering rate"), tr("Rate (hz)"), _renderingRate, 0, 60, 0, &ok);
3151  if(ok)
3152  {
3153  this->setRenderingRate(value);
3154  }
3155  }
3156  else if(a == _aLockViewZ)
3157  {
3158  if(_aLockViewZ->isChecked())
3159  {
3160  this->update();
3161  }
3162  }
3163  else if(a == _aCameraOrtho)
3164  {
3165  this->setCameraOrtho(_aCameraOrtho->isChecked());
3166  }
3167  else if(a == _aSetLighting)
3168  {
3169  this->setLighting(_aSetLighting->isChecked());
3170  }
3171  else if(a == _aSetFlatShading)
3172  {
3173  this->setShading(_aSetFlatShading->isChecked());
3174  }
3175  else if(a == _aSetEdgeVisibility)
3176  {
3177  this->setEdgeVisibility(_aSetEdgeVisibility->isChecked());
3178  }
3179  else if(a == _aBackfaceCulling)
3180  {
3182  }
3183  else if(a == _aPolygonPicking)
3184  {
3185  this->setPolygonPicking(_aPolygonPicking->isChecked());
3186  }
3187 }
3188 
3189 } /* namespace rtabmap */
void setDefaultBackgroundColor(const QColor &color)
void setLocalTransform(const Transform &transform)
Definition: CameraModel.h:108
void removeGraph(const std::string &id)
#define NULL
QAction * _aBackfaceCulling
Definition: CloudViewer.h:410
QAction * _aSetFrustumScale
Definition: CloudViewer.h:397
void setTrajectoryShown(bool shown)
void setFrustumShown(bool shown)
std::set< std::string > _coordinates
Definition: CloudViewer.h:414
void setInteractorLayer(int layer)
iterator begin(unsigned char maxDepth=0) const
Definition: UTimer.h:46
void setTrajectorySize(unsigned int value)
unsigned int getGridCellCount() const
pcl::visualization::PCLVisualizer * _visualizer
Definition: CloudViewer.h:387
std::string prettyPrint() const
Definition: Transform.cpp:274
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
std::map< std::string, vtkSmartPointer< vtkOBBTree > > _locators
Definition: CloudViewer.h:430
QAction * _aLockCamera
Definition: CloudViewer.h:388
void setNormalsStep(int step)
virtual void keyPressEvent(QKeyEvent *event)
QAction * _aShowFrustum
Definition: CloudViewer.h:396
void setNormalsScale(float scale)
void updateCameraFrustum(const Transform &pose, const StereoCameraModel &model)
static void HSVtoRGB(float *r, float *g, float *b, float h, float s, float v)
Definition: OctoMap.cpp:871
void setGridShown(bool shown)
QAction * _aSetEdgeVisibility
Definition: CloudViewer.h:409
void setCloudVisibility(const std::string &id, bool isVisible)
f
std::list< std::string > _gridLines
Definition: CloudViewer.h:435
void addOrUpdateCoordinate(const std::string &id, const Transform &transform, double scale, bool foreground=false)
void addOrUpdateText(const std::string &id, const std::string &text, const Transform &position, double scale, const QColor &color, bool foreground=true)
unsigned int _maxTrajectorySize
Definition: CloudViewer.h:422
unsigned int getTrajectorySize() const
void removeCube(const std::string &id)
void setCloudViewer(CloudViewer *cloudViewer)
Definition: CameraRGBD.h:59
void removeFrustum(const std::string &id)
void addOrUpdateCube(const std::string &id, const Transform &pose, float width, float height, float depth, const QColor &color, bool wireframe=false, bool foreground=false)
void removeQuad(const std::string &id)
Transform rotation() const
Definition: Transform.cpp:174
GLM_FUNC_DECL detail::tvec3< T, P > axis(detail::tquat< T, P > const &x)
static Transform getIdentity()
Definition: Transform.cpp:364
std::set< std::string > _quads
Definition: CloudViewer.h:419
bool removeCloud(const std::string &id)
const iterator end() const
QAction * _aPolygonPicking
Definition: CloudViewer.h:411
GLM_FUNC_DECL detail::tmat4x4< T, P > scale(detail::tmat4x4< T, P > const &m, detail::tvec3< T, P > const &v)
static const float vertices[]
Definition: quad.cpp:39
bool addOccupancyGridMap(const cv::Mat &map8U, float resolution, float xMin, float yMin, float opacity)
cv::Vec3d _lastCameraOrientation
Definition: CloudViewer.h:431
void setGridCellSize(float size)
void setLighting(bool on)
virtual void clear()
Transform getTargetPose() const
Eigen::Vector3f rotatePointAroundAxe(const Eigen::Vector3f &point, const Eigen::Vector3f &axis, float angle)
unsigned int getTreeDepth() const
Basic mathematics functions.
const QColor & getDefaultBackgroundColor() const
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
int uSign(const T &v)
Definition: UMath.h:302
Some conversion functions.
void addOrUpdateSphere(const std::string &id, const Transform &pose, float radius, const QColor &color, bool foreground=false)
bool isNormalsShown() const
void setPolygonPicking(bool enabled)
std::set< std::string > _spheres
Definition: CloudViewer.h:417
QSet< Qt::Key > _keysPressed
Definition: CloudViewer.h:436
void buildPickingLocator(bool enable)
void setCameraOrtho(bool enabled=true)
void removeLine(const std::string &id)
virtual void contextMenuEvent(QContextMenuEvent *event)
float getGridCellSize() const
bool uStrContains(const std::string &string, const std::string &substring)
Definition: UStl.h:787
GLM_FUNC_DECL genType step(genType const &edge, genType const &x)
std::set< std::string > _graphes
Definition: CloudViewer.h:413
bool updateCoordinatePose(const std::string &id, const Transform &transform)
QAction * _aSetNormalsScale
Definition: CloudViewer.h:404
bool isIdentity() const
Definition: Transform.cpp:136
bool isGridShown() const
bool addCloudTextureMesh(const std::string &id, const pcl::TextureMesh::Ptr &textureMesh, const cv::Mat &texture, const Transform &pose=Transform::getIdentity())
bool addCloud(const std::string &id, const pcl::PCLPointCloud2Ptr &binaryCloud, const Transform &pose, bool rgb, bool hasNormals, bool hasIntensity, const QColor &color=QColor())
std::set< std::string > _texts
Definition: CloudViewer.h:415
GLM_FUNC_DECL bool isNull(detail::tmat2x2< T, P > const &m, T const &epsilon)
std::string getIdByActor(vtkProp *actor) const
bool isCameraFree() const
void getCameraPosition(float &x, float &y, float &z, float &focalX, float &focalY, float &focalZ, float &upX, float &upY, float &upZ) const
void addOrUpdateLine(const std::string &id, const Transform &from, const Transform &to, const QColor &color, bool arrow=false, bool foreground=false)
#define UASSERT(condition)
GLM_FUNC_DECL genType cos(genType const &angle)
QAction * _aSetFrustumColor
Definition: CloudViewer.h:398
QMap< std::string, Transform > _addedClouds
Definition: CloudViewer.h:433
QAction * _aSetTrajectorySize
Definition: CloudViewer.h:394
Wrappers of STL for convenient functions.
QAction * _aSetBackgroundColor
Definition: CloudViewer.h:405
GLM_FUNC_DECL genType sin(genType const &angle)
const CameraModel & left() const
GLM_FUNC_DECL detail::tvec3< T, P > cross(detail::tvec3< T, P > const &x, detail::tvec3< T, P > const &y)
int getNormalsStep() const
bool isNull() const
Definition: Transform.cpp:107
void setColor(const std::string &id, const QColor &color)
void addOrUpdateFrustum(const std::string &id, const Transform &transform, const Transform &localTransform, double scale, const QColor &color=QColor())
QAction * _aResetCamera
Definition: CloudViewer.h:390
void saveSettings(QSettings &settings, const QString &group="") const
void addOrUpdateQuad(const std::string &id, const Transform &pose, float width, float height, const QColor &color, bool foreground=false)
void setGridCellCount(unsigned int count)
void setCameraPosition(float x, float y, float z, float focalX, float focalY, float focalZ, float upX, float upY, float upZ)
float getFrustumScale() const
void getGridMax(double &x, double &y, double &z) const
Definition: OctoMap.h:211
bool isCameraTargetFollow() const
void setEdgeVisibility(bool visible)
void setFrustumScale(float value)
void removeText(const std::string &id)
float r31() const
Definition: Transform.h:67
void setCloudPointSize(const std::string &id, int size)
void setNormalsShown(bool shown)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr createCloud(unsigned int treeDepth=0, std::vector< int > *obstacleIndices=0, std::vector< int > *emptyIndices=0, std::vector< int > *groundIndices=0, bool originalRefPoints=true) const
Definition: OctoMap.cpp:920
const RtabmapColorOcTree * octree() const
Definition: OctoMap.h:189
void setFrustumColor(QColor value)
void updateCameraTargetPosition(const Transform &pose)
tree
bool isCameraLockZ() const
QAction * _aShowTrajectory
Definition: CloudViewer.h:393
const QColor & getBackgroundColor() const
void normalizeRotation()
Definition: Transform.cpp:264
void setBackgroundColor(const QColor &color)
static const int frustum_indices[]
CloudViewer(QWidget *parent=0, CloudViewerInteractorStyle *style=CloudViewerInteractorStyle::New())
Definition: CloudViewer.cpp:82
bool updateFrustumPose(const std::string &id, const Transform &pose)
void setCameraLockZ(bool enabled=true)
GLM_FUNC_DECL bool isIdentity(matType< T, P > const &m, T const &epsilon)
bool isFrustumShown() const
pcl::PointCloud< pcl::PointXYZ >::Ptr _trajectory
Definition: CloudViewer.h:421
bool getCloudVisibility(const std::string &id)
vtkProp * _octomapActor
Definition: CloudViewer.h:441
void getGridMin(double &x, double &y, double &z) const
Definition: OctoMap.h:210
QAction * _aSetNormalsStep
Definition: CloudViewer.h:403
QAction * _aFollowCamera
Definition: CloudViewer.h:389
#define false
Definition: ConvertUTF.c:56
std::set< std::string > _lines
Definition: CloudViewer.h:416
float r33() const
Definition: Transform.h:69
Eigen::Quaternionf getQuaternionf() const
Definition: Transform.cpp:354
QAction * _aClearTrajectory
Definition: CloudViewer.h:395
void addOrUpdateGraph(const std::string &id, const pcl::PointCloud< pcl::PointXYZ >::Ptr &graph, const QColor &color=Qt::gray)
void setCameraTargetLocked(bool enabled=true)
#define UDEBUG(...)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
QAction * _aSetGridCellSize
Definition: CloudViewer.h:401
void updateCameraFrustums(const Transform &pose, const std::vector< CameraModel > &models)
const CameraModel & right() const
void removeSphere(const std::string &id)
static const float frustum_vertices[]
void loadSettings(QSettings &settings, const QString &group="")
double getRenderingRate() const
unsigned int _gridCellCount
Definition: CloudViewer.h:425
#define UERROR(...)
virtual void keyReleaseEvent(QKeyEvent *event)
ULogger class and convenient macros.
#define UWARN(...)
void setBackfaceCulling(bool enabled, bool frontfaceCulling)
bool isCameraOrtho() const
void setCameraTargetFollow(bool enabled=true)
std::set< std::string > _cubes
Definition: CloudViewer.h:418
QMap< std::string, Transform > _frustums
Definition: CloudViewer.h:420
virtual void mousePressEvent(QMouseEvent *event)
virtual void mouseMoveEvent(QMouseEvent *event)
double getNodeSize(unsigned depth) const
void setCloudColorIndex(const std::string &id, int index)
virtual void handleAction(QAction *event)
void removeCoordinate(const std::string &id)
Transform inverse() const
Definition: Transform.cpp:169
QAction * _aSetFlatShading
Definition: CloudViewer.h:408
QAction * _aSetGridCellCount
Definition: CloudViewer.h:400
bool addOctomap(const OctoMap *octomap, unsigned int treeDepth=0, bool volumeRepresentation=true)
bool addCloudMesh(const std::string &id, const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const std::vector< pcl::Vertices > &polygons, const Transform &pose=Transform::getIdentity())
bool addTextureMesh(const pcl::TextureMesh &mesh, const cv::Mat &texture, const std::string &id="texture", int viewport=0)
void setShading(bool on)
Eigen::Affine3f toEigen3f() const
Definition: Transform.cpp:344
QAction * _aCameraOrtho
Definition: CloudViewer.h:392
QColor getFrustumColor() const
bool isTrajectoryShown() const
QAction * _aShowNormals
Definition: CloudViewer.h:402
cv::Vec3d _lastCameraPose
Definition: CloudViewer.h:432
virtual void wheelEvent(QWheelEvent *event)
QColor getColor(const std::string &id)
std::string UTILITE_EXP uFormat(const char *fmt,...)
bool getPose(const std::string &id, Transform &pose)
bool isCameraTargetLocked() const
void removeAllFrustums(bool exceptCameraReference=false)
virtual size_t size() const
QAction * _aSetRenderingRate
Definition: CloudViewer.h:406
float getNormalsScale() const
bool updateCloudPose(const std::string &id, const Transform &pose)
QAction * _aSetLighting
Definition: CloudViewer.h:407
void setRenderingRate(double rate)
void setCloudOpacity(const std::string &id, double opacity=1.0)
float r32() const
Definition: Transform.h:68
GLM_FUNC_DECL detail::tmat4x4< T, P > orientation(detail::tvec3< T, P > const &Normal, detail::tvec3< T, P > const &Up)
double keyToCoord(key_type key, unsigned depth) const
const Transform & localTransform() const
Definition: CameraModel.h:109


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:30