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:
41  CameraModel();
42  // K is the camera intrinsic 3x3 CV_64FC1
43  // D is the distortion coefficients 1x5 CV_64FC1
44  // R is the rectification matrix 3x3 CV_64FC1 (computed from stereo or Identity)
45  // P is the projection matrix 3x4 CV_64FC1 (computed from stereo or equal to [K [0 0 1]'])
47  const std::string & name,
48  const cv::Size & imageSize,
49  const cv::Mat & K,
50  const cv::Mat & D,
51  const cv::Mat & R,
52  const cv::Mat & P,
53  const Transform & localTransform = Transform::getIdentity());
54 
55  // minimal
57  double fx,
58  double fy,
59  double cx,
60  double cy,
61  const Transform & localTransform = Transform::getIdentity(),
62  double Tx = 0.0f,
63  const cv::Size & imageSize = cv::Size(0,0));
64  // minimal to be saved
66  const std::string & name,
67  double fx,
68  double fy,
69  double cx,
70  double cy,
71  const Transform & localTransform = Transform::getIdentity(),
72  double Tx = 0.0f,
73  const cv::Size & imageSize = cv::Size(0,0));
74 
75  virtual ~CameraModel() {}
76 
77  void initRectificationMap();
78  bool isRectificationMapInitialized() {return !mapX_.empty() && !mapY_.empty();}
79 
80  bool isValidForProjection() const {return fx()>0.0 && fy()>0.0 && cx()>0.0 && cy()>0.0;}
81  bool isValidForReprojection() const {return fx()>0.0 && fy()>0.0 && cx()>0.0 && cy()>0.0 && imageWidth()>0 && imageHeight()>0;}
83  {
84  return imageSize_.width>0 &&
85  imageSize_.height>0 &&
86  !K_.empty() &&
87  !D_.empty() &&
88  !R_.empty() &&
89  !P_.empty();
90  }
91 
92  void setName(const std::string & name) {name_=name;}
93  const std::string & name() const {return name_;}
94 
95  double fx() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(0,0):P_.at<double>(0,0);}
96  double fy() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(1,1):P_.at<double>(1,1);}
97  double cx() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(0,2):P_.at<double>(0,2);}
98  double cy() const {return P_.empty()?K_.empty()?0.0:K_.at<double>(1,2):P_.at<double>(1,2);}
99  double Tx() const {return P_.empty()?0.0:P_.at<double>(0,3);}
100 
101  cv::Mat K_raw() const {return K_;} //intrinsic camera matrix (before rectification)
102  cv::Mat D_raw() const {return D_;} //intrinsic distorsion matrix (before rectification)
103  cv::Mat K() const {return !P_.empty()?P_.colRange(0,3):K_;} // if P exists, return rectified version
104  cv::Mat D() const {return P_.empty()&&!D_.empty()?D_:cv::Mat::zeros(1,5,CV_64FC1);} // if P exists, return rectified version
105  cv::Mat R() const {return R_;} //rectification matrix
106  cv::Mat P() const {return P_;} //projection matrix
107 
108  void setLocalTransform(const Transform & transform) {localTransform_ = transform;}
109  const Transform & localTransform() const {return localTransform_;}
110 
111  void setImageSize(const cv::Size & size);
112  const cv::Size & imageSize() const {return imageSize_;}
113  int imageWidth() const {return imageSize_.width;}
114  int imageHeight() const {return imageSize_.height;}
115 
116  bool load(const std::string & directory, const std::string & cameraName);
117  bool save(const std::string & directory) const;
118 
119  CameraModel scaled(double scale) const;
120  CameraModel roi(const cv::Rect & roi) const;
121 
122  double horizontalFOV() const; // in degrees
123  double verticalFOV() const; // in degrees
124 
125  // For depth images, your should use cv::INTER_NEAREST
126  cv::Mat rectifyImage(const cv::Mat & raw, int interpolation = cv::INTER_LINEAR) const;
127  cv::Mat rectifyDepth(const cv::Mat & raw) const;
128 
129  // Project 2D pixel to 3D (in /camera_link frame)
130  void project(float u, float v, float depth, float & x, float & y, float & z) const;
131  // Reproject 3D point (in /camera_link frame) to pixel
132  void reproject(float x, float y, float z, float & u, float & v) const;
133  void reproject(float x, float y, float z, int & u, int & v) const;
134  bool inFrame(int u, int v) const;
135 
136 private:
137  std::string name_;
138  cv::Size imageSize_;
139  cv::Mat K_;
140  cv::Mat D_;
141  cv::Mat R_;
142  cv::Mat P_;
143  cv::Mat mapX_;
144  cv::Mat mapY_;
146 };
147 
148 } /* namespace rtabmap */
149 #endif /* CAMERAMODEL_H_ */
void setLocalTransform(const Transform &transform)
Definition: CameraModel.h:108
int imageWidth() const
Definition: CameraModel.h:113
cv::Mat K_raw() const
Definition: CameraModel.h:101
const cv::Size & imageSize() const
Definition: CameraModel.h:112
const std::string & name() const
Definition: CameraModel.h:93
f
Transform localTransform_
Definition: CameraModel.h:145
static Transform getIdentity()
Definition: Transform.cpp:364
GLM_FUNC_DECL detail::tmat4x4< T, P > scale(detail::tmat4x4< T, P > const &m, detail::tvec3< T, P > const &v)
cv::Mat D() const
Definition: CameraModel.h:104
cv::Mat R() const
Definition: CameraModel.h:105
bool isRectificationMapInitialized()
Definition: CameraModel.h:78
#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:97
double fy() const
Definition: CameraModel.h:96
bool isValidForRectification() const
Definition: CameraModel.h:82
virtual ~CameraModel()
Definition: CameraModel.h:75
bool isValidForReprojection() const
Definition: CameraModel.h:81
cv::Mat P() const
Definition: CameraModel.h:106
double cy() const
Definition: CameraModel.h:98
bool isValidForProjection() const
Definition: CameraModel.h:80
double fx() const
Definition: CameraModel.h:95
double Tx() const
Definition: CameraModel.h:99
cv::Mat K() const
Definition: CameraModel.h:103
cv::Mat D_raw() const
Definition: CameraModel.h:102
void setName(const std::string &name)
Definition: CameraModel.h:92
int imageHeight() const
Definition: CameraModel.h:114
const Transform & localTransform() const
Definition: CameraModel.h:109


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:30