42 #include <pcl/correspondence.h>
43 #include <pcl/ModelCoefficients.h>
44 #include <pcl/PolygonMesh.h>
45 #include <pcl/TextureMesh.h>
47 #include <pcl/console/print.h>
48 #include <pcl/visualization/common/actor_map.h>
49 #include <pcl/visualization/common/common.h>
50 #include <pcl/visualization/point_cloud_geometry_handlers.h>
51 #include <pcl/visualization/point_cloud_color_handlers.h>
52 #include <pcl/visualization/point_picking_event.h>
53 #include <pcl/visualization/area_picking_event.h>
54 #include <pcl/visualization/interactor_style.h>
56 #include <vtkOrientationMarkerWidget.h>
57 #include <vtkRenderWindowInteractor.h>
62 class vtkRenderWindow;
63 class vtkAppendPolyData;
64 class vtkRenderWindow;
66 class vtkInteractorStyle;
71 class vtkUnstructuredGrid;
77 template <
typename T>
class PlanarPolygon;
79 namespace visualization
96 using Ptr = shared_ptr<PCLVisualizer>;
97 using ConstPtr = shared_ptr<const PCLVisualizer>;
111 PCLVisualizer (
const std::string &name =
"",
const bool create_interactor =
true);
141 const bool create_interactor =
true);
173 boost::signals2::connection
181 inline boost::signals2::connection
193 template<
typename T>
inline boost::signals2::connection
203 boost::signals2::connection
211 inline boost::signals2::connection
223 template<
typename T>
inline boost::signals2::connection
233 boost::signals2::connection
241 boost::signals2::connection
250 template<
typename T>
inline boost::signals2::connection
260 boost::signals2::connection
268 boost::signals2::connection
277 template<
typename T>
inline boost::signals2::connection
295 spinOnce (
int time = 1,
bool force_redraw =
false);
324 addCoordinateSystem (
double scale,
float x,
float y,
float z,
const std::string &
id =
"reference",
int viewport = 0);
362 addCoordinateSystem (
double scale,
const Eigen::Affine3f& t,
const std::string &
id =
"reference",
int viewport = 0);
388 return (removePointCloud (
id, viewport));
443 const std::string &
id =
"",
int viewport = 0);
456 addText (
const std::string &text,
int xpos,
int ypos,
double r,
double g,
double b,
457 const std::string &
id =
"",
int viewport = 0);
471 addText (
const std::string &text,
int xpos,
int ypos,
int fontsize,
double r,
double g,
double b,
472 const std::string &
id =
"",
int viewport = 0);
484 const std::string &
id =
"");
497 int xpos,
int ypos,
double r,
double g,
double b,
498 const std::string &
id =
"");
512 int xpos,
int ypos,
int fontsize,
double r,
double g,
double b,
513 const std::string &
id =
"");
561 template <
typename Po
intT>
bool
562 addText3D (
const std::string &text,
564 double textScale = 1.0,
565 double r = 1.0,
double g = 1.0,
double b = 1.0,
566 const std::string &
id =
"",
int viewport = 0);
582 template <
typename Po
intT>
bool
583 addText3D (
const std::string &text,
585 double orientation[3],
586 double textScale = 1.0,
587 double r = 1.0,
double g = 1.0,
double b = 1.0,
588 const std::string &
id =
"",
int viewport = 0);
597 return (cloud_actor_map_->find (
id) != cloud_actor_map_->end () ||
598 shape_actor_map_->find (
id) != shape_actor_map_->end () ||
599 coordinate_actor_map_->find (
id) != coordinate_actor_map_-> end());
609 template <
typename Po
intNT>
bool
611 int level = 100,
float scale = 0.02f,
612 const std::string &
id =
"cloud",
int viewport = 0);
622 template <
typename Po
intT,
typename Po
intNT>
bool
625 int level = 100,
float scale = 0.02f,
626 const std::string &
id =
"cloud",
int viewport = 0);
636 template <
typename Po
intNT>
bool
640 int level = 100,
float scale = 1.0f,
641 const std::string &
id =
"cloud",
int viewport = 0);
652 template <
typename Po
intT,
typename Po
intNT>
bool
653 addPointCloudPrincipalCurvatures (
657 int level = 100,
float scale = 1.0f,
658 const std::string &
id =
"cloud",
int viewport = 0);
668 template <
typename Po
intT,
typename GradientT>
bool
671 int level = 100,
double scale = 1e-6,
672 const std::string &
id =
"cloud",
int viewport = 0);
679 template <
typename Po
intT>
bool
681 const std::string &
id =
"cloud",
int viewport = 0);
688 template <
typename Po
intT>
bool
690 const std::string &
id =
"cloud");
698 template <
typename Po
intT>
bool
701 const std::string &
id =
"cloud");
709 template <
typename Po
intT>
bool
712 const std::string &
id =
"cloud");
720 template <
typename Po
intT>
bool
723 const std::string &
id =
"cloud",
int viewport = 0);
737 template <
typename Po
intT>
bool
740 const std::string &
id =
"cloud",
int viewport = 0);
748 template <
typename Po
intT>
bool
751 const std::string &
id =
"cloud",
int viewport = 0);
765 template <
typename Po
intT>
bool
768 const std::string &
id =
"cloud",
int viewport = 0);
783 template <
typename Po
intT>
bool
787 const std::string &
id =
"cloud",
int viewport = 0);
808 const Eigen::Vector4f& sensor_origin,
809 const Eigen::Quaternion<float>& sensor_orientation,
810 const std::string &
id =
"cloud",
int viewport = 0);
829 const Eigen::Vector4f& sensor_origin,
830 const Eigen::Quaternion<float>& sensor_orientation,
831 const std::string &
id =
"cloud",
int viewport = 0);
850 const Eigen::Vector4f& sensor_origin,
851 const Eigen::Quaternion<float>& sensor_orientation,
852 const std::string &
id =
"cloud",
int viewport = 0);
861 template <
typename Po
intT>
bool
865 const std::string &
id =
"cloud",
int viewport = 0);
874 const std::string &
id =
"cloud",
int viewport = 0)
876 return (addPointCloud<pcl::PointXYZ> (cloud,
id, viewport));
887 const std::string &
id =
"cloud",
int viewport = 0)
890 return (addPointCloud<pcl::PointXYZRGB> (cloud, color_handler,
id, viewport));
900 const std::string &
id =
"cloud",
int viewport = 0)
903 return (addPointCloud<pcl::PointXYZRGBA> (cloud, color_handler,
id, viewport));
913 const std::string &
id =
"cloud",
int viewport = 0)
916 return (addPointCloud<pcl::PointXYZL> (cloud, color_handler,
id, viewport));
926 const std::string &
id =
"cloud")
928 return (updatePointCloud<pcl::PointXYZ> (cloud,
id));
938 const std::string &
id =
"cloud")
941 return (updatePointCloud<pcl::PointXYZRGB> (cloud, color_handler,
id));
951 const std::string &
id =
"cloud")
954 return (updatePointCloud<pcl::PointXYZRGBA> (cloud, color_handler,
id));
964 const std::string &
id =
"cloud")
967 return (updatePointCloud<pcl::PointXYZL> (cloud, color_handler,
id));
977 const std::string &
id =
"polygon",
986 template <
typename Po
intT>
bool
988 const std::vector<pcl::Vertices> &vertices,
989 const std::string &
id =
"polygon",
998 template <
typename Po
intT>
bool
1000 const std::vector<pcl::Vertices> &vertices,
1001 const std::string &
id =
"polygon");
1010 const std::string &
id =
"polygon");
1019 const std::string &
id =
"polyline",
1029 template <
typename Po
intT>
bool
1032 const std::vector<int> & correspondences,
1033 const std::string &
id =
"correspondences",
1043 const std::string &
id =
"texture",
1055 template <
typename Po
intT>
bool
1060 const std::string &
id =
"correspondences",
1062 bool overwrite =
false);
1071 template <
typename Po
intT>
bool
1075 const std::string &
id =
"correspondences",
1079 return (addCorrespondences<PointT> (source_points, target_points,
1080 correspondences, 1,
id, viewport));
1091 template <
typename Po
intT>
bool
1092 updateCorrespondences (
1097 const std::string &
id =
"correspondences",
1107 template <
typename Po
intT>
bool
1112 const std::string &
id =
"correspondences",
1116 return (updateCorrespondences<PointT> (source_points, target_points,
1117 correspondences, 1,
id, viewport));
1157 const std::string &
id =
"cloud",
int viewport = 0);
1169 const std::string &
id =
"cloud",
int viewport = 0);
1180 const std::string &
id =
"cloud",
int viewport = 0);
1190 const std::string &
id =
"cloud");
1203 const std::string &
id =
"cloud");
1222 const std::string &
id,
int viewport = 0);
1234 const std::string &
id,
int viewport = 0);
1247 const std::string &
id,
int viewport = 0);
1290 template <
typename Po
intT>
bool
1292 double r,
double g,
double b,
1293 const std::string &
id =
"polygon",
int viewport = 0);
1301 template <
typename Po
intT>
bool
1303 const std::string &
id =
"polygon",
1314 template <
typename Po
intT>
bool
1316 double r,
double g,
double b,
1317 const std::string &
id =
"polygon",
1326 template <
typename P1,
typename P2>
bool
1327 addLine (
const P1 &pt1,
const P2 &pt2,
const std::string &
id =
"line",
1339 template <
typename P1,
typename P2>
bool
1340 addLine (
const P1 &pt1,
const P2 &pt2,
double r,
double g,
double b,
1341 const std::string &
id =
"line",
int viewport = 0);
1355 template <
typename P1,
typename P2>
bool
1356 addArrow (
const P1 &pt1,
const P2 &pt2,
double r,
double g,
double b,
1357 const std::string &
id =
"arrow",
int viewport = 0);
1372 template <
typename P1,
typename P2>
bool
1373 addArrow (
const P1 &pt1,
const P2 &pt2,
double r,
double g,
double b,
bool display_length,
1374 const std::string &
id =
"arrow",
int viewport = 0);
1391 template <
typename P1,
typename P2>
bool
1392 addArrow (
const P1 &pt1,
const P2 &pt2,
1393 double r_line,
double g_line,
double b_line,
1394 double r_text,
double g_text,
double b_text,
1395 const std::string &
id =
"arrow",
int viewport = 0);
1404 template <
typename Po
intT>
bool
1405 addSphere (
const PointT ¢er,
double radius,
const std::string &
id =
"sphere",
1417 template <
typename Po
intT>
bool
1418 addSphere (
const PointT ¢er,
double radius,
double r,
double g,
double b,
1419 const std::string &
id =
"sphere",
int viewport = 0);
1429 template <
typename Po
intT>
bool
1430 updateSphere (
const PointT ¢er,
double radius,
double r,
double g,
double b,
1431 const std::string &
id =
"sphere");
1440 const std::string &
id =
"PolyData",
1452 const std::string &
id =
"PolyData",
1462 const std::string &
id =
"PLYModel",
1474 const std::string &
id =
"PLYModel",
1505 const std::string &
id =
"cylinder",
1532 const std::string &
id =
"sphere",
1560 const std::string &
id =
"line",
1588 const char *
id =
"line",
1591 return addLine (coefficients, std::string (
id), viewport);
1616 const std::string &
id =
"plane",
1621 const std::string &
id =
"plane",
1644 const std::string &
id =
"circle",
1654 const std::string &
id =
"cone",
1664 const std::string &
id =
"cube",
1677 addCube (
const Eigen::Vector3f &translation,
const Eigen::Quaternionf &rotation,
1678 double width,
double height,
double depth,
1679 const std::string &
id =
"cube",
1696 addCube (
float x_min,
float x_max,
float y_min,
float y_max,
float z_min,
float z_max,
1697 double r = 1.0,
double g = 1.0,
double b = 1.0,
const std::string &
id =
"cube",
int viewport = 0);
1709 double radius_x,
double radius_y,
double radius_z,
1710 const std::string &
id =
"ellipsoid",
1776 std::vector<Eigen::Matrix4f,Eigen::aligned_allocator< Eigen::Matrix4f > > & poses, std::vector<float> & enthropies,
int tesselation_level,
1777 float view_angle = 45,
float radius_sphere = 1,
bool use_vertices =
true);
1845 double view_x,
double view_y,
double view_z,
1846 double up_x,
double up_y,
double up_z,
int viewport = 0);
1859 double up_x,
double up_y,
double up_z,
int viewport = 0);
1935 return (cloud_actor_map_);
1942 return (shape_actor_map_);
1966 setUseVbos (
bool use_vbos);
1972 setLookUpTableID (const std::
string id);
1976 createInteractor ();
1984 setupInteractor (vtkRenderWindowInteractor *iren,
1985 vtkRenderWindow *win);
1994 setupInteractor (vtkRenderWindowInteractor *iren,
1995 vtkRenderWindow *win,
1996 vtkInteractorStyle *style);
2000 getInteractorStyle ()
2021 void setupRenderWindow (
const std::string& name);
2029 void setDefaultWindowSizeAndPos ();
2037 void setupCamera (
int argc,
char **argv);
2039 struct PCL_EXPORTS ExitMainLoopTimerCallback :
public vtkCommand
2041 static ExitMainLoopTimerCallback* New ()
2043 return (
new ExitMainLoopTimerCallback);
2046 Execute (vtkObject*,
unsigned long event_id,
void*)
override;
2052 struct PCL_EXPORTS ExitCallback :
public vtkCommand
2054 static ExitCallback* New ()
2056 return (
new ExitCallback);
2059 Execute (vtkObject*,
unsigned long event_id,
void*)
override;
2061 PCLVisualizer* pcl_visualizer;
2065 struct PCL_EXPORTS FPSCallback :
public vtkCommand
2067 static FPSCallback *New () {
return (
new FPSCallback); }
2069 FPSCallback () =
default;
2070 FPSCallback (
const FPSCallback& src) =
default;
2071 FPSCallback& operator = (
const FPSCallback& src) { actor = src.actor; pcl_visualizer = src.pcl_visualizer; decimated = src.decimated; last_fps = src.last_fps;
return (*
this); }
2074 Execute (vtkObject*,
unsigned long event_id,
void*)
override;
2076 vtkTextActor *actor{
nullptr};
2077 PCLVisualizer* pcl_visualizer{
nullptr};
2078 bool decimated{
false};
2079 float last_fps{0.0f};
2086 bool stopped_{
false};
2120 bool camera_file_loaded_;
2168 bool use_scalars =
true)
const;
2178 bool use_scalars =
true)
const;
2186 template <
typename Po
intT>
void
2197 template <
typename Po
intT>
void
2198 convertPointCloudToVTKPolyData (
const PointCloudGeometryHandler<PointT> &geometry_handler,
2209 convertPointCloudToVTKPolyData (
const GeometryHandlerConstPtr &geometry_handler,
2224 vtkIdType nr_points);
2236 template <
typename Po
intT>
bool
2237 fromHandlersToScreen (
const PointCloudGeometryHandler<PointT> &geometry_handler,
2238 const PointCloudColorHandler<PointT> &color_handler,
2239 const std::string &
id,
2241 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2242 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2254 template <
typename Po
intT>
bool
2255 fromHandlersToScreen (
const PointCloudGeometryHandler<PointT> &geometry_handler,
2256 const ColorHandlerConstPtr &color_handler,
2257 const std::string &
id,
2259 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2260 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2273 fromHandlersToScreen (
const GeometryHandlerConstPtr &geometry_handler,
2274 const ColorHandlerConstPtr &color_handler,
2275 const std::string &
id,
2277 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2278 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2290 template <
typename Po
intT>
bool
2291 fromHandlersToScreen (
const GeometryHandlerConstPtr &geometry_handler,
2292 const PointCloudColorHandler<PointT> &color_handler,
2293 const std::string &
id,
2295 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2296 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2322 getTransformationMatrix (
const Eigen::Vector4f &origin,
2323 const Eigen::Quaternion<float> &orientation,
2324 Eigen::Matrix4f &transformation);
2335 vtkTexture* vtk_tex)
const;
2342 getUniqueCameraFile (
int argc,
char **argv);
2361 const Eigen::Quaternion<float> &orientation,
2370 Eigen::Matrix4f &m);
2376 #include <pcl/visualization/impl/pcl_visualizer.hpp>
PlanarPolygon represents a planar (2D) polygon, potentially in a 3D space.
PointCloud represents the base class in PCL for storing collections of 3D points.
std::vector< PointCloud< PointT >, Eigen::aligned_allocator< PointCloud< PointT > > > CloudVectorType
shared_ptr< PointCloud< PointT > > Ptr
shared_ptr< const PointCloud< PointT > > ConstPtr
/brief Class representing 3D area picking events.
Camera class holds a set of camera parameters together with the window pos/size.
/brief Class representing key hit/release events
PCL Visualizer main class.
void close()
Stop the interaction and close the visualization window.
bool setPointCloudRenderingProperties(int property, double val1, double val2, double val3, const std::string &id="cloud", int viewport=0)
Set the rendering properties of a PointCloud (3x values - e.g., RGB)
bool addPolygonMesh(const pcl::PolygonMesh &polymesh, const std::string &id="polygon", int viewport=0)
Add a PolygonMesh object to screen.
void createViewPort(double xmin, double ymin, double xmax, double ymax, int &viewport)
Create a new viewport from [xmin,ymin] -> [xmax,ymax].
void renderViewTesselatedSphere(int xres, int yres, pcl::PointCloud< pcl::PointXYZ >::CloudVectorType &cloud, std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &poses, std::vector< float > &enthropies, int tesselation_level, float view_angle=45, float radius_sphere=1, bool use_vertices=true)
The purpose of this method is to render a CAD model added to the visualizer from different viewpoints...
shared_ptr< PCLVisualizer > Ptr
void setPosition(int x, int y)
Set the position in screen coordinates.
bool addPointCloud(const pcl::PCLPointCloud2::ConstPtr &cloud, const GeometryHandlerConstPtr &geometry_handler, const Eigen::Vector4f &sensor_origin, const Eigen::Quaternion< float > &sensor_orientation, const std::string &id="cloud", int viewport=0)
Add a binary blob Point Cloud to screen.
bool addPointCloud(const pcl::PCLPointCloud2::ConstPtr &cloud, const GeometryHandlerConstPtr &geometry_handler, const ColorHandlerConstPtr &color_handler, const Eigen::Vector4f &sensor_origin, const Eigen::Quaternion< float > &sensor_orientation, const std::string &id="cloud", int viewport=0)
Add a binary blob Point Cloud to screen.
bool removePointCloud(const std::string &id="cloud", int viewport=0)
Removes a Point Cloud from screen, based on a given ID.
bool updateCoordinateSystemPose(const std::string &id, const Eigen::Affine3f &pose)
Set the pose of an existing coordinate system.
boost::signals2::connection registerAreaPickingCallback(std::function< void(const pcl::visualization::AreaPickingEvent &)> cb)
Register a callback function for area picking events.
bool addPointCloud(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &cloud, const std::string &id="cloud", int viewport=0)
Add a PointXYZRGBA Point Cloud to screen.
static void convertToVtkMatrix(const Eigen::Matrix4f &m, vtkSmartPointer< vtkMatrix4x4 > &vtk_matrix)
Convert Eigen::Matrix4f to vtkMatrix4x4.
bool addTextureMesh(const pcl::TextureMesh &polymesh, const std::string &id="texture", int viewport=0)
Add a TextureMesh object to screen.
boost::signals2::connection registerMouseCallback(void(T::*callback)(const pcl::visualization::MouseEvent &, void *), T &instance, void *cookie=nullptr)
Register a callback function for mouse events.
GeometryHandler::Ptr GeometryHandlerPtr
bool addCorrespondences(const typename pcl::PointCloud< PointT >::ConstPtr &source_points, const typename pcl::PointCloud< PointT >::ConstPtr &target_points, const pcl::Correspondences &correspondences, const std::string &id="correspondences", int viewport=0)
Add the specified correspondences to the display.
bool setShapeRenderingProperties(int property, double val1, double val2, const std::string &id, int viewport=0)
Set the rendering properties of a shape (2x values - e.g., LUT minmax values)
void setCameraPosition(double pos_x, double pos_y, double pos_z, double view_x, double view_y, double view_z, double up_x, double up_y, double up_z, int viewport=0)
Set the camera pose given by position, viewpoint and up vector.
vtkSmartPointer< vtkRenderWindowInteractor > interactor_
The render window interactor.
boost::signals2::connection registerPointPickingCallback(std::function< void(const pcl::visualization::PointPickingEvent &)> cb)
Register a callback function for point picking events.
CloudActorMapPtr getCloudActorMap()
Return a pointer to the CloudActorMap this visualizer uses.
bool addPlane(const pcl::ModelCoefficients &coefficients, const std::string &id="plane", int viewport=0)
Add a plane from a set of given model coefficients.
bool removeCoordinateSystem(const std::string &id="reference", int viewport=0)
Removes a previously added 3D axes (coordinate system)
vtkSmartPointer< vtkRendererCollection > getRendererCollection()
Return a pointer to the underlying VTK Renderer Collection.
bool updatePolygonMesh(const pcl::PolygonMesh &polymesh, const std::string &id="polygon")
Update a PolygonMesh object on screen.
void saveCameraParameters(const std::string &file)
Save the camera parameters to disk, as a .cam file.
void addCoordinateSystem(double scale, const Eigen::Affine3f &t, const std::string &id="reference", int viewport=0)
Adds 3D axes describing a coordinate system to screen at x, y, z, Roll,Pitch,Yaw.
bool updateColorHandlerIndex(const std::string &id, int index)
Update/set the color index of a rendered PointCloud based on its ID.
void setBackgroundColor(const double &r, const double &g, const double &b, int viewport=0)
Set the viewport's background color.
bool addText(const std::string &text, int xpos, int ypos, double r, double g, double b, const std::string &id="", int viewport=0)
Add a text to screen.
virtual ~PCLVisualizer()
PCL Visualizer destructor.
bool updateShapePose(const std::string &id, const Eigen::Affine3f &pose)
Set the pose of an existing shape.
void setRepresentationToSurfaceForAllActors()
Changes the visual representation for all actors to surface representation.
void setRepresentationToWireframeForAllActors()
Changes the visual representation for all actors to wireframe representation.
bool removeAllCoordinateSystems(int viewport=0)
Removes all existing 3D axes (coordinate systems)
bool addPointCloud(const pcl::PointCloud< pcl::PointXYZL >::ConstPtr &cloud, const std::string &id="cloud", int viewport=0)
Add a PointXYZL Point Cloud to screen.
void addCoordinateSystem(double scale=1.0, const std::string &id="reference", int viewport=0)
Adds 3D axes describing a coordinate system to screen at 0,0,0.
boost::signals2::connection registerKeyboardCallback(void(T::*callback)(const pcl::visualization::KeyboardEvent &, void *), T &instance, void *cookie=nullptr)
Register a callback function for keyboard events.
bool updatePointCloudPose(const std::string &id, const Eigen::Affine3f &pose)
Set the pose of an existing point cloud.
bool setPointCloudSelected(const bool selected, const std::string &id="cloud")
Set whether the point cloud is selected or not.
bool cameraParamsSet() const
Checks whether the camera parameters were manually loaded.
bool updateText(const std::string &text, int xpos, int ypos, const std::string &id="")
Update a text to screen.
void resetCameraViewpoint(const std::string &id="cloud")
Reset the camera direction from {0, 0, 0} to the center_{x, y, z} of a given dataset.
bool addModelFromPolyData(vtkSmartPointer< vtkPolyData > polydata, const std::string &id="PolyData", int viewport=0)
Add a vtkPolydata as a mesh.
bool updatePointCloud(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud, const std::string &id="cloud")
Updates the XYZ data for an existing cloud object id on screen.
bool addText(const std::string &text, int xpos, int ypos, const std::string &id="", int viewport=0)
Add a text to screen.
boost::signals2::connection registerAreaPickingCallback(void(T::*callback)(const pcl::visualization::AreaPickingEvent &, void *), T &instance, void *cookie=nullptr)
Register a callback function for area picking events.
bool addLine(const pcl::ModelCoefficients &coefficients, const std::string &id="line", int viewport=0)
Add a line from a set of given model coefficients.
bool addCircle(const pcl::ModelCoefficients &coefficients, const std::string &id="circle", int viewport=0)
Add a circle from a set of given model coefficients.
PCLVisualizer(vtkSmartPointer< vtkRenderer > ren, vtkSmartPointer< vtkRenderWindow > wind, const std::string &name="", const bool create_interactor=true)
PCL Visualizer constructor.
bool addModelFromPLYFile(const std::string &filename, vtkSmartPointer< vtkTransform > transform, const std::string &id="PLYModel", int viewport=0)
Add a PLYmodel as a mesh and applies given transformation.
bool cameraFileLoaded() const
Checks whether a camera file were automatically loaded.
void createViewPortCamera(const int viewport)
Create a new separate camera for the given viewport.
void getCameras(std::vector< Camera > &cameras)
Get the current camera parameters.
std::string getCameraFile() const
Get camera file for camera parameter saving/restoring.
bool addCube(float x_min, float x_max, float y_min, float y_max, float z_min, float z_max, double r=1.0, double g=1.0, double b=1.0, const std::string &id="cube", int viewport=0)
Add a cube.
bool addCube(const Eigen::Vector3f &translation, const Eigen::Quaternionf &rotation, double width, double height, double depth, const std::string &id="cube", int viewport=0)
Add a cube from a set of given model coefficients.
ShapeActorMapPtr getShapeActorMap()
Return a pointer to the ShapeActorMap this visualizer uses.
GeometryHandler::ConstPtr GeometryHandlerConstPtr
void setFullScreen(bool mode)
Enables/Disabled the underlying window mode to full screen.
static void convertToVtkMatrix(const Eigen::Vector4f &origin, const Eigen::Quaternion< float > &orientation, vtkSmartPointer< vtkMatrix4x4 > &vtk_matrix)
Convert origin and orientation to vtkMatrix4x4.
bool wasStopped() const
Returns true when the user tried to close the window.
bool addPlane(const pcl::ModelCoefficients &coefficients, double x, double y, double z, const std::string &id="plane", int viewport=0)
bool updatePointCloud(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const std::string &id="cloud")
Updates the XYZRGB data for an existing cloud object id on screen.
void setCameraFieldOfView(double fovy, int viewport=0)
Set the camera vertical field of view.
void removeOrientationMarkerWidgetAxes()
Disables the Orientatation Marker Widget so it is removed from the renderer.
void renderView(int xres, int yres, pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
Renders a virtual scene as seen from the camera viewpoint and returns the rendered point cloud.
bool addCone(const pcl::ModelCoefficients &coefficients, const std::string &id="cone", int viewport=0)
Add a cone from a set of given model coefficients.
int getGeometryHandlerIndex(const std::string &id)
Get the geometry handler index of a rendered PointCloud based on its ID.
void enableEDLRendering(int viewport=0)
Eye-Dome Lighting makes dark areas to improve depth perception See https://www.kitware....
void spinOnce(int time=1, bool force_redraw=false)
Spin once method.
PCLVisualizer(const std::string &name="", const bool create_interactor=true)
PCL Visualizer constructor.
void setSize(int xw, int yw)
Set the window size in screen coordinates.
bool updateText(const std::string &text, int xpos, int ypos, int fontsize, double r, double g, double b, const std::string &id="")
Update a text to screen.
bool removeAllPointClouds(int viewport=0)
Remove all point cloud data on screen from the given viewport.
ColorHandler::ConstPtr ColorHandlerConstPtr
bool addPointCloud(const pcl::PCLPointCloud2::ConstPtr &cloud, const ColorHandlerConstPtr &color_handler, const Eigen::Vector4f &sensor_origin, const Eigen::Quaternion< float > &sensor_orientation, const std::string &id="cloud", int viewport=0)
Add a binary blob Point Cloud to screen.
bool addModelFromPLYFile(const std::string &filename, const std::string &id="PLYModel", int viewport=0)
Add a PLYmodel as a mesh.
void setCameraParameters(const Camera &camera, int viewport=0)
Set the camera parameters by given a full camera data structure.
boost::signals2::connection registerPointPickingCallback(void(T::*callback)(const pcl::visualization::PointPickingEvent &, void *), T &instance, void *cookie=nullptr)
Register a callback function for point picking events.
bool addText(const std::string &text, int xpos, int ypos, int fontsize, double r, double g, double b, const std::string &id="", int viewport=0)
Add a text to screen.
bool loadCameraParameters(const std::string &file)
Load camera parameters from a camera parameters file.
void setShowFPS(bool show_fps)
Sets whether the 2D overlay text showing the framerate of the window is displayed or not.
bool getCameraParameters(int argc, char **argv)
Search for camera parameters at the command line and set them internally.
int getColorHandlerIndex(const std::string &id)
Get the color handler index of a rendered PointCloud based on its ID.
void setCameraClipDistances(double near, double far, int viewport=0)
Set the camera clipping distances.
bool addCube(const pcl::ModelCoefficients &coefficients, const std::string &id="cube", int viewport=0)
Add a cube from a set of given model coefficients.
bool removeAllShapes(int viewport=0)
Remove all 3D shape data on screen from the given viewport.
float getFPS() const
Get the current rendering framerate.
bool addPointCloudPrincipalCurvatures(const typename pcl::PointCloud< PointNT >::ConstPtr &cloud, const typename pcl::PointCloud< pcl::PrincipalCurvatures >::ConstPtr &pcs, int level=100, float scale=1.0f, const std::string &id="cloud", int viewport=0)
Add the estimated principal curvatures of a Point Cloud to screen.
boost::signals2::connection registerKeyboardCallback(void(*callback)(const pcl::visualization::KeyboardEvent &, void *), void *cookie=nullptr)
Register a callback function for keyboard events.
ColorHandler::Ptr ColorHandlerPtr
bool setShapeRenderingProperties(int property, double value, const std::string &id, int viewport=0)
Set the rendering properties of a shape.
void initCameraParameters()
Initialize camera parameters with some default values.
vtkSmartPointer< vtkRenderWindow > getRenderWindow()
Return a pointer to the underlying VTK Render Window used.
PCLVisualizer(int &argc, char **argv, const std::string &name="", PCLVisualizerInteractorStyle *style=PCLVisualizerInteractorStyle::New(), const bool create_interactor=true)
PCL Visualizer constructor.
void setCameraPosition(double pos_x, double pos_y, double pos_z, double up_x, double up_y, double up_z, int viewport=0)
Set the camera location and viewup according to the given arguments.
void resetCamera()
Reset camera parameters and render.
boost::signals2::connection registerMouseCallback(void(*callback)(const pcl::visualization::MouseEvent &, void *), void *cookie=nullptr)
Register a callback function for mouse events.
void addCoordinateSystem(double scale, float x, float y, float z, const std::string &id="reference", int viewport=0)
Adds 3D axes describing a coordinate system to screen at x, y, z.
bool setShapeRenderingProperties(int property, double val1, double val2, double val3, const std::string &id, int viewport=0)
Set the rendering properties of a shape (3x values - e.g., RGB)
bool removePolygonMesh(const std::string &id="polygon", int viewport=0)
Removes a PolygonMesh from screen, based on a given ID.
bool addPointCloud(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const std::string &id="cloud", int viewport=0)
Add a PointXYZRGB Point Cloud to screen.
bool updateText(const std::string &text, int xpos, int ypos, double r, double g, double b, const std::string &id="")
Update a text to screen.
bool contains(const std::string &id) const
Check if the cloud, shape, or coordinate with the given id was already added to this visualizer.
void setWindowName(const std::string &name)
Set the visualizer window name.
void setWindowBorders(bool mode)
Enables or disable the underlying window borders.
boost::signals2::connection registerPointPickingCallback(void(*callback)(const pcl::visualization::PointPickingEvent &, void *), void *cookie=nullptr)
Register a callback function for point picking events.
bool updatePointCloud(const pcl::PointCloud< pcl::PointXYZL >::ConstPtr &cloud, const std::string &id="cloud")
Updates the XYZL data for an existing cloud object id on screen.
bool removeText3D(const std::string &id="cloud", int viewport=0)
Removes an added 3D text from the scene, based on a given ID.
boost::signals2::connection registerAreaPickingCallback(void(*callback)(const pcl::visualization::AreaPickingEvent &, void *), void *cookie=nullptr)
Register a callback function for area picking events.
bool setPointCloudRenderingProperties(int property, double value, const std::string &id="cloud", int viewport=0)
Set the rendering properties of a PointCloud.
bool getPointCloudRenderingProperties(RenderingProperties property, double &val1, double &val2, double &val3, const std::string &id="cloud")
Get the rendering properties of a PointCloud.
void saveScreenshot(const std::string &file)
Save the current rendered image to disk, as a PNG screenshot.
PCLVisualizer(int &argc, char **argv, vtkSmartPointer< vtkRenderer > ren, vtkSmartPointer< vtkRenderWindow > wind, const std::string &name="", PCLVisualizerInteractorStyle *style=PCLVisualizerInteractorStyle::New(), const bool create_interactor=true)
PCL Visualizer constructor.
static void convertToEigenMatrix(const vtkSmartPointer< vtkMatrix4x4 > &vtk_matrix, Eigen::Matrix4f &m)
Convert vtkMatrix4x4 to an Eigen4f.
bool addPolylineFromPolygonMesh(const pcl::PolygonMesh &polymesh, const std::string &id="polyline", int viewport=0)
Add a Polygonline from a polygonMesh object to screen.
bool getPointCloudRenderingProperties(int property, double &value, const std::string &id="cloud")
Get the rendering properties of a PointCloud.
bool updatePointCloud(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &cloud, const std::string &id="cloud")
Updates the XYZRGBA data for an existing cloud object id on screen.
bool removeShape(const std::string &id="cloud", int viewport=0)
Removes an added shape from screen (line, polygon, etc.), based on a given ID.
boost::signals2::connection registerMouseCallback(std::function< void(const pcl::visualization::MouseEvent &)> cb)
Register a callback function for mouse events.
void resetStoppedFlag()
Set the stopped flag back to false.
shared_ptr< const PCLVisualizer > ConstPtr
void getCameraParameters(Camera &camera, int viewport=0) const
Get camera parameters of a given viewport (0 means default viewport).
boost::signals2::connection registerKeyboardCallback(std::function< void(const pcl::visualization::KeyboardEvent &)> cb)
Register a callback std::function for keyboard events.
Eigen::Affine3f getViewerPose(int viewport=0)
Get the current viewing pose.
bool addPointCloud(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud, const std::string &id="cloud", int viewport=0)
Add a PointXYZ Point Cloud to screen.
void addOrientationMarkerWidgetAxes(vtkRenderWindowInteractor *interactor)
Adds a widget which shows an interactive axes display for orientation.
bool addEllipsoid(const Eigen::Isometry3d &transform, double radius_x, double radius_y, double radius_z, const std::string &id="ellipsoid", int viewport=0)
Add an ellipsoid from the given parameters.
bool addCylinder(const pcl::ModelCoefficients &coefficients, const std::string &id="cylinder", int viewport=0)
Add a cylinder from a set of given model coefficients.
void setRepresentationToPointsForAllActors()
Changes the visual representation for all actors to points representation.
bool setPointCloudRenderingProperties(int property, double val1, double val2, const std::string &id="cloud", int viewport=0)
Set the rendering properties of a PointCloud (2x values - e.g., LUT minmax values)
bool addLine(const pcl::ModelCoefficients &coefficients, const char *id="line", int viewport=0)
Add a line from a set of given model coefficients.
bool updateCorrespondences(const typename pcl::PointCloud< PointT >::ConstPtr &source_points, const typename pcl::PointCloud< PointT >::ConstPtr &target_points, const pcl::Correspondences &correspondences, const std::string &id="correspondences", int viewport=0)
Update the specified correspondences to the display.
void removeCorrespondences(const std::string &id="correspondences", int viewport=0)
Remove the specified correspondences from the display.
bool addModelFromPolyData(vtkSmartPointer< vtkPolyData > polydata, vtkSmartPointer< vtkTransform > transform, const std::string &id="PolyData", int viewport=0)
Add a vtkPolydata as a mesh.
void setCameraParameters(const Eigen::Matrix3f &intrinsics, const Eigen::Matrix4f &extrinsics, int viewport=0)
Set the camera parameters via an intrinsics and and extrinsics matrix.
bool addSphere(const pcl::ModelCoefficients &coefficients, const std::string &id="sphere", int viewport=0)
Add a sphere from a set of given model coefficients.
PCLVisualizerInteractorStyle defines an unique, custom VTK based interactory style for PCL Visualizer...
static PCLVisualizerInteractorStyle * New()
Base Handler class for PointCloud colors.
shared_ptr< const PointCloudColorHandler< PointCloud > > ConstPtr
shared_ptr< PointCloudColorHandler< PointCloud > > Ptr
Base Handler class for PointCloud colors.
Label field handler class for colors.
RGBA handler class for colors.
RGB handler class for colors.
Base handler class for PointCloud geometry.
shared_ptr< PointCloudGeometryHandler< PointCloud > > Ptr
shared_ptr< const PointCloudGeometryHandler< PointCloud > > ConstPtr
Base handler class for PointCloud geometry.
/brief Class representing 3D point picking events.
PCL_EXPORTS vtkIdType fillCells(std::vector< int > &lookup, const std::vector< pcl::Vertices > &vertices, vtkSmartPointer< vtkCellArray > cell_array, int max_size_of_polygon)
RenderingProperties
Set of rendering properties.
shared_ptr< CloudActorMap > CloudActorMapPtr
shared_ptr< ShapeActorMap > ShapeActorMapPtr
shared_ptr< CoordinateActorMap > CoordinateActorMapPtr
PCL_EXPORTS void allocVtkUnstructuredGrid(vtkSmartPointer< vtkUnstructuredGrid > &polydata)
Allocate a new unstructured grid smartpointer.
std::vector< pcl::Correspondence, Eigen::aligned_allocator< pcl::Correspondence > > Correspondences
#define PCL_DEPRECATED(Major, Minor, Message)
macro for compatibility across compilers and help remove old deprecated items for the Major....
shared_ptr< const ::pcl::PCLPointCloud2 > ConstPtr
A point structure representing Euclidean xyz coordinates, and the RGB color.