rectification.hpp
Go to the documentation of this file.
00001 #ifndef __fovis_rectification_hpp__
00002 #define __fovis_rectification_hpp__
00003 
00004 #include <inttypes.h>
00005 
00006 #include <Eigen/Core>
00007 
00008 #include "camera_intrinsics.hpp"
00009 
00010 namespace fovis
00011 {
00012 
00041 class Rectification
00042 {
00043   public:
00044 
00051     Rectification(const CameraIntrinsicsParameters& input_camera_params);
00052 
00057     Rectification(const CameraIntrinsicsParameters& input_camera_params,
00058             const Eigen::Matrix3d& rotation,
00059             const CameraIntrinsicsParameters& rectified_camera_params);
00060 
00061     ~Rectification();
00062 
00066     const CameraIntrinsicsParameters& getInputCameraParameters() const {
00067       return _input_camera;
00068     }
00069 
00074     const Eigen::Matrix3d& getRectificationRotation() const {
00075       return *_rotation;
00076     }
00077 
00084     const CameraIntrinsicsParameters& getRectifiedCameraParameters() const {
00085       return _rectified_camera;
00086     }
00087 
00096     void rectifyLookup(int dist_u, int dist_v,
00097                        Eigen::Vector2d* rect_uv) const
00098     {
00099       assert(dist_u >= 0 && dist_v >= 0 && dist_u < _input_camera.width && dist_v < _input_camera.height);
00100       int pixel_index = dist_v * _input_camera.width + dist_u;
00101       rect_uv->x() = _map_x[pixel_index];
00102       rect_uv->y() = _map_y[pixel_index];
00103     }
00104 
00114     void rectifyLookupByIndex(int pixel_index,
00115                               Eigen::Vector2d* rect_uv) const
00116     {
00117       rect_uv->x() = _map_x[pixel_index];
00118       rect_uv->y() = _map_y[pixel_index];
00119     }
00120 
00128     void rectifyBilinearLookup(const Eigen::Vector2d& dist_uv,
00129                                Eigen::Vector2d* rect_uv) const {
00130       int u = (int)dist_uv.x();
00131       int v = (int)dist_uv.y();
00132 
00133       assert(u >= 0 && v >= 0 && u < _input_camera.width && v < _input_camera.height);
00134 
00135       // weights
00136       float wright  = (dist_uv.x() - u);
00137       float wbottom = (dist_uv.y() - v);
00138       float w[4] = {
00139         (1 - wright) * (1 - wbottom),
00140         wright * (1 - wbottom),
00141         (1 - wright) * wbottom,
00142         wright * wbottom
00143       };
00144 
00145       int ra_index = v * _input_camera.width + u;
00146       int neighbor_indices[4] = {
00147         ra_index,
00148         ra_index + 1,
00149         ra_index + _input_camera.width,
00150         ra_index + _input_camera.width + 1
00151       };
00152 
00153       rect_uv->x() = 0;
00154       rect_uv->y() = 0;
00155       for(int i = 0; i < 4; ++i) {
00156         rect_uv->x() += w[i] * _map_x[neighbor_indices[i]];
00157         rect_uv->y() += w[i] * _map_y[neighbor_indices[i]];
00158       }
00159     }
00160 
00164     Rectification* makeCopy() const;
00165 
00166   private:
00167     Rectification() {}
00168 
00169     void populateMap();
00170 
00171     CameraIntrinsicsParameters _input_camera;
00172 
00173     Eigen::Matrix3d* _rotation;
00174     // use a pointer above to avoid EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00175 
00176     CameraIntrinsicsParameters _rectified_camera;
00177 
00178     float* _map_x;
00179     float* _map_y;
00180 };
00181 
00182 } /*  */
00183 
00184 #endif


libfovis
Author(s): Albert Huang, Maurice Fallon
autogenerated on Thu Jun 6 2019 20:16:12