common.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id$
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         // the following variables are the actual position and size of the window on the screen and NOT the viewport!
00146         // except for the size, which is the same the viewport is assumed to be centered and same size as the window.
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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:49