Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef PCL_PCL_VISUALIZER_COMMON_H_
00038 #define PCL_PCL_VISUALIZER_COMMON_H_
00039
00040 #if defined __GNUC__
00041 #pragma GCC system_header
00042 #endif
00043
00044 #include <pcl/pcl_macros.h>
00045 #include <pcl/visualization/eigen.h>
00046 #include <vtkMatrix4x4.h>
00047
00048 namespace pcl
00049 {
00050 struct RGB;
00051
00052 namespace visualization
00053 {
00061 PCL_EXPORTS void
00062 getRandomColors (double &r, double &g, double &b, double min = 0.2, double max = 2.8);
00063
00069 PCL_EXPORTS void
00070 getRandomColors (pcl::RGB &rgb, double min = 0.2, double max = 2.8);
00071
00072 PCL_EXPORTS Eigen::Matrix4d
00073 vtkToEigen (vtkMatrix4x4* vtk_matrix);
00074
00075 PCL_EXPORTS Eigen::Vector2i
00076 worldToView (const Eigen::Vector4d &world_pt, const Eigen::Matrix4d &view_projection_matrix, int width, int height);
00077
00078 PCL_EXPORTS void
00079 getViewFrustum (const Eigen::Matrix4d &view_projection_matrix, double planes[24]);
00080
00081 enum FrustumCull
00082 {
00083 PCL_INSIDE_FRUSTUM,
00084 PCL_INTERSECT_FRUSTUM,
00085 PCL_OUTSIDE_FRUSTUM
00086 };
00087
00088 PCL_EXPORTS int
00089 cullFrustum (double planes[24], const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb);
00090
00091 PCL_EXPORTS float
00092 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);
00093
00094 enum RenderingProperties
00095 {
00096 PCL_VISUALIZER_POINT_SIZE,
00097 PCL_VISUALIZER_OPACITY,
00098 PCL_VISUALIZER_LINE_WIDTH,
00099 PCL_VISUALIZER_FONT_SIZE,
00100 PCL_VISUALIZER_COLOR,
00101 PCL_VISUALIZER_REPRESENTATION,
00102 PCL_VISUALIZER_IMMEDIATE_RENDERING,
00103 PCL_VISUALIZER_SHADING
00104 };
00105
00106 enum RenderingRepresentationProperties
00107 {
00108 PCL_VISUALIZER_REPRESENTATION_POINTS,
00109 PCL_VISUALIZER_REPRESENTATION_WIREFRAME,
00110 PCL_VISUALIZER_REPRESENTATION_SURFACE
00111 };
00112
00113 enum ShadingRepresentationProperties
00114 {
00115 PCL_VISUALIZER_SHADING_FLAT,
00116 PCL_VISUALIZER_SHADING_GOURAUD,
00117 PCL_VISUALIZER_SHADING_PHONG
00118 };
00119
00121
00122 class PCL_EXPORTS Camera
00123 {
00124 public:
00128 double focal[3];
00129
00131 double pos[3];
00132
00135 double view[3];
00136
00140 double clip[2];
00141
00143 double fovy;
00144
00145
00146
00147 double window_size[2];
00148 double window_pos[2];
00149
00150
00154 void
00155 computeViewMatrix (Eigen::Matrix4d& view_mat) const;
00156
00160 void
00161 computeProjectionMatrix (Eigen::Matrix4d& proj) const;
00162
00170 template<typename PointT> void
00171 cvtWindowCoordinates (const PointT& pt, Eigen::Vector4d& window_cord) const;
00172
00183 template<typename PointT> void
00184 cvtWindowCoordinates (const PointT& pt, Eigen::Vector4d& window_cord, const Eigen::Matrix4d& composite_mat) const;
00185 };
00186 }
00187 }
00188
00189 #include <pcl/visualization/common/impl/common.hpp>
00190
00191 #endif