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 <rtabmap/core/util2d.h>
39 #include <pcl/visualization/pcl_visualizer.h>
40 #include <pcl/common/transforms.h>
41 #include <QMenu>
42 #include <QAction>
43 #include <QtGui/QContextMenuEvent>
44 #include <QInputDialog>
45 #include <QtGui/QWheelEvent>
46 #include <QtGui/QKeyEvent>
47 #include <QColorDialog>
48 #include <QtGui/QVector3D>
49 #include <QMainWindow>
50 #include <set>
51 
52 #include <vtkCamera.h>
53 #include <vtkRenderWindow.h>
54 #include <vtkCubeSource.h>
55 #include <vtkGlyph3D.h>
56 #include <vtkGlyph3DMapper.h>
57 #include <vtkSmartVolumeMapper.h>
58 #include <vtkVolumeProperty.h>
59 #include <vtkColorTransferFunction.h>
60 #include <vtkPiecewiseFunction.h>
61 #include <vtkImageData.h>
62 #include <vtkLookupTable.h>
63 #include <vtkTextureUnitManager.h>
64 #include <vtkJPEGReader.h>
65 #include <vtkBMPReader.h>
66 #include <vtkPNMReader.h>
67 #include <vtkPNGReader.h>
68 #include <vtkTIFFReader.h>
69 #include <vtkOpenGLRenderWindow.h>
70 #include <vtkPointPicker.h>
71 #include <vtkTextActor.h>
72 #include <vtkTexture.h>
73 #include <vtkOBBTree.h>
74 #include <vtkObjectFactory.h>
75 #include <vtkQuad.h>
77 
78 #if VTK_MAJOR_VERSION >= 7
79 #include <vtkEDLShading.h>
80 #include <vtkRenderStepsPass.h>
81 #include <vtkOpenGLRenderer.h>
82 #endif
83 
84 
85 #if VTK_MAJOR_VERSION >= 8
86 #include <vtkGenericOpenGLRenderWindow.h>
87 #endif
88 
89 #ifdef RTABMAP_OCTOMAP
90 #include <rtabmap/core/OctoMap.h>
91 #endif
92 
93 namespace rtabmap {
94 
96  PCLQVTKWidget(parent),
97  _aLockCamera(0),
98  _aFollowCamera(0),
99  _aResetCamera(0),
100  _aLockViewZ(0),
101  _aCameraOrtho(0),
102  _aShowTrajectory(0),
103  _aSetTrajectorySize(0),
104  _aClearTrajectory(0),
105  _aShowCameraAxis(0),
106  _aShowFrustum(0),
107  _aSetFrustumScale(0),
108  _aSetFrustumColor(0),
109  _aShowGrid(0),
110  _aSetGridCellCount(0),
111  _aSetGridCellSize(0),
112  _aShowNormals(0),
113  _aSetNormalsStep(0),
114  _aSetNormalsScale(0),
115  _aSetBackgroundColor(0),
116  _aSetRenderingRate(0),
117  _aSetEDLShading(0),
118  _aSetLighting(0),
119  _aSetFlatShading(0),
120  _aSetEdgeVisibility(0),
121  _aBackfaceCulling(0),
122  _menu(0),
123  _trajectory(new pcl::PointCloud<pcl::PointXYZ>),
124  _maxTrajectorySize(100),
125  _frustumScale(0.5f),
126  _frustumColor(Qt::gray),
127  _gridCellCount(50),
128  _gridCellSize(1),
129  _normalsStep(1),
130  _normalsScale(0.2),
131  _buildLocator(false),
132  _lastCameraOrientation(0,0,0),
133  _lastCameraPose(0,0,0),
134  _defaultBgColor(Qt::black),
135  _currentBgColor(Qt::black),
136  _frontfaceCulling(false),
137  _renderingRate(5.0),
138  _octomapActor(0),
139  _intensityAbsMax(100.0f),
140  _coordinateFrameScale(1.0)
141 {
142  UDEBUG("");
143  this->setMinimumSize(200, 200);
144 
145  int argc = 0;
146  UASSERT(style!=0);
147  style->setCloudViewer(this);
148  style->AutoAdjustCameraClippingRangeOff();
149 #if VTK_MAJOR_VERSION > 8
150  auto renderer1 = vtkSmartPointer<vtkRenderer>::New();
152  renderWindow1->AddRenderer(renderer1);
153  _visualizer = new pcl::visualization::PCLVisualizer(
154  argc,
155  0,
156  renderer1,
157  renderWindow1,
158  "PCLVisualizer",
159  style,
160  false);
161 #else
162  _visualizer = new pcl::visualization::PCLVisualizer(
163  argc,
164  0,
165  "PCLVisualizer",
166  style,
167  false);
168 #endif
169 
170  _visualizer->setShowFPS(false);
171 
172  int viewport;
173  // Layer 0: unavailable layer, used as "all" by PCLVisualizer
174  _visualizer->createViewPort (0,0,1.0, 1.0, viewport); // Layer 1: all clouds here
175  _visualizer->createViewPort (0,0,1.0, 1.0, viewport); // Layer 2: all 3d objects here
176  _visualizer->createViewPort (0,0,1.0, 1.0, viewport); // Layer 3: text overlay
177  _visualizer->getRendererCollection()->InitTraversal ();
178  vtkRenderer* renderer = NULL;
179  int i =0;
180  while ((renderer = _visualizer->getRendererCollection()->GetNextItem ()) != NULL)
181  {
182  renderer->SetLayer(i);
183  if(i==1)
184  {
185 #if VTK_MAJOR_VERSION >= 7
186  renderer->PreserveColorBufferOff();
187 #endif
188  renderer->PreserveDepthBufferOff();
189  _visualizer->getInteractorStyle()->SetDefaultRenderer(renderer);
190  }
191  else if(i==2)
192  {
193 #if VTK_MAJOR_VERSION >= 7
194  renderer->PreserveColorBufferOn();
195 #endif
196  renderer->PreserveDepthBufferOn();
197  }
198  ++i;
199  }
200  _visualizer->getRenderWindow()->SetNumberOfLayers(4);
201 
202 #if VTK_MAJOR_VERSION > 8
203  this->setRenderWindow(_visualizer->getRenderWindow());
204 #else
205  this->SetRenderWindow(_visualizer->getRenderWindow());
206 #endif
207 
208  // Replaced by the second line, to avoid a crash in Mac OS X on close, as well as
209  // the "Invalid drawable" warning when the view is not visible.
210  //_visualizer->setupInteractor(this->GetInteractor(), this->GetRenderWindow());
211 #if VTK_MAJOR_VERSION > 8
212  this->interactor()->SetInteractorStyle (_visualizer->getInteractorStyle());
213 #else
214  this->GetInteractor()->SetInteractorStyle (_visualizer->getInteractorStyle());
215 #endif
216  // setup a simple point picker
218  UDEBUG("pick tolerance=%f", pp->GetTolerance());
219  pp->SetTolerance (pp->GetTolerance()/2.0);
220 #if VTK_MAJOR_VERSION > 8
221  this->interactor()->SetPicker (pp);
222 #else
223  this->GetInteractor()->SetPicker (pp);
224 #endif
225 
227 
228  this->setCameraPosition(
229  -1, 0, 0,
230  0, 0, 0,
231  0, 0, 1);
232 #ifndef _WIN32
233  // Crash on startup on Windows (vtk issue)
234  this->addOrUpdateCoordinate("reference", Transform::getIdentity(), 0.2);
235 #endif
236 
237  //setup menu/actions
238  createMenu();
239 
240  setMouseTracking(false);
241 }
242 
244 {
245  UDEBUG("");
246  this->clear();
247  delete _visualizer;
248  UDEBUG("");
249 }
250 
252 {
253  this->removeAllClouds();
254  this->removeAllGraphs();
255  this->removeAllCoordinates();
256  this->removeAllLines();
257  this->removeAllFrustums();
258  this->removeAllTexts();
259  this->removeOccupancyGridMap();
260  this->removeOctomap();
261 
262  if(_aShowCameraAxis->isChecked())
263  {
264  this->addOrUpdateCoordinate("reference", Transform::getIdentity(), 0.2);
265  }
266  _lastPose.setNull();
267  if(_aLockCamera->isChecked() || _aFollowCamera->isChecked())
268  {
269  resetCamera();
270  }
271  this->clearTrajectory();
272 }
273 
275 {
276  _aLockCamera = new QAction("Lock target", this);
277  _aLockCamera->setCheckable(true);
278  _aLockCamera->setChecked(false);
279  _aFollowCamera = new QAction("Follow", this);
280  _aFollowCamera->setCheckable(true);
281  _aFollowCamera->setChecked(true);
282  QAction * freeCamera = new QAction("Free", this);
283  freeCamera->setCheckable(true);
284  freeCamera->setChecked(false);
285  _aLockViewZ = new QAction("Lock view Z", this);
286  _aLockViewZ->setCheckable(true);
287  _aLockViewZ->setChecked(true);
288  _aCameraOrtho = new QAction("Ortho mode", this);
289  _aCameraOrtho->setCheckable(true);
290  _aCameraOrtho->setChecked(false);
291  _aResetCamera = new QAction("Reset position", this);
292  _aShowTrajectory= new QAction("Show trajectory", this);
293  _aShowTrajectory->setCheckable(true);
294  _aShowTrajectory->setChecked(true);
295  _aSetTrajectorySize = new QAction("Set trajectory size...", this);
296  _aClearTrajectory = new QAction("Clear trajectory", this);
297  _aShowCameraAxis= new QAction("Show base frame", this);
298  _aShowCameraAxis->setCheckable(true);
299  _aShowCameraAxis->setChecked(true);
300  _aSetFrameScale= new QAction("Set frame scale...", this);
301  _aShowCameraAxis->setChecked(true);
302  _aShowFrustum= new QAction("Show frustum", this);
303  _aShowFrustum->setCheckable(true);
304  _aShowFrustum->setChecked(false);
305  _aSetFrustumScale = new QAction("Set frustum scale...", this);
306  _aSetFrustumColor = new QAction("Set frustum color...", this);
307  _aShowGrid = new QAction("Show grid", this);
308  _aShowGrid->setCheckable(true);
309  _aSetGridCellCount = new QAction("Set cell count...", this);
310  _aSetGridCellSize = new QAction("Set cell size...", this);
311  _aShowNormals = new QAction("Show normals", this);
312  _aShowNormals->setCheckable(true);
313  _aSetNormalsStep = new QAction("Set normals step...", this);
314  _aSetNormalsScale = new QAction("Set normals scale...", this);
315  _aSetIntensityRedColormap = new QAction("Red/Yellow Colormap", this);
316  _aSetIntensityRedColormap->setCheckable(true);
317  _aSetIntensityRedColormap->setChecked(true);
318  _aSetIntensityRainbowColormap = new QAction("Rainbow Colormap", this);
319  _aSetIntensityRainbowColormap->setCheckable(true);
320  _aSetIntensityRainbowColormap->setChecked(false);
321  _aSetIntensityMaximum = new QAction("Set maximum absolute intensity...", this);
322  _aSetBackgroundColor = new QAction("Set background color...", this);
323  _aSetRenderingRate = new QAction("Set rendering rate...", this);
324  _aSetEDLShading = new QAction("Eye-Dome Lighting Shading", this);
325  _aSetEDLShading->setCheckable(true);
326  _aSetEDLShading->setChecked(false);
327 #if VTK_MAJOR_VERSION < 7
328  _aSetEDLShading->setEnabled(false);
329 #endif
330  _aSetLighting = new QAction("Lighting", this);
331  _aSetLighting->setCheckable(true);
332  _aSetLighting->setChecked(false);
333  _aSetFlatShading = new QAction("Flat Shading", this);
334  _aSetFlatShading->setCheckable(true);
335  _aSetFlatShading->setChecked(false);
336  _aSetEdgeVisibility = new QAction("Show edges", this);
337  _aSetEdgeVisibility->setCheckable(true);
338  _aSetEdgeVisibility->setChecked(false);
339  _aBackfaceCulling = new QAction("Backface culling", this);
340  _aBackfaceCulling->setCheckable(true);
341  _aBackfaceCulling->setChecked(true);
342  _aPolygonPicking = new QAction("Polygon picking", this);
343  _aPolygonPicking->setCheckable(true);
344  _aPolygonPicking->setChecked(false);
345 
346  QMenu * cameraMenu = new QMenu("Camera", this);
347  cameraMenu->addAction(_aLockCamera);
348  cameraMenu->addAction(_aFollowCamera);
349  cameraMenu->addAction(freeCamera);
350  cameraMenu->addSeparator();
351  cameraMenu->addAction(_aLockViewZ);
352  cameraMenu->addAction(_aCameraOrtho);
353  cameraMenu->addAction(_aResetCamera);
354  QActionGroup * group = new QActionGroup(this);
355  group->addAction(_aLockCamera);
356  group->addAction(_aFollowCamera);
357  group->addAction(freeCamera);
358 
359  QMenu * trajectoryMenu = new QMenu("Trajectory", this);
360  trajectoryMenu->addAction(_aShowTrajectory);
361  trajectoryMenu->addAction(_aSetTrajectorySize);
362  trajectoryMenu->addAction(_aClearTrajectory);
363 
364  QMenu * frustumMenu = new QMenu("Frustum", this);
365  frustumMenu->addAction(_aShowFrustum);
366  frustumMenu->addAction(_aSetFrustumScale);
367  frustumMenu->addAction(_aSetFrustumColor);
368 
369  QMenu * gridMenu = new QMenu("Grid", this);
370  gridMenu->addAction(_aShowGrid);
371  gridMenu->addAction(_aSetGridCellCount);
372  gridMenu->addAction(_aSetGridCellSize);
373 
374  QMenu * normalsMenu = new QMenu("Normals", this);
375  normalsMenu->addAction(_aShowNormals);
376  normalsMenu->addAction(_aSetNormalsStep);
377  normalsMenu->addAction(_aSetNormalsScale);
378 
379  QMenu * scanMenu = new QMenu("Scan color", this);
380  scanMenu->addAction(_aSetIntensityRedColormap);
381  scanMenu->addAction(_aSetIntensityRainbowColormap);
382  scanMenu->addAction(_aSetIntensityMaximum);
383 
384  //menus
385  _menu = new QMenu(this);
386  _menu->addMenu(cameraMenu);
387  _menu->addMenu(trajectoryMenu);
388  _menu->addAction(_aShowCameraAxis);
389  _menu->addAction(_aSetFrameScale);
390  _menu->addMenu(frustumMenu);
391  _menu->addMenu(gridMenu);
392  _menu->addMenu(normalsMenu);
393  _menu->addMenu(scanMenu);
394  _menu->addAction(_aSetBackgroundColor);
395  _menu->addAction(_aSetRenderingRate);
396  _menu->addAction(_aSetEDLShading);
397  _menu->addAction(_aSetLighting);
398  _menu->addAction(_aSetFlatShading);
399  _menu->addAction(_aSetEdgeVisibility);
400  _menu->addAction(_aBackfaceCulling);
401  _menu->addAction(_aPolygonPicking);
402 }
403 
404 void CloudViewer::saveSettings(QSettings & settings, const QString & group) const
405 {
406  if(!group.isEmpty())
407  {
408  settings.beginGroup(group);
409  }
410 
411  float poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ;
412  this->getCameraPosition(poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ);
413  QVector3D pose(poseX, poseY, poseZ);
414  QVector3D focal(focalX, focalY, focalZ);
415  if(!this->isCameraFree())
416  {
417  // make camera position relative to target
418  Transform T = this->getTargetPose();
419  if(this->isCameraTargetLocked())
420  {
421  T = Transform(T.x(), T.y(), T.z(), 0,0,0);
422  }
423  Transform F(focalX, focalY, focalZ, 0,0,0);
424  Transform P(poseX, poseY, poseZ, 0,0,0);
425  Transform newFocal = T.inverse() * F;
426  Transform newPose = newFocal * F.inverse() * P;
427  pose = QVector3D(newPose.x(), newPose.y(), newPose.z());
428  focal = QVector3D(newFocal.x(), newFocal.y(), newFocal.z());
429  }
430  settings.setValue("camera_pose", pose);
431  settings.setValue("camera_focal", focal);
432  settings.setValue("camera_up", QVector3D(upX, upY, upZ));
433 
434  settings.setValue("grid", this->isGridShown());
435  settings.setValue("grid_cell_count", this->getGridCellCount());
436  settings.setValue("grid_cell_size", (double)this->getGridCellSize());
437 
438  settings.setValue("normals", this->isNormalsShown());
439  settings.setValue("normals_step", this->getNormalsStep());
440  settings.setValue("normals_scale", (double)this->getNormalsScale());
441 
442  settings.setValue("intensity_red_colormap", this->isIntensityRedColormap());
443  settings.setValue("intensity_rainbow_colormap", this->isIntensityRainbowColormap());
444  settings.setValue("intensity_max", (double)this->getIntensityMax());
445 
446  settings.setValue("trajectory_shown", this->isTrajectoryShown());
447  settings.setValue("trajectory_size", this->getTrajectorySize());
448 
449  settings.setValue("camera_axis_shown", this->isCameraAxisShown());
450  settings.setValue("coordinate_frame_scale", this->getCoordinateFrameScale());
451 
452  settings.setValue("frustum_shown", this->isFrustumShown());
453  settings.setValue("frustum_scale", this->getFrustumScale());
454  settings.setValue("frustum_color", this->getFrustumColor());
455 
456  settings.setValue("camera_target_locked", this->isCameraTargetLocked());
457  settings.setValue("camera_target_follow", this->isCameraTargetFollow());
458  settings.setValue("camera_free", this->isCameraFree());
459  settings.setValue("camera_lockZ", this->isCameraLockZ());
460 
461  settings.setValue("bg_color", this->getDefaultBackgroundColor());
462  settings.setValue("rendering_rate", this->getRenderingRate());
463  if(!group.isEmpty())
464  {
465  settings.endGroup();
466  }
467 }
468 
469 void CloudViewer::loadSettings(QSettings & settings, const QString & group)
470 {
471  if(!group.isEmpty())
472  {
473  settings.beginGroup(group);
474  }
475 
476  float poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ;
477  this->getCameraPosition(poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ);
478  QVector3D pose(poseX, poseY, poseZ), focal(focalX, focalY, focalZ), up(upX, upY, upZ);
479  pose = settings.value("camera_pose", pose).value<QVector3D>();
480  focal = settings.value("camera_focal", focal).value<QVector3D>();
481  up = settings.value("camera_up", up).value<QVector3D>();
482  _lastCameraOrientation= _lastCameraPose= cv::Vec3f(0,0,0);
483  this->setCameraPosition(pose.x(),pose.y(),pose.z(), focal.x(),focal.y(),focal.z(), up.x(),up.y(),up.z());
484 
485  this->setGridShown(settings.value("grid", this->isGridShown()).toBool());
486  this->setGridCellCount(settings.value("grid_cell_count", this->getGridCellCount()).toUInt());
487  this->setGridCellSize(settings.value("grid_cell_size", this->getGridCellSize()).toFloat());
488 
489  this->setNormalsShown(settings.value("normals", this->isNormalsShown()).toBool());
490  this->setNormalsStep(settings.value("normals_step", this->getNormalsStep()).toInt());
491  this->setNormalsScale(settings.value("normals_scale", this->getNormalsScale()).toFloat());
492 
493  this->setIntensityRedColormap(settings.value("intensity_red_colormap", this->isIntensityRedColormap()).toBool());
494  this->setIntensityRainbowColormap(settings.value("intensity_rainbow_colormap", this->isIntensityRainbowColormap()).toBool());
495  this->setIntensityMax(settings.value("intensity_max", this->getIntensityMax()).toFloat());
496 
497  this->setTrajectoryShown(settings.value("trajectory_shown", this->isTrajectoryShown()).toBool());
498  this->setTrajectorySize(settings.value("trajectory_size", this->getTrajectorySize()).toUInt());
499 
500  this->setCameraAxisShown(settings.value("camera_axis_shown", this->isCameraAxisShown()).toBool());
501  this->setCoordinateFrameScale(settings.value("coordinate_frame_scale", this->getCoordinateFrameScale()).toDouble());
502 
503  this->setFrustumShown(settings.value("frustum_shown", this->isFrustumShown()).toBool());
504  this->setFrustumScale(settings.value("frustum_scale", this->getFrustumScale()).toDouble());
505  this->setFrustumColor(settings.value("frustum_color", this->getFrustumColor()).value<QColor>());
506 
507  this->setCameraTargetLocked(settings.value("camera_target_locked", this->isCameraTargetLocked()).toBool());
508  this->setCameraTargetFollow(settings.value("camera_target_follow", this->isCameraTargetFollow()).toBool());
509  if(settings.value("camera_free", this->isCameraFree()).toBool())
510  {
511  this->setCameraFree();
512  }
513  this->setCameraLockZ(settings.value("camera_lockZ", this->isCameraLockZ()).toBool());
514 
515  this->setDefaultBackgroundColor(settings.value("bg_color", this->getDefaultBackgroundColor()).value<QColor>());
516 
517  this->setRenderingRate(settings.value("rendering_rate", this->getRenderingRate()).toDouble());
518 
519  if(!group.isEmpty())
520  {
521  settings.endGroup();
522  }
523 
524  this->refreshView();
525 }
526 
528 {
529 #if VTK_MAJOR_VERSION > 8
530  this->renderWindow()->Render();
531 #else
532  this->update();
533 #endif
534 }
535 
537  const std::string & id,
538  const Transform & pose)
539 {
540  if(_addedClouds.contains(id))
541  {
542  //UDEBUG("Updating pose %s to %s", id.c_str(), pose.prettyPrint().c_str());
543  bool samePose = _addedClouds.find(id).value() == pose;
544  Eigen::Affine3f posef = pose.toEigen3f();
545  if(!samePose)
546  {
547  // PointCloud / Mesh
548  bool updated = _visualizer->updatePointCloudPose(id, posef);
549 
550 #if VTK_MAJOR_VERSION >= 7
551  if(!updated)
552  {
553  // TextureMesh, cannot use updateShapePose because it searches for vtkLODActor, not a vtkActor
554  pcl::visualization::ShapeActorMap::iterator am_it = _visualizer->getShapeActorMap()->find (id);
555  vtkActor* actor;
556  if (am_it != _visualizer->getShapeActorMap()->end ())
557  {
558  actor = vtkActor::SafeDownCast (am_it->second);
559  if (actor)
560  {
562  pcl::visualization::PCLVisualizer::convertToVtkMatrix (pose.toEigen3f().matrix (), matrix);
563  actor->SetUserMatrix (matrix);
564  actor->Modified ();
565  updated = true;
566  }
567  }
568  }
569 #endif
570 
571  if(updated)
572  {
573  _addedClouds.find(id).value() = pose;
574  std::string idNormals = id+"-normals";
575  if(_addedClouds.find(idNormals)!=_addedClouds.end())
576  {
577  _visualizer->updatePointCloudPose(idNormals, posef);
578  _addedClouds.find(idNormals).value() = pose;
579  }
580  return true;
581  }
582  }
583  }
584  return false;
585 }
586 
587 class PointCloudColorHandlerIntensityField : public pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>
588 {
589  typedef pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloud PointCloud;
590  typedef PointCloud::Ptr PointCloudPtr;
591  typedef PointCloud::ConstPtr PointCloudConstPtr;
592 
593 public:
596 
598  PointCloudColorHandlerIntensityField (const PointCloudConstPtr &cloud, float maxAbsIntensity = 0.0f, int colorMap = 0) :
599  pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloudColorHandler (cloud),
600  maxAbsIntensity_(maxAbsIntensity),
601  colormap_(colorMap)
602  {
603  field_idx_ = pcl::getFieldIndex (*cloud, "intensity");
604  if (field_idx_ != -1)
605  capable_ = true;
606  else
607  capable_ = false;
608  }
609 
612 
618 #if PCL_VERSION_COMPARE(>, 1, 11, 1)
619  virtual vtkSmartPointer<vtkDataArray> getColor () const {
621  if (!capable_ || !cloud_)
622  return scalars;
623 #else
624  virtual bool getColor (vtkSmartPointer<vtkDataArray> &scalars) const {
625  if (!capable_ || !cloud_)
626  return (false);
627 #endif
628  if (!scalars)
630  scalars->SetNumberOfComponents (3);
631 
632  vtkIdType nr_points = cloud_->width * cloud_->height;
633  // Allocate enough memory to hold all colors
634  float * intensities = new float[nr_points];
635  float intensity;
636  size_t point_offset = cloud_->fields[field_idx_].offset;
637  size_t j = 0;
638 
639  // If XYZ present, check if the points are invalid
640  int x_idx = pcl::getFieldIndex (*cloud_, "x");
641  if (x_idx != -1)
642  {
643  float x_data, y_data, z_data;
644  size_t x_point_offset = cloud_->fields[x_idx].offset;
645 
646  // Color every point
647  for (vtkIdType cp = 0; cp < nr_points; ++cp,
648  point_offset += cloud_->point_step,
649  x_point_offset += cloud_->point_step)
650  {
651  // Copy the value at the specified field
652  memcpy (&intensity, &cloud_->data[point_offset], sizeof (float));
653 
654  memcpy (&x_data, &cloud_->data[x_point_offset], sizeof (float));
655  memcpy (&y_data, &cloud_->data[x_point_offset + sizeof (float)], sizeof (float));
656  memcpy (&z_data, &cloud_->data[x_point_offset + 2 * sizeof (float)], sizeof (float));
657 
658  if (!std::isfinite (x_data) || !std::isfinite (y_data) || !std::isfinite (z_data))
659  continue;
660 
661  intensities[j++] = intensity;
662  }
663  }
664  // No XYZ data checks
665  else
666  {
667  // Color every point
668  for (vtkIdType cp = 0; cp < nr_points; ++cp, point_offset += cloud_->point_step)
669  {
670  // Copy the value at the specified field
671  memcpy (&intensity, &cloud_->data[point_offset], sizeof (float));
672 
673  intensities[j++] = intensity;
674  }
675  }
676  if (j != 0)
677  {
678  // Allocate enough memory to hold all colors
679  unsigned char* colors = new unsigned char[j * 3];
680  float min, max;
681  if(maxAbsIntensity_>0.0f)
682  {
683  max = maxAbsIntensity_;
684  }
685  else
686  {
687  uMinMax(intensities, j, min, max);
688  }
689  for(size_t k=0; k<j; ++k)
690  {
691  colors[k*3+0] = colors[k*3+1] = colors[k*3+2] = max>0?(unsigned char)(std::min(intensities[k]/max*255.0f, 255.0f)):255;
692  if(colormap_ == 1)
693  {
694  colors[k*3+0] = 255;
695  colors[k*3+2] = 0;
696  }
697  else if(colormap_ == 2)
698  {
699  float r,g,b;
700  util2d::HSVtoRGB(&r, &g, &b, colors[k*3+0]*299.0f/255.0f, 1.0f, 1.0f);
701  colors[k*3+0] = r*255.0f;
702  colors[k*3+1] = g*255.0f;
703  colors[k*3+2] = b*255.0f;
704  }
705  }
706  reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetNumberOfTuples (j);
707  reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetArray (colors, j*3, 0, vtkUnsignedCharArray::VTK_DATA_ARRAY_DELETE);
708  }
709  else
710  reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetNumberOfTuples (0);
711  //delete [] colors;
712  delete [] intensities;
713 #if PCL_VERSION_COMPARE(>, 1, 11, 1)
714  return scalars;
715 #else
716  return (true);
717 #endif
718  }
719 
720 protected:
722  virtual std::string
723  getName () const { return ("PointCloudColorHandlerIntensityField"); }
724 
726  virtual std::string
727  getFieldName () const { return ("intensity"); }
728 
729 private:
731  int colormap_; // 0=grayscale, 1=redYellow, 2=RainbowHSV
732 };
733 
735  const std::string & id,
736  const pcl::PCLPointCloud2Ptr & binaryCloud,
737  const Transform & pose,
738  bool rgb,
739  bool hasNormals,
740  bool hasIntensity,
741  const QColor & color,
742  int viewport)
743 {
744  int previousColorIndex = -1;
745  if(_addedClouds.contains(id))
746  {
747  previousColorIndex = _visualizer->getColorHandlerIndex(id);
748  this->removeCloud(id);
749  }
750 
751  Eigen::Vector4f origin(pose.x(), pose.y(), pose.z(), 0.0f);
752  Eigen::Quaternionf orientation = Eigen::Quaternionf(pose.toEigen3f().linear());
753 
754  if(hasNormals && _aShowNormals->isChecked())
755  {
756  pcl::PointCloud<pcl::PointNormal>::Ptr cloud_xyz (new pcl::PointCloud<pcl::PointNormal>);
757  pcl::fromPCLPointCloud2 (*binaryCloud, *cloud_xyz);
758  std::string idNormals = id + "-normals";
759  if(_visualizer->addPointCloudNormals<pcl::PointNormal>(cloud_xyz, _normalsStep, _normalsScale, idNormals, viewport))
760  {
761  _visualizer->updatePointCloudPose(idNormals, pose.toEigen3f());
762  _addedClouds.insert(idNormals, pose);
763  }
764  }
765 
766  // add random color channel
767  pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::Ptr colorHandler;
768  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerRandom<pcl::PCLPointCloud2> (binaryCloud));
769  if(_visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, viewport))
770  {
771  QColor c = Qt::gray;
772  if(color.isValid())
773  {
774  c = color;
775  }
776  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerCustom<pcl::PCLPointCloud2> (binaryCloud, c.red(), c.green(), c.blue()));
777  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, viewport);
778 
779  // x,y,z
780  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "x"));
781  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, viewport);
782  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "y"));
783  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, viewport);
784  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "z"));
785  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, viewport);
786 
787  if(rgb)
788  {
789  //rgb
790  colorHandler.reset(new pcl::visualization::PointCloudColorHandlerRGBField<pcl::PCLPointCloud2>(binaryCloud));
791  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, viewport);
792  }
793  else if(hasIntensity)
794  {
795  //intensity
796  colorHandler.reset(new PointCloudColorHandlerIntensityField(binaryCloud, _intensityAbsMax, _aSetIntensityRedColormap->isChecked()?1:_aSetIntensityRainbowColormap->isChecked()?2:0));
797  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, viewport);
798  }
799  else if(previousColorIndex == 5)
800  {
801  previousColorIndex = -1;
802  }
803 
804  if(hasNormals)
805  {
806  //normals
807  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "normal_x"));
808  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, viewport);
809  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "normal_y"));
810  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, viewport);
811  colorHandler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud, "normal_z"));
812  _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation, id, viewport);
813  }
814  else if(previousColorIndex > 5)
815  {
816  previousColorIndex = -1;
817  }
818 
819  if(previousColorIndex>=0)
820  {
821  _visualizer->updateColorHandlerIndex(id, previousColorIndex);
822  }
823  else if(rgb)
824  {
825  _visualizer->updateColorHandlerIndex(id, 5);
826  }
827  else if(hasNormals)
828  {
829  _visualizer->updateColorHandlerIndex(id, hasIntensity?8:7);
830  }
831  else if(hasIntensity)
832  {
833  _visualizer->updateColorHandlerIndex(id, 5);
834  }
835  else if(color.isValid())
836  {
837  _visualizer->updateColorHandlerIndex(id, 1);
838  }
839 
840  _addedClouds.insert(id, pose);
841  return true;
842  }
843  return false;
844 }
845 
847  const std::string & id,
848  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
849  const Transform & pose,
850  const QColor & color)
851 {
852  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
853  pcl::toPCLPointCloud2(*cloud, *binaryCloud);
854  return addCloud(id, binaryCloud, pose, true, true, false, color);
855 }
856 
858  const std::string & id,
859  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
860  const Transform & pose,
861  const QColor & color)
862 {
863  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
864  pcl::toPCLPointCloud2(*cloud, *binaryCloud);
865  return addCloud(id, binaryCloud, pose, true, false, false, color);
866 }
867 
869  const std::string & id,
870  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
871  const Transform & pose,
872  const QColor & color)
873 {
874  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
875  pcl::toPCLPointCloud2(*cloud, *binaryCloud);
876  return addCloud(id, binaryCloud, pose, false, true, true, color);
877 }
878 
880  const std::string & id,
881  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
882  const Transform & pose,
883  const QColor & color)
884 {
885  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
886  pcl::toPCLPointCloud2(*cloud, *binaryCloud);
887  return addCloud(id, binaryCloud, pose, false, false, true, color);
888 }
889 
891  const std::string & id,
892  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
893  const Transform & pose,
894  const QColor & color)
895 {
896  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
897  pcl::toPCLPointCloud2(*cloud, *binaryCloud);
898  return addCloud(id, binaryCloud, pose, false, true, false, color);
899 }
900 
902  const std::string & id,
903  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
904  const Transform & pose,
905  const QColor & color)
906 {
907  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
908  pcl::toPCLPointCloud2(*cloud, *binaryCloud);
909  return addCloud(id, binaryCloud, pose, false, false, false, color);
910 }
911 
913  const std::string & id,
914  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
915  const std::vector<pcl::Vertices> & polygons,
916  const Transform & pose)
917 {
918  if(_addedClouds.contains(id))
919  {
920  this->removeCloud(id);
921  }
922 
923  UDEBUG("Adding %s with %d points and %d polygons", id.c_str(), (int)cloud->size(), (int)polygons.size());
924  if(_visualizer->addPolygonMesh<pcl::PointXYZ>(cloud, polygons, id, 1))
925  {
926 #if VTK_MAJOR_VERSION >= 7
927  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.1);
928 #else
929  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.5);
930 #endif
931  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
932  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetInterpolation(_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
933  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
934  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
935  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
936  _visualizer->updatePointCloudPose(id, pose.toEigen3f());
937  if(_buildLocator)
938  {
940  tree->SetDataSet(_visualizer->getCloudActorMap()->find(id)->second.actor->GetMapper()->GetInput());
941  tree->BuildLocator();
942  _locators.insert(std::make_pair(id, tree));
943  }
944  _addedClouds.insert(id, pose);
945  return true;
946  }
947  return false;
948 }
949 
951  const std::string & id,
952  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
953  const std::vector<pcl::Vertices> & polygons,
954  const Transform & pose)
955 {
956  if(_addedClouds.contains(id))
957  {
958  this->removeCloud(id);
959  }
960 
961  UDEBUG("Adding %s with %d points and %d polygons", id.c_str(), (int)cloud->size(), (int)polygons.size());
962  if(_visualizer->addPolygonMesh<pcl::PointXYZRGB>(cloud, polygons, id, 1))
963  {
964 #if VTK_MAJOR_VERSION >= 7
965  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.1);
966 #else
967  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.5);
968 #endif
969  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
970  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetInterpolation(_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
971  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
972  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
973  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
974  _visualizer->updatePointCloudPose(id, pose.toEigen3f());
975  if(_buildLocator)
976  {
978  tree->SetDataSet(_visualizer->getCloudActorMap()->find(id)->second.actor->GetMapper()->GetInput());
979  tree->BuildLocator();
980  _locators.insert(std::make_pair(id, tree));
981  }
982  _addedClouds.insert(id, pose);
983  return true;
984  }
985  return false;
986 }
987 
989  const std::string & id,
990  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
991  const std::vector<pcl::Vertices> & polygons,
992  const Transform & pose)
993 {
994  if(_addedClouds.contains(id))
995  {
996  this->removeCloud(id);
997  }
998 
999  UDEBUG("Adding %s with %d points and %d polygons", id.c_str(), (int)cloud->size(), (int)polygons.size());
1000  if(_visualizer->addPolygonMesh<pcl::PointXYZRGBNormal>(cloud, polygons, id, 1))
1001  {
1002 #if VTK_MAJOR_VERSION >= 7
1003  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.1);
1004 #else
1005  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.5);
1006 #endif
1007  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
1008  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetInterpolation(_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
1009  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
1010  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
1011  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
1012  _visualizer->updatePointCloudPose(id, pose.toEigen3f());
1013  if(_buildLocator)
1014  {
1016  tree->SetDataSet(_visualizer->getCloudActorMap()->find(id)->second.actor->GetMapper()->GetInput());
1017  tree->BuildLocator();
1018  _locators.insert(std::make_pair(id, tree));
1019  }
1020  _addedClouds.insert(id, pose);
1021  return true;
1022  }
1023  return false;
1024 }
1025 
1027  const std::string & id,
1028  const pcl::PolygonMesh::Ptr & mesh,
1029  const Transform & pose)
1030 {
1031  if(_addedClouds.contains(id))
1032  {
1033  this->removeCloud(id);
1034  }
1035 
1036  UDEBUG("Adding %s with %d polygons", id.c_str(), (int)mesh->polygons.size());
1037  if(_visualizer->addPolygonMesh(*mesh, id, 1))
1038  {
1039 #if VTK_MAJOR_VERSION >= 7
1040  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.1);
1041 #else
1042  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetAmbient(0.5);
1043 #endif
1044  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
1045  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
1046  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
1047  _visualizer->getCloudActorMap()->find(id)->second.actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
1048  _visualizer->updatePointCloudPose(id, pose.toEigen3f());
1049  if(_buildLocator)
1050  {
1052  tree->SetDataSet(_visualizer->getCloudActorMap()->find(id)->second.actor->GetMapper()->GetInput());
1053  tree->BuildLocator();
1054  _locators.insert(std::make_pair(id, tree));
1055  }
1056  _addedClouds.insert(id, pose);
1057  return true;
1058  }
1059 
1060  return false;
1061 }
1062 
1064  const std::string & id,
1065  const pcl::TextureMesh::Ptr & textureMesh,
1066  const cv::Mat & texture,
1067  const Transform & pose)
1068 {
1069  if(_addedClouds.contains(id))
1070  {
1071  this->removeCloud(id);
1072  }
1073 
1074  UDEBUG("Adding %s", id.c_str());
1075  if(this->addTextureMesh(*textureMesh, texture, id, 1))
1076  {
1077 #if VTK_MAJOR_VERSION >= 7
1078  vtkActor* actor = vtkActor::SafeDownCast (_visualizer->getShapeActorMap()->find(id)->second);
1079 #else
1080  vtkActor* actor = vtkActor::SafeDownCast (_visualizer->getCloudActorMap()->find(id)->second.actor);
1081 #endif
1082  UASSERT(actor);
1083  if(!textureMesh->cloud.is_dense)
1084  {
1085  actor->GetTexture()->SetInterpolate(1);
1086  actor->GetTexture()->SetBlendingMode(vtkTexture::VTK_TEXTURE_BLENDING_MODE_REPLACE);
1087  }
1088  if(_buildLocator)
1089  {
1091  tree->SetDataSet(actor->GetMapper()->GetInput());
1092  tree->BuildLocator();
1093  _locators.insert(std::make_pair(id, tree));
1094  }
1095  _addedClouds.insert(id, Transform::getIdentity());
1096  this->updateCloudPose(id, pose);
1097  return true;
1098  }
1099  return false;
1100 }
1101 
1102 bool CloudViewer::addOctomap(const OctoMap * octomap, unsigned int treeDepth, bool volumeRepresentation)
1103 {
1104  UDEBUG("");
1105 #ifdef RTABMAP_OCTOMAP
1106  UASSERT(octomap!=0);
1107 
1108  pcl::IndicesPtr obstacles(new std::vector<int>);
1109 
1110  if(treeDepth == 0 || treeDepth > octomap->octree()->getTreeDepth())
1111  {
1112  if(treeDepth>0)
1113  {
1114  UWARN("Tree depth requested (%d) is deeper than the "
1115  "actual maximum tree depth of %d. Using maximum depth.",
1116  (int)treeDepth, (int)octomap->octree()->getTreeDepth());
1117  }
1118  treeDepth = octomap->octree()->getTreeDepth();
1119  }
1120 
1121  removeOctomap();
1122 
1123  if(!volumeRepresentation)
1124  {
1125  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = octomap->createCloud(treeDepth, obstacles.get(), 0, 0, false);
1126  if(obstacles->size())
1127  {
1128  //vtkSmartPointer<vtkUnsignedCharArray> colors = vtkSmartPointer<vtkUnsignedCharArray>::New();
1129  //colors->SetName("colors");
1130  //colors->SetNumberOfComponents(3);
1132  colors->SetName("colors");
1133  colors->SetNumberOfValues(obstacles->size());
1134 
1136  lut->SetNumberOfTableValues(obstacles->size());
1137  lut->Build();
1138 
1139  // Create points
1141  points->SetNumberOfPoints(obstacles->size());
1142  double s = octomap->octree()->getNodeSize(treeDepth) / 2.0;
1143  for (unsigned int i = 0; i < obstacles->size(); i++)
1144  {
1145  points->InsertPoint(i,
1146  cloud->at(obstacles->at(i)).x,
1147  cloud->at(obstacles->at(i)).y,
1148  cloud->at(obstacles->at(i)).z);
1149  colors->InsertValue(i,i);
1150 
1151  lut->SetTableValue(i,
1152  double(cloud->at(obstacles->at(i)).r) / 255.0,
1153  double(cloud->at(obstacles->at(i)).g) / 255.0,
1154  double(cloud->at(obstacles->at(i)).b) / 255.0);
1155  }
1156 
1157  // Combine into a polydata
1159  polydata->SetPoints(points);
1160  polydata->GetPointData()->SetScalars(colors);
1161 
1162  // Create anything you want here, we will use a cube for the demo.
1164  cubeSource->SetBounds(-s, s, -s, s, -s, s);
1165 
1167  mapper->SetSourceConnection(cubeSource->GetOutputPort());
1168 #if VTK_MAJOR_VERSION <= 5
1169  mapper->SetInputConnection(polydata->GetProducerPort());
1170 #else
1171  mapper->SetInputData(polydata);
1172 #endif
1173  mapper->SetScalarRange(0, obstacles->size() - 1);
1174  mapper->SetLookupTable(lut);
1175  mapper->ScalingOff();
1176  mapper->Update();
1177 
1179  octomapActor->SetMapper(mapper);
1180 
1181  octomapActor->GetProperty()->SetRepresentationToSurface();
1182  octomapActor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
1183  octomapActor->GetProperty()->SetLighting(_aSetLighting->isChecked());
1184 
1185  _visualizer->getRendererCollection()->InitTraversal ();
1186  vtkRenderer* renderer = NULL;
1187  renderer = _visualizer->getRendererCollection()->GetNextItem ();
1188  renderer = _visualizer->getRendererCollection()->GetNextItem ();
1189  UASSERT(renderer);
1190  renderer->AddActor(octomapActor);
1191 
1192  _octomapActor = octomapActor.GetPointer();
1193  return true;
1194  }
1195  }
1196  else
1197  {
1198  if(octomap->octree()->size())
1199  {
1200  // Create an image data
1201  vtkSmartPointer<vtkImageData> imageData =
1203 
1204  double sizeX, sizeY, sizeZ;
1205  double minX, minY, minZ;
1206  double maxX, maxY, maxZ;
1207  octomap->getGridMin(minX, minY, minZ);
1208  octomap->getGridMax(maxX, maxY, maxZ);
1209  sizeX = maxX-minX;
1210  sizeY = maxY-minY;
1211  sizeZ = maxZ-minZ;
1212  double cellSize = octomap->octree()->getNodeSize(treeDepth);
1213 
1214  UTimer t;
1215  // Specify the size of the image data
1216  imageData->SetExtent(0, int(sizeX/cellSize+0.5), 0, int(sizeY/cellSize+0.5), 0, int(sizeZ/cellSize+0.5)); // 3D image
1217 #if VTK_MAJOR_VERSION <= 5
1218  imageData->SetNumberOfScalarComponents(4);
1219  imageData->SetScalarTypeToUnsignedChar();
1220 #else
1221  imageData->AllocateScalars(VTK_UNSIGNED_CHAR,4);
1222 #endif
1223 
1224  int dims[3];
1225  imageData->GetDimensions(dims);
1226 
1227  memset(imageData->GetScalarPointer(), 0, imageData->GetScalarSize()*imageData->GetNumberOfScalarComponents()*dims[0]*dims[1]*dims[2]);
1228 
1229  for (RtabmapColorOcTree::iterator it = octomap->octree()->begin(treeDepth); it != octomap->octree()->end(); ++it)
1230  {
1231  if(octomap->octree()->isNodeOccupied(*it))
1232  {
1233  octomap::point3d pt = octomap->octree()->keyToCoord(it.getKey());
1234  int x = (pt.x()-minX) / cellSize;
1235  int y = (pt.y()-minY) / cellSize;
1236  int z = (pt.z()-minZ) / cellSize;
1237  if(x>=0 && x<dims[0] && y>=0 && y<dims[1] && z>=0 && z<dims[2])
1238  {
1239  unsigned char* pixel = static_cast<unsigned char*>(imageData->GetScalarPointer(x,y,z));
1240  if(octomap->octree()->getTreeDepth() == it.getDepth() && it->isColorSet())
1241  {
1242  pixel[0] = it->getColor().r;
1243  pixel[1] = it->getColor().g;
1244  pixel[2] = it->getColor().b;
1245  }
1246  else
1247  {
1248  // Gradiant color on z axis
1249  float H = (maxZ - pt.z())*299.0f/(maxZ-minZ);
1250  float r,g,b;
1251  util2d::HSVtoRGB(&r, &g, &b, H, 1, 1);
1252  pixel[0] = r*255.0f;
1253  pixel[1] = g*255.0f;
1254  pixel[2] = b*255.0f;
1255  }
1256  pixel[3] = 255;
1257  }
1258  }
1259  }
1262  volumeMapper->SetBlendModeToComposite(); // composite first
1263 #if VTK_MAJOR_VERSION <= 5
1264  volumeMapper->SetInputConnection(imageData->GetProducerPort());
1265 #else
1266  volumeMapper->SetInputData(imageData);
1267 #endif
1268  vtkSmartPointer<vtkVolumeProperty> volumeProperty =
1270  volumeProperty->ShadeOff();
1271  volumeProperty->IndependentComponentsOff();
1272 
1273  vtkSmartPointer<vtkPiecewiseFunction> compositeOpacity =
1275  compositeOpacity->AddPoint(0.0,0.0);
1276  compositeOpacity->AddPoint(255.0,1.0);
1277  volumeProperty->SetScalarOpacity(0, compositeOpacity); // composite first.
1278 
1281  volume->SetMapper(volumeMapper);
1282  volume->SetProperty(volumeProperty);
1283  volume->SetScale(cellSize);
1284  volume->SetPosition(minX, minY, minZ);
1285 
1286  _visualizer->getRendererCollection()->InitTraversal ();
1287  vtkRenderer* renderer = NULL;
1288  renderer = _visualizer->getRendererCollection()->GetNextItem ();
1289  renderer = _visualizer->getRendererCollection()->GetNextItem ();
1290  UASSERT(renderer);
1291  renderer->AddViewProp(volume);
1292 
1293  // 3D texture mode. For coverage.
1294 #if !defined(VTK_LEGACY_REMOVE) && !defined(VTK_OPENGL2) && VTK_MAJOR_VERSION < 9
1295  volumeMapper->SetRequestedRenderModeToRayCastAndTexture();
1296 #endif // VTK_LEGACY_REMOVE
1297 
1298  // Software mode, for coverage. It also makes sure we will get the same
1299  // regression image on all platforms.
1300  volumeMapper->SetRequestedRenderModeToRayCast();
1301  _octomapActor = volume.GetPointer();
1302 
1303  return true;
1304  }
1305  }
1306 #endif
1307  return false;
1308 }
1309 
1311 {
1312  UDEBUG("");
1313 #ifdef RTABMAP_OCTOMAP
1314  if(_octomapActor)
1315  {
1316  _visualizer->getRendererCollection()->InitTraversal ();
1317  vtkRenderer* renderer = NULL;
1318  renderer = _visualizer->getRendererCollection()->GetNextItem ();
1319  renderer = _visualizer->getRendererCollection()->GetNextItem ();
1320  UASSERT(renderer);
1321  renderer->RemoveActor(_octomapActor);
1322  _octomapActor = 0;
1323  }
1324 #endif
1325 }
1326 
1328  const pcl::TextureMesh &mesh,
1329  const cv::Mat & image,
1330  const std::string &id,
1331  int viewport)
1332 {
1333  // Copied from PCL 1.8, modified to ignore vertex color and accept only one material (loaded from memory instead of file)
1334 
1335 #if VTK_MAJOR_VERSION >= 7
1336  pcl::visualization::ShapeActorMap::iterator am_it = _visualizer->getShapeActorMap()->find (id);
1337  if (am_it != _visualizer->getShapeActorMap()->end ())
1338 #else
1339  pcl::visualization::CloudActorMap::iterator am_it = _visualizer->getCloudActorMap()->find (id);
1340  if (am_it != _visualizer->getCloudActorMap()->end ())
1341 #endif
1342  {
1343  PCL_ERROR ("[PCLVisualizer::addTextureMesh] A shape with id <%s> already exists!"
1344  " Please choose a different id and retry.\n",
1345  id.c_str ());
1346  return (false);
1347  }
1348  // no texture materials --> exit
1349  if (mesh.tex_materials.size () == 0)
1350  {
1351  PCL_ERROR("[PCLVisualizer::addTextureMesh] No textures found!\n");
1352  return (false);
1353  }
1354  else if (mesh.tex_materials.size() > 1)
1355  {
1356  PCL_ERROR("[PCLVisualizer::addTextureMesh] only one material per mesh is supported!\n");
1357  return (false);
1358  }
1359  // polygons are mapped to texture materials
1360  if (mesh.tex_materials.size () != mesh.tex_polygons.size ())
1361  {
1362  PCL_ERROR("[PCLVisualizer::addTextureMesh] Materials number %lu differs from polygons number %lu!\n",
1363  mesh.tex_materials.size (), mesh.tex_polygons.size ());
1364  return (false);
1365  }
1366  // each texture material should have its coordinates set
1367  if (mesh.tex_materials.size () != mesh.tex_coordinates.size ())
1368  {
1369  PCL_ERROR("[PCLVisualizer::addTextureMesh] Coordinates number %lu differs from materials number %lu!\n",
1370  mesh.tex_coordinates.size (), mesh.tex_materials.size ());
1371  return (false);
1372  }
1373  // total number of vertices
1374  std::size_t nb_vertices = 0;
1375  for (std::size_t i = 0; i < mesh.tex_polygons.size (); ++i)
1376  nb_vertices+= mesh.tex_polygons[i].size ();
1377  // no vertices --> exit
1378  if (nb_vertices == 0)
1379  {
1380  PCL_ERROR("[PCLVisualizer::addTextureMesh] No vertices found!\n");
1381  return (false);
1382  }
1383  // total number of coordinates
1384  std::size_t nb_coordinates = 0;
1385  for (std::size_t i = 0; i < mesh.tex_coordinates.size (); ++i)
1386  nb_coordinates+= mesh.tex_coordinates[i].size ();
1387  // no texture coordinates --> exit
1388  if (nb_coordinates == 0)
1389  {
1390  PCL_ERROR("[PCLVisualizer::addTextureMesh] No textures coordinates found!\n");
1391  return (false);
1392  }
1393 
1394  // Create points from mesh.cloud
1397  bool has_color = false;
1399 
1400  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ> ());
1401  pcl::fromPCLPointCloud2 (mesh.cloud, *cloud);
1402  // no points --> exit
1403  if (cloud->points.size () == 0)
1404  {
1405  PCL_ERROR("[PCLVisualizer::addTextureMesh] Cloud is empty!\n");
1406  return (false);
1407  }
1408  pcl::visualization::PCLVisualizer::convertToVtkMatrix (cloud->sensor_origin_, cloud->sensor_orientation_, transformation);
1409  poly_points->SetNumberOfPoints (cloud->points.size ());
1410  for (std::size_t i = 0; i < cloud->points.size (); ++i)
1411  {
1412  const pcl::PointXYZ &p = cloud->points[i];
1413  poly_points->InsertPoint (i, p.x, p.y, p.z);
1414  }
1415 
1416  //create polys from polyMesh.tex_polygons
1418  for (std::size_t i = 0; i < mesh.tex_polygons.size (); i++)
1419  {
1420  for (std::size_t j = 0; j < mesh.tex_polygons[i].size (); j++)
1421  {
1422  std::size_t n_points = mesh.tex_polygons[i][j].vertices.size ();
1423  polys->InsertNextCell (int (n_points));
1424  for (std::size_t k = 0; k < n_points; k++)
1425  polys->InsertCellPoint (mesh.tex_polygons[i][j].vertices[k]);
1426  }
1427  }
1428 
1430  polydata->SetPolys (polys);
1431  polydata->SetPoints (poly_points);
1432  if (has_color)
1433  polydata->GetPointData()->SetScalars(colors);
1434 
1436 #if VTK_MAJOR_VERSION < 6
1437  mapper->SetInput (polydata);
1438 #else
1439  mapper->SetInputData (polydata);
1440 #endif
1441 
1442 #if VTK_MAJOR_VERSION >= 7
1444 #else
1446 #endif
1447  vtkTextureUnitManager* tex_manager = vtkOpenGLRenderWindow::SafeDownCast (_visualizer->getRenderWindow())->GetTextureUnitManager ();
1448  if (!tex_manager)
1449  return (false);
1450 
1452  // fill vtkTexture from pcl::TexMaterial structure
1454  cvImageToVtk->SetImage(image);
1455  cvImageToVtk->Update();
1456  texture->SetInputConnection(cvImageToVtk->GetOutputPort());
1457 
1458  // set texture coordinates
1460  coordinates->SetNumberOfComponents (2);
1461  coordinates->SetNumberOfTuples (mesh.tex_coordinates[0].size ());
1462  for (std::size_t tc = 0; tc < mesh.tex_coordinates[0].size (); ++tc)
1463  {
1464  const Eigen::Vector2f &uv = mesh.tex_coordinates[0][tc];
1465  coordinates->SetTuple2 (tc, (double)uv[0], (double)uv[1]);
1466  }
1467  coordinates->SetName ("TCoords");
1468  polydata->GetPointData ()->SetTCoords(coordinates);
1469  // apply texture
1470  actor->SetTexture (texture);
1471 
1472  // set mapper
1473  actor->SetMapper (mapper);
1474 
1475  //_visualizer->addActorToRenderer (actor, viewport);
1476  // Add it to all renderers
1477  _visualizer->getRendererCollection()->InitTraversal ();
1478  vtkRenderer* renderer = NULL;
1479  int i = 0;
1480  while ((renderer = _visualizer->getRendererCollection()->GetNextItem ()) != NULL)
1481  {
1482  // Should we add the actor to all renderers?
1483  if (viewport == 0)
1484  {
1485  renderer->AddActor (actor);
1486  }
1487  else if (viewport == i) // add the actor only to the specified viewport
1488  {
1489  renderer->AddActor (actor);
1490  }
1491  ++i;
1492  }
1493 
1494  // Save the pointer/ID pair to the global actor map
1495 #if VTK_MAJOR_VERSION >= 7
1496  (*_visualizer->getShapeActorMap())[id] = actor;
1497 #else
1498  (*_visualizer->getCloudActorMap())[id].actor = actor;
1499  // Save the viewpoint transformation matrix to the global actor map
1500  (*_visualizer->getCloudActorMap())[id].viewpoint_transformation_ = transformation;
1501 #endif
1502 
1503 #if VTK_MAJOR_VERSION >= 7
1504  actor->GetProperty()->SetAmbient(0.1);
1505 #else
1506  actor->GetProperty()->SetAmbient(0.5);
1507 #endif
1508  actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
1509  actor->GetProperty()->SetInterpolation(_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
1510  actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
1511  actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
1512  actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
1513  return true;
1514 }
1515 
1517  const cv::Mat & map8U,
1518  float resolution, // cell size
1519  float xMin,
1520  float yMin,
1521  float opacity)
1522 {
1523  UASSERT(map8U.channels() == 1 && map8U.type() == CV_8U);
1524 
1525  float xSize = float(map8U.cols) * resolution;
1526  float ySize = float(map8U.rows) * resolution;
1527 
1528  UDEBUG("resolution=%f, xSize=%f, ySize=%f, xMin=%f, yMin=%f", resolution, xSize, ySize, xMin, yMin);
1529 #if VTK_MAJOR_VERSION >= 7
1530  if(_visualizer->getShapeActorMap()->find("map") != _visualizer->getShapeActorMap()->end())
1531  {
1532  _visualizer->removeShape("map");
1533  }
1534 #else
1535  if(_visualizer->getCloudActorMap()->find("map") != _visualizer->getCloudActorMap()->end())
1536  {
1537  _visualizer->removePointCloud("map");
1538  }
1539 #endif
1540 
1541  if(xSize > 0.0f && ySize > 0.0f)
1542  {
1543  pcl::TextureMeshPtr mesh(new pcl::TextureMesh());
1544  pcl::PointCloud<pcl::PointXYZ> cloud;
1545  cloud.push_back(pcl::PointXYZ(xMin, yMin, 0));
1546  cloud.push_back(pcl::PointXYZ(xSize+xMin, yMin, 0));
1547  cloud.push_back(pcl::PointXYZ(xSize+xMin, ySize+yMin, 0));
1548  cloud.push_back(pcl::PointXYZ(xMin, ySize+yMin, 0));
1549  pcl::toPCLPointCloud2(cloud, mesh->cloud);
1550 
1551  std::vector<pcl::Vertices> polygons(1);
1552  polygons[0].vertices.push_back(0);
1553  polygons[0].vertices.push_back(1);
1554  polygons[0].vertices.push_back(2);
1555  polygons[0].vertices.push_back(3);
1556  polygons[0].vertices.push_back(0);
1557  mesh->tex_polygons.push_back(polygons);
1558 
1559  // default texture materials parameters
1560  pcl::TexMaterial material;
1561  material.tex_file = "";
1562  mesh->tex_materials.push_back(material);
1563 
1564 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
1565  std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > coordinates;
1566 #else
1567  std::vector<Eigen::Vector2f> coordinates;
1568 #endif
1569  coordinates.push_back(Eigen::Vector2f(0,1));
1570  coordinates.push_back(Eigen::Vector2f(1,1));
1571  coordinates.push_back(Eigen::Vector2f(1,0));
1572  coordinates.push_back(Eigen::Vector2f(0,0));
1573  mesh->tex_coordinates.push_back(coordinates);
1574 
1575  this->addTextureMesh(*mesh, map8U, "map", 1);
1576  setCloudOpacity("map", opacity);
1577  }
1578  return true;
1579 }
1580 
1582 {
1583 #if VTK_MAJOR_VERSION >= 7
1584  if(_visualizer->getShapeActorMap()->find("map") != _visualizer->getShapeActorMap()->end())
1585  {
1586  _visualizer->removeShape("map");
1587  }
1588 #else
1589  if(_visualizer->getCloudActorMap()->find("map") != _visualizer->getCloudActorMap()->end())
1590  {
1591  _visualizer->removePointCloud("map");
1592  }
1593 #endif
1594 }
1595 
1597  const std::string & id,
1598  const Transform & transform,
1599  double scale,
1600  bool foreground)
1601 {
1602  if(id.empty())
1603  {
1604  UERROR("id should not be empty!");
1605  return;
1606  }
1607 
1608  removeCoordinate(id);
1609 
1610  if(!transform.isNull())
1611  {
1612  _coordinates.insert(id);
1613 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
1614  _visualizer->addCoordinateSystem(scale*_coordinateFrameScale, transform.toEigen3f(), id, foreground?3:2);
1615 #else
1616  // Well, on older versions, just update the main coordinate
1617  _visualizer->addCoordinateSystem(scale*_coordinateFrameScale, transform.toEigen3f(), 0);
1618 #endif
1619  }
1620 }
1621 
1623  const std::string & id,
1624  const Transform & pose)
1625 {
1626 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
1627  if(_coordinates.find(id) != _coordinates.end() && !pose.isNull())
1628  {
1629  UDEBUG("Updating pose %s to %s", id.c_str(), pose.prettyPrint().c_str());
1630  return _visualizer->updateCoordinateSystemPose(id, pose.toEigen3f());
1631  }
1632 #else
1633  UERROR("CloudViewer::updateCoordinatePose() is not available on PCL < 1.7.2");
1634 #endif
1635  return false;
1636 }
1637 
1638 void CloudViewer::removeCoordinate(const std::string & id)
1639 {
1640  if(id.empty())
1641  {
1642  UERROR("id should not be empty!");
1643  return;
1644  }
1645 
1646  if(_coordinates.find(id) != _coordinates.end())
1647  {
1648 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
1649  _visualizer->removeCoordinateSystem(id);
1650 #else
1651  // Well, on older versions, just update the main coordinate
1652  _visualizer->removeCoordinateSystem(0);
1653 #endif
1654  _coordinates.erase(id);
1655  }
1656 }
1657 
1658 void CloudViewer::removeAllCoordinates(const std::string & prefix)
1659 {
1660  std::set<std::string> coordinates = _coordinates;
1661  for(std::set<std::string>::iterator iter = coordinates.begin(); iter!=coordinates.end(); ++iter)
1662  {
1663  if(prefix.empty() || iter->find(prefix) != std::string::npos)
1664  {
1665  this->removeCoordinate(*iter);
1666  }
1667  }
1668  UASSERT(!prefix.empty() || _coordinates.empty());
1669 }
1670 
1672  const std::string & id,
1673  const Transform & from,
1674  const Transform & to,
1675  const QColor & color,
1676  bool arrow,
1677  bool foreground)
1678 {
1679  if(id.empty())
1680  {
1681  UERROR("id should not be empty!");
1682  return;
1683  }
1684 
1685  removeLine(id);
1686 
1687  if(!from.isNull() && !to.isNull())
1688  {
1689  _lines.insert(id);
1690 
1691  QColor c = Qt::gray;
1692  if(color.isValid())
1693  {
1694  c = color;
1695  }
1696 
1697  pcl::PointXYZ pt1(from.x(), from.y(), from.z());
1698  pcl::PointXYZ pt2(to.x(), to.y(), to.z());
1699 
1700  if(arrow)
1701  {
1702  _visualizer->addArrow(pt2, pt1, c.redF(), c.greenF(), c.blueF(), false, id, foreground?3:2);
1703  }
1704  else
1705  {
1706  _visualizer->addLine(pt2, pt1, c.redF(), c.greenF(), c.blueF(), id, foreground?3:2);
1707  }
1708  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1709  }
1710 }
1711 
1712 void CloudViewer::removeLine(const std::string & id)
1713 {
1714  if(id.empty())
1715  {
1716  UERROR("id should not be empty!");
1717  return;
1718  }
1719 
1720  if(_lines.find(id) != _lines.end())
1721  {
1722  _visualizer->removeShape(id);
1723  _lines.erase(id);
1724  }
1725 }
1726 
1728 {
1729  std::set<std::string> arrows = _lines;
1730  for(std::set<std::string>::iterator iter = arrows.begin(); iter!=arrows.end(); ++iter)
1731  {
1732  this->removeLine(*iter);
1733  }
1734  UASSERT(_lines.empty());
1735 }
1736 
1738  const std::string & id,
1739  const Transform & pose,
1740  float radius,
1741  const QColor & color,
1742  bool foreground)
1743 {
1744  if(id.empty())
1745  {
1746  UERROR("id should not be empty!");
1747  return;
1748  }
1749 
1750  removeSphere(id);
1751 
1752  if(!pose.isNull())
1753  {
1754  _spheres.insert(id);
1755 
1756  QColor c = Qt::gray;
1757  if(color.isValid())
1758  {
1759  c = color;
1760  }
1761 
1762  pcl::PointXYZ center(pose.x(), pose.y(), pose.z());
1763  _visualizer->addSphere(center, radius, c.redF(), c.greenF(), c.blueF(), id, foreground?3:2);
1764  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1765  }
1766 }
1767 
1768 void CloudViewer::removeSphere(const std::string & id)
1769 {
1770  if(id.empty())
1771  {
1772  UERROR("id should not be empty!");
1773  return;
1774  }
1775 
1776  if(_spheres.find(id) != _spheres.end())
1777  {
1778  _visualizer->removeShape(id);
1779  _spheres.erase(id);
1780  }
1781 }
1782 
1784 {
1785  std::set<std::string> spheres = _spheres;
1786  for(std::set<std::string>::iterator iter = spheres.begin(); iter!=spheres.end(); ++iter)
1787  {
1788  this->removeSphere(*iter);
1789  }
1790  UASSERT(_spheres.empty());
1791 }
1792 
1794  const std::string & id,
1795  const Transform & pose,
1796  float width,
1797  float height,
1798  float depth,
1799  const QColor & color,
1800  bool wireframe,
1801  bool foreground)
1802 {
1803  if(id.empty())
1804  {
1805  UERROR("id should not be empty!");
1806  return;
1807  }
1808 
1809  removeCube(id);
1810 
1811  if(!pose.isNull())
1812  {
1813  _cubes.insert(id);
1814 
1815  QColor c = Qt::gray;
1816  if(color.isValid())
1817  {
1818  c = color;
1819  }
1820  _visualizer->addCube(Eigen::Vector3f(pose.x(), pose.y(), pose.z()), pose.getQuaternionf(), width, height, depth, id, foreground?3:2);
1821  if(wireframe)
1822  {
1823  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_REPRESENTATION, pcl::visualization::PCL_VISUALIZER_REPRESENTATION_WIREFRAME, id);
1824  }
1825  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, c.redF(), c.greenF(), c.blueF(), id);
1826  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1827  }
1828 }
1829 
1830 void CloudViewer::removeCube(const std::string & id)
1831 {
1832  if(id.empty())
1833  {
1834  UERROR("id should not be empty!");
1835  return;
1836  }
1837 
1838  if(_cubes.find(id) != _cubes.end())
1839  {
1840  _visualizer->removeShape(id);
1841  _cubes.erase(id);
1842  }
1843 }
1844 
1846 {
1847  std::set<std::string> cubes = _cubes;
1848  for(std::set<std::string>::iterator iter = cubes.begin(); iter!=cubes.end(); ++iter)
1849  {
1850  this->removeCube(*iter);
1851  }
1852  UASSERT(_cubes.empty());
1853 }
1854 
1856  const std::string & id,
1857  const Transform & pose,
1858  float width,
1859  float height,
1860  const QColor & color,
1861  bool foreground)
1862 {
1863  addOrUpdateQuad(id, pose, width/2.0f, width/2.0f, height/2.0f, height/2.0f, color, foreground);
1864 }
1865 
1867  const std::string & id,
1868  const Transform & pose,
1869  float widthLeft,
1870  float widthRight,
1871  float heightBottom,
1872  float heightTop,
1873  const QColor & color,
1874  bool foreground)
1875 {
1876  if(id.empty())
1877  {
1878  UERROR("id should not be empty!");
1879  return;
1880  }
1881 
1882  removeQuad(id);
1883 
1884  if(!pose.isNull())
1885  {
1886  _quads.insert(id);
1887 
1888  QColor c = Qt::gray;
1889  if(color.isValid())
1890  {
1891  c = color;
1892  }
1893 
1894  // Create four points (must be in counter clockwise order)
1895  double p0[3] = {0.0, -widthLeft, heightTop};
1896  double p1[3] = {0.0, -widthLeft, -heightBottom};
1897  double p2[3] = {0.0, widthRight, -heightBottom};
1898  double p3[3] = {0.0, widthRight, heightTop};
1899 
1900  // Add the points to a vtkPoints object
1903  points->InsertNextPoint(p0);
1904  points->InsertNextPoint(p1);
1905  points->InsertNextPoint(p2);
1906  points->InsertNextPoint(p3);
1907 
1908  // Create a quad on the four points
1911  quad->GetPointIds()->SetId(0,0);
1912  quad->GetPointIds()->SetId(1,1);
1913  quad->GetPointIds()->SetId(2,2);
1914  quad->GetPointIds()->SetId(3,3);
1915 
1916  // Create a cell array to store the quad in
1919  quads->InsertNextCell(quad);
1920 
1921  // Create a polydata to store everything in
1922  vtkSmartPointer<vtkPolyData> polydata =
1924 
1925  // Add the points and quads to the dataset
1926  polydata->SetPoints(points);
1927  polydata->SetPolys(quads);
1928 
1929  // Setup actor and mapper
1932 #if VTK_MAJOR_VERSION <= 5
1933  mapper->SetInput(polydata);
1934 #else
1935  mapper->SetInputData(polydata);
1936 #endif
1937 
1940  actor->SetMapper(mapper);
1941  actor->GetProperty()->SetColor(c.redF(), c.greenF(), c.blueF());
1942 
1943  //_visualizer->addActorToRenderer (actor, viewport);
1944  // Add it to all renderers
1945  _visualizer->getRendererCollection()->InitTraversal ();
1946  vtkRenderer* renderer = NULL;
1947  int i = 0;
1948  while ((renderer = _visualizer->getRendererCollection()->GetNextItem ()) != NULL)
1949  {
1950  if ((foreground?3:2) == i) // add the actor only to the specified viewport
1951  {
1952  renderer->AddActor (actor);
1953  }
1954  ++i;
1955  }
1956 
1957  // Save the pointer/ID pair to the global actor map
1958  (*_visualizer->getCloudActorMap())[id].actor = actor;
1959 
1960  // Save the viewpoint transformation matrix to the global actor map
1962  pcl::visualization::PCLVisualizer::convertToVtkMatrix (pose.toEigen3f().matrix (), transformation);
1963  (*_visualizer->getCloudActorMap())[id].viewpoint_transformation_ = transformation;
1964  (*_visualizer->getCloudActorMap())[id].actor->SetUserMatrix (transformation);
1965  (*_visualizer->getCloudActorMap())[id].actor->Modified ();
1966 
1967  (*_visualizer->getCloudActorMap())[id].actor->GetProperty()->SetLighting(false);
1968  _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1969  }
1970 }
1971 
1972 void CloudViewer::removeQuad(const std::string & id)
1973 {
1974  if(id.empty())
1975  {
1976  UERROR("id should not be empty!");
1977  return;
1978  }
1979 
1980  if(_quads.find(id) != _quads.end())
1981  {
1982  _visualizer->removeShape(id);
1983  _quads.erase(id);
1984  }
1985 }
1986 
1988 {
1989  std::set<std::string> quads = _quads;
1990  for(std::set<std::string>::iterator iter = quads.begin(); iter!=quads.end(); ++iter)
1991  {
1992  this->removeQuad(*iter);
1993  }
1994  UASSERT(_quads.empty());
1995 }
1996 
1997 static const float frustum_vertices[] = {
1998  0.0f, 0.0f, 0.0f,
1999  1.0f, 1.0f, 1.0f,
2000  1.0f, -1.0f, 1.0f,
2001  -1.0f, -1.0f, 1.0f,
2002  -1.0f, 1.0f, 1.0f};
2003 
2004 static const int frustum_indices[] = {
2005  1, 2, 3, 4, 1, 0, 2, 0, 3, 0, 4};
2006 
2008  const std::string & id,
2009  const Transform & pose,
2010  const Transform & localTransform,
2011  double scale,
2012  const QColor & color,
2013  float fovX,
2014  float fovY)
2015 {
2016  if(id.empty())
2017  {
2018  UERROR("id should not be empty!");
2019  return;
2020  }
2021 
2022 #if PCL_VERSION_COMPARE(<, 1, 7, 2)
2023  this->removeFrustum(id);
2024 #endif
2025 
2026  if(!pose.isNull())
2027  {
2028  if(_frustums.find(id)==_frustums.end())
2029  {
2030  _frustums.insert(id, Transform());
2031 
2032  int frustumSize = sizeof(frustum_vertices)/sizeof(float);
2033  UASSERT(frustumSize>0 && frustumSize % 3 == 0);
2034  frustumSize/=3;
2035  pcl::PointCloud<pcl::PointXYZ> frustumPoints;
2036  frustumPoints.resize(frustumSize);
2037  float scaleX = tan((fovX>0?fovX:1.1)/2.0f) * scale;
2038  float scaleY = tan((fovY>0?fovY:0.85)/2.0f) * scale;
2039  float scaleZ = scale;
2040  QColor c = Qt::gray;
2041  if(color.isValid())
2042  {
2043  c = color;
2044  }
2045  Transform opticalRotInv(0, -1, 0, 0, 0, 0, -1, 0, 1, 0, 0, 0);
2046 
2047 #if PCL_VERSION_COMPARE(<, 1, 7, 2)
2048  Eigen::Affine3f t = (pose*localTransform).toEigen3f();
2049 #else
2050  Eigen::Affine3f t = (localTransform).toEigen3f();
2051 #endif
2052  for(int i=0; i<frustumSize; ++i)
2053  {
2054  frustumPoints[i].x = frustum_vertices[i*3]*scaleX;
2055  frustumPoints[i].y = frustum_vertices[i*3+1]*scaleY;
2056  frustumPoints[i].z = frustum_vertices[i*3+2]*scaleZ;
2057  frustumPoints[i] = pcl::transformPoint(frustumPoints[i], t);
2058  }
2059 
2060  pcl::PolygonMesh mesh;
2061  pcl::Vertices vertices;
2062  vertices.vertices.resize(sizeof(frustum_indices)/sizeof(int));
2063  for(unsigned int i=0; i<vertices.vertices.size(); ++i)
2064  {
2065  vertices.vertices[i] = frustum_indices[i];
2066  }
2067  pcl::toPCLPointCloud2(frustumPoints, mesh.cloud);
2068  mesh.polygons.push_back(vertices);
2069  _visualizer->addPolylineFromPolygonMesh(mesh, id, 2);
2070  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, c.redF(), c.greenF(), c.blueF(), id);
2071  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
2072  }
2073 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2074  if(!this->updateFrustumPose(id, pose))
2075  {
2076  UERROR("Failed updating pose of frustum %s!?", id.c_str());
2077  }
2078 #endif
2079  }
2080  else
2081  {
2082  removeFrustum(id);
2083  }
2084 }
2085 
2087  const std::string & id,
2088  const Transform & pose)
2089 {
2090 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2091  QMap<std::string, Transform>::iterator iter=_frustums.find(id);
2092  if(iter != _frustums.end() && !pose.isNull())
2093  {
2094  if(iter.value() == pose)
2095  {
2096  // same pose, just return
2097  return true;
2098  }
2099 
2100  pcl::visualization::ShapeActorMap::iterator am_it = _visualizer->getShapeActorMap()->find (id);
2101 
2102  vtkActor* actor;
2103 
2104  if (am_it == _visualizer->getShapeActorMap()->end ())
2105  return (false);
2106  else
2107  actor = vtkActor::SafeDownCast (am_it->second);
2108 
2109  if (!actor)
2110  return (false);
2111 
2113 
2114  pcl::visualization::PCLVisualizer::convertToVtkMatrix (pose.toEigen3f().matrix (), matrix);
2115 
2116  actor->SetUserMatrix (matrix);
2117  actor->Modified ();
2118 
2119  iter.value() = pose;
2120 
2121  return true;
2122  }
2123 #else
2124  UERROR("updateFrustumPose() cannot be used with PCL<1.7.2. Use addOrUpdateFrustum() instead.");
2125 #endif
2126  return false;
2127 }
2128 
2129 void CloudViewer::removeFrustum(const std::string & id)
2130 {
2131  if(id.empty())
2132  {
2133  UERROR("id should not be empty!");
2134  return;
2135  }
2136 
2137  if(_frustums.find(id) != _frustums.end())
2138  {
2139  _visualizer->removeShape(id);
2140  _frustums.remove(id);
2141  }
2142 }
2143 
2144 void CloudViewer::removeAllFrustums(bool exceptCameraReference)
2145 {
2146  QMap<std::string, Transform> frustums = _frustums;
2147  for(QMap<std::string, Transform>::iterator iter = frustums.begin(); iter!=frustums.end(); ++iter)
2148  {
2149  if(!exceptCameraReference || !uStrContains(iter.key(), "reference_frustum"))
2150  {
2151  this->removeFrustum(iter.key());
2152  }
2153  }
2154  UASSERT(exceptCameraReference || _frustums.empty());
2155 }
2156 
2158  const std::string & id,
2159  const pcl::PointCloud<pcl::PointXYZ>::Ptr & graph,
2160  const QColor & color)
2161 {
2162  if(id.empty())
2163  {
2164  UERROR("id should not be empty!");
2165  return;
2166  }
2167 
2168  removeGraph(id);
2169 
2170  if(graph->size())
2171  {
2172  _graphes.insert(id);
2173 
2174  pcl::PolygonMesh mesh;
2175  pcl::Vertices vertices;
2176  vertices.vertices.resize(graph->size());
2177  for(unsigned int i=0; i<vertices.vertices.size(); ++i)
2178  {
2179  vertices.vertices[i] = i;
2180  }
2181  pcl::toPCLPointCloud2(*graph, mesh.cloud);
2182  mesh.polygons.push_back(vertices);
2183  _visualizer->addPolylineFromPolygonMesh(mesh, id, 2);
2184  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, color.redF(), color.greenF(), color.blueF(), id);
2185  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, color.alphaF(), id);
2186 
2187  pcl::PCLPointCloud2Ptr binaryCloud(new pcl::PCLPointCloud2);
2188  pcl::toPCLPointCloud2(*graph, *binaryCloud);
2189  this->addCloud(id+"_nodes", binaryCloud, Transform::getIdentity(), false, false, false, color, 2);
2190  this->setCloudPointSize(id+"_nodes", 5);
2191  }
2192 }
2193 
2194 void CloudViewer::removeGraph(const std::string & id)
2195 {
2196  if(id.empty())
2197  {
2198  UERROR("id should not be empty!");
2199  return;
2200  }
2201 
2202  if(_graphes.find(id) != _graphes.end())
2203  {
2204  _visualizer->removeShape(id);
2205  _graphes.erase(id);
2206  removeCloud(id+"_nodes");
2207  }
2208 }
2209 
2211 {
2212  std::set<std::string> graphes = _graphes;
2213  for(std::set<std::string>::iterator iter = graphes.begin(); iter!=graphes.end(); ++iter)
2214  {
2215  this->removeGraph(*iter);
2216  }
2217  UASSERT(_graphes.empty());
2218 }
2219 
2221  const std::string & id,
2222  const std::string & text,
2223  const Transform & position,
2224  double scale,
2225  const QColor & color,
2226  bool foreground)
2227 {
2228  if(id.empty())
2229  {
2230  UERROR("id should not be empty!");
2231  return;
2232  }
2233 
2234  removeText(id);
2235 
2236  if(!position.isNull())
2237  {
2238  _texts.insert(id);
2239  _visualizer->addText3D(
2240  text,
2241  pcl::PointXYZ(position.x(), position.y(), position.z()),
2242  scale,
2243  color.redF(),
2244  color.greenF(),
2245  color.blueF(),
2246  id,
2247  foreground?3:2);
2248  }
2249 }
2250 
2251 void CloudViewer::removeText(const std::string & id)
2252 {
2253  if(id.empty())
2254  {
2255  UERROR("id should not be empty!");
2256  return;
2257  }
2258 
2259  if(_texts.find(id) != _texts.end())
2260  {
2261  _visualizer->removeText3D(id);
2262  _texts.erase(id);
2263  }
2264 }
2265 
2267 {
2268  std::set<std::string> texts = _texts;
2269  for(std::set<std::string>::iterator iter = texts.begin(); iter!=texts.end(); ++iter)
2270  {
2271  this->removeText(*iter);
2272  }
2273  UASSERT(_texts.empty());
2274 }
2275 
2277 {
2278  return _aShowTrajectory->isChecked();
2279 }
2280 
2282 {
2283  return _maxTrajectorySize;
2284 }
2285 
2287 {
2288  _aShowTrajectory->setChecked(shown);
2289 }
2290 
2291 void CloudViewer::setTrajectorySize(unsigned int value)
2292 {
2293  _maxTrajectorySize = value;
2294 }
2295 
2297 {
2298  _trajectory->clear();
2299  _visualizer->removeShape("trajectory");
2300  this->refreshView();
2301 }
2302 
2304 {
2305  return _aShowCameraAxis->isChecked();
2306 }
2307 
2309 {
2310  if(!shown)
2311  {
2312  this->removeCoordinate("reference");
2313  }
2314  else
2315  {
2316  this->addOrUpdateCoordinate("reference", Transform::getIdentity(), 0.2);
2317  }
2318  this->refreshView();
2319  _aShowCameraAxis->setChecked(shown);
2320 }
2321 
2323 {
2324  return _coordinateFrameScale;
2325 }
2326 
2328 {
2329  _coordinateFrameScale = std::max(0.1, scale);
2330 }
2331 
2333 {
2334  return _aShowFrustum->isChecked();
2335 }
2336 
2338 {
2339  return _frustumScale;
2340 }
2341 
2343 {
2344  return _frustumColor;
2345 }
2346 
2348 {
2349  if(!shown)
2350  {
2351  QMap<std::string, Transform> frustumsCopy = _frustums;
2352  for(QMap<std::string, Transform>::iterator iter=frustumsCopy.begin(); iter!=frustumsCopy.end(); ++iter)
2353  {
2354  if(uStrContains(iter.key(), "reference_frustum"))
2355  {
2356  this->removeFrustum(iter.key());
2357  }
2358  }
2359  std::set<std::string> linesCopy = _lines;
2360  for(std::set<std::string>::iterator iter=linesCopy.begin(); iter!=linesCopy.end(); ++iter)
2361  {
2362  if(uStrContains(*iter, "reference_frustum_line"))
2363  {
2364  this->removeLine(*iter);
2365  }
2366  }
2367  this->refreshView();
2368  }
2369  _aShowFrustum->setChecked(shown);
2370 }
2371 
2373 {
2374  _frustumScale = value;
2375 }
2376 
2378 {
2379  if(!value.isValid())
2380  {
2381  value = Qt::gray;
2382  }
2383  for(QMap<std::string, Transform>::iterator iter=_frustums.begin(); iter!=_frustums.end(); ++iter)
2384  {
2385  _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, value.redF(), value.greenF(), value.blueF(), iter.key());
2386  }
2387  this->refreshView();
2388  _frustumColor = value;
2389 }
2390 
2392 {
2393  _lastCameraOrientation= _lastCameraPose = cv::Vec3f(0,0,0);
2394  if((_aFollowCamera->isChecked() || _aLockCamera->isChecked()) && !_lastPose.isNull())
2395  {
2396  // reset relative to last current pose
2397  cv::Point3f pt = util3d::transformPoint(cv::Point3f(_lastPose.x(), _lastPose.y(), _lastPose.z()), ( _lastPose.rotation()*Transform(-1, 0, 0)).translation());
2398  if(_aCameraOrtho->isChecked())
2399  {
2400  this->setCameraPosition(
2401  _lastPose.x(), _lastPose.y(), _lastPose.z()+5,
2402  _lastPose.x(), _lastPose.y(), _lastPose.z(),
2403  1, 0, 0);
2404  }
2405  else if(_aLockViewZ->isChecked())
2406  {
2407  this->setCameraPosition(
2408  pt.x, pt.y, pt.z,
2409  _lastPose.x(), _lastPose.y(), _lastPose.z(),
2410  0, 0, 1);
2411  }
2412  else
2413  {
2414  this->setCameraPosition(
2415  pt.x, pt.y, pt.z,
2416  _lastPose.x(), _lastPose.y(), _lastPose.z(),
2418  }
2419  }
2420  else if(_aCameraOrtho->isChecked())
2421  {
2422  this->setCameraPosition(
2423  0, 0, 5,
2424  0, 0, 0,
2425  1, 0, 0);
2426  }
2427  else
2428  {
2429  this->setCameraPosition(
2430  -1, 0, 0,
2431  0, 0, 0,
2432  0, 0, 1);
2433  }
2434 }
2435 
2437 {
2438  QMap<std::string, Transform> addedClouds = _addedClouds;
2439  QList<std::string> ids = _addedClouds.keys();
2440  for(QList<std::string>::iterator iter = ids.begin(); iter!=ids.end(); ++iter)
2441  {
2442  removeCloud(*iter);
2443  }
2444  UASSERT(_addedClouds.empty());
2445  UASSERT(_locators.empty());
2446 }
2447 
2448 
2449 bool CloudViewer::removeCloud(const std::string & id)
2450 {
2451  bool success = _visualizer->removePointCloud(id);
2452 #if VTK_MAJOR_VERSION >= 7
2453  if(!success)
2454  {
2455  success = _visualizer->removeShape(id);
2456  }
2457 #endif
2458  _visualizer->removePointCloud(id+"-normals");
2459  _addedClouds.remove(id); // remove after visualizer
2460  _addedClouds.remove(id+"-normals");
2461  _locators.erase(id);
2462  return success;
2463 }
2464 
2465 bool CloudViewer::getPose(const std::string & id, Transform & pose)
2466 {
2467  if(_addedClouds.contains(id))
2468  {
2469  pose = _addedClouds.value(id);
2470  return true;
2471  }
2472  return false;
2473 }
2474 
2476 {
2477  if(_lastPose.isNull())
2478  {
2479  return Transform::getIdentity();
2480  }
2481  return _lastPose;
2482 }
2483 
2484 std::string CloudViewer::getIdByActor(vtkProp * actor) const
2485 {
2486  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
2487  for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2488  {
2489  if(iter->second.actor.GetPointer() == actor)
2490  {
2491  return iter->first;
2492  }
2493  }
2494 
2495 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2496  // getShapeActorMap() not available in version < 1.7.2
2497  pcl::visualization::ShapeActorMapPtr shapeActorMap = _visualizer->getShapeActorMap();
2498  for(pcl::visualization::ShapeActorMap::iterator iter=shapeActorMap->begin(); iter!=shapeActorMap->end(); ++iter)
2499  {
2500  if(iter->second.GetPointer() == actor)
2501  {
2502  std::string id = iter->first;
2503  while(id.size() && id.at(id.size()-1) == '*')
2504  {
2505  id.erase(id.size()-1);
2506  }
2507 
2508  return id;
2509  }
2510  }
2511 #endif
2512  return std::string();
2513 }
2514 
2515 QColor CloudViewer::getColor(const std::string & id)
2516 {
2517  QColor color;
2518  pcl::visualization::CloudActorMap::iterator iter = _visualizer->getCloudActorMap()->find(id);
2519  if(iter != _visualizer->getCloudActorMap()->end())
2520  {
2521  double r,g,b,a;
2522  iter->second.actor->GetProperty()->GetColor(r,g,b);
2523  a = iter->second.actor->GetProperty()->GetOpacity();
2524  color.setRgbF(r, g, b, a);
2525  }
2526 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2527  // getShapeActorMap() not available in version < 1.7.2
2528  else
2529  {
2530  std::string idLayer1 = id+"*";
2531  std::string idLayer2 = id+"**";
2532  pcl::visualization::ShapeActorMap::iterator iter = _visualizer->getShapeActorMap()->find(id);
2533  if(iter == _visualizer->getShapeActorMap()->end())
2534  {
2535  iter = _visualizer->getShapeActorMap()->find(idLayer1);
2536  if(iter == _visualizer->getShapeActorMap()->end())
2537  {
2538  iter = _visualizer->getShapeActorMap()->find(idLayer2);
2539  }
2540  }
2541  if(iter != _visualizer->getShapeActorMap()->end())
2542  {
2543  vtkActor * actor = vtkActor::SafeDownCast(iter->second);
2544  if(actor)
2545  {
2546  double r,g,b,a;
2547  actor->GetProperty()->GetColor(r,g,b);
2548  a = actor->GetProperty()->GetOpacity();
2549  color.setRgbF(r, g, b, a);
2550  }
2551  }
2552  }
2553 #endif
2554  return color;
2555 }
2556 
2557 void CloudViewer::setColor(const std::string & id, const QColor & color)
2558 {
2559  pcl::visualization::CloudActorMap::iterator iter = _visualizer->getCloudActorMap()->find(id);
2560  if(iter != _visualizer->getCloudActorMap()->end())
2561  {
2562  iter->second.actor->GetProperty()->SetColor(color.redF(),color.greenF(),color.blueF());
2563  iter->second.actor->GetProperty()->SetOpacity(color.alphaF());
2564  }
2565 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2566  // getShapeActorMap() not available in version < 1.7.2
2567  else
2568  {
2569  std::string idLayer1 = id+"*";
2570  std::string idLayer2 = id+"**";
2571  pcl::visualization::ShapeActorMap::iterator iter = _visualizer->getShapeActorMap()->find(id);
2572  if(iter == _visualizer->getShapeActorMap()->end())
2573  {
2574  iter = _visualizer->getShapeActorMap()->find(idLayer1);
2575  if(iter == _visualizer->getShapeActorMap()->end())
2576  {
2577  iter = _visualizer->getShapeActorMap()->find(idLayer2);
2578  }
2579  }
2580  if(iter != _visualizer->getShapeActorMap()->end())
2581  {
2582  vtkActor * actor = vtkActor::SafeDownCast(iter->second);
2583  if(actor)
2584  {
2585  actor->GetProperty()->SetColor(color.redF(),color.greenF(),color.blueF());
2586  actor->GetProperty()->SetOpacity(color.alphaF());
2587  }
2588  }
2589  }
2590 #endif
2591 }
2592 
2593 void CloudViewer::setBackfaceCulling(bool enabled, bool frontfaceCulling)
2594 {
2595  _aBackfaceCulling->setChecked(enabled);
2596  _frontfaceCulling = frontfaceCulling;
2597 
2598  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
2599  for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2600  {
2601  iter->second.actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
2602  iter->second.actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
2603  }
2604 #if VTK_MAJOR_VERSION >= 7
2605  pcl::visualization::ShapeActorMapPtr shapeActorMap = _visualizer->getShapeActorMap();
2606  for(pcl::visualization::ShapeActorMap::iterator iter=shapeActorMap->begin(); iter!=shapeActorMap->end(); ++iter)
2607  {
2608  vtkActor* actor = vtkActor::SafeDownCast (iter->second);
2609  if(actor)
2610  {
2611  actor->GetProperty()->SetBackfaceCulling(_aBackfaceCulling->isChecked());
2612  actor->GetProperty()->SetFrontfaceCulling(_frontfaceCulling);
2613  }
2614  }
2615 #endif
2616  this->refreshView();
2617 }
2618 
2620 {
2621  _aPolygonPicking->setChecked(enabled);
2622 
2623  if(!_aPolygonPicking->isChecked())
2624  {
2626  pp->SetTolerance (pp->GetTolerance());
2627  #if VTK_MAJOR_VERSION > 8
2628  this->interactor()->SetPicker (pp);
2629 #else
2630  this->GetInteractor()->SetPicker (pp);
2631 #endif
2632  setMouseTracking(false);
2633  }
2634  else
2635  {
2637  pp->SetTolerance (pp->GetTolerance());
2638 #if VTK_MAJOR_VERSION > 8
2639  this->interactor()->SetPicker (pp);
2640 #else
2641  this->GetInteractor()->SetPicker (pp);
2642 #endif
2643  setMouseTracking(true);
2644  }
2645 }
2646 
2647 
2648 
2650 {
2651  _renderingRate = rate;
2652  _visualizer->getInteractorStyle()->GetInteractor()->SetDesiredUpdateRate(_renderingRate);
2653 }
2654 
2656 {
2657 #if VTK_MAJOR_VERSION >= 7
2658  _aSetEDLShading->setChecked(on);
2659  _visualizer->getRendererCollection()->InitTraversal ();
2660  vtkRenderer* renderer = NULL;
2661  renderer = _visualizer->getRendererCollection()->GetNextItem ();
2662  renderer = _visualizer->getRendererCollection()->GetNextItem (); // Get Layer 1
2663  UASSERT(renderer);
2664 
2665  vtkOpenGLRenderer* glrenderer = vtkOpenGLRenderer::SafeDownCast(renderer);
2666  UASSERT(glrenderer);
2667  if(on)
2668  {
2669  // EDL shader
2672  edl->SetDelegatePass(basicPasses);
2673  glrenderer->SetPass(edl);
2674  }
2675  else if(glrenderer->GetPass())
2676  {
2677  glrenderer->GetPass()->ReleaseGraphicsResources(NULL);
2678  glrenderer->SetPass(NULL);
2679  }
2680 
2681  this->refreshView();
2682 #else
2683  if(on)
2684  {
2685  UERROR("RTAB-Map must be built with VTK>=7 to enable EDL shading!");
2686  }
2687 #endif
2688 }
2689 
2691 {
2692  _aSetLighting->setChecked(on);
2693  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
2694  for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2695  {
2696  iter->second.actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
2697  }
2698 #if VTK_MAJOR_VERSION >= 7
2699  pcl::visualization::ShapeActorMapPtr shapeActorMap = _visualizer->getShapeActorMap();
2700  for(pcl::visualization::ShapeActorMap::iterator iter=shapeActorMap->begin(); iter!=shapeActorMap->end(); ++iter)
2701  {
2702  vtkActor* actor = vtkActor::SafeDownCast (iter->second);
2703  if(actor && _addedClouds.contains(iter->first))
2704  {
2705  actor->GetProperty()->SetLighting(_aSetLighting->isChecked());
2706  }
2707  }
2708 #endif
2709  this->refreshView();
2710 }
2711 
2713 {
2714  _aSetFlatShading->setChecked(on);
2715  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
2716  for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2717  {
2718  iter->second.actor->GetProperty()->SetInterpolation(_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG); // VTK_FLAT - VTK_GOURAUD - VTK_PHONG
2719  }
2720 #if VTK_MAJOR_VERSION >= 7
2721  pcl::visualization::ShapeActorMapPtr shapeActorMap = _visualizer->getShapeActorMap();
2722  for(pcl::visualization::ShapeActorMap::iterator iter=shapeActorMap->begin(); iter!=shapeActorMap->end(); ++iter)
2723  {
2724  vtkActor* actor = vtkActor::SafeDownCast (iter->second);
2725  if(actor && _addedClouds.contains(iter->first))
2726  {
2727  actor->GetProperty()->SetInterpolation(_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG); // VTK_FLAT - VTK_GOURAUD - VTK_PHONG
2728  }
2729  }
2730 #endif
2731  this->refreshView();
2732 }
2733 
2735 {
2736  _aSetEdgeVisibility->setChecked(visible);
2737  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
2738  for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2739  {
2740  iter->second.actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
2741  }
2742 #if VTK_MAJOR_VERSION >= 7
2743  pcl::visualization::ShapeActorMapPtr shapeActorMap = _visualizer->getShapeActorMap();
2744  for(pcl::visualization::ShapeActorMap::iterator iter=shapeActorMap->begin(); iter!=shapeActorMap->end(); ++iter)
2745  {
2746  vtkActor* actor = vtkActor::SafeDownCast (iter->second);
2747  if(actor && _addedClouds.contains(iter->first))
2748  {
2749  actor->GetProperty()->SetEdgeVisibility(_aSetEdgeVisibility->isChecked());
2750  }
2751  }
2752 #endif
2753  this->refreshView();
2754 }
2755 
2757 {
2758  _visualizer->getRendererCollection()->InitTraversal ();
2759  vtkRenderer* renderer = NULL;
2760  int i =0;
2761  while ((renderer = _visualizer->getRendererCollection()->GetNextItem ()) != NULL)
2762  {
2763  if(i==layer)
2764  {
2765  _visualizer->getInteractorStyle()->SetDefaultRenderer(renderer);
2766  _visualizer->getInteractorStyle()->SetCurrentRenderer(renderer);
2767  return;
2768  }
2769  ++i;
2770  }
2771  UWARN("Could not set layer %d to interactor (layers=%d).", layer, _visualizer->getRendererCollection()->GetNumberOfItems());
2772 }
2773 
2775  float & x, float & y, float & z,
2776  float & focalX, float & focalY, float & focalZ,
2777  float & upX, float & upY, float & upZ) const
2778 {
2779  std::vector<pcl::visualization::Camera> cameras;
2780  _visualizer->getCameras(cameras);
2781  if(cameras.size())
2782  {
2783  x = cameras.begin()->pos[0];
2784  y = cameras.begin()->pos[1];
2785  z = cameras.begin()->pos[2];
2786  focalX = cameras.begin()->focal[0];
2787  focalY = cameras.begin()->focal[1];
2788  focalZ = cameras.begin()->focal[2];
2789  upX = cameras.begin()->view[0];
2790  upY = cameras.begin()->view[1];
2791  upZ = cameras.begin()->view[2];
2792  }
2793  else
2794  {
2795  UERROR("No camera set!?");
2796  }
2797 }
2798 
2800  float x, float y, float z,
2801  float focalX, float focalY, float focalZ,
2802  float upX, float upY, float upZ)
2803 {
2804  vtkRenderer* renderer = NULL;
2805  double boundingBox[6] = {1, -1, 1, -1, 1, -1};
2806 
2807  // compute global bounding box
2808  _visualizer->getRendererCollection()->InitTraversal ();
2809  while ((renderer = _visualizer->getRendererCollection()->GetNextItem ()) != NULL)
2810  {
2811  vtkSmartPointer<vtkCamera> cam = renderer->GetActiveCamera ();
2812  cam->SetPosition (x, y, z);
2813  cam->SetFocalPoint (focalX, focalY, focalZ);
2814  cam->SetViewUp (upX, upY, upZ);
2815 
2816  double BB[6];
2817  renderer->ComputeVisiblePropBounds(BB);
2818  for (int i = 0; i < 6; i++) {
2819  if (i % 2 == 0) {
2820  // Even Index is Min
2821  if (BB[i] < boundingBox[i]) {
2822  boundingBox[i] = BB[i];
2823  }
2824  } else {
2825  // Odd Index is Max
2826  if (BB[i] > boundingBox[i]) {
2827  boundingBox[i] = BB[i];
2828  }
2829  }
2830  }
2831  }
2832 
2833  _visualizer->getRendererCollection()->InitTraversal ();
2834  while ((renderer = _visualizer->getRendererCollection()->GetNextItem ()) != NULL)
2835  {
2836  renderer->ResetCameraClippingRange(boundingBox);
2837  }
2838 
2839  _visualizer->getRenderWindow()->Render ();
2840 }
2841 
2843 {
2844  if(!pose.isNull())
2845  {
2846  Eigen::Affine3f m = pose.toEigen3f();
2847  Eigen::Vector3f pos = m.translation();
2848 
2849  Eigen::Vector3f lastPos(0,0,0);
2850  if(_trajectory->size())
2851  {
2852  lastPos[0]=_trajectory->back().x;
2853  lastPos[1]=_trajectory->back().y;
2854  lastPos[2]=_trajectory->back().z;
2855  }
2856 
2857  _trajectory->push_back(pcl::PointXYZ(pos[0], pos[1], pos[2]));
2858  if(_maxTrajectorySize>0)
2859  {
2860  while(_trajectory->size() > _maxTrajectorySize)
2861  {
2862  _trajectory->erase(_trajectory->begin());
2863  }
2864  }
2865  if(_aShowTrajectory->isChecked())
2866  {
2867  _visualizer->removeShape("trajectory");
2868  pcl::PolygonMesh mesh;
2869  pcl::Vertices vertices;
2870  vertices.vertices.resize(_trajectory->size());
2871  for(unsigned int i=0; i<vertices.vertices.size(); ++i)
2872  {
2873  vertices.vertices[i] = i;
2874  }
2875  pcl::toPCLPointCloud2(*_trajectory, mesh.cloud);
2876  mesh.polygons.push_back(vertices);
2877  _visualizer->addPolylineFromPolygonMesh(mesh, "trajectory", 2);
2878  }
2879 
2880  if(pose != _lastPose || _lastPose.isNull())
2881  {
2882  if(_lastPose.isNull())
2883  {
2885  }
2886 
2887  std::vector<pcl::visualization::Camera> cameras;
2888  _visualizer->getCameras(cameras);
2889 
2890  if(_aLockCamera->isChecked() || _aCameraOrtho->isChecked())
2891  {
2892  //update camera position
2893  Eigen::Vector3f diff = pos - Eigen::Vector3f(_lastPose.x(), _lastPose.y(), _lastPose.z());
2894  cameras.front().pos[0] += diff[0];
2895  cameras.front().pos[1] += diff[1];
2896  cameras.front().pos[2] += diff[2];
2897  cameras.front().focal[0] += diff[0];
2898  cameras.front().focal[1] += diff[1];
2899  cameras.front().focal[2] += diff[2];
2900  }
2901  else if(_aFollowCamera->isChecked())
2902  {
2903  Eigen::Vector3f vPosToFocal = Eigen::Vector3f(cameras.front().focal[0] - cameras.front().pos[0],
2904  cameras.front().focal[1] - cameras.front().pos[1],
2905  cameras.front().focal[2] - cameras.front().pos[2]).normalized();
2906  Eigen::Vector3f zAxis(cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
2907  Eigen::Vector3f yAxis = zAxis.cross(vPosToFocal);
2908  Eigen::Vector3f xAxis = yAxis.cross(zAxis);
2909  Transform PR(xAxis[0], xAxis[1], xAxis[2],0,
2910  yAxis[0], yAxis[1], yAxis[2],0,
2911  zAxis[0], zAxis[1], zAxis[2],0);
2912 
2913  PR.normalizeRotation();
2914 
2915  Transform P(PR[0], PR[1], PR[2], cameras.front().pos[0],
2916  PR[4], PR[5], PR[6], cameras.front().pos[1],
2917  PR[8], PR[9], PR[10], cameras.front().pos[2]);
2918  Transform F(PR[0], PR[1], PR[2], cameras.front().focal[0],
2919  PR[4], PR[5], PR[6], cameras.front().focal[1],
2920  PR[8], PR[9], PR[10], cameras.front().focal[2]);
2921  Transform N = pose;
2922  Transform O = _lastPose;
2923  Transform O2N = O.inverse()*N;
2924  Transform F2O = F.inverse()*O;
2925  Transform T = F2O * O2N * F2O.inverse();
2926  Transform Fp = F * T;
2927  Transform P2F = P.inverse()*F;
2928  Transform Pp = P * P2F * T * P2F.inverse();
2929 
2930  cameras.front().pos[0] = Pp.x();
2931  cameras.front().pos[1] = Pp.y();
2932  cameras.front().pos[2] = Pp.z();
2933  cameras.front().focal[0] = Fp.x();
2934  cameras.front().focal[1] = Fp.y();
2935  cameras.front().focal[2] = Fp.z();
2936  //FIXME: the view up is not set properly...
2937  cameras.front().view[0] = _aLockViewZ->isChecked()?0:Fp[8];
2938  cameras.front().view[1] = _aLockViewZ->isChecked()?0:Fp[9];
2939  cameras.front().view[2] = _aLockViewZ->isChecked()?1:Fp[10];
2940  }
2941 
2942  if(_aShowCameraAxis->isChecked())
2943  {
2944 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2945  if(_coordinates.find("reference") != _coordinates.end())
2946  {
2947  this->updateCoordinatePose("reference", pose);
2948  }
2949  else
2950 #endif
2951  {
2952  this->addOrUpdateCoordinate("reference", pose, 0.2);
2953  }
2954  }
2955 
2956  this->setCameraPosition(
2957  cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
2958  cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
2959  cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
2960  }
2961  }
2962 
2963  _lastPose = pose;
2964 }
2965 
2967 {
2968  std::vector<CameraModel> models;
2969  models.push_back(model.left());
2970  CameraModel right = model.right();
2971  if(!model.left().localTransform().isNull())
2972  {
2973  right.setLocalTransform(model.left().localTransform() * Transform(model.baseline(), 0, 0, 0, 0, 0));
2974  }
2975  models.push_back(right);
2976  updateCameraFrustums(pose, models);
2977 }
2978 
2980 {
2981  std::vector<CameraModel> models;
2982  models.push_back(model);
2983  updateCameraFrustums(pose, models);
2984 }
2985 
2986 void CloudViewer::updateCameraFrustums(const Transform & pose, const std::vector<CameraModel> & models)
2987 {
2988  if(!pose.isNull())
2989  {
2990  if(_aShowFrustum->isChecked())
2991  {
2992  Transform baseToCamera;
2993  for(unsigned int i=0; i<models.size(); ++i)
2994  {
2995  baseToCamera = Transform::getIdentity();
2996  if(!models[i].localTransform().isNull() && !models[i].localTransform().isIdentity())
2997  {
2998  baseToCamera = models[i].localTransform();
2999  }
3000  std::string id = uFormat("reference_frustum_%d", i);
3001  this->removeFrustum(id);
3002  this->addOrUpdateFrustum(id, pose, baseToCamera, _frustumScale, _frustumColor, models[i].fovX(), models[i].fovY());
3003  if(!baseToCamera.isIdentity())
3004  {
3005  this->addOrUpdateLine(uFormat("reference_frustum_line_%d", i), pose, pose * baseToCamera, _frustumColor);
3006  }
3007  }
3008  }
3009  }
3010 }
3011 void CloudViewer::updateCameraFrustums(const Transform & pose, const std::vector<StereoCameraModel> & stereoModels)
3012 {
3013  std::vector<CameraModel> models;
3014  for(size_t i=0; i<stereoModels.size(); ++i)
3015  {
3016  models.push_back(stereoModels[i].left());
3017  CameraModel right = stereoModels[i].right();
3018  if(!stereoModels[i].left().localTransform().isNull())
3019  {
3020  right.setLocalTransform(stereoModels[i].left().localTransform() * Transform(stereoModels[i].baseline(), 0, 0, 0, 0, 0));
3021  }
3022  models.push_back(right);
3023  updateCameraFrustums(pose, models);
3024  }
3025 }
3026 
3028 {
3029  return _defaultBgColor;
3030 }
3031 
3032 void CloudViewer::setDefaultBackgroundColor(const QColor & color)
3033 {
3035  {
3036  setBackgroundColor(color);
3037  }
3038  _defaultBgColor = color;
3039 }
3040 
3041 const QColor & CloudViewer::getBackgroundColor() const
3042 {
3043  return _currentBgColor;
3044 }
3045 
3046 void CloudViewer::setBackgroundColor(const QColor & color)
3047 {
3048  _currentBgColor = color;
3049  _visualizer->setBackgroundColor(color.redF(), color.greenF(), color.blueF());
3050 }
3051 
3052 void CloudViewer::setCloudVisibility(const std::string & id, bool isVisible)
3053 {
3054  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
3055  pcl::visualization::CloudActorMap::iterator iter = cloudActorMap->find(id);
3056  if(iter != cloudActorMap->end())
3057  {
3058  iter->second.actor->SetVisibility(isVisible?1:0);
3059 
3060  iter = cloudActorMap->find(id+"-normals");
3061  if(iter != cloudActorMap->end())
3062  {
3063  iter->second.actor->SetVisibility(isVisible&&_aShowNormals->isChecked()?1:0);
3064  }
3065  }
3066  else
3067  {
3068 #if VTK_MAJOR_VERSION >= 7
3069  pcl::visualization::ShapeActorMapPtr shapeActorMap = _visualizer->getShapeActorMap();
3070  pcl::visualization::ShapeActorMap::iterator iter = shapeActorMap->find(id);
3071  if(iter != shapeActorMap->end())
3072  {
3073  vtkActor* actor = vtkActor::SafeDownCast (iter->second);
3074  if(actor)
3075  {
3076  actor->SetVisibility(isVisible?1:0);
3077  return;
3078  }
3079  }
3080 #endif
3081  UERROR("Cannot find actor named \"%s\".", id.c_str());
3082  }
3083 }
3084 
3085 bool CloudViewer::getCloudVisibility(const std::string & id)
3086 {
3087  pcl::visualization::CloudActorMapPtr cloudActorMap = _visualizer->getCloudActorMap();
3088  pcl::visualization::CloudActorMap::iterator iter = cloudActorMap->find(id);
3089  if(iter != cloudActorMap->end())
3090  {
3091  return iter->second.actor->GetVisibility() != 0;
3092  }
3093  else
3094  {
3095 #if VTK_MAJOR_VERSION >= 7
3096  pcl::visualization::ShapeActorMapPtr shapeActorMap = _visualizer->getShapeActorMap();
3097  pcl::visualization::ShapeActorMap::iterator iter = shapeActorMap->find(id);
3098  if(iter != shapeActorMap->end())
3099  {
3100  vtkActor* actor = vtkActor::SafeDownCast (iter->second);
3101  if(actor)
3102  {
3103  return actor->GetVisibility() != 0;
3104  }
3105  }
3106 #endif
3107  UERROR("Cannot find actor named \"%s\".", id.c_str());
3108  }
3109  return false;
3110 }
3111 
3112 void CloudViewer::setCloudColorIndex(const std::string & id, int index)
3113 {
3114  if(index>0)
3115  {
3116  _visualizer->updateColorHandlerIndex(id, index-1);
3117  }
3118 }
3119 
3120 void CloudViewer::setCloudOpacity(const std::string & id, double opacity)
3121 {
3122  double lastOpacity;
3123  if(_visualizer->getPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, lastOpacity, id))
3124  {
3125  if(lastOpacity != opacity)
3126  {
3127  _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, opacity, id);
3128  }
3129  }
3130 #if VTK_MAJOR_VERSION >= 7
3131  else
3132  {
3133  pcl::visualization::ShapeActorMap::iterator am_it = _visualizer->getShapeActorMap()->find (id);
3134  if (am_it != _visualizer->getShapeActorMap()->end ())
3135  {
3136  vtkActor* actor = vtkActor::SafeDownCast (am_it->second);
3137  if(actor)
3138  {
3139  actor->GetProperty ()->SetOpacity (opacity);
3140  actor->Modified ();
3141  }
3142  }
3143  }
3144 #endif
3145 }
3146 
3147 void CloudViewer::setCloudPointSize(const std::string & id, int size)
3148 {
3149  double lastSize;
3150  if(_visualizer->getPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, lastSize, id))
3151  {
3152  if((int)lastSize != size)
3153  {
3154  _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, (double)size, id);
3155  }
3156  }
3157 }
3158 
3160 {
3161  _aLockCamera->setChecked(enabled);
3162 }
3163 
3165 {
3166  _aFollowCamera->setChecked(enabled);
3167 }
3168 
3170 {
3171  _aLockCamera->setChecked(false);
3172  _aFollowCamera->setChecked(false);
3173 }
3174 
3176 {
3177  _lastCameraOrientation= _lastCameraPose = cv::Vec3f(0,0,0);
3178  _aLockViewZ->setChecked(enabled);
3179 }
3181 {
3182  _lastCameraOrientation= _lastCameraPose = cv::Vec3f(0,0,0);
3183 #if VTK_MAJOR_VERSION > 8
3184  CloudViewerInteractorStyle * interactor = CloudViewerInteractorStyle::SafeDownCast(this->interactor()->GetInteractorStyle());
3185 #else
3186  CloudViewerInteractorStyle * interactor = CloudViewerInteractorStyle::SafeDownCast(this->GetInteractor()->GetInteractorStyle());
3187 #endif
3188  if(interactor)
3189  {
3190  interactor->setOrthoMode(enabled);
3191  this->refreshView();
3192  }
3193  _aCameraOrtho->setChecked(enabled);
3194 }
3196 {
3197  return _aLockCamera->isChecked();
3198 }
3200 {
3201  return _aFollowCamera->isChecked();
3202 }
3204 {
3205  return !_aFollowCamera->isChecked() && !_aLockCamera->isChecked();
3206 }
3208 {
3209  return _aLockViewZ->isChecked();
3210 }
3212 {
3213  return _aCameraOrtho->isChecked();
3214 }
3216 {
3217  return _aBackfaceCulling->isChecked();
3218 }
3220 {
3221  return _frontfaceCulling;
3222 }
3224 {
3225  return _aPolygonPicking->isChecked();
3226 }
3228 {
3229  return _aSetEDLShading->isChecked();
3230 }
3232 {
3233  return _aSetLighting->isChecked();
3234 }
3236 {
3237  return _aSetFlatShading->isChecked();
3238 }
3240 {
3241  return _aSetEdgeVisibility->isChecked();
3242 }
3244 {
3245  return _renderingRate;
3246 }
3247 
3249 {
3250  _aShowGrid->setChecked(shown);
3251  if(shown)
3252  {
3253  this->addGrid();
3254  }
3255  else
3256  {
3257  this->removeGrid();
3258  }
3259 }
3261 {
3262  return _aShowGrid->isChecked();
3263 }
3264 unsigned int CloudViewer::getGridCellCount() const
3265 {
3266  return _gridCellCount;
3267 }
3269 {
3270  return _gridCellSize;
3271 }
3272 void CloudViewer::setGridCellCount(unsigned int count)
3273 {
3274  if(count > 0)
3275  {
3276  _gridCellCount = count;
3277  if(_aShowGrid->isChecked())
3278  {
3279  this->removeGrid();
3280  this->addGrid();
3281  }
3282  }
3283  else
3284  {
3285  UERROR("Cannot set grid cell count < 1, count=%d", count);
3286  }
3287 }
3289 {
3290  if(size > 0)
3291  {
3292  _gridCellSize = size;
3293  if(_aShowGrid->isChecked())
3294  {
3295  this->removeGrid();
3296  this->addGrid();
3297  }
3298  }
3299  else
3300  {
3301  UERROR("Cannot set grid cell size <= 0, value=%f", size);
3302  }
3303 }
3305 {
3306  if(_gridLines.empty())
3307  {
3308  float cellSize = _gridCellSize;
3309  int cellCount = _gridCellCount;
3310  double r=0.5;
3311  double g=0.5;
3312  double b=0.5;
3313  int id = 0;
3314  float min = -float(cellCount/2) * cellSize;
3315  float max = float(cellCount/2) * cellSize;
3316  std::string name;
3317  for(float i=min; i<=max; i += cellSize)
3318  {
3319  //over x
3320  name = uFormat("line%d", ++id);
3321  _visualizer->addLine(
3322  pcl::PointXYZ(i, min, 0.0f),
3323  pcl::PointXYZ(i, max, 0.0f),
3324  r, g, b, name, 2);
3325  _gridLines.push_back(name);
3326  //over y or z
3327  name = uFormat("line%d", ++id);
3328  _visualizer->addLine(
3329  pcl::PointXYZ(min, i, 0),
3330  pcl::PointXYZ(max, i, 0),
3331  r, g, b, name, 2);
3332  _gridLines.push_back(name);
3333  }
3334  // this will update clipping planes
3335  std::vector<pcl::visualization::Camera> cameras;
3336  _visualizer->getCameras(cameras);
3337  this->setCameraPosition(
3338  cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
3339  cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
3340  cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
3341  }
3342 }
3343 
3345 {
3346  for(std::list<std::string>::iterator iter = _gridLines.begin(); iter!=_gridLines.end(); ++iter)
3347  {
3348  _visualizer->removeShape(*iter);
3349  }
3350  _gridLines.clear();
3351 }
3352 
3354 {
3355  _aShowNormals->setChecked(shown);
3356  QList<std::string> ids = _addedClouds.keys();
3357  for(QList<std::string>::iterator iter = ids.begin(); iter!=ids.end(); ++iter)
3358  {
3359  std::string idNormals = *iter + "-normals";
3360  if(_addedClouds.find(idNormals) != _addedClouds.end())
3361  {
3362  this->setCloudVisibility(idNormals, this->getCloudVisibility(*iter) && shown);
3363  }
3364  }
3365 }
3367 {
3368  return _aShowNormals->isChecked();
3369 }
3371 {
3372  return _normalsStep;
3373 }
3375 {
3376  return _normalsScale;
3377 }
3379 {
3380  if(step > 0)
3381  {
3382  _normalsStep = step;
3383  }
3384  else
3385  {
3386  UERROR("Cannot set normals step <= 0, step=%d", step);
3387  }
3388 }
3390 {
3391  if(scale > 0)
3392  {
3394  }
3395  else
3396  {
3397  UERROR("Cannot set normals scale <= 0, value=%f", scale);
3398  }
3399 }
3400 
3402 {
3403  return _aSetIntensityRedColormap->isChecked();
3404 }
3406 {
3407  return _aSetIntensityRainbowColormap->isChecked();
3408 }
3410 {
3411  return _intensityAbsMax;
3412 }
3413 
3415 {
3416  _aSetIntensityRedColormap->setChecked(on);
3417  if(on)
3418  {
3419  _aSetIntensityRainbowColormap->setChecked(false);
3420  }
3421 }
3423 {
3424  _aSetIntensityRainbowColormap->setChecked(on);
3425  if(on)
3426  {
3427  _aSetIntensityRedColormap->setChecked(false);
3428  }
3429 }
3431 {
3432  if(value >= 0.0f)
3433  {
3434  _intensityAbsMax = value;
3435  }
3436  else
3437  {
3438  UERROR("Cannot set normals scale < 0, value=%f", value);
3439  }
3440 }
3441 
3443 {
3444  _buildLocator = enable;
3445 }
3446 
3447 Eigen::Vector3f rotatePointAroundAxe(
3448  const Eigen::Vector3f & point,
3449  const Eigen::Vector3f & axis,
3450  float angle)
3451 {
3452  Eigen::Vector3f direction = point;
3453  Eigen::Vector3f zAxis = axis;
3454  float dotProdZ = zAxis.dot(direction);
3455  Eigen::Vector3f ptOnZaxis = zAxis * dotProdZ;
3456  direction -= ptOnZaxis;
3457  Eigen::Vector3f xAxis = direction.normalized();
3458  Eigen::Vector3f yAxis = zAxis.cross(xAxis);
3459 
3460  Eigen::Matrix3f newFrame;
3461  newFrame << xAxis[0], yAxis[0], zAxis[0],
3462  xAxis[1], yAxis[1], zAxis[1],
3463  xAxis[2], yAxis[2], zAxis[2];
3464 
3465  // transform to axe frame
3466  // transpose=inverse for orthogonal matrices
3467  Eigen::Vector3f newDirection = newFrame.transpose() * direction;
3468 
3469  // rotate about z
3470  float cosTheta = cos(angle);
3471  float sinTheta = sin(angle);
3472  float magnitude = newDirection.norm();
3473  newDirection[0] = ( magnitude * cosTheta );
3474  newDirection[1] = ( magnitude * sinTheta );
3475 
3476  // transform back to global frame
3477  direction = newFrame * newDirection;
3478 
3479  return direction + ptOnZaxis;
3480 }
3481 
3482 void CloudViewer::keyReleaseEvent(QKeyEvent * event) {
3483  if(event->key() == Qt::Key_Up ||
3484  event->key() == Qt::Key_Down ||
3485  event->key() == Qt::Key_Left ||
3486  event->key() == Qt::Key_Right)
3487  {
3488  _keysPressed -= (Qt::Key)event->key();
3489  }
3490  else
3491  {
3492  PCLQVTKWidget::keyPressEvent(event);
3493  }
3494 }
3495 
3496 void CloudViewer::keyPressEvent(QKeyEvent * event)
3497 {
3498  if(event->key() == Qt::Key_Up ||
3499  event->key() == Qt::Key_Down ||
3500  event->key() == Qt::Key_Left ||
3501  event->key() == Qt::Key_Right)
3502  {
3503  _keysPressed += (Qt::Key)event->key();
3504 
3505  std::vector<pcl::visualization::Camera> cameras;
3506  _visualizer->getCameras(cameras);
3507 
3508  //update camera position
3509  Eigen::Vector3f pos(cameras.front().pos[0], cameras.front().pos[1], _aLockViewZ->isChecked()?0:cameras.front().pos[2]);
3510  Eigen::Vector3f focal(cameras.front().focal[0], cameras.front().focal[1], _aLockViewZ->isChecked()?0:cameras.front().focal[2]);
3511  Eigen::Vector3f viewUp(cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
3512  Eigen::Vector3f cummulatedDir(0,0,0);
3513  Eigen::Vector3f cummulatedFocalDir(0,0,0);
3514  float step = 0.2f;
3515  float stepRot = 0.02f; // radian
3516  if(_keysPressed.contains(Qt::Key_Up))
3517  {
3518  Eigen::Vector3f dir;
3519  if(event->modifiers() & Qt::ShiftModifier)
3520  {
3521  dir = viewUp * step;// up
3522  }
3523  else
3524  {
3525  dir = (focal-pos).normalized() * step; // forward
3526  }
3527  cummulatedDir += dir;
3528  }
3529  if(_keysPressed.contains(Qt::Key_Down))
3530  {
3531  Eigen::Vector3f dir;
3532  if(event->modifiers() & Qt::ShiftModifier)
3533  {
3534  dir = viewUp * -step;// down
3535  }
3536  else
3537  {
3538  dir = (focal-pos).normalized() * -step; // backward
3539  }
3540  cummulatedDir += dir;
3541  }
3542  if(_keysPressed.contains(Qt::Key_Right))
3543  {
3544  if(event->modifiers() & Qt::ShiftModifier)
3545  {
3546  // rotate right
3547  Eigen::Vector3f point = (focal-pos);
3548  Eigen::Vector3f newPoint = rotatePointAroundAxe(point, viewUp, -stepRot);
3549  Eigen::Vector3f diff = newPoint - point;
3550  cummulatedFocalDir += diff;
3551  }
3552  else
3553  {
3554  Eigen::Vector3f dir = ((focal-pos).cross(viewUp)).normalized() * step; // strafing right
3555  cummulatedDir += dir;
3556  }
3557  }
3558  if(_keysPressed.contains(Qt::Key_Left))
3559  {
3560  if(event->modifiers() & Qt::ShiftModifier)
3561  {
3562  // rotate left
3563  Eigen::Vector3f point = (focal-pos);
3564  Eigen::Vector3f newPoint = rotatePointAroundAxe(point, viewUp, stepRot);
3565  Eigen::Vector3f diff = newPoint - point;
3566  cummulatedFocalDir += diff;
3567  }
3568  else
3569  {
3570  Eigen::Vector3f dir = ((focal-pos).cross(viewUp)).normalized() * -step; // strafing left
3571  cummulatedDir += dir;
3572  }
3573  }
3574 
3575  cameras.front().pos[0] += cummulatedDir[0];
3576  cameras.front().pos[1] += cummulatedDir[1];
3577  cameras.front().pos[2] += cummulatedDir[2];
3578  cameras.front().focal[0] += cummulatedDir[0] + cummulatedFocalDir[0];
3579  cameras.front().focal[1] += cummulatedDir[1] + cummulatedFocalDir[1];
3580  cameras.front().focal[2] += cummulatedDir[2] + cummulatedFocalDir[2];
3581  this->setCameraPosition(
3582  cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
3583  cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
3584  cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
3585 
3586  Q_EMIT configChanged();
3587  }
3588  else
3589  {
3590  PCLQVTKWidget::keyPressEvent(event);
3591  }
3592 }
3593 
3594 void CloudViewer::mousePressEvent(QMouseEvent * event)
3595 {
3596  if(event->button() == Qt::RightButton)
3597  {
3598  event->accept();
3599  }
3600  else
3601  {
3602  PCLQVTKWidget::mousePressEvent(event);
3603  }
3604 }
3605 
3606 void CloudViewer::mouseMoveEvent(QMouseEvent * event)
3607 {
3608  PCLQVTKWidget::mouseMoveEvent(event);
3609 
3610  std::vector<pcl::visualization::Camera> cameras;
3611  _visualizer->getCameras(cameras);
3612 
3613  // camera view up z locked?
3614  if(_aLockViewZ->isChecked() && !_aCameraOrtho->isChecked())
3615  {
3616  cv::Vec3d newCameraOrientation = cv::Vec3d(0,0,1).cross(cv::Vec3d(cameras.front().pos)-cv::Vec3d(cameras.front().focal));
3617 
3618  if( _lastCameraOrientation!=cv::Vec3d(0,0,0) &&
3619  _lastCameraPose!=cv::Vec3d(0,0,0) &&
3620  (uSign(_lastCameraOrientation[0]) != uSign(newCameraOrientation[0]) &&
3621  uSign(_lastCameraOrientation[1]) != uSign(newCameraOrientation[1])))
3622  {
3623  cameras.front().pos[0] = _lastCameraPose[0];
3624  cameras.front().pos[1] = _lastCameraPose[1];
3625  cameras.front().pos[2] = _lastCameraPose[2];
3626  }
3627  else if(newCameraOrientation != cv::Vec3d(0,0,0))
3628  {
3629  _lastCameraOrientation = newCameraOrientation;
3630  _lastCameraPose = cv::Vec3d(cameras.front().pos);
3631  }
3632  else
3633  {
3634  if(cameras.front().view[2] == 0)
3635  {
3636  cameras.front().pos[0] -= 0.00001*cameras.front().view[0];
3637  cameras.front().pos[1] -= 0.00001*cameras.front().view[1];
3638  }
3639  else
3640  {
3641  cameras.front().pos[0] -= 0.00001;
3642  }
3643  }
3644  cameras.front().view[0] = 0;
3645  cameras.front().view[1] = 0;
3646  cameras.front().view[2] = 1;
3647  }
3648 
3649  this->setCameraPosition(
3650  cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
3651  cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
3652  cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
3653 
3654  Q_EMIT configChanged();
3655 }
3656 
3657 void CloudViewer::wheelEvent(QWheelEvent * event)
3658 {
3659  PCLQVTKWidget::wheelEvent(event);
3660 
3661  std::vector<pcl::visualization::Camera> cameras;
3662  _visualizer->getCameras(cameras);
3663 
3664  if(_aLockViewZ->isChecked() && !_aCameraOrtho->isChecked())
3665  {
3666  _lastCameraPose = cv::Vec3d(cameras.front().pos);
3667  }
3668 
3669  this->setCameraPosition(
3670  cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
3671  cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
3672  cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
3673 
3674  Q_EMIT configChanged();
3675 }
3676 
3677 void CloudViewer::contextMenuEvent(QContextMenuEvent * event)
3678 {
3679  QAction * a = _menu->exec(event->globalPos());
3680  if(a)
3681  {
3682  handleAction(a);
3683  Q_EMIT configChanged();
3684  }
3685 }
3686 
3687 void CloudViewer::handleAction(QAction * a)
3688 {
3689  if(a == _aSetTrajectorySize)
3690  {
3691  bool ok;
3692  int value = QInputDialog::getInt(this, tr("Set trajectory size"), tr("Size (0=infinite)"), _maxTrajectorySize, 0, 10000, 10, &ok);
3693  if(ok)
3694  {
3695  _maxTrajectorySize = value;
3696  }
3697  }
3698  else if(a == _aClearTrajectory)
3699  {
3700  this->clearTrajectory();
3701  }
3702  else if(a == _aShowCameraAxis)
3703  {
3704  this->setCameraAxisShown(a->isChecked());
3705  }
3706  else if(a == _aSetFrameScale)
3707  {
3708  bool ok;
3709  double value = QInputDialog::getDouble(this, tr("Set frame scale"), tr("Scale"), _coordinateFrameScale, 0.1, 999.0, 1, &ok);
3710  if(ok)
3711  {
3712  this->setCoordinateFrameScale(value);
3713  }
3714  }
3715  else if(a == _aShowFrustum)
3716  {
3717  this->setFrustumShown(a->isChecked());
3718  }
3719  else if(a == _aSetFrustumScale)
3720  {
3721  bool ok;
3722  double value = QInputDialog::getDouble(this, tr("Set frustum scale"), tr("Scale"), _frustumScale, 0.0, 999.0, 1, &ok);
3723  if(ok)
3724  {
3725  this->setFrustumScale(value);
3726  }
3727  }
3728  else if(a == _aSetFrustumColor)
3729  {
3730  QColor value = QColorDialog::getColor(_frustumColor, this);
3731  if(value.isValid())
3732  {
3733  this->setFrustumColor(value);
3734  }
3735  }
3736  else if(a == _aResetCamera)
3737  {
3738  this->resetCamera();
3739  }
3740  else if(a == _aShowGrid)
3741  {
3742  if(_aShowGrid->isChecked())
3743  {
3744  this->addGrid();
3745  }
3746  else
3747  {
3748  this->removeGrid();
3749  }
3750 
3751  this->refreshView();
3752  }
3753  else if(a == _aSetGridCellCount)
3754  {
3755  bool ok;
3756  int value = QInputDialog::getInt(this, tr("Set grid cell count"), tr("Count"), _gridCellCount, 1, 10000, 10, &ok);
3757  if(ok)
3758  {
3759  this->setGridCellCount(value);
3760  }
3761  }
3762  else if(a == _aSetGridCellSize)
3763  {
3764  bool ok;
3765  double value = QInputDialog::getDouble(this, tr("Set grid cell size"), tr("Size (m)"), _gridCellSize, 0.01, 1000, 2, &ok);
3766  if(ok)
3767  {
3768  this->setGridCellSize(value);
3769  }
3770  }
3771  else if(a == _aShowNormals)
3772  {
3773  this->setNormalsShown(_aShowNormals->isChecked());
3774  this->refreshView();
3775  }
3776  else if(a == _aSetNormalsStep)
3777  {
3778  bool ok;
3779  int value = QInputDialog::getInt(this, tr("Set normals step"), tr("Step"), _normalsStep, 1, 10000, 1, &ok);
3780  if(ok)
3781  {
3782  this->setNormalsStep(value);
3783  }
3784  }
3785  else if(a == _aSetNormalsScale)
3786  {
3787  bool ok;
3788  double value = QInputDialog::getDouble(this, tr("Set normals scale"), tr("Scale (m)"), _normalsScale, 0.01, 10, 2, &ok);
3789  if(ok)
3790  {
3791  this->setNormalsScale(value);
3792  }
3793  }
3794  else if(a == _aSetIntensityMaximum)
3795  {
3796  bool ok;
3797  double value = QInputDialog::getDouble(this, tr("Set maximum absolute intensity"), tr("Intensity (0=auto)"), _intensityAbsMax, 0.0, 99999, 2, &ok);
3798  if(ok)
3799  {
3800  this->setIntensityMax(value);
3801  }
3802  }
3803  else if(a == _aSetIntensityRedColormap)
3804  {
3806  }
3807  else if(a == _aSetIntensityRainbowColormap)
3808  {
3810  }
3811  else if(a == _aSetBackgroundColor)
3812  {
3813  QColor color = this->getDefaultBackgroundColor();
3814  color = QColorDialog::getColor(color, this);
3815  if(color.isValid())
3816  {
3817  this->setDefaultBackgroundColor(color);
3818  this->refreshView();
3819  }
3820  }
3821  else if(a == _aSetRenderingRate)
3822  {
3823  bool ok;
3824  double value = QInputDialog::getDouble(this, tr("Rendering rate"), tr("Rate (hz)"), _renderingRate, 0, 60, 0, &ok);
3825  if(ok)
3826  {
3827  this->setRenderingRate(value);
3828  }
3829  }
3830  else if(a == _aLockViewZ)
3831  {
3832  if(_aLockViewZ->isChecked())
3833  {
3834  this->refreshView();
3835  }
3836  }
3837  else if(a == _aCameraOrtho)
3838  {
3839  this->setCameraOrtho(_aCameraOrtho->isChecked());
3840  }
3841  else if(a == _aSetEDLShading)
3842  {
3843  this->setEDLShading(_aSetEDLShading->isChecked());
3844  }
3845  else if(a == _aSetLighting)
3846  {
3847  this->setLighting(_aSetLighting->isChecked());
3848  }
3849  else if(a == _aSetFlatShading)
3850  {
3851  this->setShading(_aSetFlatShading->isChecked());
3852  }
3853  else if(a == _aSetEdgeVisibility)
3854  {
3855  this->setEdgeVisibility(_aSetEdgeVisibility->isChecked());
3856  }
3857  else if(a == _aBackfaceCulling)
3858  {
3860  }
3861  else if(a == _aPolygonPicking)
3862  {
3863  this->setPolygonPicking(_aPolygonPicking->isChecked());
3864  }
3865 }
3866 
3867 } /* namespace rtabmap */
void setDefaultBackgroundColor(const QColor &color)
void setLocalTransform(const Transform &transform)
Definition: CameraModel.h:115
QAction * _aShowCameraAxis
Definition: CloudViewer.h:433
void removeGraph(const std::string &id)
#define NULL
unsigned int getTrajectorySize() const
QAction * _aBackfaceCulling
Definition: CloudViewer.h:453
QAction * _aSetFrustumScale
Definition: CloudViewer.h:436
bool isIntensityRedColormap() const
void setTrajectoryShown(bool shown)
void setFrustumShown(bool shown)
rtabmap::CameraThread * cam
boost::shared_ptr< const PointCloudColorHandlerIntensityField > ConstPtr
std::set< std::string > _coordinates
Definition: CloudViewer.h:457
void setInteractorLayer(int layer)
Definition: UTimer.h:46
void setTrajectorySize(unsigned int value)
const iterator end() const
pcl::visualization::PCLVisualizer * _visualizer
Definition: CloudViewer.h:424
float r33() const
Definition: Transform.h:70
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, std::vector< int > *frontierIndices=0, std::vector< double > *cloudProb=0) const
Definition: OctoMap.cpp:1054
GLM_FUNC_DECL bool isfinite(genType const &x)
Test whether or not a scalar or each vector component is a finite value. (From GLM_GTX_compatibility)...
float getIntensityMax() const
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:473
bool isCameraFree() const
QAction * _aLockCamera
Definition: CloudViewer.h:425
bool isLightingOn() const
void setNormalsStep(int step)
virtual void keyPressEvent(QKeyEvent *event)
QAction * _aShowFrustum
Definition: CloudViewer.h:435
void setNormalsScale(float scale)
QAction * _aSetIntensityRainbowColormap
Definition: CloudViewer.h:445
void updateCameraFrustum(const Transform &pose, const StereoCameraModel &model)
void setCoordinateFrameScale(double scale)
void setGridShown(bool shown)
QAction * _aSetEdgeVisibility
Definition: CloudViewer.h:452
void uMinMax(const T *v, unsigned int size, T &min, T &max, unsigned int &indexMin, unsigned int &indexMax)
Definition: UMath.h:226
void setCloudVisibility(const std::string &id, bool isVisible)
f
std::list< std::string > _gridLines
Definition: CloudViewer.h:478
x
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:465
void removeCube(const std::string &id)
void setCloudViewer(CloudViewer *cloudViewer)
float getGridCellSize() const
float getNormalsScale() const
void removeFrustum(const std::string &id)
T
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)
GLM_FUNC_DECL detail::tvec3< T, P > axis(detail::tquat< T, P > const &x)
static Transform getIdentity()
Definition: Transform.cpp:401
void getGridMin(double &x, double &y, double &z) const
Definition: OctoMap.h:213
std::set< std::string > _quads
Definition: CloudViewer.h:462
bool isCameraAxisShown() const
bool removeCloud(const std::string &id)
double keyToCoord(key_type key, unsigned depth) const
bool isIntensityRainbowColormap() const
QAction * _aPolygonPicking
Definition: CloudViewer.h:454
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:474
void setGridCellSize(float size)
void setEDLShading(bool on)
void setLighting(bool on)
virtual std::string getFieldName() const
Get the name of the field used.
virtual void clear()
float r32() const
Definition: Transform.h:69
Eigen::Vector3f rotatePointAroundAxe(const Eigen::Vector3f &point, const Eigen::Vector3f &axis, float angle)
Basic mathematics functions.
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
int uSign(const T &v)
Definition: UMath.h:302
bool isShadingOn() const
Some conversion functions.
void addOrUpdateSphere(const std::string &id, const Transform &pose, float radius, const QColor &color, bool foreground=false)
unsigned int getGridCellCount() const
void setPolygonPicking(bool enabled)
QVTKWidget PCLQVTKWidget
Definition: CloudViewer.h:45
std::set< std::string > _spheres
Definition: CloudViewer.h:460
int getNormalsStep() const
void getCameraPosition(float &x, float &y, float &z, float &focalX, float &focalY, float &focalZ, float &upX, float &upY, float &upZ) const
QSet< Qt::Key > _keysPressed
Definition: CloudViewer.h:479
void buildPickingLocator(bool enable)
void setCameraOrtho(bool enabled=true)
bool isFrustumShown() const
void removeLine(const std::string &id)
virtual void contextMenuEvent(QContextMenuEvent *event)
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)
boost::shared_ptr< PointCloudColorHandlerIntensityField > Ptr
void getGridMax(double &x, double &y, double &z) const
Definition: OctoMap.h:214
std::set< std::string > _graphes
Definition: CloudViewer.h:456
QAction * _aSetEDLShading
Definition: CloudViewer.h:449
bool updateCoordinatePose(const std::string &id, const Transform &transform)
QAction * _aSetNormalsScale
Definition: CloudViewer.h:443
bool addCloudTextureMesh(const std::string &id, const pcl::TextureMesh::Ptr &textureMesh, const cv::Mat &texture, const Transform &pose=Transform::getIdentity())
std::set< std::string > _texts
Definition: CloudViewer.h:458
void setIntensityRedColormap(bool value)
GLM_FUNC_DECL bool isNull(detail::tmat2x2< T, P > const &m, T const &epsilon)
pcl::visualization::PointCloudColorHandler< pcl::PCLPointCloud2 >::PointCloud PointCloud
void addOrUpdateLine(const std::string &id, const Transform &from, const Transform &to, const QColor &color, bool arrow=false, bool foreground=false)
bool isTrajectoryShown() const
#define UASSERT(condition)
GLM_FUNC_DECL genType cos(genType const &angle)
QAction * _aSetFrustumColor
Definition: CloudViewer.h:437
QMap< std::string, Transform > _addedClouds
Definition: CloudViewer.h:476
bool isCameraOrtho() const
QAction * _aSetTrajectorySize
Definition: CloudViewer.h:431
Wrappers of STL for convenient functions.
void setCameraAxisShown(bool shown)
QAction * _aSetBackgroundColor
Definition: CloudViewer.h:447
bool isEdgeVisible() const
GLM_FUNC_DECL genType sin(genType const &angle)
GLM_FUNC_DECL detail::tvec3< T, P > cross(detail::tvec3< T, P > const &x, detail::tvec3< T, P > const &y)
transformation
void removeAllCoordinates(const std::string &prefix="")
void setColor(const std::string &id, const QColor &color)
string name
QAction * _aResetCamera
Definition: CloudViewer.h:427
iterator begin(unsigned char maxDepth=0) const
void addOrUpdateQuad(const std::string &id, const Transform &pose, float width, float height, const QColor &color, bool foreground=false)
double getRenderingRate() const
void setGridCellCount(unsigned int count)
virtual bool getColor(vtkSmartPointer< vtkDataArray > &scalars) const
Obtain the actual color for the input dataset as vtk scalars.
void setCameraPosition(float x, float y, float z, float focalX, float focalY, float focalZ, float upX, float upY, float upZ)
Transform getTargetPose() const
virtual ~PointCloudColorHandlerIntensityField()
Empty destructor.
void setEdgeVisibility(bool visible)
bool isPolygonPicking() const
void setFrustumScale(float value)
std::string prettyPrint() const
Definition: Transform.cpp:316
void removeText(const std::string &id)
bool isCameraLockZ() const
void setCloudPointSize(const std::string &id, int size)
void setNormalsShown(bool shown)
bool isNormalsShown() const
double getNodeSize(unsigned depth) const
bool isBackfaceCulling() const
std::string getIdByActor(vtkProp *actor) const
const Transform & localTransform() const
Definition: CameraModel.h:116
void setFrustumColor(QColor value)
bool isCameraTargetLocked() const
void updateCameraTargetPosition(const Transform &pose)
tree
bool isCameraTargetFollow() const
const RtabmapColorOcTree * octree() const
Definition: OctoMap.h:190
void addOrUpdateFrustum(const std::string &id, const Transform &pose, const Transform &localTransform, double scale, const QColor &color=QColor(), float fovX=1.1, float fovY=0.85)
translation
QAction * _aShowTrajectory
Definition: CloudViewer.h:430
QColor getFrustumColor() const
Eigen::Affine3f toEigen3f() const
Definition: Transform.cpp:381
double _coordinateFrameScale
Definition: CloudViewer.h:486
void normalizeRotation()
Definition: Transform.cpp:306
void setBackgroundColor(const QColor &color)
static const int frustum_indices[]
CloudViewer(QWidget *parent=0, CloudViewerInteractorStyle *style=CloudViewerInteractorStyle::New())
Definition: CloudViewer.cpp:95
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)
Transform rotation() const
Definition: Transform.cpp:195
bool isNull() const
Definition: Transform.cpp:107
pcl::PointCloud< pcl::PointXYZ >::Ptr _trajectory
Definition: CloudViewer.h:464
bool addCloud(const std::string &id, const pcl::PCLPointCloud2Ptr &binaryCloud, const Transform &pose, bool rgb, bool hasNormals, bool hasIntensity, const QColor &color=QColor(), int viewport=1)
bool getCloudVisibility(const std::string &id)
vtkProp * _octomapActor
Definition: CloudViewer.h:484
QAction * _aSetNormalsStep
Definition: CloudViewer.h:442
QAction * _aFollowCamera
Definition: CloudViewer.h:426
#define false
Definition: ConvertUTF.c:56
GLM_FUNC_DECL genType tan(genType const &angle)
std::set< std::string > _lines
Definition: CloudViewer.h:459
Eigen::Quaternionf getQuaternionf() const
Definition: Transform.cpp:391
QAction * _aClearTrajectory
Definition: CloudViewer.h:432
void addOrUpdateGraph(const std::string &id, const pcl::PointCloud< pcl::PointXYZ >::Ptr &graph, const QColor &color=Qt::gray)
float getFrustumScale() const
bool isGridShown() const
const QColor & getBackgroundColor() const
QAction * _aSetIntensityMaximum
Definition: CloudViewer.h:446
void setCameraTargetLocked(bool enabled=true)
#define UDEBUG(...)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
QAction * _aSetGridCellSize
Definition: CloudViewer.h:440
void updateCameraFrustums(const Transform &pose, const std::vector< CameraModel > &models)
double getCoordinateFrameScale() const
void removeSphere(const std::string &id)
static const float frustum_vertices[]
void loadSettings(QSettings &settings, const QString &group="")
bool isEDLShadingOn() const
void setIntensityMax(float value)
void saveSettings(QSettings &settings, const QString &group="") const
unsigned int _gridCellCount
Definition: CloudViewer.h:468
#define UERROR(...)
const QColor & getDefaultBackgroundColor() const
virtual void keyReleaseEvent(QKeyEvent *event)
ULogger class and convenient macros.
#define UWARN(...)
void setBackfaceCulling(bool enabled, bool frontfaceCulling)
diff
QAction * _aSetFrameScale
Definition: CloudViewer.h:434
virtual size_t size() const
void setCameraTargetFollow(bool enabled=true)
std::set< std::string > _cubes
Definition: CloudViewer.h:461
QMap< std::string, Transform > _frustums
Definition: CloudViewer.h:463
virtual void mousePressEvent(QMouseEvent *event)
virtual void mouseMoveEvent(QMouseEvent *event)
void setCloudColorIndex(const std::string &id, int index)
model
Definition: trace.py:4
virtual void handleAction(QAction *event)
void removeCoordinate(const std::string &id)
float r31() const
Definition: Transform.h:68
QAction * _aSetFlatShading
Definition: CloudViewer.h:451
QAction * _aSetGridCellCount
Definition: CloudViewer.h:439
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)
QAction * _aCameraOrtho
Definition: CloudViewer.h:429
QAction * _aSetIntensityRedColormap
Definition: CloudViewer.h:444
QAction * _aShowNormals
Definition: CloudViewer.h:441
cv::Vec3d _lastCameraPose
Definition: CloudViewer.h:475
void RTABMAP_EXP HSVtoRGB(float *r, float *g, float *b, float h, float s, float v)
Definition: util2d.cpp:2047
PointCloudColorHandlerIntensityField(const PointCloudConstPtr &cloud, float maxAbsIntensity=0.0f, int colorMap=0)
Constructor.
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 isFrontfaceCulling() const
void removeAllFrustums(bool exceptCameraReference=false)
const CameraModel & right() const
QAction * _aSetRenderingRate
Definition: CloudViewer.h:448
virtual std::string getName() const
Get the name of the class.
bool updateCloudPose(const std::string &id, const Transform &pose)
QAction * _aSetLighting
Definition: CloudViewer.h:450
bool isIdentity() const
Definition: Transform.cpp:136
void setRenderingRate(double rate)
Transform inverse() const
Definition: Transform.cpp:178
void setCloudOpacity(const std::string &id, double opacity=1.0)
unsigned int getTreeDepth() const
GLM_FUNC_DECL detail::tmat4x4< T, P > orientation(detail::tvec3< T, P > const &Normal, detail::tvec3< T, P > const &Up)
void setIntensityRainbowColormap(bool value)
const CameraModel & left() const


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:28