31 #include <rtabmap/core/Version.h> 39 #include <pcl/visualization/pcl_visualizer.h> 40 #include <pcl/common/transforms.h> 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> 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> 78 #if VTK_MAJOR_VERSION >= 7 79 #include <vtkEDLShading.h> 80 #include <vtkRenderStepsPass.h> 81 #include <vtkOpenGLRenderer.h> 85 #if VTK_MAJOR_VERSION >= 8 86 #include <vtkGenericOpenGLRenderWindow.h> 89 #ifdef RTABMAP_OCTOMAP 103 _aSetTrajectorySize(0),
104 _aClearTrajectory(0),
107 _aSetFrustumScale(0),
108 _aSetFrustumColor(0),
110 _aSetGridCellCount(0),
111 _aSetGridCellSize(0),
114 _aSetNormalsScale(0),
115 _aSetBackgroundColor(0),
116 _aSetRenderingRate(0),
120 _aSetEdgeVisibility(0),
121 _aBackfaceCulling(0),
123 _trajectory(new
pcl::PointCloud<
pcl::PointXYZ>),
124 _maxTrajectorySize(100),
126 _frustumColor(Qt::gray),
131 _buildLocator(
false),
132 _lastCameraOrientation(0,0,0),
133 _lastCameraPose(0,0,0),
134 _defaultBgColor(Qt::black),
135 _currentBgColor(Qt::black),
136 _frontfaceCulling(
false),
139 _intensityAbsMax(100.0
f),
140 _coordinateFrameScale(1.0)
143 this->setMinimumSize(200, 200);
148 style->AutoAdjustCameraClippingRangeOff();
149 #if VTK_MAJOR_VERSION > 8 152 renderWindow1->AddRenderer(renderer1);
153 _visualizer =
new pcl::visualization::PCLVisualizer(
162 _visualizer =
new pcl::visualization::PCLVisualizer(
174 _visualizer->createViewPort (0,0,1.0, 1.0, viewport);
175 _visualizer->createViewPort (0,0,1.0, 1.0, viewport);
176 _visualizer->createViewPort (0,0,1.0, 1.0, viewport);
177 _visualizer->getRendererCollection()->InitTraversal ();
178 vtkRenderer* renderer =
NULL;
180 while ((renderer =
_visualizer->getRendererCollection()->GetNextItem ()) !=
NULL)
182 renderer->SetLayer(i);
185 #if VTK_MAJOR_VERSION >= 7 186 renderer->PreserveColorBufferOff();
188 renderer->PreserveDepthBufferOff();
189 _visualizer->getInteractorStyle()->SetDefaultRenderer(renderer);
193 #if VTK_MAJOR_VERSION >= 7 194 renderer->PreserveColorBufferOn();
196 renderer->PreserveDepthBufferOn();
200 _visualizer->getRenderWindow()->SetNumberOfLayers(4);
202 #if VTK_MAJOR_VERSION > 8 203 this->setRenderWindow(
_visualizer->getRenderWindow());
205 this->SetRenderWindow(
_visualizer->getRenderWindow());
211 #if VTK_MAJOR_VERSION > 8 212 this->interactor()->SetInteractorStyle (
_visualizer->getInteractorStyle());
214 this->GetInteractor()->SetInteractorStyle (
_visualizer->getInteractorStyle());
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);
223 this->GetInteractor()->SetPicker (pp);
240 setMouseTracking(
false);
282 QAction * freeCamera =
new QAction(
"Free",
this);
283 freeCamera->setCheckable(
true);
284 freeCamera->setChecked(
false);
327 #if VTK_MAJOR_VERSION < 7 346 QMenu * cameraMenu =
new QMenu(
"Camera",
this);
349 cameraMenu->addAction(freeCamera);
350 cameraMenu->addSeparator();
354 QActionGroup * group =
new QActionGroup(
this);
357 group->addAction(freeCamera);
359 QMenu * trajectoryMenu =
new QMenu(
"Trajectory",
this);
364 QMenu * frustumMenu =
new QMenu(
"Frustum",
this);
369 QMenu * gridMenu =
new QMenu(
"Grid",
this);
374 QMenu * normalsMenu =
new QMenu(
"Normals",
this);
379 QMenu * scanMenu =
new QMenu(
"Scan color",
this);
385 _menu =
new QMenu(
this);
386 _menu->addMenu(cameraMenu);
387 _menu->addMenu(trajectoryMenu);
390 _menu->addMenu(frustumMenu);
391 _menu->addMenu(gridMenu);
392 _menu->addMenu(normalsMenu);
393 _menu->addMenu(scanMenu);
408 settings.beginGroup(group);
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);
423 Transform F(focalX, focalY, focalZ, 0,0,0);
427 pose = QVector3D(newPose.
x(), newPose.
y(), newPose.
z());
428 focal = QVector3D(newFocal.
x(), newFocal.
y(), newFocal.
z());
430 settings.setValue(
"camera_pose", pose);
431 settings.setValue(
"camera_focal", focal);
432 settings.setValue(
"camera_up", QVector3D(upX, upY, upZ));
473 settings.beginGroup(group);
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>();
483 this->
setCameraPosition(pose.x(),pose.y(),pose.z(), focal.x(),focal.y(),focal.z(), up.x(),up.y(),up.z());
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());
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());
493 this->
setIntensityRedColormap(settings.value(
"intensity_red_colormap", this->isIntensityRedColormap()).toBool());
495 this->
setIntensityMax(settings.value(
"intensity_max", this->getIntensityMax()).toFloat());
497 this->
setTrajectoryShown(settings.value(
"trajectory_shown", this->isTrajectoryShown()).toBool());
498 this->
setTrajectorySize(settings.value(
"trajectory_size", this->getTrajectorySize()).toUInt());
500 this->
setCameraAxisShown(settings.value(
"camera_axis_shown", this->isCameraAxisShown()).toBool());
501 this->
setCoordinateFrameScale(settings.value(
"coordinate_frame_scale", this->getCoordinateFrameScale()).toDouble());
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>());
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())
513 this->
setCameraLockZ(settings.value(
"camera_lockZ", this->isCameraLockZ()).toBool());
517 this->
setRenderingRate(settings.value(
"rendering_rate", this->getRenderingRate()).toDouble());
529 #if VTK_MAJOR_VERSION > 8 530 this->renderWindow()->Render();
537 const std::string &
id,
544 Eigen::Affine3f posef = pose.
toEigen3f();
548 bool updated =
_visualizer->updatePointCloudPose(
id, posef);
550 #if VTK_MAJOR_VERSION >= 7 554 pcl::visualization::ShapeActorMap::iterator am_it =
_visualizer->getShapeActorMap()->find (
id);
556 if (am_it !=
_visualizer->getShapeActorMap()->end ())
558 actor = vtkActor::SafeDownCast (am_it->second);
562 pcl::visualization::PCLVisualizer::convertToVtkMatrix (pose.
toEigen3f().matrix (), matrix);
563 actor->SetUserMatrix (matrix);
574 std::string idNormals =
id+
"-normals";
577 _visualizer->updatePointCloudPose(idNormals, posef);
589 typedef pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloud
PointCloud;
599 pcl::visualization::PointCloudColorHandler<
pcl::PCLPointCloud2>::PointCloudColorHandler (cloud),
600 maxAbsIntensity_(maxAbsIntensity),
603 field_idx_ = pcl::getFieldIndex (*cloud,
"intensity");
604 if (field_idx_ != -1)
618 #if PCL_VERSION_COMPARE(>, 1, 11, 1) 621 if (!capable_ || !cloud_)
625 if (!capable_ || !cloud_)
630 scalars->SetNumberOfComponents (3);
632 vtkIdType nr_points = cloud_->width * cloud_->height;
634 float * intensities =
new float[nr_points];
636 size_t point_offset = cloud_->fields[field_idx_].offset;
640 int x_idx = pcl::getFieldIndex (*cloud_,
"x");
643 float x_data, y_data, z_data;
644 size_t x_point_offset = cloud_->fields[x_idx].offset;
647 for (vtkIdType cp = 0; cp < nr_points; ++cp,
648 point_offset += cloud_->point_step,
649 x_point_offset += cloud_->point_step)
652 memcpy (&intensity, &cloud_->data[point_offset], sizeof (
float));
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));
661 intensities[j++] = intensity;
668 for (vtkIdType cp = 0; cp < nr_points; ++cp, point_offset += cloud_->point_step)
671 memcpy (&intensity, &cloud_->data[point_offset], sizeof (
float));
673 intensities[j++] = intensity;
679 unsigned char* colors =
new unsigned char[j * 3];
681 if(maxAbsIntensity_>0.0
f)
683 max = maxAbsIntensity_;
687 uMinMax(intensities, j, min, max);
689 for(
size_t k=0; k<j; ++k)
691 colors[k*3+0] = colors[k*3+1] = colors[k*3+2] = max>0?(
unsigned char)(
std::min(intensities[k]/max*255.0
f, 255.0f)):255;
697 else if(colormap_ == 2)
701 colors[k*3+0] = r*255.0f;
702 colors[k*3+1] = g*255.0f;
703 colors[k*3+2] = b*255.0f;
706 reinterpret_cast<vtkUnsignedCharArray*
>(&(*scalars))->SetNumberOfTuples (j);
707 reinterpret_cast<vtkUnsignedCharArray*
>(&(*scalars))->SetArray (colors, j*3, 0, vtkUnsignedCharArray::VTK_DATA_ARRAY_DELETE);
710 reinterpret_cast<vtkUnsignedCharArray*
>(&(*scalars))->SetNumberOfTuples (0);
712 delete [] intensities;
713 #if PCL_VERSION_COMPARE(>, 1, 11, 1) 723 getName ()
const {
return (
"PointCloudColorHandlerIntensityField"); }
735 const std::string &
id,
736 const pcl::PCLPointCloud2Ptr & binaryCloud,
741 const QColor & color,
744 int previousColorIndex = -1;
747 previousColorIndex =
_visualizer->getColorHandlerIndex(
id);
751 Eigen::Vector4f origin(pose.
x(), pose.
y(), pose.
z(), 0.0f);
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";
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))
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);
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);
790 colorHandler.reset(
new pcl::visualization::PointCloudColorHandlerRGBField<pcl::PCLPointCloud2>(binaryCloud));
791 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation,
id, viewport);
793 else if(hasIntensity)
797 _visualizer->addPointCloud (binaryCloud, colorHandler, origin, orientation,
id, viewport);
799 else if(previousColorIndex == 5)
801 previousColorIndex = -1;
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);
814 else if(previousColorIndex > 5)
816 previousColorIndex = -1;
819 if(previousColorIndex>=0)
821 _visualizer->updateColorHandlerIndex(
id, previousColorIndex);
829 _visualizer->updateColorHandlerIndex(
id, hasIntensity?8:7);
831 else if(hasIntensity)
835 else if(color.isValid())
847 const std::string &
id,
848 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
850 const QColor & color)
852 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
853 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
854 return addCloud(
id, binaryCloud, pose,
true,
true,
false, color);
858 const std::string &
id,
859 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
861 const QColor & color)
863 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
864 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
865 return addCloud(
id, binaryCloud, pose,
true,
false,
false, color);
869 const std::string &
id,
870 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
872 const QColor & color)
874 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
875 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
876 return addCloud(
id, binaryCloud, pose,
false,
true,
true, color);
880 const std::string &
id,
881 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
883 const QColor & color)
885 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
886 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
887 return addCloud(
id, binaryCloud, pose,
false,
false,
true, color);
891 const std::string &
id,
892 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
894 const QColor & color)
896 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
897 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
898 return addCloud(
id, binaryCloud, pose,
false,
true,
false, color);
902 const std::string &
id,
903 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
905 const QColor & color)
907 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
908 pcl::toPCLPointCloud2(*cloud, *binaryCloud);
909 return addCloud(
id, binaryCloud, pose,
false,
false,
false, color);
913 const std::string &
id,
914 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
915 const std::vector<pcl::Vertices> & polygons,
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))
926 #if VTK_MAJOR_VERSION >= 7 927 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.1);
929 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.5);
932 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetInterpolation(
_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
940 tree->SetDataSet(
_visualizer->getCloudActorMap()->find(
id)->second.actor->GetMapper()->GetInput());
941 tree->BuildLocator();
942 _locators.insert(std::make_pair(
id, tree));
951 const std::string &
id,
952 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
953 const std::vector<pcl::Vertices> & polygons,
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))
964 #if VTK_MAJOR_VERSION >= 7 965 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.1);
967 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.5);
970 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetInterpolation(
_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
978 tree->SetDataSet(
_visualizer->getCloudActorMap()->find(
id)->second.actor->GetMapper()->GetInput());
979 tree->BuildLocator();
980 _locators.insert(std::make_pair(
id, tree));
989 const std::string &
id,
990 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
991 const std::vector<pcl::Vertices> & polygons,
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))
1002 #if VTK_MAJOR_VERSION >= 7 1003 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.1);
1005 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.5);
1008 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetInterpolation(
_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
1016 tree->SetDataSet(
_visualizer->getCloudActorMap()->find(
id)->second.actor->GetMapper()->GetInput());
1017 tree->BuildLocator();
1018 _locators.insert(std::make_pair(
id, tree));
1027 const std::string &
id,
1028 const pcl::PolygonMesh::Ptr & mesh,
1036 UDEBUG(
"Adding %s with %d polygons",
id.c_str(), (
int)mesh->polygons.size());
1039 #if VTK_MAJOR_VERSION >= 7 1040 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.1);
1042 _visualizer->getCloudActorMap()->find(
id)->second.actor->GetProperty()->SetAmbient(0.5);
1052 tree->SetDataSet(
_visualizer->getCloudActorMap()->find(
id)->second.actor->GetMapper()->GetInput());
1053 tree->BuildLocator();
1054 _locators.insert(std::make_pair(
id, tree));
1064 const std::string &
id,
1065 const pcl::TextureMesh::Ptr & textureMesh,
1066 const cv::Mat & texture,
1074 UDEBUG(
"Adding %s",
id.c_str());
1077 #if VTK_MAJOR_VERSION >= 7 1078 vtkActor* actor = vtkActor::SafeDownCast (
_visualizer->getShapeActorMap()->find(
id)->second);
1080 vtkActor* actor = vtkActor::SafeDownCast (
_visualizer->getCloudActorMap()->find(
id)->second.actor);
1083 if(!textureMesh->cloud.is_dense)
1085 actor->GetTexture()->SetInterpolate(1);
1086 actor->GetTexture()->SetBlendingMode(vtkTexture::VTK_TEXTURE_BLENDING_MODE_REPLACE);
1091 tree->SetDataSet(actor->GetMapper()->GetInput());
1092 tree->BuildLocator();
1093 _locators.insert(std::make_pair(
id, tree));
1105 #ifdef RTABMAP_OCTOMAP 1108 pcl::IndicesPtr obstacles(
new std::vector<int>);
1114 UWARN(
"Tree depth requested (%d) is deeper than the " 1115 "actual maximum tree depth of %d. Using maximum depth.",
1123 if(!volumeRepresentation)
1125 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = octomap->
createCloud(treeDepth, obstacles.get(), 0, 0,
false);
1126 if(obstacles->size())
1132 colors->SetName(
"colors");
1133 colors->SetNumberOfValues(obstacles->size());
1136 lut->SetNumberOfTableValues(obstacles->size());
1141 points->SetNumberOfPoints(obstacles->size());
1143 for (
unsigned int i = 0; i < obstacles->size(); i++)
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);
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);
1159 polydata->SetPoints(points);
1160 polydata->GetPointData()->SetScalars(colors);
1164 cubeSource->SetBounds(-s, s, -s, s, -s, s);
1167 mapper->SetSourceConnection(cubeSource->GetOutputPort());
1168 #if VTK_MAJOR_VERSION <= 5 1169 mapper->SetInputConnection(polydata->GetProducerPort());
1171 mapper->SetInputData(polydata);
1173 mapper->SetScalarRange(0, obstacles->size() - 1);
1174 mapper->SetLookupTable(lut);
1175 mapper->ScalingOff();
1179 octomapActor->SetMapper(mapper);
1181 octomapActor->GetProperty()->SetRepresentationToSurface();
1183 octomapActor->GetProperty()->SetLighting(
_aSetLighting->isChecked());
1185 _visualizer->getRendererCollection()->InitTraversal ();
1186 vtkRenderer* renderer =
NULL;
1187 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
1188 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
1190 renderer->AddActor(octomapActor);
1204 double sizeX, sizeY, sizeZ;
1205 double minX, minY, minZ;
1206 double maxX, maxY, maxZ;
1216 imageData->SetExtent(0,
int(sizeX/cellSize+0.5), 0,
int(sizeY/cellSize+0.5), 0,
int(sizeZ/cellSize+0.5));
1217 #if VTK_MAJOR_VERSION <= 5 1218 imageData->SetNumberOfScalarComponents(4);
1219 imageData->SetScalarTypeToUnsignedChar();
1221 imageData->AllocateScalars(VTK_UNSIGNED_CHAR,4);
1225 imageData->GetDimensions(dims);
1227 memset(imageData->GetScalarPointer(), 0, imageData->GetScalarSize()*imageData->GetNumberOfScalarComponents()*dims[0]*dims[1]*dims[2]);
1231 if(octomap->
octree()->isNodeOccupied(*it))
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])
1239 unsigned char* pixel =
static_cast<unsigned char*
>(imageData->GetScalarPointer(x,y,z));
1242 pixel[0] = it->getColor().r;
1243 pixel[1] = it->getColor().g;
1244 pixel[2] = it->getColor().b;
1249 float H = (maxZ - pt.
z())*299.0
f/(maxZ-minZ);
1252 pixel[0] = r*255.0f;
1253 pixel[1] = g*255.0f;
1254 pixel[2] = b*255.0f;
1262 volumeMapper->SetBlendModeToComposite();
1263 #if VTK_MAJOR_VERSION <= 5 1264 volumeMapper->SetInputConnection(imageData->GetProducerPort());
1266 volumeMapper->SetInputData(imageData);
1270 volumeProperty->ShadeOff();
1271 volumeProperty->IndependentComponentsOff();
1275 compositeOpacity->AddPoint(0.0,0.0);
1276 compositeOpacity->AddPoint(255.0,1.0);
1277 volumeProperty->SetScalarOpacity(0, compositeOpacity);
1281 volume->SetMapper(volumeMapper);
1282 volume->SetProperty(volumeProperty);
1283 volume->SetScale(cellSize);
1284 volume->SetPosition(minX, minY, minZ);
1286 _visualizer->getRendererCollection()->InitTraversal ();
1287 vtkRenderer* renderer =
NULL;
1288 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
1289 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
1291 renderer->AddViewProp(volume);
1294 #if !defined(VTK_LEGACY_REMOVE) && !defined(VTK_OPENGL2) && VTK_MAJOR_VERSION < 9 1295 volumeMapper->SetRequestedRenderModeToRayCastAndTexture();
1296 #endif // VTK_LEGACY_REMOVE 1300 volumeMapper->SetRequestedRenderModeToRayCast();
1313 #ifdef RTABMAP_OCTOMAP 1316 _visualizer->getRendererCollection()->InitTraversal ();
1317 vtkRenderer* renderer =
NULL;
1318 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
1319 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
1328 const pcl::TextureMesh &mesh,
1329 const cv::Mat & image,
1330 const std::string &
id,
1335 #if VTK_MAJOR_VERSION >= 7 1336 pcl::visualization::ShapeActorMap::iterator am_it =
_visualizer->getShapeActorMap()->find (
id);
1337 if (am_it !=
_visualizer->getShapeActorMap()->end ())
1339 pcl::visualization::CloudActorMap::iterator am_it =
_visualizer->getCloudActorMap()->find (
id);
1340 if (am_it !=
_visualizer->getCloudActorMap()->end ())
1343 PCL_ERROR (
"[PCLVisualizer::addTextureMesh] A shape with id <%s> already exists!" 1344 " Please choose a different id and retry.\n",
1349 if (mesh.tex_materials.size () == 0)
1351 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] No textures found!\n");
1354 else if (mesh.tex_materials.size() > 1)
1356 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] only one material per mesh is supported!\n");
1360 if (mesh.tex_materials.size () != mesh.tex_polygons.size ())
1362 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] Materials number %lu differs from polygons number %lu!\n",
1363 mesh.tex_materials.size (), mesh.tex_polygons.size ());
1367 if (mesh.tex_materials.size () != mesh.tex_coordinates.size ())
1369 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] Coordinates number %lu differs from materials number %lu!\n",
1370 mesh.tex_coordinates.size (), mesh.tex_materials.size ());
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 ();
1378 if (nb_vertices == 0)
1380 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] No vertices found!\n");
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 ();
1388 if (nb_coordinates == 0)
1390 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] No textures coordinates found!\n");
1397 bool has_color =
false;
1400 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (
new pcl::PointCloud<pcl::PointXYZ> ());
1401 pcl::fromPCLPointCloud2 (mesh.cloud, *cloud);
1403 if (cloud->points.size () == 0)
1405 PCL_ERROR(
"[PCLVisualizer::addTextureMesh] Cloud is empty!\n");
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)
1412 const pcl::PointXYZ &p = cloud->points[i];
1413 poly_points->InsertPoint (i, p.x, p.y, p.z);
1418 for (std::size_t i = 0; i < mesh.tex_polygons.size (); i++)
1420 for (std::size_t j = 0; j < mesh.tex_polygons[i].size (); j++)
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]);
1430 polydata->SetPolys (polys);
1431 polydata->SetPoints (poly_points);
1433 polydata->GetPointData()->SetScalars(colors);
1436 #if VTK_MAJOR_VERSION < 6 1437 mapper->SetInput (polydata);
1439 mapper->SetInputData (polydata);
1442 #if VTK_MAJOR_VERSION >= 7 1447 vtkTextureUnitManager* tex_manager = vtkOpenGLRenderWindow::SafeDownCast (
_visualizer->getRenderWindow())->GetTextureUnitManager ();
1454 cvImageToVtk->SetImage(image);
1455 cvImageToVtk->Update();
1456 texture->SetInputConnection(cvImageToVtk->GetOutputPort());
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)
1464 const Eigen::Vector2f &uv = mesh.tex_coordinates[0][tc];
1465 coordinates->SetTuple2 (tc, (
double)uv[0], (
double)uv[1]);
1467 coordinates->SetName (
"TCoords");
1468 polydata->GetPointData ()->SetTCoords(coordinates);
1470 actor->SetTexture (texture);
1473 actor->SetMapper (mapper);
1477 _visualizer->getRendererCollection()->InitTraversal ();
1478 vtkRenderer* renderer =
NULL;
1480 while ((renderer =
_visualizer->getRendererCollection()->GetNextItem ()) !=
NULL)
1485 renderer->AddActor (actor);
1487 else if (viewport == i)
1489 renderer->AddActor (actor);
1495 #if VTK_MAJOR_VERSION >= 7 1498 (*
_visualizer->getCloudActorMap())[
id].actor = actor;
1500 (*
_visualizer->getCloudActorMap())[
id].viewpoint_transformation_ = transformation;
1503 #if VTK_MAJOR_VERSION >= 7 1504 actor->GetProperty()->SetAmbient(0.1);
1506 actor->GetProperty()->SetAmbient(0.5);
1508 actor->GetProperty()->SetLighting(
_aSetLighting->isChecked());
1509 actor->GetProperty()->SetInterpolation(
_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
1517 const cv::Mat & map8U,
1523 UASSERT(map8U.channels() == 1 && map8U.type() == CV_8U);
1525 float xSize = float(map8U.cols) * resolution;
1526 float ySize = float(map8U.rows) * resolution;
1528 UDEBUG(
"resolution=%f, xSize=%f, ySize=%f, xMin=%f, yMin=%f", resolution, xSize, ySize, xMin, yMin);
1529 #if VTK_MAJOR_VERSION >= 7 1541 if(xSize > 0.0
f && ySize > 0.0
f)
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);
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);
1561 material.tex_file =
"";
1562 mesh->tex_materials.push_back(material);
1564 #if PCL_VERSION_COMPARE(>=, 1, 8, 0) 1565 std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > coordinates;
1567 std::vector<Eigen::Vector2f> coordinates;
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);
1583 #if VTK_MAJOR_VERSION >= 7 1597 const std::string &
id,
1604 UERROR(
"id should not be empty!");
1613 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 1623 const std::string &
id,
1626 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 1633 UERROR(
"CloudViewer::updateCoordinatePose() is not available on PCL < 1.7.2");
1642 UERROR(
"id should not be empty!");
1648 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 1661 for(std::set<std::string>::iterator iter = coordinates.begin(); iter!=coordinates.end(); ++iter)
1663 if(prefix.empty() || iter->find(prefix) != std::string::npos)
1672 const std::string &
id,
1675 const QColor & color,
1681 UERROR(
"id should not be empty!");
1691 QColor c = Qt::gray;
1697 pcl::PointXYZ pt1(from.
x(), from.
y(), from.
z());
1698 pcl::PointXYZ pt2(to.
x(), to.
y(), to.
z());
1702 _visualizer->addArrow(pt2, pt1, c.redF(), c.greenF(), c.blueF(),
false, id, foreground?3:2);
1706 _visualizer->addLine(pt2, pt1, c.redF(), c.greenF(), c.blueF(), id, foreground?3:2);
1708 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1716 UERROR(
"id should not be empty!");
1729 std::set<std::string> arrows =
_lines;
1730 for(std::set<std::string>::iterator iter = arrows.begin(); iter!=arrows.end(); ++iter)
1738 const std::string &
id,
1741 const QColor & color,
1746 UERROR(
"id should not be empty!");
1756 QColor c = Qt::gray;
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);
1772 UERROR(
"id should not be empty!");
1785 std::set<std::string> spheres =
_spheres;
1786 for(std::set<std::string>::iterator iter = spheres.begin(); iter!=spheres.end(); ++iter)
1794 const std::string &
id,
1799 const QColor & color,
1805 UERROR(
"id should not be empty!");
1815 QColor c = Qt::gray;
1823 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_REPRESENTATION, pcl::visualization::PCL_VISUALIZER_REPRESENTATION_WIREFRAME,
id);
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);
1834 UERROR(
"id should not be empty!");
1847 std::set<std::string> cubes =
_cubes;
1848 for(std::set<std::string>::iterator iter = cubes.begin(); iter!=cubes.end(); ++iter)
1856 const std::string &
id,
1860 const QColor & color,
1863 addOrUpdateQuad(
id, pose, width/2.0
f, width/2.0
f, height/2.0
f, height/2.0
f, color, foreground);
1867 const std::string &
id,
1873 const QColor & color,
1878 UERROR(
"id should not be empty!");
1888 QColor c = Qt::gray;
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};
1903 points->InsertNextPoint(p0);
1904 points->InsertNextPoint(p1);
1905 points->InsertNextPoint(p2);
1906 points->InsertNextPoint(p3);
1911 quad->GetPointIds()->SetId(0,0);
1912 quad->GetPointIds()->SetId(1,1);
1913 quad->GetPointIds()->SetId(2,2);
1914 quad->GetPointIds()->SetId(3,3);
1919 quads->InsertNextCell(quad);
1926 polydata->SetPoints(points);
1927 polydata->SetPolys(quads);
1932 #if VTK_MAJOR_VERSION <= 5 1933 mapper->SetInput(polydata);
1935 mapper->SetInputData(polydata);
1940 actor->SetMapper(mapper);
1941 actor->GetProperty()->SetColor(c.redF(), c.greenF(), c.blueF());
1945 _visualizer->getRendererCollection()->InitTraversal ();
1946 vtkRenderer* renderer =
NULL;
1948 while ((renderer =
_visualizer->getRendererCollection()->GetNextItem ()) !=
NULL)
1950 if ((foreground?3:2) == i)
1952 renderer->AddActor (actor);
1958 (*
_visualizer->getCloudActorMap())[
id].actor = actor;
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 ();
1967 (*
_visualizer->getCloudActorMap())[
id].actor->GetProperty()->SetLighting(
false);
1968 _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, c.alphaF(), id);
1976 UERROR(
"id should not be empty!");
1989 std::set<std::string> quads =
_quads;
1990 for(std::set<std::string>::iterator iter = quads.begin(); iter!=quads.end(); ++iter)
2005 1, 2, 3, 4, 1, 0, 2, 0, 3, 0, 4};
2008 const std::string &
id,
2012 const QColor & color,
2018 UERROR(
"id should not be empty!");
2022 #if PCL_VERSION_COMPARE(<, 1, 7, 2) 2033 UASSERT(frustumSize>0 && frustumSize % 3 == 0);
2035 pcl::PointCloud<pcl::PointXYZ> frustumPoints;
2036 frustumPoints.resize(frustumSize);
2037 float scaleX =
tan((fovX>0?fovX:1.1)/2.0
f) *
scale;
2038 float scaleY =
tan((fovY>0?fovY:0.85)/2.0
f) *
scale;
2039 float scaleZ =
scale;
2040 QColor c = Qt::gray;
2045 Transform opticalRotInv(0, -1, 0, 0, 0, 0, -1, 0, 1, 0, 0, 0);
2047 #if PCL_VERSION_COMPARE(<, 1, 7, 2) 2048 Eigen::Affine3f t = (pose*localTransform).toEigen3f();
2050 Eigen::Affine3f t = (localTransform).toEigen3f();
2052 for(
int i=0; i<frustumSize; ++i)
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;
2060 pcl::PolygonMesh mesh;
2062 vertices.vertices.resize(
sizeof(frustum_indices)/
sizeof(
int));
2063 for(
unsigned int i=0; i<vertices.vertices.size(); ++i)
2065 vertices.vertices[i] = frustum_indices[i];
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);
2073 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 2076 UERROR(
"Failed updating pose of frustum %s!?",
id.c_str());
2087 const std::string &
id,
2090 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 2091 QMap<std::string, Transform>::iterator iter=
_frustums.find(
id);
2094 if(iter.value() == pose)
2100 pcl::visualization::ShapeActorMap::iterator am_it =
_visualizer->getShapeActorMap()->find (
id);
2104 if (am_it ==
_visualizer->getShapeActorMap()->end ())
2107 actor = vtkActor::SafeDownCast (am_it->second);
2114 pcl::visualization::PCLVisualizer::convertToVtkMatrix (pose.
toEigen3f().matrix (), matrix);
2116 actor->SetUserMatrix (matrix);
2119 iter.value() = pose;
2124 UERROR(
"updateFrustumPose() cannot be used with PCL<1.7.2. Use addOrUpdateFrustum() instead.");
2133 UERROR(
"id should not be empty!");
2146 QMap<std::string, Transform> frustums =
_frustums;
2147 for(QMap<std::string, Transform>::iterator iter = frustums.begin(); iter!=frustums.end(); ++iter)
2149 if(!exceptCameraReference || !
uStrContains(iter.key(),
"reference_frustum"))
2158 const std::string &
id,
2159 const pcl::PointCloud<pcl::PointXYZ>::Ptr & graph,
2160 const QColor & color)
2164 UERROR(
"id should not be empty!");
2174 pcl::PolygonMesh mesh;
2176 vertices.vertices.resize(graph->size());
2177 for(
unsigned int i=0; i<vertices.vertices.size(); ++i)
2179 vertices.vertices[i] = i;
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);
2187 pcl::PCLPointCloud2Ptr binaryCloud(
new pcl::PCLPointCloud2);
2188 pcl::toPCLPointCloud2(*graph, *binaryCloud);
2198 UERROR(
"id should not be empty!");
2212 std::set<std::string> graphes =
_graphes;
2213 for(std::set<std::string>::iterator iter = graphes.begin(); iter!=graphes.end(); ++iter)
2221 const std::string &
id,
2222 const std::string & text,
2225 const QColor & color,
2230 UERROR(
"id should not be empty!");
2241 pcl::PointXYZ(position.
x(), position.
y(), position.
z()),
2255 UERROR(
"id should not be empty!");
2268 std::set<std::string> texts =
_texts;
2269 for(std::set<std::string>::iterator iter = texts.begin(); iter!=texts.end(); ++iter)
2351 QMap<std::string, Transform> frustumsCopy =
_frustums;
2352 for(QMap<std::string, Transform>::iterator iter=frustumsCopy.begin(); iter!=frustumsCopy.end(); ++iter)
2359 std::set<std::string> linesCopy =
_lines;
2360 for(std::set<std::string>::iterator iter=linesCopy.begin(); iter!=linesCopy.end(); ++iter)
2379 if(!value.isValid())
2383 for(QMap<std::string, Transform>::iterator iter=
_frustums.begin(); iter!=
_frustums.end(); ++iter)
2385 _visualizer->setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, value.redF(), value.greenF(), value.blueF(), iter.key());
2438 QMap<std::string, Transform> addedClouds =
_addedClouds;
2440 for(QList<std::string>::iterator iter = ids.begin(); iter!=ids.end(); ++iter)
2452 #if VTK_MAJOR_VERSION >= 7 2486 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
2487 for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2489 if(iter->second.actor.GetPointer() == actor)
2495 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 2497 pcl::visualization::ShapeActorMapPtr shapeActorMap =
_visualizer->getShapeActorMap();
2498 for(pcl::visualization::ShapeActorMap::iterator iter=shapeActorMap->begin(); iter!=shapeActorMap->end(); ++iter)
2500 if(iter->second.GetPointer() == actor)
2502 std::string
id = iter->first;
2503 while(
id.size() &&
id.at(
id.size()-1) ==
'*')
2505 id.erase(
id.size()-1);
2512 return std::string();
2518 pcl::visualization::CloudActorMap::iterator iter =
_visualizer->getCloudActorMap()->find(
id);
2519 if(iter !=
_visualizer->getCloudActorMap()->end())
2522 iter->second.actor->GetProperty()->GetColor(r,g,b);
2523 a = iter->second.actor->GetProperty()->GetOpacity();
2524 color.setRgbF(r, g, b, a);
2526 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 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())
2535 iter =
_visualizer->getShapeActorMap()->find(idLayer1);
2536 if(iter ==
_visualizer->getShapeActorMap()->end())
2538 iter =
_visualizer->getShapeActorMap()->find(idLayer2);
2541 if(iter !=
_visualizer->getShapeActorMap()->end())
2543 vtkActor * actor = vtkActor::SafeDownCast(iter->second);
2547 actor->GetProperty()->GetColor(r,g,b);
2548 a = actor->GetProperty()->GetOpacity();
2549 color.setRgbF(r, g, b, a);
2559 pcl::visualization::CloudActorMap::iterator iter =
_visualizer->getCloudActorMap()->find(
id);
2560 if(iter !=
_visualizer->getCloudActorMap()->end())
2562 iter->second.actor->GetProperty()->SetColor(color.redF(),color.greenF(),color.blueF());
2563 iter->second.actor->GetProperty()->SetOpacity(color.alphaF());
2565 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 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())
2574 iter =
_visualizer->getShapeActorMap()->find(idLayer1);
2575 if(iter ==
_visualizer->getShapeActorMap()->end())
2577 iter =
_visualizer->getShapeActorMap()->find(idLayer2);
2580 if(iter !=
_visualizer->getShapeActorMap()->end())
2582 vtkActor * actor = vtkActor::SafeDownCast(iter->second);
2585 actor->GetProperty()->SetColor(color.redF(),color.greenF(),color.blueF());
2586 actor->GetProperty()->SetOpacity(color.alphaF());
2598 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
2599 for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2601 iter->second.actor->GetProperty()->SetBackfaceCulling(
_aBackfaceCulling->isChecked());
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)
2608 vtkActor* actor = vtkActor::SafeDownCast (iter->second);
2626 pp->SetTolerance (pp->GetTolerance());
2627 #if VTK_MAJOR_VERSION > 8 2628 this->interactor()->SetPicker (pp);
2630 this->GetInteractor()->SetPicker (pp);
2632 setMouseTracking(
false);
2637 pp->SetTolerance (pp->GetTolerance());
2638 #if VTK_MAJOR_VERSION > 8 2639 this->interactor()->SetPicker (pp);
2641 this->GetInteractor()->SetPicker (pp);
2643 setMouseTracking(
true);
2657 #if VTK_MAJOR_VERSION >= 7 2659 _visualizer->getRendererCollection()->InitTraversal ();
2660 vtkRenderer* renderer =
NULL;
2661 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
2662 renderer =
_visualizer->getRendererCollection()->GetNextItem ();
2665 vtkOpenGLRenderer* glrenderer = vtkOpenGLRenderer::SafeDownCast(renderer);
2672 edl->SetDelegatePass(basicPasses);
2673 glrenderer->SetPass(edl);
2675 else if(glrenderer->GetPass())
2677 glrenderer->GetPass()->ReleaseGraphicsResources(
NULL);
2678 glrenderer->SetPass(
NULL);
2685 UERROR(
"RTAB-Map must be built with VTK>=7 to enable EDL shading!");
2693 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
2694 for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2696 iter->second.actor->GetProperty()->SetLighting(
_aSetLighting->isChecked());
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)
2702 vtkActor* actor = vtkActor::SafeDownCast (iter->second);
2705 actor->GetProperty()->SetLighting(
_aSetLighting->isChecked());
2715 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
2716 for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
2718 iter->second.actor->GetProperty()->SetInterpolation(
_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
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)
2724 vtkActor* actor = vtkActor::SafeDownCast (iter->second);
2727 actor->GetProperty()->SetInterpolation(
_aSetFlatShading->isChecked()?VTK_FLAT:VTK_PHONG);
2737 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
2738 for(pcl::visualization::CloudActorMap::iterator iter=cloudActorMap->begin(); iter!=cloudActorMap->end(); ++iter)
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)
2746 vtkActor* actor = vtkActor::SafeDownCast (iter->second);
2758 _visualizer->getRendererCollection()->InitTraversal ();
2759 vtkRenderer* renderer =
NULL;
2761 while ((renderer =
_visualizer->getRendererCollection()->GetNextItem ()) !=
NULL)
2765 _visualizer->getInteractorStyle()->SetDefaultRenderer(renderer);
2766 _visualizer->getInteractorStyle()->SetCurrentRenderer(renderer);
2771 UWARN(
"Could not set layer %d to interactor (layers=%d).", layer,
_visualizer->getRendererCollection()->GetNumberOfItems());
2775 float & x,
float & y,
float & z,
2776 float & focalX,
float & focalY,
float & focalZ,
2777 float & upX,
float & upY,
float & upZ)
const 2779 std::vector<pcl::visualization::Camera> cameras;
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];
2795 UERROR(
"No camera set!?");
2800 float x,
float y,
float z,
2801 float focalX,
float focalY,
float focalZ,
2802 float upX,
float upY,
float upZ)
2804 vtkRenderer* renderer =
NULL;
2805 double boundingBox[6] = {1, -1, 1, -1, 1, -1};
2808 _visualizer->getRendererCollection()->InitTraversal ();
2809 while ((renderer =
_visualizer->getRendererCollection()->GetNextItem ()) !=
NULL)
2812 cam->SetPosition (x, y, z);
2813 cam->SetFocalPoint (focalX, focalY, focalZ);
2814 cam->SetViewUp (upX, upY, upZ);
2817 renderer->ComputeVisiblePropBounds(BB);
2818 for (
int i = 0; i < 6; i++) {
2821 if (BB[i] < boundingBox[i]) {
2822 boundingBox[i] = BB[i];
2826 if (BB[i] > boundingBox[i]) {
2827 boundingBox[i] = BB[i];
2833 _visualizer->getRendererCollection()->InitTraversal ();
2834 while ((renderer =
_visualizer->getRendererCollection()->GetNextItem ()) !=
NULL)
2836 renderer->ResetCameraClippingRange(boundingBox);
2847 Eigen::Vector3f pos = m.translation();
2849 Eigen::Vector3f lastPos(0,0,0);
2857 _trajectory->push_back(pcl::PointXYZ(pos[0], pos[1], pos[2]));
2868 pcl::PolygonMesh mesh;
2871 for(
unsigned int i=0; i<vertices.vertices.size(); ++i)
2873 vertices.vertices[i] = i;
2876 mesh.polygons.push_back(vertices);
2877 _visualizer->addPolylineFromPolygonMesh(mesh,
"trajectory", 2);
2887 std::vector<pcl::visualization::Camera> cameras;
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];
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);
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]);
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();
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];
2944 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 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]);
2968 std::vector<CameraModel> models;
2969 models.push_back(model.
left());
2975 models.push_back(right);
2981 std::vector<CameraModel> models;
2982 models.push_back(model);
2993 for(
unsigned int i=0; i<models.size(); ++i)
2996 if(!models[i].localTransform().
isNull() && !models[i].localTransform().
isIdentity())
2998 baseToCamera = models[i].localTransform();
3000 std::string
id =
uFormat(
"reference_frustum_%d", i);
3013 std::vector<CameraModel> models;
3014 for(
size_t i=0; i<stereoModels.size(); ++i)
3016 models.push_back(stereoModels[i].left());
3018 if(!stereoModels[i].left().localTransform().
isNull())
3022 models.push_back(right);
3049 _visualizer->setBackgroundColor(color.redF(), color.greenF(), color.blueF());
3054 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
3055 pcl::visualization::CloudActorMap::iterator iter = cloudActorMap->find(
id);
3056 if(iter != cloudActorMap->end())
3058 iter->second.actor->SetVisibility(isVisible?1:0);
3060 iter = cloudActorMap->find(
id+
"-normals");
3061 if(iter != cloudActorMap->end())
3063 iter->second.actor->SetVisibility(isVisible&&
_aShowNormals->isChecked()?1:0);
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())
3073 vtkActor* actor = vtkActor::SafeDownCast (iter->second);
3076 actor->SetVisibility(isVisible?1:0);
3081 UERROR(
"Cannot find actor named \"%s\".",
id.c_str());
3087 pcl::visualization::CloudActorMapPtr cloudActorMap =
_visualizer->getCloudActorMap();
3088 pcl::visualization::CloudActorMap::iterator iter = cloudActorMap->find(
id);
3089 if(iter != cloudActorMap->end())
3091 return iter->second.actor->GetVisibility() != 0;
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())
3100 vtkActor* actor = vtkActor::SafeDownCast (iter->second);
3103 return actor->GetVisibility() != 0;
3107 UERROR(
"Cannot find actor named \"%s\".",
id.c_str());
3116 _visualizer->updateColorHandlerIndex(
id, index-1);
3123 if(
_visualizer->getPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, lastOpacity,
id))
3125 if(lastOpacity != opacity)
3127 _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, opacity,
id);
3130 #if VTK_MAJOR_VERSION >= 7 3133 pcl::visualization::ShapeActorMap::iterator am_it =
_visualizer->getShapeActorMap()->find (
id);
3134 if (am_it !=
_visualizer->getShapeActorMap()->end ())
3136 vtkActor* actor = vtkActor::SafeDownCast (am_it->second);
3139 actor->GetProperty ()->SetOpacity (opacity);
3150 if(
_visualizer->getPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, lastSize,
id))
3152 if((
int)lastSize != size)
3154 _visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, (
double)size,
id);
3183 #if VTK_MAJOR_VERSION > 8 3184 CloudViewerInteractorStyle * interactor = CloudViewerInteractorStyle::SafeDownCast(this->interactor()->GetInteractorStyle());
3186 CloudViewerInteractorStyle * interactor = CloudViewerInteractorStyle::SafeDownCast(this->GetInteractor()->GetInteractorStyle());
3285 UERROR(
"Cannot set grid cell count < 1, count=%d", count);
3301 UERROR(
"Cannot set grid cell size <= 0, value=%f", size);
3314 float min = -float(cellCount/2) * cellSize;
3315 float max = float(cellCount/2) * cellSize;
3317 for(
float i=min; i<=
max; i += cellSize)
3320 name =
uFormat(
"line%d", ++
id);
3322 pcl::PointXYZ(i, min, 0.0
f),
3323 pcl::PointXYZ(i, max, 0.0
f),
3327 name =
uFormat(
"line%d", ++
id);
3329 pcl::PointXYZ(min, i, 0),
3330 pcl::PointXYZ(max, i, 0),
3335 std::vector<pcl::visualization::Camera> cameras;
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]);
3346 for(std::list<std::string>::iterator iter =
_gridLines.begin(); iter!=
_gridLines.end(); ++iter)
3357 for(QList<std::string>::iterator iter = ids.begin(); iter!=ids.end(); ++iter)
3359 std::string idNormals = *iter +
"-normals";
3386 UERROR(
"Cannot set normals step <= 0, step=%d", step);
3397 UERROR(
"Cannot set normals scale <= 0, value=%f", scale);
3438 UERROR(
"Cannot set normals scale < 0, value=%f", value);
3448 const Eigen::Vector3f & point,
3449 const Eigen::Vector3f &
axis,
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);
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];
3467 Eigen::Vector3f newDirection = newFrame.transpose() * direction;
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 );
3477 direction = newFrame * newDirection;
3479 return direction + ptOnZaxis;
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)
3492 PCLQVTKWidget::keyPressEvent(event);
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)
3505 std::vector<pcl::visualization::Camera> cameras;
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);
3515 float stepRot = 0.02f;
3518 Eigen::Vector3f dir;
3519 if(event->modifiers() & Qt::ShiftModifier)
3521 dir = viewUp *
step;
3525 dir = (focal-pos).normalized() *
step;
3527 cummulatedDir += dir;
3531 Eigen::Vector3f dir;
3532 if(event->modifiers() & Qt::ShiftModifier)
3534 dir = viewUp * -
step;
3538 dir = (focal-pos).normalized() * -
step;
3540 cummulatedDir += dir;
3544 if(event->modifiers() & Qt::ShiftModifier)
3547 Eigen::Vector3f point = (focal-pos);
3549 Eigen::Vector3f
diff = newPoint - point;
3550 cummulatedFocalDir += diff;
3554 Eigen::Vector3f dir = ((focal-pos).
cross(viewUp)).normalized() *
step;
3555 cummulatedDir += dir;
3560 if(event->modifiers() & Qt::ShiftModifier)
3563 Eigen::Vector3f point = (focal-pos);
3565 Eigen::Vector3f
diff = newPoint - point;
3566 cummulatedFocalDir += diff;
3570 Eigen::Vector3f dir = ((focal-pos).
cross(viewUp)).normalized() * -
step;
3571 cummulatedDir += dir;
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];
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]);
3590 PCLQVTKWidget::keyPressEvent(event);
3596 if(event->button() == Qt::RightButton)
3602 PCLQVTKWidget::mousePressEvent(event);
3608 PCLQVTKWidget::mouseMoveEvent(event);
3610 std::vector<pcl::visualization::Camera> cameras;
3616 cv::Vec3d newCameraOrientation = cv::Vec3d(0,0,1).cross(cv::Vec3d(cameras.front().pos)-cv::Vec3d(cameras.front().focal));
3627 else if(newCameraOrientation != cv::Vec3d(0,0,0))
3634 if(cameras.front().view[2] == 0)
3636 cameras.front().pos[0] -= 0.00001*cameras.front().view[0];
3637 cameras.front().pos[1] -= 0.00001*cameras.front().view[1];
3641 cameras.front().pos[0] -= 0.00001;
3644 cameras.front().view[0] = 0;
3645 cameras.front().view[1] = 0;
3646 cameras.front().view[2] = 1;
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]);
3659 PCLQVTKWidget::wheelEvent(event);
3661 std::vector<pcl::visualization::Camera> cameras;
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]);
3679 QAction * a =
_menu->exec(event->globalPos());
3692 int value = QInputDialog::getInt(
this, tr(
"Set trajectory size"), tr(
"Size (0=infinite)"),
_maxTrajectorySize, 0, 10000, 10, &ok);
3709 double value = QInputDialog::getDouble(
this, tr(
"Set frame scale"), tr(
"Scale"),
_coordinateFrameScale, 0.1, 999.0, 1, &ok);
3722 double value = QInputDialog::getDouble(
this, tr(
"Set frustum scale"), tr(
"Scale"),
_frustumScale, 0.0, 999.0, 1, &ok);
3756 int value = QInputDialog::getInt(
this, tr(
"Set grid cell count"), tr(
"Count"),
_gridCellCount, 1, 10000, 10, &ok);
3765 double value = QInputDialog::getDouble(
this, tr(
"Set grid cell size"), tr(
"Size (m)"),
_gridCellSize, 0.01, 1000, 2, &ok);
3779 int value = QInputDialog::getInt(
this, tr(
"Set normals step"), tr(
"Step"),
_normalsStep, 1, 10000, 1, &ok);
3788 double value = QInputDialog::getDouble(
this, tr(
"Set normals scale"), tr(
"Scale (m)"),
_normalsScale, 0.01, 10, 2, &ok);
3797 double value = QInputDialog::getDouble(
this, tr(
"Set maximum absolute intensity"), tr(
"Intensity (0=auto)"),
_intensityAbsMax, 0.0, 99999, 2, &ok);
3814 color = QColorDialog::getColor(color,
this);
3824 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)
QAction * _aShowCameraAxis
void removeGraph(const std::string &id)
unsigned int getTrajectorySize() const
QAction * _aBackfaceCulling
QAction * _aSetFrustumScale
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
void setInteractorLayer(int layer)
void setTrajectorySize(unsigned int value)
const iterator end() const
pcl::visualization::PCLVisualizer * _visualizer
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
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
bool isCameraFree() const
bool isLightingOn() const
void setNormalsStep(int step)
virtual void keyPressEvent(QKeyEvent *event)
void setNormalsScale(float scale)
QAction * _aSetIntensityRainbowColormap
void updateCameraFrustum(const Transform &pose, const StereoCameraModel &model)
void setCoordinateFrameScale(double scale)
void setGridShown(bool shown)
QAction * _aSetEdgeVisibility
void uMinMax(const T *v, unsigned int size, T &min, T &max, unsigned int &indexMin, unsigned int &indexMax)
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
void removeCube(const std::string &id)
void setCloudViewer(CloudViewer *cloudViewer)
float getGridCellSize() const
float getNormalsScale() const
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)
void getGridMin(double &x, double &y, double &z) const
std::set< std::string > _quads
bool isCameraAxisShown() const
bool removeCloud(const std::string &id)
double keyToCoord(key_type key, unsigned depth) const
bool isIntensityRainbowColormap() 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 setEDLShading(bool on)
void setLighting(bool on)
virtual std::string getFieldName() const
Get the name of the field used.
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)
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)
std::set< std::string > _spheres
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
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)
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
std::set< std::string > _graphes
QAction * _aSetEDLShading
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())
std::set< std::string > _texts
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
QMap< std::string, Transform > _addedClouds
bool isCameraOrtho() const
QAction * _aSetTrajectorySize
Wrappers of STL for convenient functions.
void setCameraAxisShown(bool shown)
QAction * _aSetBackgroundColor
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)
void removeAllCoordinates(const std::string &prefix="")
void setColor(const std::string &id, const QColor &color)
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)
void removeText(const std::string &id)
bool isCameraLockZ() const
void removeOccupancyGridMap()
void setCloudPointSize(const std::string &id, int size)
PointCloud::ConstPtr PointCloudConstPtr
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
void setFrustumColor(QColor value)
bool isCameraTargetLocked() const
void updateCameraTargetPosition(const Transform &pose)
bool isCameraTargetFollow() const
const RtabmapColorOcTree * octree() const
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)
QAction * _aShowTrajectory
QColor getFrustumColor() const
double _coordinateFrameScale
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)
pcl::PointCloud< pcl::PointXYZ >::Ptr _trajectory
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)
QAction * _aSetNormalsStep
GLM_FUNC_DECL genType tan(genType const &angle)
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)
float getFrustumScale() const
const QColor & getBackgroundColor() const
QAction * _aSetIntensityMaximum
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)
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
const QColor & getDefaultBackgroundColor() const
virtual void keyReleaseEvent(QKeyEvent *event)
ULogger class and convenient macros.
void setBackfaceCulling(bool enabled, bool frontfaceCulling)
QAction * _aSetFrameScale
virtual size_t size() 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)
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)
QAction * _aSetIntensityRedColormap
cv::Vec3d _lastCameraPose
void RTABMAP_EXP HSVtoRGB(float *r, float *g, float *b, float h, float s, float v)
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,...)
PointCloud::Ptr PointCloudPtr
bool getPose(const std::string &id, Transform &pose)
bool isFrontfaceCulling() const
void removeAllFrustums(bool exceptCameraReference=false)
const CameraModel & right() const
QAction * _aSetRenderingRate
virtual std::string getName() const
Get the name of the class.
bool updateCloudPose(const std::string &id, const Transform &pose)
void setRenderingRate(double rate)
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