00001 00060 #ifndef FIELD_OF_VIEW_H__ 00061 #define FIELD_OF_VIEW_H__ 00062 00063 //################## 00064 //#### includes #### 00065 00066 #include <Eigen/Core> 00067 #include <Eigen/Geometry> 00068 #include <iostream> 00069 00070 namespace cob_3d_mapping 00071 { 00072 00073 /* 00074 * \brief Class to compute the field of view of a camera 00075 */ 00076 class FieldOfView 00077 { 00078 public: 00080 FieldOfView () : 00081 p_0_cam_ (0, 0, 0) 00082 { 00083 computeFieldOfView (); 00084 } 00085 00087 ~FieldOfView () 00088 { 00090 } 00091 00097 void 00098 setSensorFoV_hor (double val) 00099 { 00100 sensor_fov_hor_ = val * M_PI / 180; 00101 } 00102 00108 void 00109 setSensorFoV_ver (double val) 00110 { 00111 sensor_fov_ver_ = val * M_PI / 180; 00112 } 00113 00119 void 00120 setSensorMaxRange (double val) 00121 { 00122 sensor_max_range_ = val; 00123 } 00124 00135 void 00136 getFOV (Eigen::Vector3d& p_0, Eigen::Vector3d& p_1, Eigen::Vector3d& p_2, Eigen::Vector3d& p_3, 00137 Eigen::Vector3d& p_4) 00138 { 00139 p_0 = p_0_; 00140 p_1 = p_1_; 00141 p_2 = p_2_; 00142 p_3 = p_3_; 00143 p_4 = p_4_; 00144 } 00145 00153 void 00154 computeFieldOfView (); 00155 00166 void 00167 transformFOV (Eigen::Affine3d& t) 00168 { 00169 p_0_ = t * p_0_cam_; 00170 p_1_ = t * p_1_cam_; 00171 p_2_ = t * p_2_cam_; 00172 p_3_ = t * p_3_cam_; 00173 p_4_ = t * p_4_cam_; 00174 } 00175 00176 protected: 00177 double sensor_fov_hor_; 00178 double sensor_fov_ver_; 00179 double sensor_max_range_; 00180 00181 Eigen::Vector3d p_0_; 00182 Eigen::Vector3d p_1_; 00183 Eigen::Vector3d p_2_; 00184 Eigen::Vector3d p_3_; 00185 Eigen::Vector3d p_4_; 00186 00187 Eigen::Vector3d p_0_cam_; 00188 Eigen::Vector3d p_1_cam_; 00189 Eigen::Vector3d p_2_cam_; 00190 Eigen::Vector3d p_3_cam_; 00191 Eigen::Vector3d p_4_cam_; 00192 00193 }; 00194 00195 } //namespace 00196 00197 #endif 00198