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
293 spinOnce (
int time = 1,
bool force_redraw =
false);
322 addCoordinateSystem (
double scale,
float x,
float y,
float z,
const std::string &
id =
"reference",
int viewport = 0);
360 addCoordinateSystem (
double scale,
const Eigen::Affine3f& t,
const std::string &
id =
"reference",
int viewport = 0);
386 return (removePointCloud (
id, viewport));
441 const std::string &
id =
"",
int viewport = 0);
454 addText (
const std::string &text,
int xpos,
int ypos,
double r,
double g,
double b,
455 const std::string &
id =
"",
int viewport = 0);
469 addText (
const std::string &text,
int xpos,
int ypos,
int fontsize,
double r,
double g,
double b,
470 const std::string &
id =
"",
int viewport = 0);
482 const std::string &
id =
"");
495 int xpos,
int ypos,
double r,
double g,
double b,
496 const std::string &
id =
"");
510 int xpos,
int ypos,
int fontsize,
double r,
double g,
double b,
511 const std::string &
id =
"");
559 template <
typename Po
intT>
bool
560 addText3D (
const std::string &text,
562 double textScale = 1.0,
563 double r = 1.0,
double g = 1.0,
double b = 1.0,
564 const std::string &
id =
"",
int viewport = 0);
580 template <
typename Po
intT>
bool
581 addText3D (
const std::string &text,
583 double orientation[3],
584 double textScale = 1.0,
585 double r = 1.0,
double g = 1.0,
double b = 1.0,
586 const std::string &
id =
"",
int viewport = 0);
595 return (cloud_actor_map_->find (
id) != cloud_actor_map_->end () ||
596 shape_actor_map_->find (
id) != shape_actor_map_->end () ||
597 coordinate_actor_map_->find (
id) != coordinate_actor_map_-> end());
607 template <
typename Po
intNT>
bool
609 int level = 100,
float scale = 0.02f,
610 const std::string &
id =
"cloud",
int viewport = 0);
620 template <
typename Po
intT,
typename Po
intNT>
bool
623 int level = 100,
float scale = 0.02f,
624 const std::string &
id =
"cloud",
int viewport = 0);
634 template <
typename Po
intNT>
bool
638 int level = 100,
float scale = 1.0f,
639 const std::string &
id =
"cloud",
int viewport = 0);
650 template <
typename Po
intT,
typename Po
intNT>
bool
651 addPointCloudPrincipalCurvatures (
655 int level = 100,
float scale = 1.0f,
656 const std::string &
id =
"cloud",
int viewport = 0);
666 template <
typename Po
intT,
typename GradientT>
bool
669 int level = 100,
double scale = 1e-6,
670 const std::string &
id =
"cloud",
int viewport = 0);
677 template <
typename Po
intT>
bool
679 const std::string &
id =
"cloud",
int viewport = 0);
686 template <
typename Po
intT>
bool
688 const std::string &
id =
"cloud");
696 template <
typename Po
intT>
bool
699 const std::string &
id =
"cloud");
707 template <
typename Po
intT>
bool
710 const std::string &
id =
"cloud");
718 template <
typename Po
intT>
bool
721 const std::string &
id =
"cloud",
int viewport = 0);
735 template <
typename Po
intT>
bool
738 const std::string &
id =
"cloud",
int viewport = 0);
746 template <
typename Po
intT>
bool
749 const std::string &
id =
"cloud",
int viewport = 0);
763 template <
typename Po
intT>
bool
766 const std::string &
id =
"cloud",
int viewport = 0);
781 template <
typename Po
intT>
bool
785 const std::string &
id =
"cloud",
int viewport = 0);
806 const Eigen::Vector4f& sensor_origin,
807 const Eigen::Quaternion<float>& sensor_orientation,
808 const std::string &
id =
"cloud",
int viewport = 0);
827 const Eigen::Vector4f& sensor_origin,
828 const Eigen::Quaternion<float>& sensor_orientation,
829 const std::string &
id =
"cloud",
int viewport = 0);
848 const Eigen::Vector4f& sensor_origin,
849 const Eigen::Quaternion<float>& sensor_orientation,
850 const std::string &
id =
"cloud",
int viewport = 0);
859 template <
typename Po
intT>
bool
863 const std::string &
id =
"cloud",
int viewport = 0);
872 const std::string &
id =
"cloud",
int viewport = 0)
874 return (addPointCloud<pcl::PointXYZ> (cloud,
id, viewport));
885 const std::string &
id =
"cloud",
int viewport = 0)
888 return (addPointCloud<pcl::PointXYZRGB> (cloud, color_handler,
id, viewport));
898 const std::string &
id =
"cloud",
int viewport = 0)
901 return (addPointCloud<pcl::PointXYZRGBA> (cloud, color_handler,
id, viewport));
911 const std::string &
id =
"cloud",
int viewport = 0)
914 return (addPointCloud<pcl::PointXYZL> (cloud, color_handler,
id, viewport));
924 const std::string &
id =
"cloud")
926 return (updatePointCloud<pcl::PointXYZ> (cloud,
id));
936 const std::string &
id =
"cloud")
939 return (updatePointCloud<pcl::PointXYZRGB> (cloud, color_handler,
id));
949 const std::string &
id =
"cloud")
952 return (updatePointCloud<pcl::PointXYZRGBA> (cloud, color_handler,
id));
962 const std::string &
id =
"cloud")
965 return (updatePointCloud<pcl::PointXYZL> (cloud, color_handler,
id));
975 const std::string &
id =
"polygon",
984 template <
typename Po
intT>
bool
986 const std::vector<pcl::Vertices> &vertices,
987 const std::string &
id =
"polygon",
996 template <
typename Po
intT>
bool
998 const std::vector<pcl::Vertices> &vertices,
999 const std::string &
id =
"polygon");
1008 const std::string &
id =
"polygon");
1017 const std::string &
id =
"polyline",
1027 template <
typename Po
intT>
bool
1030 const std::vector<int> & correspondences,
1031 const std::string &
id =
"correspondences",
1041 const std::string &
id =
"texture",
1053 template <
typename Po
intT>
bool
1058 const std::string &
id =
"correspondences",
1060 bool overwrite =
false);
1069 template <
typename Po
intT>
bool
1073 const std::string &
id =
"correspondences",
1077 return (addCorrespondences<PointT> (source_points, target_points,
1078 correspondences, 1,
id, viewport));
1089 template <
typename Po
intT>
bool
1090 updateCorrespondences (
1095 const std::string &
id =
"correspondences",
1105 template <
typename Po
intT>
bool
1110 const std::string &
id =
"correspondences",
1114 return (updateCorrespondences<PointT> (source_points, target_points,
1115 correspondences, 1,
id, viewport));
1155 const std::string &
id =
"cloud",
int viewport = 0);
1167 const std::string &
id =
"cloud",
int viewport = 0);
1178 const std::string &
id =
"cloud",
int viewport = 0);
1188 const std::string &
id =
"cloud");
1201 const std::string &
id =
"cloud");
1220 const std::string &
id,
int viewport = 0);
1232 const std::string &
id,
int viewport = 0);
1245 const std::string &
id,
int viewport = 0);
1288 template <
typename Po
intT>
bool
1290 double r,
double g,
double b,
1291 const std::string &
id =
"polygon",
int viewport = 0);
1299 template <
typename Po
intT>
bool
1301 const std::string &
id =
"polygon",
1312 template <
typename Po
intT>
bool
1314 double r,
double g,
double b,
1315 const std::string &
id =
"polygon",
1324 template <
typename P1,
typename P2>
bool
1325 addLine (
const P1 &pt1,
const P2 &pt2,
const std::string &
id =
"line",
1337 template <
typename P1,
typename P2>
bool
1338 addLine (
const P1 &pt1,
const P2 &pt2,
double r,
double g,
double b,
1339 const std::string &
id =
"line",
int viewport = 0);
1353 template <
typename P1,
typename P2>
bool
1354 addArrow (
const P1 &pt1,
const P2 &pt2,
double r,
double g,
double b,
1355 const std::string &
id =
"arrow",
int viewport = 0);
1370 template <
typename P1,
typename P2>
bool
1371 addArrow (
const P1 &pt1,
const P2 &pt2,
double r,
double g,
double b,
bool display_length,
1372 const std::string &
id =
"arrow",
int viewport = 0);
1389 template <
typename P1,
typename P2>
bool
1390 addArrow (
const P1 &pt1,
const P2 &pt2,
1391 double r_line,
double g_line,
double b_line,
1392 double r_text,
double g_text,
double b_text,
1393 const std::string &
id =
"arrow",
int viewport = 0);
1402 template <
typename Po
intT>
bool
1403 addSphere (
const PointT ¢er,
double radius,
const std::string &
id =
"sphere",
1415 template <
typename Po
intT>
bool
1416 addSphere (
const PointT ¢er,
double radius,
double r,
double g,
double b,
1417 const std::string &
id =
"sphere",
int viewport = 0);
1427 template <
typename Po
intT>
bool
1428 updateSphere (
const PointT ¢er,
double radius,
double r,
double g,
double b,
1429 const std::string &
id =
"sphere");
1438 const std::string &
id =
"PolyData",
1450 const std::string &
id =
"PolyData",
1460 const std::string &
id =
"PLYModel",
1472 const std::string &
id =
"PLYModel",
1503 const std::string &
id =
"cylinder",
1530 const std::string &
id =
"sphere",
1558 const std::string &
id =
"line",
1586 const char *
id =
"line",
1589 return addLine (coefficients, std::string (
id), viewport);
1614 const std::string &
id =
"plane",
1619 const std::string &
id =
"plane",
1642 const std::string &
id =
"circle",
1652 const std::string &
id =
"cone",
1662 const std::string &
id =
"cube",
1675 addCube (
const Eigen::Vector3f &translation,
const Eigen::Quaternionf &rotation,
1676 double width,
double height,
double depth,
1677 const std::string &
id =
"cube",
1694 addCube (
float x_min,
float x_max,
float y_min,
float y_max,
float z_min,
float z_max,
1695 double r = 1.0,
double g = 1.0,
double b = 1.0,
const std::string &
id =
"cube",
int viewport = 0);
1707 double radius_x,
double radius_y,
double radius_z,
1708 const std::string &
id =
"ellipsoid",
1765 std::vector<Eigen::Matrix4f,Eigen::aligned_allocator< Eigen::Matrix4f > > & poses, std::vector<float> & enthropies,
int tesselation_level,
1766 float view_angle = 45,
float radius_sphere = 1,
bool use_vertices =
true);
1838 double view_x,
double view_y,
double view_z,
1839 double up_x,
double up_y,
double up_z,
int viewport = 0);
1852 double up_x,
double up_y,
double up_z,
int viewport = 0);
1928 return (cloud_actor_map_);
1935 return (shape_actor_map_);
1977 vtkRenderWindow *win);
1987 vtkRenderWindow *win,
1988 vtkInteractorStyle *style);
2013 void setupRenderWindow (
const std::string& name);
2021 void setDefaultWindowSizeAndPos ();
2029 void setupCamera (
int argc,
char **argv);
2031 struct PCL_EXPORTS ExitMainLoopTimerCallback :
public vtkCommand
2033 static ExitMainLoopTimerCallback* New ()
2035 return (
new ExitMainLoopTimerCallback);
2038 Execute (vtkObject*,
unsigned long event_id,
void*)
override;
2044 struct PCL_EXPORTS ExitCallback :
public vtkCommand
2046 static ExitCallback* New ()
2048 return (
new ExitCallback);
2051 Execute (vtkObject*,
unsigned long event_id,
void*)
override;
2053 PCLVisualizer* pcl_visualizer;
2057 struct PCL_EXPORTS FPSCallback :
public vtkCommand
2059 static FPSCallback *New () {
return (
new FPSCallback); }
2061 FPSCallback () : actor (), pcl_visualizer (), decimated (), last_fps(0.0f) {}
2062 FPSCallback (
const FPSCallback& src) : vtkCommand (src), actor (src.actor), pcl_visualizer (src.pcl_visualizer), decimated (src.decimated), last_fps (src.last_fps) {}
2063 FPSCallback& operator = (
const FPSCallback& src) { actor = src.actor; pcl_visualizer = src.pcl_visualizer; decimated = src.decimated; last_fps = src.last_fps;
return (*
this); }
2066 Execute (vtkObject*,
unsigned long event_id,
void*)
override;
2068 vtkTextActor *actor;
2069 PCLVisualizer* pcl_visualizer;
2112 bool camera_file_loaded_;
2160 bool use_scalars =
true)
const;
2170 bool use_scalars =
true)
const;
2178 template <
typename Po
intT>
void
2189 template <
typename Po
intT>
void
2190 convertPointCloudToVTKPolyData (
const PointCloudGeometryHandler<PointT> &geometry_handler,
2201 convertPointCloudToVTKPolyData (
const GeometryHandlerConstPtr &geometry_handler,
2216 vtkIdType nr_points);
2228 template <
typename Po
intT>
bool
2229 fromHandlersToScreen (
const PointCloudGeometryHandler<PointT> &geometry_handler,
2230 const PointCloudColorHandler<PointT> &color_handler,
2231 const std::string &
id,
2233 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2234 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2246 template <
typename Po
intT>
bool
2247 fromHandlersToScreen (
const PointCloudGeometryHandler<PointT> &geometry_handler,
2248 const ColorHandlerConstPtr &color_handler,
2249 const std::string &
id,
2251 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2252 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2265 fromHandlersToScreen (
const GeometryHandlerConstPtr &geometry_handler,
2266 const ColorHandlerConstPtr &color_handler,
2267 const std::string &
id,
2269 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2270 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2282 template <
typename Po
intT>
bool
2283 fromHandlersToScreen (
const GeometryHandlerConstPtr &geometry_handler,
2284 const PointCloudColorHandler<PointT> &color_handler,
2285 const std::string &
id,
2287 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2288 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2314 getTransformationMatrix (
const Eigen::Vector4f &origin,
2315 const Eigen::Quaternion<float> &orientation,
2316 Eigen::Matrix4f &transformation);
2327 vtkTexture* vtk_tex)
const;
2334 getUniqueCameraFile (
int argc,
char **argv);
2353 const Eigen::Quaternion<float> &orientation,
2362 Eigen::Matrix4f &m);
2368 #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 visualizaton 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.
void setupInteractor(vtkRenderWindowInteractor *iren, vtkRenderWindow *win, vtkInteractorStyle *style)
Set up PCLVisualizer with custom interactor style for a given vtkRenderWindowInteractor object attach...
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.
void updateCamera()
Update camera parameters and render.
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.
void setLookUpTableID(const std::string id)
Set the ID of a cloud or shape to be used for LUT display.
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 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.
void setUseVbos(bool use_vbos)
Use Vertex Buffer Objects renderers.
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 setupInteractor(vtkRenderWindowInteractor *iren, vtkRenderWindow *win)
Set up our unique PCL interactor style for a given vtkRenderWindowInteractor object attached to a giv...
void setCameraClipDistances(double near, double far, int viewport=0)
Set the camera clipping distances.
void createInteractor()
Create the internal Interactor object.
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.
vtkSmartPointer< PCLVisualizerInteractorStyle > getInteractorStyle()
Get a pointer to the current interactor style used.
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
shared_ptr< const ::pcl::PCLPointCloud2 > ConstPtr
A point structure representing Euclidean xyz coordinates, and the RGB color.