00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef CAMERAMODEL_H_
00029 #define CAMERAMODEL_H_
00030
00031 #include <opencv2/opencv.hpp>
00032
00033 #include "rtabmap/core/RtabmapExp.h"
00034 #include "rtabmap/core/Transform.h"
00035
00036 namespace rtabmap {
00037
00038 class RTABMAP_EXP CameraModel
00039 {
00040 public:
00041 CameraModel();
00042
00043
00044
00045
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
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
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 bool isRectificationMapInitialized() {return !mapX_.empty() && !mapY_.empty();}
00079
00080 bool isValidForProjection() const {return fx()>0.0 && fy()>0.0 && cx()>0.0 && cy()>0.0;}
00081 bool isValidForReprojection() const {return fx()>0.0 && fy()>0.0 && cx()>0.0 && cy()>0.0 && imageWidth()>0 && imageHeight()>0;}
00082 bool isValidForRectification() const
00083 {
00084 return imageSize_.width>0 &&
00085 imageSize_.height>0 &&
00086 !K_.empty() &&
00087 !D_.empty() &&
00088 !R_.empty() &&
00089 !P_.empty();
00090 }
00091
00092 void setName(const std::string & name) {name_=name;}
00093 const std::string & name() const {return name_;}
00094
00095 double fx() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(0,0):P_.at<double>(0,0);}
00096 double fy() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(1,1):P_.at<double>(1,1);}
00097 double cx() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(0,2):P_.at<double>(0,2);}
00098 double cy() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(1,2):P_.at<double>(1,2);}
00099 double Tx() const {return P_.empty()?0.0:P_.at<double>(0,3);}
00100
00101 cv::Mat K_raw() const {return K_;}
00102 cv::Mat D_raw() const {return D_;}
00103 cv::Mat K() const {return !P_.empty()?P_.colRange(0,3):K_;}
00104 cv::Mat D() const {return P_.empty()&&!D_.empty()?D_:cv::Mat::zeros(1,5,CV_64FC1);}
00105 cv::Mat R() const {return R_;}
00106 cv::Mat P() const {return P_;}
00107
00108 void setLocalTransform(const Transform & transform) {localTransform_ = transform;}
00109 const Transform & localTransform() const {return localTransform_;}
00110
00111 void setImageSize(const cv::Size & size);
00112 const cv::Size & imageSize() const {return imageSize_;}
00113 int imageWidth() const {return imageSize_.width;}
00114 int imageHeight() const {return imageSize_.height;}
00115
00116 bool load(const std::string & directory, const std::string & cameraName);
00117 bool save(const std::string & directory) const;
00118
00119 CameraModel scaled(double scale) const;
00120 CameraModel roi(const cv::Rect & roi) const;
00121
00122 double horizontalFOV() const;
00123 double verticalFOV() const;
00124
00125
00126 cv::Mat rectifyImage(const cv::Mat & raw, int interpolation = cv::INTER_LINEAR) const;
00127 cv::Mat rectifyDepth(const cv::Mat & raw) const;
00128
00129
00130 void project(float u, float v, float depth, float & x, float & y, float & z) const;
00131
00132 void reproject(float x, float y, float z, float & u, float & v) const;
00133 void reproject(float x, float y, float z, int & u, int & v) const;
00134 bool inFrame(int u, int v) const;
00135
00136 private:
00137 std::string name_;
00138 cv::Size imageSize_;
00139 cv::Mat K_;
00140 cv::Mat D_;
00141 cv::Mat R_;
00142 cv::Mat P_;
00143 cv::Mat mapX_;
00144 cv::Mat mapY_;
00145 Transform localTransform_;
00146 };
00147
00148 }
00149 #endif