#include <pcl/ModelCoefficients.h>
#include <pcl/point_cloud.h>
#include <pcl/visualization/eigen.h>
#include <pcl/geometry/planar_polygon.h>
#include <pcl/visualization/common/impl/shapes.hpp>
Go to the source code of this file.
Namespaces | |
namespace | pcl |
namespace | pcl::visualization |
Functions | |
PCL_EXPORTS void | pcl::visualization::allocVtkUnstructuredGrid (vtkSmartPointer< vtkUnstructuredGrid > &polydata) |
Allocate a new unstructured grid smartpointer. For internal use only. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | pcl::visualization::create2DCircle (const pcl::ModelCoefficients &coefficients, double z=0.0) |
Create a 2d circle shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | pcl::visualization::createCone (const pcl::ModelCoefficients &coefficients) |
Create a cone shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | pcl::visualization::createCube (const pcl::ModelCoefficients &coefficients) |
Creaet a cube shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | pcl::visualization::createCube (const Eigen::Vector3f &translation, const Eigen::Quaternionf &rotation, double width, double height, double depth) |
Creaet a cube shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | pcl::visualization::createCube (double x_min, double x_max, double y_min, double y_max, double z_min, double z_max) |
Create a cube from a set of bounding points. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | pcl::visualization::createCylinder (const pcl::ModelCoefficients &coefficients, int numsides=30) |
Create a cylinder shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | pcl::visualization::createLine (const Eigen::Vector4f &pt1, const Eigen::Vector4f &pt2) |
Create a line shape from two points. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | pcl::visualization::createLine (const pcl::ModelCoefficients &coefficients) |
Create a line shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | pcl::visualization::createPlane (const pcl::ModelCoefficients &coefficients) |
Create a planar shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | pcl::visualization::createPlane (const pcl::ModelCoefficients &coefficients, double x, double y, double z) |
Create a planar shape from a set of model coefficients. | |
template<typename PointT > | |
vtkSmartPointer< vtkDataSet > | pcl::visualization::createPolygon (const typename pcl::PointCloud< PointT >::ConstPtr &cloud) |
Create a 3d poly line from a set of points. | |
template<typename PointT > | |
vtkSmartPointer< vtkDataSet > | pcl::visualization::createPolygon (const pcl::PlanarPolygon< PointT > &planar_polygon) |
Create a 3d poly line from a set of points on the boundary of a planar region. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | pcl::visualization::createSphere (const Eigen::Vector4f ¢er, double radius, int res=10) |
Create a sphere shape from a point and a radius. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | pcl::visualization::createSphere (const pcl::ModelCoefficients &coefficients, int res=10) |
Create a sphere shape from a set of model coefficients. |
Define methods or creating 3D shapes from parametric models
Definition in file shapes.h.