MRPT  1.9.9
TCamera.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2019, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
12 #include <mrpt/math/CMatrixFixed.h>
14 #include <array>
15 
16 namespace mrpt::img
17 {
18 /** Parameters for the Brown-Conrady camera lens distortion model.
19  * The parameters obtained for one camera resolution can be used for any other
20  * resolution by means of the method TCamera::scaleToResolution()
21  *
22  * \sa The application camera-calib-gui for calibrating a camera
23  * \ingroup mrpt_img_grp
24  */
26 {
28 
29  // This must be added for declaration of MEX-related functions
31 
32  public:
33  /** @name Camera parameters
34  @{ */
35 
36  /** Camera resolution */
37  uint32_t ncols{640}, nrows{480};
38 
39  /** Matrix of intrinsic parameters (containing the focal length and
40  * principal point coordinates):
41  *
42  * [ fx 0 cx ]
43  * A = [ 0 fy cy ]
44  * [ 0 0 1 ]
45  *
46  */
48  /** [k1 k2 t1 t2 k3 k4 k5 k6] -> k_i: parameters of radial distortion, t_i:
49  * parameters of tangential distortion (default=0) */
50  std::array<double, 8> dist{{.0, .0, .0, .0, .0, .0, .0, .0}};
51  /** The focal length of the camera, in meters (can be used among
52  * 'intrinsicParams' to determine the pixel size). */
53  double focalLengthMeters{.0};
54 
55  /** @} */
56 
57  /** Rescale all the parameters for a new camera resolution (it raises an
58  * exception if the aspect ratio is modified, which is not permitted).
59  */
60  void scaleToResolution(unsigned int new_ncols, unsigned int new_nrows);
61 
62  /** Save as a config block:
63  * \code
64  * [SECTION]
65  * resolution = [NCOLS NROWS]
66  * cx = CX
67  * cy = CY
68  * fx = FX
69  * fy = FY
70  * dist = [K1 K2 T1 T2 K3]
71  * focal_length = FOCAL_LENGTH
72  * \endcode
73  */
74  void saveToConfigFile(
75  const std::string& section, mrpt::config::CConfigFileBase& cfg) const;
76 
77  /** Load all the params from a config source, in the format used in
78  * saveToConfigFile(), that is:
79  *
80  * \code
81  * [SECTION]
82  * resolution = [NCOLS NROWS]
83  * cx = CX
84  * cy = CY
85  * fx = FX
86  * fy = FY
87  * dist = [K1 K2 T1 T2 K3]
88  * focal_length = FOCAL_LENGTH [optional field]
89  * \endcode
90  * \exception std::exception on missing fields
91  */
92  void loadFromConfigFile(
93  const std::string& section, const mrpt::config::CConfigFileBase& cfg);
94  /** overload This signature is consistent with the rest of MRPT APIs */
95  inline void loadFromConfigFile(
96  const mrpt::config::CConfigFileBase& cfg, const std::string& section)
97  {
98  loadFromConfigFile(section, cfg);
99  }
100 
101  /** Dumps all the parameters as a multi-line string, with the same format
102  * than \a saveToConfigFile. \sa saveToConfigFile */
103  std::string dumpAsText() const;
104 
105  /** Set the matrix of intrinsic params of the camera from the individual
106  * values of focal length and principal point coordinates (in pixels)
107  */
109  double fx, double fy, double cx, double cy)
110  {
112  intrinsicParams(0, 0) = fx;
113  intrinsicParams(1, 1) = fy;
114  intrinsicParams(0, 2) = cx;
115  intrinsicParams(1, 2) = cy;
116  intrinsicParams(2, 2) = 1.0;
117  }
118 
119  /** Get the vector of distortion params of the camera */
121  mrpt::math::CMatrixDouble15& distParVector) const
122  {
123  for (size_t i = 0; i < distParVector.size(); i++)
124  distParVector(0, i) = dist[i];
125  }
126 
127  /** Get a vector with the distortion params of the camera */
128  inline std::vector<double> getDistortionParamsAsVector() const
129  {
130  std::vector<double> v(8);
131  for (size_t i = 0; i < 8; i++) v[i] = dist[i];
132  return v;
133  }
134 
135  /** Set the whole vector of distortion params of the camera */
137  const mrpt::math::CMatrixDouble15& distParVector)
138  {
139  dist.fill(0);
140  for (size_t i = 0; i < 5; i++) dist[i] = distParVector(0, i);
141  }
142 
143  /** Set the whole vector of distortion params of the camera from a 4, 5, or
144  * 8-vector (see definition of \a dist for parameter order) */
145  template <class VECTORLIKE>
146  void setDistortionParamsVector(const VECTORLIKE& distParVector)
147  {
148  auto N = static_cast<size_t>(distParVector.size());
149  ASSERT_(N == 4 || N == 5 || N == 8);
150  dist.fill(0); // Default values
151  for (size_t i = 0; i < N; i++) dist[i] = distParVector[i];
152  }
153 
154  /** Set the vector of distortion params of the camera from the individual
155  * values of the distortion coefficients
156  */
158  double k1, double k2, double p1, double p2, double k3 = 0)
159  {
160  dist[0] = k1;
161  dist[1] = k2;
162  dist[2] = p1;
163  dist[3] = p2;
164  dist[4] = k3;
165  }
166 
167  /** Get the value of the principal point x-coordinate (in pixels). */
168  inline double cx() const { return intrinsicParams(0, 2); }
169  /** Get the value of the principal point y-coordinate (in pixels). */
170  inline double cy() const { return intrinsicParams(1, 2); }
171  /** Get the value of the focal length x-value (in pixels). */
172  inline double fx() const { return intrinsicParams(0, 0); }
173  /** Get the value of the focal length y-value (in pixels). */
174  inline double fy() const { return intrinsicParams(1, 1); }
175  /** Set the value of the principal point x-coordinate (in pixels). */
176  inline void cx(double val) { intrinsicParams(0, 2) = val; }
177  /** Set the value of the principal point y-coordinate (in pixels). */
178  inline void cy(double val) { intrinsicParams(1, 2) = val; }
179  /** Set the value of the focal length x-value (in pixels). */
180  inline void fx(double val) { intrinsicParams(0, 0) = val; }
181  /** Set the value of the focal length y-value (in pixels). */
182  inline void fy(double val) { intrinsicParams(1, 1) = val; }
183  /** Get the value of the k1 distortion parameter. */
184  inline double k1() const { return dist[0]; }
185  /** Get the value of the k2 distortion parameter. */
186  inline double k2() const { return dist[1]; }
187  /** Get the value of the p1 distortion parameter. */
188  inline double p1() const { return dist[2]; }
189  /** Get the value of the p2 distortion parameter. */
190  inline double p2() const { return dist[3]; }
191  /** Get the value of the k3 distortion parameter. */
192  inline double k3() const { return dist[4]; }
193  /** Get the value of the k4 distortion parameter. */
194  inline double k4() const { return dist[5]; }
195  /** Get the value of the k5 distortion parameter. */
196  inline double k5() const { return dist[6]; }
197  /** Get the value of the k6 distortion parameter. */
198  inline double k6() const { return dist[7]; }
199 
200  /** Set the value of the k1 distortion parameter. */
201  inline void k1(double val) { dist[0] = val; }
202  /** Set the value of the k2 distortion parameter. */
203  inline void k2(double val) { dist[1] = val; }
204  /** Set the value of the p1 distortion parameter. */
205  inline void p1(double val) { dist[2] = val; }
206  /** Set the value of the p2 distortion parameter. */
207  inline void p2(double val) { dist[3] = val; }
208  /** Set the value of the k3 distortion parameter. */
209  inline void k3(double val) { dist[4] = val; }
210  /** Set the value of the k4 distortion parameter. */
211  inline void k4(double val) { dist[5] = val; }
212  /** Set the value of the k5 distortion parameter. */
213  inline void k5(double val) { dist[6] = val; }
214  /** Set the value of the k6 distortion parameter. */
215  inline void k6(double val) { dist[7] = val; }
216 
217 }; // end class TCamera
218 
219 bool operator==(const mrpt::img::TCamera& a, const mrpt::img::TCamera& b);
220 bool operator!=(const mrpt::img::TCamera& a, const mrpt::img::TCamera& b);
221 
222 } // namespace mrpt::img
223 // Add for declaration of mexplus::from template specialization
224 DECLARE_MEXPLUS_FROM(mrpt::img::TCamera) // Not working at the beginning?
double k3() const
Get the value of the k3 distortion parameter.
Definition: TCamera.h:192
uint32_t nrows
Definition: TCamera.h:37
void k2(double val)
Set the value of the k2 distortion parameter.
Definition: TCamera.h:203
void loadFromConfigFile(const mrpt::config::CConfigFileBase &cfg, const std::string &section)
overload This signature is consistent with the rest of MRPT APIs
Definition: TCamera.h:95
constexpr matrix_size_t size() const
Get a 2-vector with [NROWS NCOLS] (as in MATLAB command size(x))
Definition: CMatrixFixed.h:233
void scaleToResolution(unsigned int new_ncols, unsigned int new_nrows)
Rescale all the parameters for a new camera resolution (it raises an exception if the aspect ratio is...
Definition: TCamera.cpp:197
double fx() const
Get the value of the focal length x-value (in pixels).
Definition: TCamera.h:172
double k6() const
Get the value of the k6 distortion parameter.
Definition: TCamera.h:198
void setDistortionParamsFromValues(double k1, double k2, double p1, double p2, double k3=0)
Set the vector of distortion params of the camera from the individual values of the distortion coeffi...
Definition: TCamera.h:157
#define DECLARE_MEXPLUS_FROM(complete_type)
This must be inserted if a custom conversion method for MEX API is implemented in the class...
void p2(double val)
Set the value of the p2 distortion parameter.
Definition: TCamera.h:207
double fy() const
Get the value of the focal length y-value (in pixels).
Definition: TCamera.h:174
void fy(double val)
Set the value of the focal length y-value (in pixels).
Definition: TCamera.h:182
std::string dumpAsText() const
Dumps all the parameters as a multi-line string, with the same format than saveToConfigFile.
Definition: TCamera.cpp:28
void k1(double val)
Set the value of the k1 distortion parameter.
Definition: TCamera.h:201
void loadFromConfigFile(const std::string &section, const mrpt::config::CConfigFileBase &cfg)
Load all the params from a config source, in the format used in saveToConfigFile(), that is:
Definition: TCamera.cpp:159
double k2() const
Get the value of the k2 distortion parameter.
Definition: TCamera.h:186
void k3(double val)
Set the value of the k3 distortion parameter.
Definition: TCamera.h:209
mrpt::math::CMatrixDouble33 intrinsicParams
Matrix of intrinsic parameters (containing the focal length and principal point coordinates): ...
Definition: TCamera.h:47
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
double focalLengthMeters
The focal length of the camera, in meters (can be used among &#39;intrinsicParams&#39; to determine the pixel...
Definition: TCamera.h:53
This class allows loading and storing values and vectors of different types from a configuration text...
double cy() const
Get the value of the principal point y-coordinate (in pixels).
Definition: TCamera.h:170
#define DECLARE_MEX_CONVERSION
This must be inserted if a custom conversion method for MEX API is implemented in the class...
void setDistortionParamsVector(const mrpt::math::CMatrixDouble15 &distParVector)
Set the whole vector of distortion params of the camera.
Definition: TCamera.h:136
void getDistortionParamsVector(mrpt::math::CMatrixDouble15 &distParVector) const
Get the vector of distortion params of the camera.
Definition: TCamera.h:120
int val
Definition: mrpt_jpeglib.h:957
GLubyte GLubyte b
Definition: glext.h:6372
Parameters for the Brown-Conrady camera lens distortion model.
Definition: TCamera.h:25
void cy(double val)
Set the value of the principal point y-coordinate (in pixels).
Definition: TCamera.h:178
GLsizei const GLchar ** string
Definition: glext.h:4116
double p1() const
Get the value of the p1 distortion parameter.
Definition: TCamera.h:188
std::array< double, 8 > dist
[k1 k2 t1 t2 k3 k4 k5 k6] -> k_i: parameters of radial distortion, t_i: parameters of tangential dist...
Definition: TCamera.h:50
void k4(double val)
Set the value of the k4 distortion parameter.
Definition: TCamera.h:211
double k5() const
Get the value of the k5 distortion parameter.
Definition: TCamera.h:196
bool operator==(const mrpt::img::TCamera &a, const mrpt::img::TCamera &b)
Definition: TCamera.cpp:225
double cx() const
Get the value of the principal point x-coordinate (in pixels).
Definition: TCamera.h:168
const GLdouble * v
Definition: glext.h:3684
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
void k6(double val)
Set the value of the k6 distortion parameter.
Definition: TCamera.h:215
void saveToConfigFile(const std::string &section, mrpt::config::CConfigFileBase &cfg) const
Save as a config block:
Definition: TCamera.cpp:137
void setDistortionParamsVector(const VECTORLIKE &distParVector)
Set the whole vector of distortion params of the camera from a 4, 5, or 8-vector (see definition of d...
Definition: TCamera.h:146
void fx(double val)
Set the value of the focal length x-value (in pixels).
Definition: TCamera.h:180
double k4() const
Get the value of the k4 distortion parameter.
Definition: TCamera.h:194
The virtual base class which provides a unified interface for all persistent objects in MRPT...
Definition: CSerializable.h:30
void p1(double val)
Set the value of the p1 distortion parameter.
Definition: TCamera.h:205
void cx(double val)
Set the value of the principal point x-coordinate (in pixels).
Definition: TCamera.h:176
double p2() const
Get the value of the p2 distortion parameter.
Definition: TCamera.h:190
double k1() const
Get the value of the k1 distortion parameter.
Definition: TCamera.h:184
void setIntrinsicParamsFromValues(double fx, double fy, double cx, double cy)
Set the matrix of intrinsic params of the camera from the individual values of focal length and princ...
Definition: TCamera.h:108
bool operator!=(const mrpt::img::TCamera &a, const mrpt::img::TCamera &b)
Definition: TCamera.cpp:232
GLubyte GLubyte GLubyte a
Definition: glext.h:6372
uint32_t ncols
Camera resolution.
Definition: TCamera.h:37
void k5(double val)
Set the value of the k5 distortion parameter.
Definition: TCamera.h:213
std::vector< double > getDistortionParamsAsVector() const
Get a vector with the distortion params of the camera.
Definition: TCamera.h:128



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: dad381fd7 Sun Oct 20 13:36:46 2019 +0200 at dom oct 20 13:40:10 CEST 2019