CameraModel.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef CAMERAMODEL_H_
00029 #define CAMERAMODEL_H_
00030 
00031 #include <opencv2/opencv.hpp>
00032 
00033 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00034 #include "rtabmap/core/Transform.h"
00035 
00036 namespace rtabmap {
00037 
00038 class RTABMAP_EXP CameraModel
00039 {
00040 public:
00041         CameraModel();
00042         // K is the camera intrinsic 3x3 CV_64FC1
00043         // D is the distortion coefficients 1x5 CV_64FC1
00044         // R is the rectification matrix 3x3 CV_64FC1 (computed from stereo or Identity)
00045         // P is the projection matrix 3x4 CV_64FC1 (computed from stereo or equal to [K [0 0 1]'])
00046         CameraModel(
00047                         const std::string & name,
00048                         const cv::Size & imageSize,
00049                         const cv::Mat & K,
00050                         const cv::Mat & D,
00051                         const cv::Mat & R,
00052                         const cv::Mat & P,
00053                         const Transform & localTransform = Transform::getIdentity());
00054 
00055         // minimal
00056         CameraModel(
00057                         double fx,
00058                         double fy,
00059                         double cx,
00060                         double cy,
00061                         const Transform & localTransform = Transform::getIdentity(),
00062                         double Tx = 0.0f,
00063                         const cv::Size & imageSize = cv::Size(0,0));
00064         // minimal to be saved
00065         CameraModel(
00066                         const std::string & name,
00067                         double fx,
00068                         double fy,
00069                         double cx,
00070                         double cy,
00071                         const Transform & localTransform = Transform::getIdentity(),
00072                         double Tx = 0.0f,
00073                         const cv::Size & imageSize = cv::Size(0,0));
00074 
00075         virtual ~CameraModel() {}
00076 
00077         void initRectificationMap();
00078 
00079         bool isValidForProjection() const {return fx()>0.0 && fy()>0.0;}
00080         bool isValidForRectification() const
00081         {
00082                 return imageSize_.width>0 &&
00083                            imageSize_.height>0 &&
00084                            !K_.empty() &&
00085                            !D_.empty() &&
00086                            !R_.empty() &&
00087                            !P_.empty();
00088         }
00089 
00090         void setName(const std::string & name) {name_=name;}
00091         const std::string & name() const {return name_;}
00092 
00093         double fx() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(0,0):P_.at<double>(0,0);}
00094         double fy() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(1,1):P_.at<double>(1,1);}
00095         double cx() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(0,2):P_.at<double>(0,2);}
00096         double cy() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(1,2):P_.at<double>(1,2);}
00097         double Tx() const {return P_.empty()?0.0:P_.at<double>(0,3);}
00098 
00099         cv::Mat K_raw() const {return K_;} //intrinsic camera matrix (before rectification)
00100         cv::Mat D_raw() const {return D_;} //intrinsic distorsion matrix (before rectification)
00101         cv::Mat K() const {return !P_.empty()?P_.colRange(0,3):K_;} // if P exists, return rectified version
00102         cv::Mat D() const {return P_.empty()&&!D_.empty()?D_:cv::Mat::zeros(1,5,CV_64FC1);} // if P exists, return rectified version
00103         cv::Mat R() const {return R_;} //rectification matrix
00104         cv::Mat P() const {return P_;} //projection matrix
00105 
00106         void setLocalTransform(const Transform & transform) {localTransform_ = transform;}
00107         const Transform & localTransform() const {return localTransform_;}
00108 
00109         void setImageSize(const cv::Size & size) {imageSize_ = size;}
00110         const cv::Size & imageSize() const {return imageSize_;}
00111         int imageWidth() const {return imageSize_.width;}
00112         int imageHeight() const {return imageSize_.height;}
00113 
00114         bool load(const std::string & directory, const std::string & cameraName);
00115         bool save(const std::string & directory) const;
00116 
00117         CameraModel scaled(double scale) const;
00118 
00119         double horizontalFOV() const; // in degrees
00120         double verticalFOV() const;   // in degrees
00121 
00122         // For depth images, your should use cv::INTER_NEAREST
00123         cv::Mat rectifyImage(const cv::Mat & raw, int interpolation = cv::INTER_LINEAR) const;
00124         cv::Mat rectifyDepth(const cv::Mat & raw) const;
00125 
00126 private:
00127         std::string name_;
00128         cv::Size imageSize_;
00129         cv::Mat K_;
00130         cv::Mat D_;
00131         cv::Mat R_;
00132         cv::Mat P_;
00133         cv::Mat mapX_;
00134         cv::Mat mapY_;
00135         Transform localTransform_;
00136 };
00137 
00138 } /* namespace rtabmap */
00139 #endif /* CAMERAMODEL_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:15