CameraModel.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef CAMERAMODEL_H_
29 #define CAMERAMODEL_H_
30 
31 #include <opencv2/opencv.hpp>
32 
33 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
34 #include "rtabmap/core/Transform.h"
35 
36 namespace rtabmap {
37 
39 {
40 public:
45  static Transform opticalRotation() {return Transform(0,0,1,0, -1,0,0,0, 0,-1,0,0);}
46 
47 public:
48  CameraModel();
49  // K is the camera intrinsic 3x3 CV_64FC1
50  // D is the distortion coefficients 1x5 CV_64FC1
51  // R is the rectification matrix 3x3 CV_64FC1 (computed from stereo or Identity)
52  // P is the projection matrix 3x4 CV_64FC1 (computed from stereo or equal to [K [0 0 1]'])
54  const std::string & name,
55  const cv::Size & imageSize,
56  const cv::Mat & K,
57  const cv::Mat & D,
58  const cv::Mat & R,
59  const cv::Mat & P,
60  const Transform & localTransform = opticalRotation());
61 
62  // minimal
64  double fx,
65  double fy,
66  double cx,
67  double cy,
68  const Transform & localTransform = opticalRotation(),
69  double Tx = 0.0f,
70  const cv::Size & imageSize = cv::Size(0,0));
71  // minimal to be saved
73  const std::string & name,
74  double fx,
75  double fy,
76  double cx,
77  double cy,
78  const Transform & localTransform = opticalRotation(),
79  double Tx = 0.0f,
80  const cv::Size & imageSize = cv::Size(0,0));
81 
82  virtual ~CameraModel() {}
83 
84  void initRectificationMap();
85  bool isRectificationMapInitialized() const {return !mapX_.empty() && !mapY_.empty();}
86 
87  bool isValidForProjection() const {return fx()>0.0 && fy()>0.0 && cx()>0.0 && cy()>0.0;}
88  bool isValidForReprojection() const {return fx()>0.0 && fy()>0.0 && cx()>0.0 && cy()>0.0 && imageWidth()>0 && imageHeight()>0;}
90  {
91  return imageSize_.width>0 &&
92  imageSize_.height>0 &&
93  !K_.empty() &&
94  !D_.empty() &&
95  !R_.empty() &&
96  !P_.empty();
97  }
98 
99  void setName(const std::string & name) {name_=name;}
100  const std::string & name() const {return name_;}
101 
102  double fx() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(0,0):P_.at<double>(0,0);}
103  double fy() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(1,1):P_.at<double>(1,1);}
104  double cx() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(0,2):P_.at<double>(0,2);}
105  double cy() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(1,2):P_.at<double>(1,2);}
106  double Tx() const {return P_.empty()?0.0:P_.at<double>(0,3);}
107 
108  cv::Mat K_raw() const {return K_;} //intrinsic camera matrix (before rectification)
109  cv::Mat D_raw() const {return D_;} //intrinsic distorsion matrix (before rectification)
110  cv::Mat K() const {return !P_.empty()?P_.colRange(0,3):K_;} // if P exists, return rectified version
111  cv::Mat D() const {return P_.empty()&&!D_.empty()?D_:cv::Mat::zeros(1,5,CV_64FC1);} // if P exists, return rectified version
112  cv::Mat R() const {return R_;} //rectification matrix
113  cv::Mat P() const {return P_;} //projection matrix
114 
115  void setLocalTransform(const Transform & transform) {localTransform_ = transform;}
116  const Transform & localTransform() const {return localTransform_;}
117 
118  void setImageSize(const cv::Size & size);
119  const cv::Size & imageSize() const {return imageSize_;}
120  int imageWidth() const {return imageSize_.width;}
121  int imageHeight() const {return imageSize_.height;}
122 
123  double fovX() const; // in radians
124  double fovY() const; // in radians
125  double horizontalFOV() const; // in degrees
126  double verticalFOV() const; // in degrees
127 
128  bool load(const std::string & filePath);
129  bool load(const std::string & directory, const std::string & cameraName);
130  bool save(const std::string & directory) const;
131  std::vector<unsigned char> serialize() const;
132  unsigned int deserialize(const std::vector<unsigned char>& data);
133  unsigned int deserialize(const unsigned char * data, unsigned int dataSize);
134 
135  CameraModel scaled(double scale) const;
136  CameraModel roi(const cv::Rect & roi) const;
137 
138  // For depth images, your should use cv::INTER_NEAREST
139  cv::Mat rectifyImage(const cv::Mat & raw, int interpolation = cv::INTER_LINEAR) const;
140  cv::Mat rectifyDepth(const cv::Mat & raw) const;
141 
142  // Project 2D pixel to 3D (in /camera_link frame)
143  void project(float u, float v, float depth, float & x, float & y, float & z) const;
144  // Reproject 3D point (in /camera_link frame) to pixel
145  void reproject(float x, float y, float z, float & u, float & v) const;
146  void reproject(float x, float y, float z, int & u, int & v) const;
147  bool inFrame(int u, int v) const;
148 
149 private:
150  std::string name_;
151  cv::Size imageSize_;
152  cv::Mat K_;
153  cv::Mat D_;
154  cv::Mat R_;
155  cv::Mat P_;
156  cv::Mat mapX_;
157  cv::Mat mapY_;
159 };
160 
161 RTABMAP_EXP std::ostream& operator<<(std::ostream& os, const CameraModel& model);
162 
163 } /* namespace rtabmap */
164 #endif /* CAMERAMODEL_H_ */
void setLocalTransform(const Transform &transform)
Definition: CameraModel.h:115
int imageWidth() const
Definition: CameraModel.h:120
cv::Mat K_raw() const
Definition: CameraModel.h:108
bool isRectificationMapInitialized() const
Definition: CameraModel.h:85
const cv::Size & imageSize() const
Definition: CameraModel.h:119
void serialize(const Eigen::Matrix< S, T, U > &mat, std::ostream &strm)
const std::string & name() const
Definition: CameraModel.h:100
f
Transform localTransform_
Definition: CameraModel.h:158
GLM_FUNC_DECL detail::tmat4x4< T, P > scale(detail::tmat4x4< T, P > const &m, detail::tvec3< T, P > const &v)
static Transform opticalRotation()
Definition: CameraModel.h:45
cv::Mat D() const
Definition: CameraModel.h:111
cv::Mat R() const
Definition: CameraModel.h:112
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
GLM_FUNC_DECL detail::tvec3< T, P > project(detail::tvec3< T, P > const &obj, detail::tmat4x4< T, P > const &model, detail::tmat4x4< T, P > const &proj, detail::tvec4< U, P > const &viewport)
double cx() const
Definition: CameraModel.h:104
double fy() const
Definition: CameraModel.h:103
bool isValidForRectification() const
Definition: CameraModel.h:89
virtual ~CameraModel()
Definition: CameraModel.h:82
bool isValidForReprojection() const
Definition: CameraModel.h:88
cv::Mat P() const
Definition: CameraModel.h:113
double cy() const
Definition: CameraModel.h:105
bool isValidForProjection() const
Definition: CameraModel.h:87
double fx() const
Definition: CameraModel.h:102
double Tx() const
Definition: CameraModel.h:106
RTABMAP_EXP std::ostream & operator<<(std::ostream &os, const CameraModel &model)
cv::Mat K() const
Definition: CameraModel.h:110
cv::Mat D_raw() const
Definition: CameraModel.h:109
void setName(const std::string &name)
Definition: CameraModel.h:99
int imageHeight() const
Definition: CameraModel.h:121
void deserialize(std::istream &strm, Eigen::Matrix< S, T, U > *mat)
const Transform & localTransform() const
Definition: CameraModel.h:116


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:58