Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008 #ifndef RENDER_VIEWS_TESSELATED_SPHERE_H_
00009 #define RENDER_VIEWS_TESSELATED_SPHERE_H_
00010
00011 #include <vtkSmartPointer.h>
00012 #include <vtkPolyData.h>
00013 #include <pcl/common/common.h>
00014 #include <boost/function.hpp>
00015
00016 namespace pcl
00017 {
00018 namespace apps
00019 {
00027 class PCL_EXPORTS RenderViewsTesselatedSphere
00028 {
00029 private:
00030 std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > poses_;
00031 std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> generated_views_;
00032 std::vector<float> entropies_;
00033 int resolution_;
00034 int tesselation_level_;
00035 bool use_vertices_;
00036 float view_angle_;
00037 float radius_sphere_;
00038 bool compute_entropy_;
00039 vtkSmartPointer<vtkPolyData> polydata_;
00040 bool gen_organized_;
00041 boost::function<bool
00042 (const Eigen::Vector3f &)> campos_constraints_func_;
00043
00044 struct camPosConstraintsAllTrue
00045 {
00046 bool
00047 operator() (const Eigen::Vector3f & ) const
00048 {
00049 return true;
00050 }
00051 ;
00052 };
00053
00054 public:
00055 RenderViewsTesselatedSphere ()
00056 {
00057 resolution_ = 150;
00058 tesselation_level_ = 1;
00059 use_vertices_ = false;
00060 view_angle_ = 57;
00061 radius_sphere_ = 1.f;
00062 compute_entropy_ = false;
00063 gen_organized_ = false;
00064 campos_constraints_func_ = camPosConstraintsAllTrue ();
00065 }
00066
00067 void
00068 setCamPosConstraints (boost::function<bool (const Eigen::Vector3f &)> & bb)
00069 {
00070 campos_constraints_func_ = bb;
00071 }
00072
00073
00074
00075
00076 void
00077 setGenOrganized (bool b)
00078 {
00079 gen_organized_ = b;
00080 }
00081
00082
00083
00084
00085 void
00086 setResolution (int res)
00087 {
00088 resolution_ = res;
00089 }
00090
00091
00092
00093
00094
00095 void
00096 setUseVertices (bool use)
00097 {
00098 use_vertices_ = use;
00099 }
00100
00101
00102
00103
00104 void
00105 setRadiusSphere (float radius)
00106 {
00107 radius_sphere_ = radius;
00108 }
00109
00110
00111
00112
00113 void
00114 setComputeEntropies (bool compute)
00115 {
00116 compute_entropy_ = compute;
00117 }
00118
00119
00120
00121
00122 void
00123 setTesselationLevel (int level)
00124 {
00125 tesselation_level_ = level;
00126 }
00127
00128
00129
00130
00131 void
00132 setViewAngle (float angle)
00133 {
00134 view_angle_ = angle;
00135 }
00136
00137
00138
00139
00140 void
00141 addModelFromPolyData (vtkSmartPointer<vtkPolyData> &polydata)
00142 {
00143 polydata_ = polydata;
00144 }
00145
00146
00147
00148 void
00149 generateViews ();
00150
00151
00152
00153
00154 void
00155 getPoses (std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > & poses)
00156 {
00157 poses = poses_;
00158 }
00159
00160
00161
00162
00163 void
00164 getViews (std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> & views)
00165 {
00166 views = generated_views_;
00167 }
00168
00169
00170
00171
00172 void
00173 getEntropies (std::vector<float> & entropies)
00174 {
00175 entropies = entropies_;
00176 }
00177 };
00178
00179 }
00180 }
00181
00182 #endif