Namespaces | |
namespace | context_items |
Classes | |
class | AreaPickingEvent |
class | Camera |
Camera class holds a set of camera parameters together with the window pos/size. More... | |
class | CloudActor |
class | CloudViewer |
Simple point cloud visualization class. More... | |
struct | FEllipticArc2D |
Class for storing EllipticArc; every ellipse , circle are covered by this. More... | |
struct | Figure2D |
Abstract class for storing figure information. All the derived class uses the same method draw() to invoke different drawing function of vtkContext2D. More... | |
class | FloatImageUtils |
struct | FPoints2D |
Class for storing Points. More... | |
struct | FPolygon2D |
Class for Polygon. More... | |
struct | FPolyLine2D |
Class for PolyLine. More... | |
struct | FQuad2D |
Class for storing Quads. More... | |
class | ImageViewer |
ImageViewer is a class for 2D image visualization. More... | |
class | ImageViewerInteractorStyle |
An image viewer interactor style, tailored for ImageViewer. More... | |
class | KeyboardEvent |
class | MouseEvent |
struct | PCLContextImageItem |
struct | PCLContextItem |
class | PCLHistogramVisualizer |
PCL histogram visualizer main class. More... | |
class | PCLHistogramVisualizerInteractorStyle |
PCL histogram visualizer interactory style class. More... | |
class | PCLImageCanvasSource2D |
PCLImageCanvasSource2D represents our own custom version of vtkImageCanvasSource2D, used by the ImageViewer class. More... | |
class | PCLPainter2D |
PCL Painter2D main class. Class for drawing 2D figures. More... | |
class | PCLPlotter |
PCL Plotter main class. Given point correspondences this class can be used to plot the data one against the other and display it on the screen. It also has methods for providing plot for important functions like histogram etc. Important functions of PCLHistogramVisualizer are redefined here so that this single class can take responsibility of all plotting related functionalities. More... | |
class | PCLSimpleBufferVisualizer |
PCL simple buffer visualizer main class. More... | |
class | PCLVisualizer |
PCL Visualizer main class. More... | |
class | PCLVisualizerInteractor |
The PCLVisualizer interactor. More... | |
class | PCLVisualizerInteractorStyle |
PCLVisualizerInteractorStyle defines an unique, custom VTK based interactory style for PCL Visualizer applications. Besides defining the rendering style, we also create a list of custom actions that are triggered on different keys being pressed: More... | |
class | PointCloudColorHandler |
Base Handler class for PointCloud colors. More... | |
class | PointCloudColorHandler< pcl::PCLPointCloud2 > |
Base Handler class for PointCloud colors. More... | |
class | PointCloudColorHandlerCustom |
Handler for predefined user colors. The color at each point will be drawn as the use given R, G, B values. More... | |
class | PointCloudColorHandlerCustom< pcl::PCLPointCloud2 > |
Handler for predefined user colors. The color at each point will be drawn as the use given R, G, B values. More... | |
class | PointCloudColorHandlerGenericField |
Generic field handler class for colors. Uses an user given field to extract 1D data and display the color at each point using a min-max lookup table. More... | |
class | PointCloudColorHandlerGenericField< pcl::PCLPointCloud2 > |
Generic field handler class for colors. Uses an user given field to extract 1D data and display the color at each point using a min-max lookup table. More... | |
class | PointCloudColorHandlerHSVField |
HSV handler class for colors. Uses the data present in the "h", "s", "v" fields as the color at each point. More... | |
class | PointCloudColorHandlerHSVField< pcl::PCLPointCloud2 > |
HSV handler class for colors. Uses the data present in the "h", "s", "v" fields as the color at each point. More... | |
class | PointCloudColorHandlerRandom |
Handler for random PointCloud colors (i.e., R, G, B will be randomly chosen) More... | |
class | PointCloudColorHandlerRandom< pcl::PCLPointCloud2 > |
Handler for random PointCloud colors (i.e., R, G, B will be randomly chosen) More... | |
class | PointCloudColorHandlerRGBField |
RGB handler class for colors. Uses the data present in the "rgb" or "rgba" fields as the color at each point. More... | |
class | PointCloudColorHandlerRGBField< pcl::PCLPointCloud2 > |
RGB handler class for colors. Uses the data present in the "rgb" or "rgba" fields as the color at each point. More... | |
class | PointCloudGeometryHandler |
Base handler class for PointCloud geometry. More... | |
class | PointCloudGeometryHandler< pcl::PCLPointCloud2 > |
Base handler class for PointCloud geometry. More... | |
class | PointCloudGeometryHandlerCustom |
Custom handler class for PointCloud geometry. Given an input dataset and three user defined fields, all data present in them is extracted and displayed on screen as XYZ data. More... | |
class | PointCloudGeometryHandlerCustom< pcl::PCLPointCloud2 > |
Custom handler class for PointCloud geometry. Given an input dataset and three user defined fields, all data present in them is extracted and displayed on screen as XYZ data. More... | |
class | PointCloudGeometryHandlerSurfaceNormal |
Surface normal handler class for PointCloud geometry. Given an input dataset, all data present in fields "normal_x", "normal_y", and "normal_z" is extracted and dislayed on screen as XYZ data. More... | |
class | PointCloudGeometryHandlerSurfaceNormal< pcl::PCLPointCloud2 > |
Surface normal handler class for PointCloud geometry. Given an input dataset, all data present in fields "normal_x", "normal_y", and "normal_z" is extracted and dislayed on screen as XYZ data. More... | |
class | PointCloudGeometryHandlerXYZ |
XYZ handler class for PointCloud geometry. Given an input dataset, all XYZ data present in fields "x", "y", and "z" is extracted and displayed on screen. More... | |
class | PointCloudGeometryHandlerXYZ< pcl::PCLPointCloud2 > |
XYZ handler class for PointCloud geometry. Given an input dataset, all XYZ data present in fields "x", "y", and "z" is extracted and displayed on screen. More... | |
class | PointPickingCallback |
class | PointPickingEvent |
class | RangeImageVisualizer |
Range image visualizer class. More... | |
class | RenWinInteract |
class | Window |
Typedefs | |
typedef boost::unordered_map < std::string, CloudActor > | CloudActorMap |
typedef boost::shared_ptr < CloudActorMap > | CloudActorMapPtr |
typedef std::map< int, vtkSmartPointer< vtkProp > > | CoordinateActorMap |
typedef std::map< std::string, RenWinInteract > | RenWinInteractMap |
typedef boost::unordered_map < std::string, vtkSmartPointer < vtkProp > > | ShapeActorMap |
typedef boost::shared_ptr < ShapeActorMap > | ShapeActorMapPtr |
typedef Eigen::Array< unsigned char, 3, 1 > | Vector3ub |
Enumerations | |
enum | FrustumCull { PCL_INSIDE_FRUSTUM, PCL_INTERSECT_FRUSTUM, PCL_OUTSIDE_FRUSTUM } |
enum | InteractorKeyboardModifier { INTERACTOR_KB_MOD_ALT, INTERACTOR_KB_MOD_CTRL, INTERACTOR_KB_MOD_SHIFT } |
A list of potential keyboard modifiers for PCLVisualizerInteractorStyle. Defaults to Alt. More... | |
enum | RenderingProperties { PCL_VISUALIZER_POINT_SIZE, PCL_VISUALIZER_OPACITY, PCL_VISUALIZER_LINE_WIDTH, PCL_VISUALIZER_FONT_SIZE, PCL_VISUALIZER_COLOR, PCL_VISUALIZER_REPRESENTATION, PCL_VISUALIZER_IMMEDIATE_RENDERING, PCL_VISUALIZER_SHADING } |
enum | RenderingRepresentationProperties { PCL_VISUALIZER_REPRESENTATION_POINTS, PCL_VISUALIZER_REPRESENTATION_WIREFRAME, PCL_VISUALIZER_REPRESENTATION_SURFACE } |
enum | ShadingRepresentationProperties { PCL_VISUALIZER_SHADING_FLAT, PCL_VISUALIZER_SHADING_GOURAUD, PCL_VISUALIZER_SHADING_PHONG } |
Functions | |
PCL_EXPORTS void | allocVtkUnstructuredGrid (vtkSmartPointer< vtkUnstructuredGrid > &polydata) |
Allocate a new unstructured grid smartpointer. For internal use only. | |
static const Vector3ub | blue_color (0, 0, 255) |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | create2DCircle (const pcl::ModelCoefficients &coefficients, double z=0.0) |
Create a 2d circle shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | createCone (const pcl::ModelCoefficients &coefficients) |
Create a cone shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | createCube (const pcl::ModelCoefficients &coefficients) |
Creaet a cube shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | 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 > | 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 > | createCylinder (const pcl::ModelCoefficients &coefficients, int numsides=30) |
Create a cylinder shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | createLine (const Eigen::Vector4f &pt1, const Eigen::Vector4f &pt2) |
Create a line shape from two points. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | createLine (const pcl::ModelCoefficients &coefficients) |
Create a line shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | createPlane (const pcl::ModelCoefficients &coefficients) |
Create a planar shape from a set of model coefficients. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | 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 > | createPolygon (const typename pcl::PointCloud< PointT >::ConstPtr &cloud) |
Create a 3d poly line from a set of points. | |
template<typename PointT > | |
vtkSmartPointer< vtkDataSet > | 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 > | createSphere (const Eigen::Vector4f ¢er, double radius, int res=10) |
Create a sphere shape from a point and a radius. | |
PCL_EXPORTS vtkSmartPointer < vtkDataSet > | createSphere (const pcl::ModelCoefficients &coefficients, int res=10) |
Create a sphere shape from a set of model coefficients. | |
PCL_EXPORTS int | cullFrustum (double planes[24], const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb) |
PCL_EXPORTS void | getCorrespondingPointCloud (vtkPolyData *src, const pcl::PointCloud< pcl::PointXYZ > &tgt, std::vector< int > &indices) |
Obtain a list of corresponding indices, for a set of vtk points, from a pcl::PointCloud. | |
PCL_EXPORTS void | getRandomColors (double &r, double &g, double &b, double min=0.2, double max=2.8) |
Get (good) random values for R/G/B. | |
PCL_EXPORTS void | getRandomColors (pcl::RGB &rgb, double min=0.2, double max=2.8) |
Get (good) random values for R/G/B. | |
PCL_EXPORTS void | getViewFrustum (const Eigen::Matrix4d &view_projection_matrix, double planes[24]) |
static const Vector3ub | green_color (0, 255, 0) |
static const Vector3ub | red_color (255, 0, 0) |
PCL_EXPORTS bool | savePointData (vtkPolyData *data, const std::string &out_file, const boost::shared_ptr< CloudActorMap > &actors) |
Saves the vtk-formatted Point Cloud data into a set of files, based on whether the data comes from previously loaded PCD files. The PCD files are matched using the a list of names for the actors on screen. | |
PCL_EXPORTS float | viewScreenArea (const Eigen::Vector3d &eye, const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const Eigen::Matrix4d &view_projection_matrix, int width, int height) |
vtkStandardNewMacro (PCLContextItem) | |
vtkStandardNewMacro (PCLContextImageItem) | |
vtkStandardNewMacro (ImageViewerInteractorStyle) | |
vtkStandardNewMacro (PCLVisualizerInteractorStyle) | |
vtkStandardNewMacro (PCLHistogramVisualizerInteractorStyle) | |
PCL_EXPORTS Eigen::Matrix4d | vtkToEigen (vtkMatrix4x4 *vtk_matrix) |
PCL_EXPORTS Eigen::Vector2i | worldToView (const Eigen::Vector4d &world_pt, const Eigen::Matrix4d &view_projection_matrix, int width, int height) |
typedef boost::unordered_map<std::string, CloudActor> pcl::visualization::CloudActorMap |
Definition at line 99 of file actor_map.h.
typedef boost::shared_ptr<CloudActorMap> pcl::visualization::CloudActorMapPtr |
Definition at line 100 of file actor_map.h.
typedef std::map<int, vtkSmartPointer<vtkProp> > pcl::visualization::CoordinateActorMap |
Definition at line 105 of file actor_map.h.
typedef std::map<std::string, RenWinInteract> pcl::visualization::RenWinInteractMap |
Definition at line 82 of file ren_win_interact_map.h.
typedef boost::unordered_map<std::string, vtkSmartPointer<vtkProp> > pcl::visualization::ShapeActorMap |
Definition at line 102 of file actor_map.h.
typedef boost::shared_ptr<ShapeActorMap> pcl::visualization::ShapeActorMapPtr |
Definition at line 103 of file actor_map.h.
typedef Eigen::Array<unsigned char, 3, 1> pcl::visualization::Vector3ub |
Definition at line 65 of file image_viewer.h.
Definition at line 81 of file visualization/include/pcl/visualization/common/common.h.
A list of potential keyboard modifiers for PCLVisualizerInteractorStyle. Defaults to Alt.
Definition at line 69 of file interactor_style.h.
Definition at line 94 of file visualization/include/pcl/visualization/common/common.h.
PCL_VISUALIZER_REPRESENTATION_POINTS | |
PCL_VISUALIZER_REPRESENTATION_WIREFRAME | |
PCL_VISUALIZER_REPRESENTATION_SURFACE |
Definition at line 106 of file visualization/include/pcl/visualization/common/common.h.
Definition at line 113 of file visualization/include/pcl/visualization/common/common.h.
void pcl::visualization::allocVtkUnstructuredGrid | ( | vtkSmartPointer< vtkUnstructuredGrid > & | polydata | ) |
Allocate a new unstructured grid smartpointer. For internal use only.
[out] | polydata | the resultant unstructured grid. |
Definition at line 299 of file shapes.cpp.
static const Vector3ub pcl::visualization::blue_color | ( | 0 | , |
0 | , | ||
255 | |||
) | [static] |
vtkSmartPointer< vtkDataSet > pcl::visualization::create2DCircle | ( | const pcl::ModelCoefficients & | coefficients, |
double | z = 0.0 |
||
) |
Create a 2d circle shape from a set of model coefficients.
[in] | coefficients | the model coefficients (x, y, radius) |
[in] | z | (optional) specify a z value (default: 0) |
// The following are given (or computed using sample consensus techniques -- see SampleConsensusModelCircle2D) // float x, y, radius; pcl::ModelCoefficients circle_coeff; circle_coeff.values.resize (3); // We need 3 values circle_coeff.values[0] = x; circle_coeff.values[1] = y; circle_coeff.values[2] = radius; vtkSmartPointer<vtkDataSet> data = pcl::visualization::create2DCircle (circle_coeff, z);
Definition at line 211 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl::visualization::createCone | ( | const pcl::ModelCoefficients & | coefficients | ) |
Create a cone shape from a set of model coefficients.
[in] | coefficients | the cone coefficients (point_on_axis, axis_direction, radius) |
Definition at line 249 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl::visualization::createCube | ( | const pcl::ModelCoefficients & | coefficients | ) |
Creaet a cube shape from a set of model coefficients.
[in] | coefficients | the cube coefficients (Tx, Ty, Tz, Qx, Qy, Qz, Qw, width, height, depth) |
Definition at line 89 of file shapes.cpp.
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.
[in] | translation | a translation to apply to the cube from 0,0,0 |
[in] | rotation | a quaternion-based rotation to apply to the cube |
[in] | width | the cube's width |
[in] | height | the cube's height |
[in] | depth | the cube's depth |
Definition at line 114 of file shapes.cpp.
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.
[in] | x_min | is the minimum x value of the box |
[in] | x_max | is the maximum x value of the box |
[in] | y_min | is the minimum y value of the box |
[in] | y_max | is the maximum y value of the box |
[in] | z_min | is the minimum z value of the box |
[in] | z_max | is the maximum z value of the box |
[in] | id | the cube id/name (default: "cube") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 139 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl::visualization::createCylinder | ( | const pcl::ModelCoefficients & | coefficients, |
int | numsides = 30 |
||
) |
Create a cylinder shape from a set of model coefficients.
[in] | coefficients | the model coefficients (point_on_axis, axis_direction, radius) |
[in] | numsides | (optional) the number of sides used for rendering the cylinder |
// The following are given (or computed using sample consensus techniques -- see SampleConsensusModelCylinder) // Eigen::Vector3f pt_on_axis, axis_direction; // float radius; pcl::ModelCoefficients cylinder_coeff; cylinder_coeff.values.resize (7); // We need 7 values cylinder_coeff.values[0] = pt_on_axis.x (); cylinder_coeff.values[1] = pt_on_axis.y (); cylinder_coeff.values[2] = pt_on_axis.z (); cylinder_coeff.values[3] = axis_direction.x (); cylinder_coeff.values[4] = axis_direction.y (); cylinder_coeff.values[5] = axis_direction.z (); cylinder_coeff.values[6] = radius; vtkSmartPointer<vtkDataSet> data = pcl::visualization::createCylinder (cylinder_coeff, numsides);
Definition at line 52 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl::visualization::createLine | ( | const Eigen::Vector4f & | pt1, |
const Eigen::Vector4f & | pt2 | ||
) |
Create a line shape from two points.
[in] | pt1 | the first point on the line |
[in] | pt2 | the end point on the line |
Definition at line 288 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl::visualization::createLine | ( | const pcl::ModelCoefficients & | coefficients | ) |
Create a line shape from a set of model coefficients.
[in] | coefficients | the model coefficients (point_on_line, line_direction) |
// The following are given (or computed using sample consensus techniques -- see SampleConsensusModelLine) // Eigen::Vector3f point_on_line, line_direction; pcl::ModelCoefficients line_coeff; line_coeff.values.resize (6); // We need 6 values line_coeff.values[0] = point_on_line.x (); line_coeff.values[1] = point_on_line.y (); line_coeff.values[2] = point_on_line.z (); line_coeff.values[3] = line_direction.x (); line_coeff.values[4] = line_direction.y (); line_coeff.values[5] = line_direction.z (); vtkSmartPointer<vtkDataSet> data = pcl::visualization::createLine (line_coeff);
Definition at line 153 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl::visualization::createPlane | ( | const pcl::ModelCoefficients & | coefficients | ) |
Create a planar shape from a set of model coefficients.
[in] | coefficients | the model coefficients (a, b, c, d with ax+by+cz+d=0) |
// The following are given (or computed using sample consensus techniques -- see SampleConsensusModelPlane) // Eigen::Vector4f plane_parameters; pcl::ModelCoefficients plane_coeff; plane_coeff.values.resize (4); // We need 4 values plane_coeff.values[0] = plane_parameters.x (); plane_coeff.values[1] = plane_parameters.y (); plane_coeff.values[2] = plane_parameters.z (); plane_coeff.values[3] = plane_parameters.w (); vtkSmartPointer<vtkDataSet> data = pcl::visualization::createPlane (plane_coeff);
Definition at line 167 of file shapes.cpp.
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.
[in] | coefficients | the model coefficients (a, b, c, d with ax+by+cz+d=0) |
[in] | x,y,z | projection of this point on the plane is used to get the center of the plane. |
Definition at line 182 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl::visualization::createPolygon | ( | const typename pcl::PointCloud< PointT >::ConstPtr & | cloud | ) | [inline] |
Create a 3d poly line from a set of points.
[in] | cloud | the set of points used to create the 3d polyline |
Definition at line 47 of file shapes.hpp.
vtkSmartPointer< vtkDataSet > pcl::visualization::createPolygon | ( | const pcl::PlanarPolygon< PointT > & | planar_polygon | ) | [inline] |
Create a 3d poly line from a set of points on the boundary of a planar region.
[in] | planar_polygon | the set of points used to create the 3d polyline |
Definition at line 77 of file shapes.hpp.
vtkSmartPointer< vtkDataSet > pcl::visualization::createSphere | ( | const Eigen::Vector4f & | center, |
double | radius, | ||
int | res = 10 |
||
) |
Create a sphere shape from a point and a radius.
[in] | center | the center of the sphere (as an Eigen Vector4f, with only the first 3 coordinates used) |
[in] | radius | the radius of the sphere |
[in] | res | (optional) the resolution used for rendering the model |
Definition at line 265 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl::visualization::createSphere | ( | const pcl::ModelCoefficients & | coefficients, |
int | res = 10 |
||
) |
Create a sphere shape from a set of model coefficients.
[in] | coefficients | the model coefficients (sphere center, radius) |
[in] | res | (optional) the resolution used for rendering the model |
// The following are given (or computed using sample consensus techniques -- see SampleConsensusModelSphere) // Eigen::Vector3f sphere_center; // float radius; pcl::ModelCoefficients sphere_coeff; sphere_coeff.values.resize (4); // We need 4 values sphere_coeff.values[0] = sphere_center.x (); sphere_coeff.values[1] = sphere_center.y (); sphere_coeff.values[2] = sphere_center.z (); sphere_coeff.values[3] = radius; vtkSmartPointer<vtkDataSet> data = pcl::visualization::createSphere (sphere_coeff, resolution);
Definition at line 68 of file shapes.cpp.
int pcl::visualization::cullFrustum | ( | double | planes[24], |
const Eigen::Vector3d & | min_bb, | ||
const Eigen::Vector3d & | max_bb | ||
) |
Definition at line 150 of file visualization/src/common/common.cpp.
void pcl::visualization::getCorrespondingPointCloud | ( | vtkPolyData * | src, |
const pcl::PointCloud< pcl::PointXYZ > & | tgt, | ||
std::vector< int > & | indices | ||
) |
Obtain a list of corresponding indices, for a set of vtk points, from a pcl::PointCloud.
src | the set of vtk points |
tgt | the target pcl::PointCloud that we need to obtain indices from |
indices | the resultant list of indices |
Definition at line 49 of file visualization/src/common/io.cpp.
void pcl::visualization::getRandomColors | ( | double & | r, |
double & | g, | ||
double & | b, | ||
double | min = 0.2 , |
||
double | max = 2.8 |
||
) |
Get (good) random values for R/G/B.
[out] | r | the resultant R color value |
[out] | g | the resultant G color value |
[out] | b | the resultant B color value |
[in] | min | minimum value for the colors |
[in] | max | maximum value for the colors |
Definition at line 44 of file visualization/src/common/common.cpp.
void pcl::visualization::getRandomColors | ( | pcl::RGB & | rgb, |
double | min = 0.2 , |
||
double | max = 2.8 |
||
) |
Get (good) random values for R/G/B.
[out] | rgb | the resultant RGB color value |
[in] | min | minimum value for the colors |
[in] | max | maximum value for the colors |
Definition at line 61 of file visualization/src/common/common.cpp.
void pcl::visualization::getViewFrustum | ( | const Eigen::Matrix4d & | view_projection_matrix, |
double | planes[24] | ||
) |
Definition at line 118 of file visualization/src/common/common.cpp.
static const Vector3ub pcl::visualization::green_color | ( | 0 | , |
255 | , | ||
0 | |||
) | [static] |
static const Vector3ub pcl::visualization::red_color | ( | 255 | , |
0 | , | ||
0 | |||
) | [static] |
bool pcl::visualization::savePointData | ( | vtkPolyData * | data, |
const std::string & | out_file, | ||
const boost::shared_ptr< CloudActorMap > & | actors | ||
) |
Saves the vtk-formatted Point Cloud data into a set of files, based on whether the data comes from previously loaded PCD files. The PCD files are matched using the a list of names for the actors on screen.
data | the vtk data |
out_file | the output file (extra indices will be appended to it) |
actors | the list of actors present on screen |
Definition at line 87 of file visualization/src/common/io.cpp.
float pcl::visualization::viewScreenArea | ( | const Eigen::Vector3d & | eye, |
const Eigen::Vector3d & | min_bb, | ||
const Eigen::Vector3d & | max_bb, | ||
const Eigen::Matrix4d & | view_projection_matrix, | ||
int | width, | ||
int | height | ||
) |
Definition at line 259 of file visualization/src/common/common.cpp.
pcl::visualization::vtkStandardNewMacro | ( | PCLContextItem | ) |
pcl::visualization::vtkStandardNewMacro | ( | PCLContextImageItem | ) |
pcl::visualization::vtkStandardNewMacro | ( | ImageViewerInteractorStyle | ) |
pcl::visualization::vtkStandardNewMacro | ( | PCLVisualizerInteractorStyle | ) |
pcl::visualization::vtkStandardNewMacro | ( | PCLHistogramVisualizerInteractorStyle | ) |
Eigen::Matrix4d pcl::visualization::vtkToEigen | ( | vtkMatrix4x4 * | vtk_matrix | ) |
Definition at line 83 of file visualization/src/common/common.cpp.
Eigen::Vector2i pcl::visualization::worldToView | ( | const Eigen::Vector4d & | world_pt, |
const Eigen::Matrix4d & | view_projection_matrix, | ||
int | width, | ||
int | height | ||
) |
Definition at line 99 of file visualization/src/common/common.cpp.