31 #include <rtabmap/core/Version.h> 38 #include <pcl/visualization/pcl_visualizer.h> 39 #include <pcl/common/transforms.h> 42 #include <QtGui/QContextMenuEvent> 43 #include <QInputDialog> 44 #include <QtGui/QWheelEvent> 45 #include <QtGui/QKeyEvent> 46 #include <QColorDialog> 47 #include <QtGui/QVector3D> 48 #include <QMainWindow> 51 #include <vtkCamera.h> 52 #include <vtkRenderWindow.h> 53 #include <vtkCubeSource.h> 54 #include <vtkGlyph3D.h> 55 #include <vtkGlyph3DMapper.h> 56 #include <vtkSmartVolumeMapper.h> 57 #include <vtkVolumeProperty.h> 58 #include <vtkColorTransferFunction.h> 59 #include <vtkPiecewiseFunction.h> 60 #include <vtkImageData.h> 61 #include <vtkLookupTable.h> 62 #include <vtkTextureUnitManager.h> 63 #include <vtkJPEGReader.h> 64 #include <vtkBMPReader.h> 65 #include <vtkPNMReader.h> 66 #include <vtkPNGReader.h> 67 #include <vtkTIFFReader.h> 68 #include <vtkOpenGLRenderWindow.h> 69 #include <vtkPointPicker.h> 70 #include <vtkTextActor.h> 71 #include <vtkOBBTree.h> 72 #include <vtkObjectFactory.h> 76 #ifdef RTABMAP_OCTOMAP 90 _aSetTrajectorySize(0),
96 _aSetGridCellCount(0),
100 _aSetNormalsScale(0),
101 _aSetBackgroundColor(0),
102 _aSetRenderingRate(0),
105 _aSetEdgeVisibility(0),
106 _aBackfaceCulling(0),
108 _trajectory(new
pcl::PointCloud<
pcl::PointXYZ>),
109 _maxTrajectorySize(100),
111 _frustumColor(Qt::gray),
116 _buildLocator(
false),
117 _lastCameraOrientation(0,0,0),
118 _lastCameraPose(0,0,0),
119 _defaultBgColor(Qt::black),
120 _currentBgColor(Qt::black),
121 _frontfaceCulling(
false),
126 this->setMinimumSize(200, 200);
131 _visualizer =
new pcl::visualization::PCLVisualizer(
141 _visualizer->createViewPort (0,0,1.0, 1.0, viewport);
142 _visualizer->createViewPort (0,0,1.0, 1.0, viewport);
143 _visualizer->getRendererCollection()->InitTraversal ();
144 vtkRenderer* renderer =
NULL;
146 while ((renderer =
_visualizer->getRendererCollection()->GetNextItem ()) !=
NULL)
148 renderer->SetLayer(i);
151 _visualizer->getInteractorStyle()->SetDefaultRenderer(renderer);
155 _visualizer->getRenderWindow()->SetNumberOfLayers(3);
157 this->SetRenderWindow(
_visualizer->getRenderWindow());
162 this->GetInteractor()->SetInteractorStyle (
_visualizer->getInteractorStyle());
165 UDEBUG(
"pick tolerance=%f", pp->GetTolerance());
166 pp->SetTolerance (pp->GetTolerance()/2.0);
167 this->GetInteractor()->SetPicker (pp);
183 setMouseTracking(
false);
222 QAction * freeCamera =
new QAction(
"Free",
this);
223 freeCamera->setCheckable(
true);
224 freeCamera->setChecked(
false);
268 QMenu * cameraMenu =
new QMenu(
"Camera",
this);
271 cameraMenu->addAction(freeCamera);
272 cameraMenu->addSeparator();
276 QActionGroup * group =
new QActionGroup(
this);
279 group->addAction(freeCamera);
281 QMenu * trajectoryMenu =
new QMenu(
"Trajectory",
this);
286 QMenu * frustumMenu =
new QMenu(
"Frustum",
this);
291 QMenu * gridMenu =
new QMenu(
"Grid",
this);
296 QMenu * normalsMenu =
new QMenu(
"Normals",
this);
302 _menu =
new QMenu(
this);
303 _menu->addMenu(cameraMenu);
304 _menu->addMenu(trajectoryMenu);
305 _menu->addMenu(frustumMenu);
306 _menu->addMenu(gridMenu);
307 _menu->addMenu(normalsMenu);
321 settings.beginGroup(group);
324 float poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ;
325 this->
getCameraPosition(poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ);
326 QVector3D pose(poseX, poseY, poseZ);
327 QVector3D focal(focalX, focalY, focalZ);
336 Transform F(focalX, focalY, focalZ, 0,0,0);
340 pose = QVector3D(newPose.
x(), newPose.
y(), newPose.
z());
341 focal = QVector3D(newFocal.
x(), newFocal.
y(), newFocal.
z());
343 settings.setValue(
"camera_pose", pose);
344 settings.setValue(
"camera_focal", focal);
345 settings.setValue(
"camera_up", QVector3D(upX, upY, upZ));
380 settings.beginGroup(group);
383 float poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ;
384 this->
getCameraPosition(poseX, poseY, poseZ, focalX, focalY, focalZ, upX, upY, upZ);
385 QVector3D pose(poseX, poseY, poseZ), focal(focalX, focalY, focalZ), up(upX, upY, upZ);
386 pose = settings.value(
"camera_pose", pose).value<QVector3D>();
387 focal = settings.value(
"camera_focal", focal).value<QVector3D>();
388 up = settings.value(
"camera_up", up).value<QVector3D>();
389 this->
setCameraPosition(pose.x(),pose.y(),pose.z(), focal.x(),focal.y(),focal.z(), up.x(),up.y(),up.z());
391 this->
setGridShown(settings.value(
"grid", this->isGridShown()).toBool());
392 this->
setGridCellCount(settings.value(
"grid_cell_count", this->getGridCellCount()).toUInt());
393 this->
setGridCellSize(settings.value(
"grid_cell_size", this->getGridCellSize()).toFloat());
395 this->
setNormalsShown(settings.value(
"normals", this->isNormalsShown()).toBool());
396 this->
setNormalsStep(settings.value(
"normals_step", this->getNormalsStep()).toInt());
397 this->
setNormalsScale(settings.value(
"normals_scale", this->getNormalsScale()).toFloat());
399 this->
setTrajectoryShown(settings.value(
"trajectory_shown", this->isTrajectoryShown()).toBool());
400 this->
setTrajectorySize(settings.value(
"trajectory_size", this->getTrajectorySize()).toUInt());
402 this->
setFrustumShown(settings.value(
"frustum_shown", this->isFrustumShown()).toBool());
403 this->
setFrustumScale(settings.value(
"frustum_scale", this->getFrustumScale()).toDouble());
404 this->
setFrustumColor(settings.value(
"frustum_color", this->getFrustumColor()).value<QColor>());
406 this->
setCameraTargetLocked(settings.value(
"camera_target_locked", this->isCameraTargetLocked()).toBool());
407 this->
setCameraTargetFollow(settings.value(
"camera_target_follow", this->isCameraTargetFollow()).toBool());
408 if(settings.value(
"camera_free", this->isCameraFree()).toBool())
412 this->
setCameraLockZ(settings.value(
"camera_lockZ", this->isCameraLockZ()).toBool());
413 this->
setCameraOrtho(settings.value(
"camera_ortho", this->isCameraOrtho()).toBool());
417 this->
setRenderingRate(settings.value(
"rendering_rate", this->getRenderingRate()).toDouble());
428 const std::string &
id,
435 Eigen::Affine3f posef = pose.
toEigen3f();
442 std::string idNormals =
id+
"-normals";
445 _visualizer->updatePointCloudPose(idNormals, posef);
456 const std::string &
id,
457 const pcl::PCLPointCloud2Ptr & binaryCloud,
462 const QColor & color)
464 int previousColorIndex = -1;
467 previousColorIndex =
_visualizer->getColorHandlerIndex(
id);
471 Eigen::Vector4f origin(pose.
x(), pose.
y(), pose.
z(), 0.0f);
476 pcl::PointCloud<pcl::PointNormal>::Ptr cloud_xyz (
new pcl::PointCloud<pcl::PointNormal>);
477 pcl::fromPCLPointCloud2 (*binaryCloud, *cloud_xyz);
478 std::string idNormals =
id +
"-normals";
487 pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::Ptr colorHandler;
488 colorHandler.reset (
new pcl::visualization::PointCloudColorHandlerRandom<pcl::PCLPointCloud2> (binaryCloud));
489 if(
_visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation,
id, 1))
496 colorHandler.reset (
new pcl::visualization::PointCloudColorHandlerCustom<pcl::PCLPointCloud2> (binaryCloud, c.red(), c.green(), c.blue()));
497 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation,
id, 1);
500 colorHandler.reset (
new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud,
"x"));
501 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation,
id, 1);
502 colorHandler.reset (
new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud,
"y"));
503 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation,
id, 1);
504 colorHandler.reset (
new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud,
"z"));
505 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation,
id, 1);
510 colorHandler.reset(
new pcl::visualization::PointCloudColorHandlerRGBField<pcl::PCLPointCloud2>(binaryCloud));
511 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation,
id, 1);
513 else if(hasIntensity)
516 colorHandler.reset(
new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2>(binaryCloud,
"intensity"));
517 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation,
id, 1);
519 else if(previousColorIndex == 5)
521 previousColorIndex = -1;
527 colorHandler.reset (
new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud,
"normal_x"));
528 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation,
id, 1);
529 colorHandler.reset (
new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud,
"normal_y"));
530 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation,
id, 1);
531 colorHandler.reset (
new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (binaryCloud,
"normal_z"));
532 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation,
id, 1);
534 else if(previousColorIndex > 5)
536 previousColorIndex = -1;
539 if(previousColorIndex>=0)
541 _visualizer->updateColorHandlerIndex(
id, previousColorIndex);
549 _visualizer->updateColorHandlerIndex(
id, hasIntensity?8:7);
551 else if(hasIntensity)
555 else if(color.isValid())
567 const std::string &
id,
568 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
570 const QColor & color)
572 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
573 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
574 return addCloud(
id, binaryCloud, pose,
true,
true,
false, color);
578 const std::string &
id,
579 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
581 const QColor & color)
583 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
584 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
585 return addCloud(
id, binaryCloud, pose,
true,
false,
false, color);
589 const std::string &
id,
590 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
592 const QColor & color)
594 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
595 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
596 return addCloud(
id, binaryCloud, pose,
false,
true,
true, color);
600 const std::string &
id,
601 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
603 const QColor & color)
605 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
606 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
607 return addCloud(
id, binaryCloud, pose,
false,
false,
true, color);
611 const std::string &
id,
612 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
614 const QColor & color)
616 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
617 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
618 return addCloud(
id, binaryCloud, pose,
false,
true,
false, color);
622 const std::string &
id,
623 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
625 const QColor & color)
627 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
628 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
629 return addCloud(
id, binaryCloud, pose,
false,
false,
false, color);
633 const std::string &
id,
634 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
635 const std::vector<pcl::Vertices> & polygons,
643 UDEBUG(
"Adding %s with %d points and %d polygons",
id.c_str(), (
int)cloud->size(), (int)polygons.size());
644 if(
_visualizer->addPolygonMesh<pcl::PointXYZ>(cloud, polygons,
id, 1))
646 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.5);
648 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetInterpolation(
_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
656 tree->SetDataSet(
_visualizer->getCloudActorMap()->find(
id)->second.actor->GetMapper()->GetInput());
657 tree->BuildLocator();
658 _locators.insert(std::make_pair(
id, tree));
667 const std::string &
id,
668 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
669 const std::vector<pcl::Vertices> & polygons,
677 UDEBUG(
"Adding %s with %d points and %d polygons",
id.c_str(), (
int)cloud->size(), (int)polygons.size());
678 if(
_visualizer->addPolygonMesh<pcl::PointXYZRGB>(cloud, polygons,
id, 1))
680 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.5);
682 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetInterpolation(
_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
690 tree->SetDataSet(
_visualizer->getCloudActorMap()->find(
id)->second.actor->GetMapper()->GetInput());
691 tree->BuildLocator();
692 _locators.insert(std::make_pair(
id, tree));
701 const std::string &
id,
702 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
703 const std::vector<pcl::Vertices> & polygons,
711 UDEBUG(
"Adding %s with %d points and %d polygons",
id.c_str(), (
int)cloud->size(), (int)polygons.size());
712 if(
_visualizer->addPolygonMesh<pcl::PointXYZRGBNormal>(cloud, polygons,
id, 1))
714 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.5);
716 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetInterpolation(
_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
724 tree->SetDataSet(
_visualizer->getCloudActorMap()->find(
id)->second.actor->GetMapper()->GetInput());
725 tree->BuildLocator();
726 _locators.insert(std::make_pair(
id, tree));
735 const std::string &
id,
736 const pcl::PolygonMesh::Ptr & mesh,
744 UDEBUG(
"Adding %s with %d polygons",
id.c_str(), (
int)mesh->polygons.size());
747 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.5);
756 tree->SetDataSet(
_visualizer->getCloudActorMap()->find(
id)->second.actor->GetMapper()->GetInput());
757 tree->BuildLocator();
758 _locators.insert(std::make_pair(
id, tree));
768 const std::string &
id,
769 const pcl::TextureMesh::Ptr & textureMesh,
770 const cv::Mat & texture,
778 UDEBUG(
"Adding %s",
id.c_str());
782 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetInterpolation(
_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
786 if(!textureMesh->cloud.is_dense)
788 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetTexture()->SetInterpolate(1);
789 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetTexture()->SetBlendingMode(vtkTexture::VTK_TEXTURE_BLENDING_MODE_REPLACE);
795 tree->SetDataSet(
_visualizer->getCloudActorMap()->find(
id)->second.actor->GetMapper()->GetInput());
796 tree->BuildLocator();
797 _locators.insert(std::make_pair(
id, tree));
808 #ifdef RTABMAP_OCTOMAP 811 pcl::IndicesPtr obstacles(
new std::vector<int>);
817 UWARN(
"Tree depth requested (%d) is deeper than the " 818 "actual maximum tree depth of %d. Using maximum depth.",
826 if(!volumeRepresentation)
828 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = octomap->
createCloud(treeDepth, obstacles.get(), 0, 0,
false);
829 if(obstacles->size())
835 colors->SetName(
"colors");
836 colors->SetNumberOfValues(obstacles->size());
839 lut->SetNumberOfTableValues(obstacles->size());
844 points->SetNumberOfPoints(obstacles->size());
846 for (
unsigned int i = 0; i < obstacles->size(); i++)
848 points->InsertPoint(i,
849 cloud->at(obstacles->at(i)).x,
850 cloud->at(obstacles->at(i)).y,
851 cloud->at(obstacles->at(i)).z);
852 colors->InsertValue(i,i);
854 lut->SetTableValue(i,
855 double(cloud->at(obstacles->at(i)).r) / 255.0,
856 double(cloud->at(obstacles->at(i)).g) / 255.0,
857 double(cloud->at(obstacles->at(i)).b) / 255.0);
862 polydata->SetPoints(points);
863 polydata->GetPointData()->SetScalars(colors);
867 cubeSource->SetBounds(-s, s, -s, s, -s, s);
870 mapper->SetSourceConnection(cubeSource->GetOutputPort());
871 #if VTK_MAJOR_VERSION <= 5 872 mapper->SetInputConnection(polydata->GetProducerPort());
874 mapper->SetInputData(polydata);
876 mapper->SetScalarRange(0, obstacles->size() - 1);
877 mapper->SetLookupTable(lut);
878 mapper->ScalingOff();
882 octomapActor->SetMapper(mapper);
884 octomapActor->GetProperty()->SetRepresentationToSurface();
886 octomapActor->GetProperty()->SetLighting(
_aSetLighting->isChecked());
888 _visualizer->getRendererCollection()->InitTraversal ();
889 vtkRenderer* renderer =
NULL;
890 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
891 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
893 renderer->AddActor(octomapActor);
907 double sizeX, sizeY, sizeZ;
908 double minX, minY, minZ;
909 double maxX, maxY, maxZ;
919 imageData->SetExtent(0,
int(sizeX/cellSize+0.5), 0,
int(sizeY/cellSize+0.5), 0,
int(sizeZ/cellSize+0.5));
920 #if VTK_MAJOR_VERSION <= 5 921 imageData->SetNumberOfScalarComponents(4);
922 imageData->SetScalarTypeToUnsignedChar();
924 imageData->AllocateScalars(VTK_UNSIGNED_CHAR,4);
928 imageData->GetDimensions(dims);
930 memset(imageData->GetScalarPointer(), 0, imageData->GetScalarSize()*imageData->GetNumberOfScalarComponents()*dims[0]*dims[1]*dims[2]);
934 if(octomap->
octree()->isNodeOccupied(*it))
937 int x = (pt.
x()-minX) / cellSize;
938 int y = (pt.
y()-minY) / cellSize;
939 int z = (pt.
z()-minZ) / cellSize;
940 if(x>=0 && x<dims[0] && y>=0 && y<dims[1] && z>=0 && z<dims[2])
942 unsigned char* pixel =
static_cast<unsigned char*
>(imageData->GetScalarPointer(x,y,z));
945 pixel[0] = it->getColor().r;
946 pixel[1] = it->getColor().g;
947 pixel[2] = it->getColor().b;
952 float H = (maxZ - pt.
z())*299.0
f/(maxZ-minZ);
965 volumeMapper->SetBlendModeToComposite();
966 #if VTK_MAJOR_VERSION <= 5 967 volumeMapper->SetInputConnection(imageData->GetProducerPort());
969 volumeMapper->SetInputData(imageData);
973 volumeProperty->ShadeOff();
974 volumeProperty->IndependentComponentsOff();
978 compositeOpacity->AddPoint(0.0,0.0);
979 compositeOpacity->AddPoint(255.0,1.0);
980 volumeProperty->SetScalarOpacity(0, compositeOpacity);
984 volume->SetMapper(volumeMapper);
985 volume->SetProperty(volumeProperty);
986 volume->SetScale(cellSize);
987 volume->SetPosition(minX, minY, minZ);
989 _visualizer->getRendererCollection()->InitTraversal ();
990 vtkRenderer* renderer =
NULL;
991 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
992 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
994 renderer->AddViewProp(volume);
997 #if !defined(VTK_LEGACY_REMOVE) && !defined(VTK_OPENGL2) 998 volumeMapper->SetRequestedRenderModeToRayCastAndTexture();
999 #endif // VTK_LEGACY_REMOVE 1003 volumeMapper->SetRequestedRenderModeToRayCast();
1016 #ifdef RTABMAP_OCTOMAP 1019 _visualizer->getRendererCollection()->InitTraversal ();
1020 vtkRenderer* renderer =
NULL;
1021 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
1022 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
1031 const pcl::TextureMesh &mesh,
1032 const cv::Mat & image,
1033 const std::string &
id,
1038 pcl::visualization::CloudActorMap::iterator am_it =
_visualizer->getCloudActorMap()->find (
id);
1039 if (am_it !=
_visualizer->getCloudActorMap()->end ())
1041 PCL_ERROR (
"[PCLVisualizer::addTextureMesh] A shape with id <%s> already exists!" 1042 " Please choose a different id and retry.\n",
1047 if (mesh.tex_materials.size () == 0)
1049 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] No textures found!\n");
1052 else if (mesh.tex_materials.size() > 1)
1054 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] only one material per mesh is supported!\n");
1058 if (mesh.tex_materials.size () != mesh.tex_polygons.size ())
1060 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] Materials number %lu differs from polygons number %lu!\n",
1061 mesh.tex_materials.size (), mesh.tex_polygons.size ());
1065 if (mesh.tex_materials.size () != mesh.tex_coordinates.size ())
1067 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] Coordinates number %lu differs from materials number %lu!\n",
1068 mesh.tex_coordinates.size (), mesh.tex_materials.size ());
1072 std::size_t nb_vertices = 0;
1073 for (std::size_t i = 0; i < mesh.tex_polygons.size (); ++i)
1074 nb_vertices+= mesh.tex_polygons[i].size ();
1076 if (nb_vertices == 0)
1078 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] No vertices found!\n");
1082 std::size_t nb_coordinates = 0;
1083 for (std::size_t i = 0; i < mesh.tex_coordinates.size (); ++i)
1084 nb_coordinates+= mesh.tex_coordinates[i].size ();
1086 if (nb_coordinates == 0)
1088 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] No textures coordinates found!\n");
1095 bool has_color =
false;
1098 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (
new pcl::PointCloud<pcl::PointXYZ> ());
1099 pcl::fromPCLPointCloud2 (mesh.cloud, *cloud);
1101 if (cloud->points.size () == 0)
1103 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] Cloud is empty!\n");
1106 pcl::visualization::PCLVisualizer::convertToVtkMatrix (cloud->sensor_origin_, cloud->sensor_orientation_, transformation);
1107 poly_points->SetNumberOfPoints (cloud->points.size ());
1108 for (std::size_t i = 0; i < cloud->points.size (); ++i)
1110 const pcl::PointXYZ &p = cloud->points[i];
1111 poly_points->InsertPoint (i, p.x, p.y, p.z);
1116 for (std::size_t i = 0; i < mesh.tex_polygons.size (); i++)
1118 for (std::size_t j = 0; j < mesh.tex_polygons[i].size (); j++)
1120 std::size_t n_points = mesh.tex_polygons[i][j].vertices.size ();
1121 polys->InsertNextCell (
int (n_points));
1122 for (std::size_t k = 0; k < n_points; k++)
1123 polys->InsertCellPoint (mesh.tex_polygons[i][j].vertices[k]);
1128 polydata->SetPolys (polys);
1129 polydata->SetPoints (poly_points);
1131 polydata->GetPointData()->SetScalars(colors);
1134 #if VTK_MAJOR_VERSION < 6 1135 mapper->SetInput (polydata);
1137 mapper->SetInputData (polydata);
1141 vtkTextureUnitManager* tex_manager = vtkOpenGLRenderWindow::SafeDownCast (
_visualizer->getRenderWindow())->GetTextureUnitManager ();
1148 cvImageToVtk->SetImage(image);
1149 cvImageToVtk->Update();
1150 texture->SetInputConnection(cvImageToVtk->GetOutputPort());
1154 coordinates->SetNumberOfComponents (2);
1155 coordinates->SetNumberOfTuples (mesh.tex_coordinates[0].size ());
1156 for (std::size_t tc = 0; tc < mesh.tex_coordinates[0].size (); ++tc)
1158 const Eigen::Vector2f &uv = mesh.tex_coordinates[0][tc];
1159 coordinates->SetTuple2 (tc, (
double)uv[0], (
double)uv[1]);
1161 coordinates->SetName (
"TCoords");
1162 polydata->GetPointData ()->SetTCoords(coordinates);
1164 actor->SetTexture (texture);
1167 actor->SetMapper (mapper);
1171 _visualizer->getRendererCollection()->InitTraversal ();
1172 vtkRenderer* renderer =
NULL;
1174 while ((renderer =
_visualizer->getRendererCollection()->GetNextItem ()) !=
NULL)
1179 renderer->AddActor (actor);
1181 else if (viewport == i)
1183 renderer->AddActor (actor);
1189 (*
_visualizer->getCloudActorMap())[
id].actor = actor;
1192 (*
_visualizer->getCloudActorMap())[
id].viewpoint_transformation_ = transformation;
1194 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.5);
1196 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetInterpolation(
_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
1204 const cv::Mat & map8U,
1210 UASSERT(map8U.channels() == 1 && map8U.type() == CV_8U);
1212 float xSize = float(map8U.cols) * resolution;
1213 float ySize = float(map8U.rows) * resolution;
1215 UDEBUG(
"resolution=%f, xSize=%f, ySize=%f, xMin=%f, yMin=%f", resolution, xSize, ySize, xMin, yMin);
1221 if(xSize > 0.0
f && ySize > 0.0
f)
1223 pcl::TextureMeshPtr mesh(
new pcl::TextureMesh());
1224 pcl::PointCloud<pcl::PointXYZ> cloud;
1225 cloud.push_back(pcl::PointXYZ(xMin, yMin, 0));
1226 cloud.push_back(pcl::PointXYZ(xSize+xMin, yMin, 0));
1227 cloud.push_back(pcl::PointXYZ(xSize+xMin, ySize+yMin, 0));
1228 cloud.push_back(pcl::PointXYZ(xMin, ySize+yMin, 0));
1229 pcl::toPCLPointCloud2(cloud, mesh->cloud);
1231 std::vector<pcl::Vertices> polygons(1);
1232 polygons[0].vertices.push_back(0);
1233 polygons[0].vertices.push_back(1);
1234 polygons[0].vertices.push_back(2);
1235 polygons[0].vertices.push_back(3);
1236 polygons[0].vertices.push_back(0);
1237 mesh->tex_polygons.push_back(polygons);
1241 material.tex_file =
"";
1242 mesh->tex_materials.push_back(material);
1244 #if PCL_VERSION_COMPARE(>=, 1, 8, 0) 1245 std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > coordinates;
1247 std::vector<Eigen::Vector2f> coordinates;
1249 coordinates.push_back(Eigen::Vector2f(0,1));
1250 coordinates.push_back(Eigen::Vector2f(1,1));
1251 coordinates.push_back(Eigen::Vector2f(1,0));
1252 coordinates.push_back(Eigen::Vector2f(0,0));
1253 mesh->tex_coordinates.push_back(coordinates);
1270 const std::string &
id,
1277 UERROR(
"id should not be empty!");
1286 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 1296 const std::string &
id,
1299 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 1306 UERROR(
"CloudViewer::updateCoordinatePose() is not available on PCL < 1.7.2");
1315 UERROR(
"id should not be empty!");
1321 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 1334 for(std::set<std::string>::iterator iter = coordinates.begin(); iter!=coordinates.end(); ++iter)
1342 const std::string &
id,
1345 const QColor & color,
1351 UERROR(
"id should not be empty!");
1361 QColor c = Qt::gray;
1367 pcl::PointXYZ pt1(from.
x(), from.
y(), from.
z());
1368 pcl::PointXYZ pt2(to.
x(), to.
y(), to.
z());
1372 _visualizer->addArrow(pt2, pt1, c.redF(), c.greenF(), c.blueF(),
false, id, foreground?2:1);
1376 _visualizer->addLine(pt2, pt1, c.redF(), c.greenF(), c.blueF(), id, foreground?2:1);
1378 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1386 UERROR(
"id should not be empty!");
1399 std::set<std::string> arrows =
_lines;
1400 for(std::set<std::string>::iterator iter = arrows.begin(); iter!=arrows.end(); ++iter)
1408 const std::string &
id,
1411 const QColor & color,
1416 UERROR(
"id should not be empty!");
1426 QColor c = Qt::gray;
1432 pcl::PointXYZ center(pose.
x(), pose.
y(), pose.
z());
1433 _visualizer->addSphere(center, radius, c.redF(), c.greenF(), c.blueF(), id, foreground?2:1);
1434 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1442 UERROR(
"id should not be empty!");
1455 std::set<std::string> spheres =
_spheres;
1456 for(std::set<std::string>::iterator iter = spheres.begin(); iter!=spheres.end(); ++iter)
1464 const std::string &
id,
1469 const QColor & color,
1475 UERROR(
"id should not be empty!");
1485 QColor c = Qt::gray;
1493 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_REPRESENTATION, pcl::visualization::PCL_VISUALIZER_REPRESENTATION_WIREFRAME,
id);
1495 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, c.redF(), c.greenF(), c.blueF(), id);
1496 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1504 UERROR(
"id should not be empty!");
1517 std::set<std::string> cubes =
_cubes;
1518 for(std::set<std::string>::iterator iter = cubes.begin(); iter!=cubes.end(); ++iter)
1526 const std::string &
id,
1530 const QColor & color,
1533 addOrUpdateQuad(
id, pose, width/2.0
f, width/2.0
f, height/2.0
f, height/2.0
f, color, foreground);
1537 const std::string &
id,
1543 const QColor & color,
1548 UERROR(
"id should not be empty!");
1558 QColor c = Qt::gray;
1565 double p0[3] = {0.0, -widthLeft, heightTop};
1566 double p1[3] = {0.0, -widthLeft, -heightBottom};
1567 double p2[3] = {0.0, widthRight, -heightBottom};
1568 double p3[3] = {0.0, widthRight, heightTop};
1573 points->InsertNextPoint(p0);
1574 points->InsertNextPoint(p1);
1575 points->InsertNextPoint(p2);
1576 points->InsertNextPoint(p3);
1581 quad->GetPointIds()->SetId(0,0);
1582 quad->GetPointIds()->SetId(1,1);
1583 quad->GetPointIds()->SetId(2,2);
1584 quad->GetPointIds()->SetId(3,3);
1589 quads->InsertNextCell(quad);
1596 polydata->SetPoints(points);
1597 polydata->SetPolys(quads);
1602 #if VTK_MAJOR_VERSION <= 5 1603 mapper->SetInput(polydata);
1605 mapper->SetInputData(polydata);
1610 actor->SetMapper(mapper);
1611 actor->GetProperty()->SetColor(c.redF(), c.greenF(), c.blueF());
1615 _visualizer->getRendererCollection()->InitTraversal ();
1616 vtkRenderer* renderer =
NULL;
1618 while ((renderer =
_visualizer->getRendererCollection()->GetNextItem ()) !=
NULL)
1620 if ((foreground?2:1) == i)
1622 renderer->AddActor (actor);
1628 (*
_visualizer->getCloudActorMap())[
id].actor = actor;
1632 pcl::visualization::PCLVisualizer::convertToVtkMatrix (pose.
toEigen3f().matrix (), transformation);
1633 (*
_visualizer->getCloudActorMap())[
id].viewpoint_transformation_ = transformation;
1634 (*
_visualizer->getCloudActorMap())[
id].actor->SetUserMatrix (transformation);
1635 (*
_visualizer->getCloudActorMap())[
id].actor->Modified ();
1637 (*
_visualizer->getCloudActorMap())[
id].actor->GetProperty()->SetLighting(
false);
1638 _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1646 UERROR(
"id should not be empty!");
1659 std::set<std::string> quads =
_quads;
1660 for(std::set<std::string>::iterator iter = quads.begin(); iter!=quads.end(); ++iter)
1675 1, 2, 3, 4, 1, 0, 2, 0, 3, 0, 4};
1678 const std::string &
id,
1682 const QColor & color)
1686 UERROR(
"id should not be empty!");
1690 #if PCL_VERSION_COMPARE(<, 1, 7, 2) 1701 UASSERT(frustumSize>0 && frustumSize % 3 == 0);
1703 pcl::PointCloud<pcl::PointXYZ> frustumPoints;
1704 frustumPoints.resize(frustumSize);
1705 float scaleX = 0.5f *
scale;
1706 float scaleY = 0.4f *
scale;
1707 float scaleZ = 0.3f *
scale;
1708 QColor c = Qt::gray;
1713 Transform opticalRotInv(0, -1, 0, 0, 0, 0, -1, 0, 1, 0, 0, 0);
1715 #if PCL_VERSION_COMPARE(<, 1, 7, 2) 1716 Eigen::Affine3f t = (transform*localTransform*opticalRotInv).toEigen3f();
1718 Eigen::Affine3f t = (localTransform*opticalRotInv).toEigen3f();
1720 for(
int i=0; i<frustumSize; ++i)
1722 frustumPoints[i].x = frustum_vertices[i*3]*scaleX;
1723 frustumPoints[i].y = frustum_vertices[i*3+1]*scaleY;
1724 frustumPoints[i].z = frustum_vertices[i*3+2]*scaleZ;
1728 pcl::PolygonMesh mesh;
1730 vertices.vertices.resize(
sizeof(frustum_indices)/
sizeof(
int));
1731 for(
unsigned int i=0; i<vertices.vertices.size(); ++i)
1733 vertices.vertices[i] = frustum_indices[i];
1735 pcl::toPCLPointCloud2(frustumPoints, mesh.cloud);
1736 mesh.polygons.push_back(vertices);
1737 _visualizer->addPolylineFromPolygonMesh(mesh,
id, 1);
1738 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, c.redF(), c.greenF(), c.blueF(), id);
1739 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1741 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 1744 UERROR(
"Failed updating pose of frustum %s!?",
id.c_str());
1755 const std::string &
id,
1758 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 1759 QMap<std::string, Transform>::iterator iter=
_frustums.find(
id);
1762 if(iter.value() == pose)
1768 pcl::visualization::ShapeActorMap::iterator am_it =
_visualizer->getShapeActorMap()->find (
id);
1772 if (am_it ==
_visualizer->getShapeActorMap()->end ())
1775 actor = vtkActor::SafeDownCast (am_it->second);
1782 pcl::visualization::PCLVisualizer::convertToVtkMatrix (pose.
toEigen3f().matrix (), matrix);
1784 actor->SetUserMatrix (matrix);
1787 iter.value() = pose;
1792 UERROR(
"updateFrustumPose() cannot be used with PCL<1.7.2. Use addOrUpdateFrustum() instead.");
1801 UERROR(
"id should not be empty!");
1814 QMap<std::string, Transform> frustums =
_frustums;
1815 for(QMap<std::string, Transform>::iterator iter = frustums.begin(); iter!=frustums.end(); ++iter)
1817 if(!exceptCameraReference || !
uStrContains(iter.key(),
"reference_frustum"))
1826 const std::string &
id,
1827 const pcl::PointCloud<pcl::PointXYZ>::Ptr & graph,
1828 const QColor & color)
1832 UERROR(
"id should not be empty!");
1842 pcl::PolygonMesh mesh;
1844 vertices.vertices.resize(graph->size());
1845 for(
unsigned int i=0; i<vertices.vertices.size(); ++i)
1847 vertices.vertices[i] = i;
1849 pcl::toPCLPointCloud2(*graph, mesh.cloud);
1850 mesh.polygons.push_back(vertices);
1851 _visualizer->addPolylineFromPolygonMesh(mesh,
id, 1);
1852 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, color.redF(), color.greenF(), color.blueF(), id);
1853 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, color.alphaF(), id);
1864 UERROR(
"id should not be empty!");
1878 std::set<std::string> graphes =
_graphes;
1879 for(std::set<std::string>::iterator iter = graphes.begin(); iter!=graphes.end(); ++iter)
1887 const std::string &
id,
1888 const std::string & text,
1891 const QColor & color,
1896 UERROR(
"id should not be empty!");
1907 pcl::PointXYZ(position.
x(), position.
y(), position.
z()),
1921 UERROR(
"id should not be empty!");
1934 std::set<std::string> texts =
_texts;
1935 for(std::set<std::string>::iterator iter = texts.begin(); iter!=texts.end(); ++iter)
1988 QMap<std::string, Transform> frustumsCopy =
_frustums;
1989 for(QMap<std::string, Transform>::iterator iter=frustumsCopy.begin(); iter!=frustumsCopy.end(); ++iter)
1996 std::set<std::string> linesCopy =
_lines;
1997 for(std::set<std::string>::iterator iter=linesCopy.begin(); iter!=linesCopy.end(); ++iter)
2016 if(!value.isValid())
2020 for(QMap<std::string, Transform>::iterator iter=
_frustums.begin(); iter!=
_frustums.end(); ++iter)
2022 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, value.redF(), value.greenF(), value.blueF(), iter.key());
2113 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
2114 for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2116 if(iter->second.actor.GetPointer() == actor)
2122 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 2124 pcl::visualization::ShapeActorMapPtr shapeActorMap =
_visualizer->getShapeActorMap();
2125 for(pcl::visualization::ShapeActorMap::iterator iter=shapeActorMap->begin(); iter!=shapeActorMap->end(); ++iter)
2127 if(iter->second.GetPointer() == actor)
2129 std::string
id = iter->first;
2130 while(
id.back() ==
'*')
2132 id.erase(
id.size()-1);
2139 return std::string();
2145 pcl::visualization::CloudActorMap::iterator iter =
_visualizer->getCloudActorMap()->find(
id);
2146 if(iter !=
_visualizer->getCloudActorMap()->end())
2149 iter->second.actor->GetProperty()->GetColor(r,g,b);
2150 a = iter->second.actor->GetProperty()->GetOpacity();
2151 color.setRgbF(r, g, b, a);
2153 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 2157 std::string idLayer1 =
id+
"*";
2158 std::string idLayer2 =
id+
"**";
2159 pcl::visualization::ShapeActorMap::iterator iter =
_visualizer->getShapeActorMap()->find(
id);
2160 if(iter ==
_visualizer->getShapeActorMap()->end())
2162 iter =
_visualizer->getShapeActorMap()->find(idLayer1);
2163 if(iter ==
_visualizer->getShapeActorMap()->end())
2165 iter =
_visualizer->getShapeActorMap()->find(idLayer2);
2168 if(iter !=
_visualizer->getShapeActorMap()->end())
2170 vtkActor * actor = vtkActor::SafeDownCast(iter->second);
2174 actor->GetProperty()->GetColor(r,g,b);
2175 a = actor->GetProperty()->GetOpacity();
2176 color.setRgbF(r, g, b, a);
2186 pcl::visualization::CloudActorMap::iterator iter =
_visualizer->getCloudActorMap()->find(
id);
2187 if(iter !=
_visualizer->getCloudActorMap()->end())
2189 iter->second.actor->GetProperty()->SetColor(color.redF(),color.greenF(),color.blueF());
2190 iter->second.actor->GetProperty()->SetOpacity(color.alphaF());
2192 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 2196 std::string idLayer1 =
id+
"*";
2197 std::string idLayer2 =
id+
"**";
2198 pcl::visualization::ShapeActorMap::iterator iter =
_visualizer->getShapeActorMap()->find(
id);
2199 if(iter ==
_visualizer->getShapeActorMap()->end())
2201 iter =
_visualizer->getShapeActorMap()->find(idLayer1);
2202 if(iter ==
_visualizer->getShapeActorMap()->end())
2204 iter =
_visualizer->getShapeActorMap()->find(idLayer2);
2207 if(iter !=
_visualizer->getShapeActorMap()->end())
2209 vtkActor * actor = vtkActor::SafeDownCast(iter->second);
2212 actor->GetProperty()->SetColor(color.redF(),color.greenF(),color.blueF());
2213 actor->GetProperty()->SetOpacity(color.alphaF());
2225 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
2226 for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2228 iter->second.actor->GetProperty()->SetBackfaceCulling(
_aBackfaceCulling->isChecked());
2241 pp->SetTolerance (pp->GetTolerance());
2242 this->GetInteractor()->SetPicker (pp);
2243 setMouseTracking(
false);
2248 pp->SetTolerance (pp->GetTolerance());
2249 this->GetInteractor()->SetPicker (pp);
2250 setMouseTracking(
true);
2265 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
2266 for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2268 iter->second.actor->GetProperty()->SetLighting(
_aSetLighting->isChecked());
2276 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
2277 for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2279 iter->second.actor->GetProperty()->SetInterpolation(
_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
2287 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
2288 for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2297 _visualizer->getRendererCollection()->InitTraversal ();
2298 vtkRenderer* renderer =
NULL;
2300 while ((renderer =
_visualizer->getRendererCollection()->GetNextItem ()) !=
NULL)
2304 _visualizer->getInteractorStyle()->SetDefaultRenderer(renderer);
2305 _visualizer->getInteractorStyle()->SetCurrentRenderer(renderer);
2310 UWARN(
"Could not set layer %d to interactor (layers=%d).", layer,
_visualizer->getRendererCollection()->GetNumberOfItems());
2314 float & x,
float & y,
float & z,
2315 float & focalX,
float & focalY,
float & focalZ,
2316 float & upX,
float & upY,
float & upZ)
const 2318 std::vector<pcl::visualization::Camera> cameras;
2322 x = cameras.begin()->pos[0];
2323 y = cameras.begin()->pos[1];
2324 z = cameras.begin()->pos[2];
2325 focalX = cameras.begin()->focal[0];
2326 focalY = cameras.begin()->focal[1];
2327 focalZ = cameras.begin()->focal[2];
2328 upX = cameras.begin()->view[0];
2329 upY = cameras.begin()->view[1];
2330 upZ = cameras.begin()->view[2];
2334 UERROR(
"No camera set!?");
2339 float x,
float y,
float z,
2340 float focalX,
float focalY,
float focalZ,
2341 float upX,
float upY,
float upZ)
2344 _visualizer->setCameraPosition(x,y,z, focalX,focalY,focalX, upX,upY,upZ, 1);
2352 Eigen::Vector3f pos = m.translation();
2354 Eigen::Vector3f lastPos(0,0,0);
2362 _trajectory->push_back(pcl::PointXYZ(pos[0], pos[1], pos[2]));
2373 pcl::PolygonMesh mesh;
2376 for(
unsigned int i=0; i<vertices.vertices.size(); ++i)
2378 vertices.vertices[i] = i;
2381 mesh.polygons.push_back(vertices);
2382 _visualizer->addPolylineFromPolygonMesh(mesh,
"trajectory", 1);
2392 std::vector<pcl::visualization::Camera> cameras;
2399 cameras.front().pos[0] += diff[0];
2400 cameras.front().pos[1] += diff[1];
2401 cameras.front().pos[2] += diff[2];
2402 cameras.front().focal[0] += diff[0];
2403 cameras.front().focal[1] += diff[1];
2404 cameras.front().focal[2] += diff[2];
2408 Eigen::Vector3f vPosToFocal = Eigen::Vector3f(cameras.front().focal[0] - cameras.front().pos[0],
2409 cameras.front().focal[1] - cameras.front().pos[1],
2410 cameras.front().focal[2] - cameras.front().pos[2]).normalized();
2411 Eigen::Vector3f zAxis(cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
2412 Eigen::Vector3f yAxis = zAxis.cross(vPosToFocal);
2413 Eigen::Vector3f xAxis = yAxis.cross(zAxis);
2414 Transform PR(xAxis[0], xAxis[1], xAxis[2],0,
2415 yAxis[0], yAxis[1], yAxis[2],0,
2416 zAxis[0], zAxis[1], zAxis[2],0);
2420 Transform P(PR[0], PR[1], PR[2], cameras.front().pos[0],
2421 PR[4], PR[5], PR[6], cameras.front().pos[1],
2422 PR[8], PR[9], PR[10], cameras.front().pos[2]);
2423 Transform F(PR[0], PR[1], PR[2], cameras.front().focal[0],
2424 PR[4], PR[5], PR[6], cameras.front().focal[1],
2425 PR[8], PR[9], PR[10], cameras.front().focal[2]);
2435 cameras.front().pos[0] = Pp.
x();
2436 cameras.front().pos[1] = Pp.
y();
2437 cameras.front().pos[2] = Pp.
z();
2438 cameras.front().focal[0] = Fp.
x();
2439 cameras.front().focal[1] = Fp.
y();
2440 cameras.front().focal[2] = Fp.
z();
2442 cameras.front().view[0] =
_aLockViewZ->isChecked()?0:Fp[8];
2443 cameras.front().view[1] =
_aLockViewZ->isChecked()?0:Fp[9];
2444 cameras.front().view[2] =
_aLockViewZ->isChecked()?1:Fp[10];
2447 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 2459 cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
2460 cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
2461 cameras.front().view[0], cameras.front().view[1], cameras.front().view[2], 1);
2470 std::vector<CameraModel> models;
2471 models.push_back(model.
left());
2477 models.push_back(right);
2483 std::vector<CameraModel> models;
2484 models.push_back(model);
2495 for(
unsigned int i=0; i<models.size(); ++i)
2498 if(!models[i].localTransform().
isNull() && !models[i].localTransform().
isIdentity())
2500 baseToCamera = models[i].localTransform();
2502 std::string
id =
uFormat(
"reference_frustum_%d", i);
2536 _visualizer->setBackgroundColor(color.redF(), color.greenF(), color.blueF());
2541 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
2542 pcl::visualization::CloudActorMap::iterator iter = cloudActorMap->find(
id);
2543 if(iter != cloudActorMap->end())
2545 iter->second.actor->SetVisibility(isVisible?1:0);
2547 iter = cloudActorMap->find(
id+
"-normals");
2548 if(iter != cloudActorMap->end())
2550 iter->second.actor->SetVisibility(isVisible&&
_aShowNormals->isChecked()?1:0);
2555 UERROR(
"Cannot find actor named \"%s\".",
id.c_str());
2561 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
2562 pcl::visualization::CloudActorMap::iterator iter = cloudActorMap->find(
id);
2563 if(iter != cloudActorMap->end())
2565 return iter->second.actor->GetVisibility() != 0;
2569 UERROR(
"Cannot find actor named \"%s\".",
id.c_str());
2578 _visualizer->updateColorHandlerIndex(
id, index-1);
2585 _visualizer->getPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, lastOpacity,
id);
2586 if(lastOpacity != opacity)
2588 _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, opacity,
id);
2595 _visualizer->getPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, lastSize,
id);
2596 if((
int)lastSize != size)
2598 _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, (
double)size,
id);
2626 CloudViewerInteractorStyle * interactor = CloudViewerInteractorStyle::SafeDownCast(this->GetInteractor()->GetInteractorStyle());
2696 UERROR(
"Cannot set grid cell count < 1, count=%d", count);
2712 UERROR(
"Cannot set grid cell size <= 0, value=%f", size);
2725 float min = -float(cellCount/2) * cellSize;
2726 float max = float(cellCount/2) * cellSize;
2728 for(
float i=min; i<=
max; i += cellSize)
2731 name =
uFormat(
"line%d", ++
id);
2732 _visualizer->addLine(pcl::PointXYZ(i, min, 0.0
f), pcl::PointXYZ(i, max, 0.0
f), r, g, b, name, 1);
2735 name =
uFormat(
"line%d", ++
id);
2737 pcl::PointXYZ(min, i, 0),
2738 pcl::PointXYZ(max, i, 0),
2747 for(std::list<std::string>::iterator iter =
_gridLines.begin(); iter!=
_gridLines.end(); ++iter)
2758 for(QList<std::string>::iterator iter = ids.begin(); iter!=ids.end(); ++iter)
2760 std::string idNormals = *iter +
"-normals";
2787 UERROR(
"Cannot set normals step <= 0, step=%d", step);
2798 UERROR(
"Cannot set normals scale <= 0, value=%f", scale);
2808 const Eigen::Vector3f & point,
2809 const Eigen::Vector3f &
axis,
2812 Eigen::Vector3f direction = point;
2813 Eigen::Vector3f zAxis =
axis;
2814 float dotProdZ = zAxis.dot(direction);
2815 Eigen::Vector3f ptOnZaxis = zAxis * dotProdZ;
2816 direction -= ptOnZaxis;
2817 Eigen::Vector3f xAxis = direction.normalized();
2818 Eigen::Vector3f yAxis = zAxis.cross(xAxis);
2820 Eigen::Matrix3f newFrame;
2821 newFrame << xAxis[0], yAxis[0], zAxis[0],
2822 xAxis[1], yAxis[1], zAxis[1],
2823 xAxis[2], yAxis[2], zAxis[2];
2827 Eigen::Vector3f newDirection = newFrame.transpose() * direction;
2830 float cosTheta =
cos(angle);
2831 float sinTheta =
sin(angle);
2832 float magnitude = newDirection.norm();
2833 newDirection[0] = ( magnitude * cosTheta );
2834 newDirection[1] = ( magnitude * sinTheta );
2837 direction = newFrame * newDirection;
2839 return direction + ptOnZaxis;
2843 if(event->key() == Qt::Key_Up ||
2844 event->key() == Qt::Key_Down ||
2845 event->key() == Qt::Key_Left ||
2846 event->key() == Qt::Key_Right)
2852 QVTKWidget::keyPressEvent(event);
2858 if(event->key() == Qt::Key_Up ||
2859 event->key() == Qt::Key_Down ||
2860 event->key() == Qt::Key_Left ||
2861 event->key() == Qt::Key_Right)
2865 std::vector<pcl::visualization::Camera> cameras;
2869 Eigen::Vector3f pos(cameras.front().pos[0], cameras.front().pos[1],
_aLockViewZ->isChecked()?0:cameras.front().pos[2]);
2870 Eigen::Vector3f focal(cameras.front().focal[0], cameras.front().focal[1],
_aLockViewZ->isChecked()?0:cameras.front().focal[2]);
2871 Eigen::Vector3f viewUp(cameras.front().view[0], cameras.front().view[1], cameras.front().view[2]);
2872 Eigen::Vector3f cummulatedDir(0,0,0);
2873 Eigen::Vector3f cummulatedFocalDir(0,0,0);
2875 float stepRot = 0.02f;
2878 Eigen::Vector3f dir;
2879 if(event->modifiers() & Qt::ShiftModifier)
2881 dir = viewUp *
step;
2885 dir = (focal-pos).normalized() *
step;
2887 cummulatedDir += dir;
2891 Eigen::Vector3f dir;
2892 if(event->modifiers() & Qt::ShiftModifier)
2894 dir = viewUp * -
step;
2898 dir = (focal-pos).normalized() * -
step;
2900 cummulatedDir += dir;
2904 if(event->modifiers() & Qt::ShiftModifier)
2907 Eigen::Vector3f point = (focal-pos);
2909 Eigen::Vector3f diff = newPoint - point;
2910 cummulatedFocalDir += diff;
2914 Eigen::Vector3f dir = ((focal-pos).
cross(viewUp)).normalized() *
step;
2915 cummulatedDir += dir;
2920 if(event->modifiers() & Qt::ShiftModifier)
2923 Eigen::Vector3f point = (focal-pos);
2925 Eigen::Vector3f diff = newPoint - point;
2926 cummulatedFocalDir += diff;
2930 Eigen::Vector3f dir = ((focal-pos).
cross(viewUp)).normalized() * -
step;
2931 cummulatedDir += dir;
2935 cameras.front().pos[0] += cummulatedDir[0];
2936 cameras.front().pos[1] += cummulatedDir[1];
2937 cameras.front().pos[2] += cummulatedDir[2];
2938 cameras.front().focal[0] += cummulatedDir[0] + cummulatedFocalDir[0];
2939 cameras.front().focal[1] += cummulatedDir[1] + cummulatedFocalDir[1];
2940 cameras.front().focal[2] += cummulatedDir[2] + cummulatedFocalDir[2];
2942 cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
2943 cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
2944 cameras.front().view[0], cameras.front().view[1], cameras.front().view[2], 1);
2952 QVTKWidget::keyPressEvent(event);
2958 if(event->button() == Qt::RightButton)
2964 QVTKWidget::mousePressEvent(event);
2970 QVTKWidget::mouseMoveEvent(event);
2975 std::vector<pcl::visualization::Camera> cameras;
2978 cv::Vec3d newCameraOrientation = cv::Vec3d(0,0,1).cross(cv::Vec3d(cameras.front().pos)-cv::Vec3d(cameras.front().focal));
2989 else if(newCameraOrientation != cv::Vec3d(0,0,0))
2996 if(cameras.front().view[2] == 0)
2998 cameras.front().pos[0] -= 0.00001*cameras.front().view[0];
2999 cameras.front().pos[1] -= 0.00001*cameras.front().view[1];
3003 cameras.front().pos[0] -= 0.00001;
3006 cameras.front().view[0] = 0;
3007 cameras.front().view[1] = 0;
3008 cameras.front().view[2] = 1;
3011 cameras.front().pos[0], cameras.front().pos[1], cameras.front().pos[2],
3012 cameras.front().focal[0], cameras.front().focal[1], cameras.front().focal[2],
3013 cameras.front().view[0], cameras.front().view[1], cameras.front().view[2], 1);
3023 QVTKWidget::wheelEvent(event);
3026 std::vector<pcl::visualization::Camera> cameras;
3035 QAction * a =
_menu->exec(event->globalPos());
3048 int value = QInputDialog::getInt(
this, tr(
"Set trajectory size"), tr(
"Size (0=infinite)"),
_maxTrajectorySize, 0, 10000, 10, &ok);
3065 double value = QInputDialog::getDouble(
this, tr(
"Set frustum scale"), tr(
"Scale"),
_frustumScale, 0.0, 999.0, 1, &ok);
3099 int value = QInputDialog::getInt(
this, tr(
"Set grid cell count"), tr(
"Count"),
_gridCellCount, 1, 10000, 10, &ok);
3108 double value = QInputDialog::getDouble(
this, tr(
"Set grid cell size"), tr(
"Size (m)"),
_gridCellSize, 0.01, 10, 2, &ok);
3122 int value = QInputDialog::getInt(
this, tr(
"Set normals step"), tr(
"Step"),
_normalsStep, 1, 10000, 1, &ok);
3131 double value = QInputDialog::getDouble(
this, tr(
"Set normals scale"), tr(
"Scale (m)"),
_normalsScale, 0.01, 10, 2, &ok);
3140 color = QColorDialog::getColor(color,
this);
3150 double value = QInputDialog::getDouble(
this, tr(
"Rendering rate"), tr(
"Rate (hz)"),
_renderingRate, 0, 60, 0, &ok);
void setDefaultBackgroundColor(const QColor &color)
void setLocalTransform(const Transform &transform)
void removeGraph(const std::string &id)
void removeAllCoordinates()
QAction * _aBackfaceCulling
QAction * _aSetFrustumScale
void setTrajectoryShown(bool shown)
void setFrustumShown(bool shown)
std::set< std::string > _coordinates
void setInteractorLayer(int layer)
iterator begin(unsigned char maxDepth=0) const
void setTrajectorySize(unsigned int value)
unsigned int getGridCellCount() const
pcl::visualization::PCLVisualizer * _visualizer
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
void setNormalsStep(int step)
virtual void keyPressEvent(QKeyEvent *event)
void setNormalsScale(float scale)
void updateCameraFrustum(const Transform &pose, const StereoCameraModel &model)
static void HSVtoRGB(float *r, float *g, float *b, float h, float s, float v)
void setGridShown(bool shown)
QAction * _aSetEdgeVisibility
void setCloudVisibility(const std::string &id, bool isVisible)
std::list< std::string > _gridLines
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
unsigned int getTrajectorySize() const
void removeCube(const std::string &id)
void setCloudViewer(CloudViewer *cloudViewer)
void removeFrustum(const std::string &id)
void addOrUpdateCube(const std::string &id, const Transform &pose, float width, float height, float depth, const QColor &color, bool wireframe=false, bool foreground=false)
void removeQuad(const std::string &id)
GLM_FUNC_DECL detail::tvec3< T, P > axis(detail::tquat< T, P > const &x)
std::set< std::string > _quads
bool removeCloud(const std::string &id)
const iterator end() const
QAction * _aPolygonPicking
static const float vertices[]
bool addOccupancyGridMap(const cv::Mat &map8U, float resolution, float xMin, float yMin, float opacity)
cv::Vec3d _lastCameraOrientation
void setGridCellSize(float size)
void setLighting(bool on)
Transform getTargetPose() const
Eigen::Vector3f rotatePointAroundAxe(const Eigen::Vector3f &point, const Eigen::Vector3f &axis, float angle)
unsigned int getTreeDepth() const
Basic mathematics functions.
const QColor & getDefaultBackgroundColor() const
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
Some conversion functions.
void addOrUpdateSphere(const std::string &id, const Transform &pose, float radius, const QColor &color, bool foreground=false)
bool isNormalsShown() const
void setPolygonPicking(bool enabled)
std::set< std::string > _spheres
QSet< Qt::Key > _keysPressed
void buildPickingLocator(bool enable)
void setCameraOrtho(bool enabled=true)
void removeLine(const std::string &id)
virtual void contextMenuEvent(QContextMenuEvent *event)
float getGridCellSize() const
bool uStrContains(const std::string &string, const std::string &substring)
GLM_FUNC_DECL genType step(genType const &edge, genType const &x)
std::set< std::string > _graphes
bool updateCoordinatePose(const std::string &id, const Transform &transform)
QAction * _aSetNormalsScale
bool addCloudTextureMesh(const std::string &id, const pcl::TextureMesh::Ptr &textureMesh, const cv::Mat &texture, const Transform &pose=Transform::getIdentity())
bool addCloud(const std::string &id, const pcl::PCLPointCloud2Ptr &binaryCloud, const Transform &pose, bool rgb, bool hasNormals, bool hasIntensity, const QColor &color=QColor())
std::set< std::string > _texts
GLM_FUNC_DECL bool isNull(detail::tmat2x2< T, P > const &m, T const &epsilon)
std::string getIdByActor(vtkProp *actor) const
bool isCameraFree() const
void getCameraPosition(float &x, float &y, float &z, float &focalX, float &focalY, float &focalZ, float &upX, float &upY, float &upZ) const
void addOrUpdateLine(const std::string &id, const Transform &from, const Transform &to, const QColor &color, bool arrow=false, bool foreground=false)
#define UASSERT(condition)
GLM_FUNC_DECL genType cos(genType const &angle)
QAction * _aSetFrustumColor
QMap< std::string, Transform > _addedClouds
QAction * _aSetTrajectorySize
Wrappers of STL for convenient functions.
QAction * _aSetBackgroundColor
GLM_FUNC_DECL genType sin(genType const &angle)
const CameraModel & left() const
GLM_FUNC_DECL detail::tvec3< T, P > cross(detail::tvec3< T, P > const &x, detail::tvec3< T, P > const &y)
int getNormalsStep() const
void setColor(const std::string &id, const QColor &color)
void addOrUpdateFrustum(const std::string &id, const Transform &transform, const Transform &localTransform, double scale, const QColor &color=QColor())
void saveSettings(QSettings &settings, const QString &group="") const
void addOrUpdateQuad(const std::string &id, const Transform &pose, float width, float height, const QColor &color, bool foreground=false)
void setGridCellCount(unsigned int count)
void setCameraPosition(float x, float y, float z, float focalX, float focalY, float focalZ, float upX, float upY, float upZ)
float getFrustumScale() const
void getGridMax(double &x, double &y, double &z) const
bool isCameraTargetFollow() const
void setEdgeVisibility(bool visible)
void setFrustumScale(float value)
void removeText(const std::string &id)
void removeOccupancyGridMap()
void setCloudPointSize(const std::string &id, int size)
void setNormalsShown(bool shown)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr createCloud(unsigned int treeDepth=0, std::vector< int > *obstacleIndices=0, std::vector< int > *emptyIndices=0, std::vector< int > *groundIndices=0, bool originalRefPoints=true) const
const RtabmapColorOcTree * octree() const
void setFrustumColor(QColor value)
void updateCameraTargetPosition(const Transform &pose)
bool isCameraLockZ() const
QAction * _aShowTrajectory
const QColor & getBackgroundColor() const
void setBackgroundColor(const QColor &color)
static const int frustum_indices[]
CloudViewer(QWidget *parent=0, CloudViewerInteractorStyle *style=CloudViewerInteractorStyle::New())
bool updateFrustumPose(const std::string &id, const Transform &pose)
void setCameraLockZ(bool enabled=true)
GLM_FUNC_DECL bool isIdentity(matType< T, P > const &m, T const &epsilon)
bool isFrustumShown() const
pcl::PointCloud< pcl::PointXYZ >::Ptr _trajectory
bool getCloudVisibility(const std::string &id)
void getGridMin(double &x, double &y, double &z) const
QAction * _aSetNormalsStep
std::set< std::string > _lines
QAction * _aClearTrajectory
void addOrUpdateGraph(const std::string &id, const pcl::PointCloud< pcl::PointXYZ >::Ptr &graph, const QColor &color=Qt::gray)
void setCameraTargetLocked(bool enabled=true)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
void setOrthoMode(bool enabled)
QAction * _aSetGridCellSize
void updateCameraFrustums(const Transform &pose, const std::vector< CameraModel > &models)
const CameraModel & right() const
void removeSphere(const std::string &id)
static const float frustum_vertices[]
void loadSettings(QSettings &settings, const QString &group="")
double getRenderingRate() const
unsigned int _gridCellCount
virtual void keyReleaseEvent(QKeyEvent *event)
ULogger class and convenient macros.
void setBackfaceCulling(bool enabled, bool frontfaceCulling)
bool isCameraOrtho() const
void setCameraTargetFollow(bool enabled=true)
std::set< std::string > _cubes
QMap< std::string, Transform > _frustums
virtual void mousePressEvent(QMouseEvent *event)
virtual void mouseMoveEvent(QMouseEvent *event)
double getNodeSize(unsigned depth) const
void setCloudColorIndex(const std::string &id, int index)
virtual void handleAction(QAction *event)
void removeCoordinate(const std::string &id)
QAction * _aSetFlatShading
QAction * _aSetGridCellCount
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)
QColor getFrustumColor() const
bool isTrajectoryShown() const
cv::Vec3d _lastCameraPose
virtual void wheelEvent(QWheelEvent *event)
QColor getColor(const std::string &id)
std::string UTILITE_EXP uFormat(const char *fmt,...)
bool getPose(const std::string &id, Transform &pose)
bool isCameraTargetLocked() const
void removeAllFrustums(bool exceptCameraReference=false)
virtual size_t size() const
QAction * _aSetRenderingRate
float getNormalsScale() const
bool updateCloudPose(const std::string &id, const Transform &pose)
void setRenderingRate(double rate)
void setCloudOpacity(const std::string &id, double opacity=1.0)
GLM_FUNC_DECL detail::tmat4x4< T, P > orientation(detail::tvec3< T, P > const &Normal, detail::tvec3< T, P > const &Up)
double keyToCoord(key_type key, unsigned depth) const
const Transform & localTransform() const