Main MRPT website > C++ reference
MRPT logo
TCamera.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2015, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 #ifndef TCamera_H
10 #define TCamera_H
11 
17 #include <mrpt/poses/CPose3DQuat.h>
18 
19 namespace mrpt
20 {
21  namespace utils
22  {
24 
25  /** Structure to hold the parameters of a pinhole camera model.
26  * The parameters obtained for one camera resolution can be used for any other resolution by means of the method TCamera::scaleToResolution()
27  *
28  * \sa mrpt::vision::CCamModel, the application <a href="http://www.mrpt.org/Application:camera-calib-gui" >camera-calib-gui</a> for calibrating a camera
29  * \ingroup mrpt_base_grp
30  */
31  class BASE_IMPEXP TCamera : public mrpt::utils::CSerializable
32  {
34 
35  public:
36  TCamera() : ncols(640), nrows(480), focalLengthMeters(0)
37  {
38  intrinsicParams.set_unsafe(0,0,507.808);
39  intrinsicParams.set_unsafe(1,1,507.808);
40  intrinsicParams.set_unsafe(0,2,356.2368);
41  intrinsicParams.set_unsafe(1,2,252.9216);
42  intrinsicParams.set_unsafe(2,2,1);
43  for (size_t i=0;i<dist.SizeAtCompileTime ;i++)
44  dist[i] = 0;
45  }
46 
47  /** @name Camera parameters
48  @{ */
49 
50  uint32_t ncols,nrows; //!< Camera resolution
51  mrpt::math::CMatrixDouble33 intrinsicParams; //!< Matrix of intrinsic parameters (containing the focal length and principal point coordinates)
52  mrpt::math::CArrayDouble<5> dist; //!< [k1 k2 t1 t2 k3] -> k_i: parameters of radial distortion, t_i: parameters of tangential distortion (default=0)
53  double focalLengthMeters; //!< The focal length of the camera, in meters (can be used among 'intrinsicParams' to determine the pixel size).
54 
55  /** @} */
56 
57  /** Rescale all the parameters for a new camera resolution (it raises an exception if the aspect ratio is modified, which is not permitted).
58  */
59  void scaleToResolution(unsigned int new_ncols, unsigned int new_nrows);
60 
61  /** Save as a config block:
62  * \code
63  * [SECTION]
64  * resolution = [NCOLS NROWS]
65  * cx = CX
66  * cy = CY
67  * fx = FX
68  * fy = FY
69  * dist = [K1 K2 T1 T2 K3]
70  * focal_length = FOCAL_LENGTH
71  * \endcode
72  */
73  void saveToConfigFile( const std::string &section, mrpt::utils::CConfigFileBase &cfg ) const;
74 
75  /** Load all the params from a config source, in the format used in saveToConfigFile(), that is:
76  *
77  * \code
78  * [SECTION]
79  * resolution = [NCOLS NROWS]
80  * cx = CX
81  * cy = CY
82  * fx = FX
83  * fy = FY
84  * dist = [K1 K2 T1 T2 K3]
85  * focal_length = FOCAL_LENGTH [optional field]
86  * \endcode
87  * \exception std::exception on missing fields
88  */
89  void loadFromConfigFile(const std::string &section, const mrpt::utils::CConfigFileBase &cfg );
90 
91  /** Dumps all the parameters as a multi-line string, with the same format than \a saveToConfigFile. \sa saveToConfigFile */
92  std::string dumpAsText() const;
93 
94 
95  /** Set the matrix of intrinsic params of the camera from the individual values of focal length and principal point coordinates (in pixels)
96  */
97  inline void setIntrinsicParamsFromValues ( double fx, double fy, double cx, double cy )
98  {
99  intrinsicParams.set_unsafe( 0, 0, fx );
100  intrinsicParams.set_unsafe( 1, 1, fy );
101  intrinsicParams.set_unsafe( 0, 2, cx );
102  intrinsicParams.set_unsafe( 1, 2, cy );
103  }
104 
105  /** Get the vector of distortion params of the camera */
106  inline void getDistortionParamsVector ( mrpt::math::CMatrixDouble15 &distParVector ) const
107  {
108  for (size_t i=0;i<5;i++)
109  distParVector.set_unsafe(0,i, dist[i]);
110  }
111 
112  /** Get a vector with the distortion params of the camera */
113  inline std::vector<double> getDistortionParamsAsVector () const {
114  std::vector<double> v(5);
115  for (size_t i=0;i<5;i++)
116  v[i] = dist[i];
117  return v;
118  }
119 
120  /** Set the whole vector of distortion params of the camera */
122  {
123  for (size_t i=0;i<5;i++)
124  dist[i] = distParVector.get_unsafe(0,i);
125  }
126 
127  /** Set the whole vector of distortion params of the camera from a 4 or 5-vector */
128  template <class VECTORLIKE>
129  void setDistortionParamsVector( const VECTORLIKE &distParVector )
130  {
131  size_t N = static_cast<size_t>(distParVector.size());
132  ASSERT_(N==4 || N==5)
133  dist[4] = 0; // Default value
134  for (size_t i=0;i<N;i++) dist[i] = distParVector[i];
135  }
136 
137  /** Set the vector of distortion params of the camera from the individual values of the distortion coefficients
138  */
139  inline void setDistortionParamsFromValues( double k1, double k2, double p1, double p2, double k3 = 0 )
140  {
141  dist[0] = k1;
142  dist[1] = k2;
143  dist[2] = p1;
144  dist[3] = p2;
145  dist[4] = k3;
146  }
147 
148  /** Get the value of the principal point x-coordinate (in pixels). */
149  inline double cx() const { return intrinsicParams(0,2); }
150  /** Get the value of the principal point y-coordinate (in pixels). */
151  inline double cy() const { return intrinsicParams(1,2); }
152  /** Get the value of the focal length x-value (in pixels). */
153  inline double fx() const { return intrinsicParams(0,0); }
154  /** Get the value of the focal length y-value (in pixels). */
155  inline double fy() const { return intrinsicParams(1,1); }
156 
157  /** Set the value of the principal point x-coordinate (in pixels). */
158  inline void cx(double val) { intrinsicParams(0,2)=val; }
159  /** Set the value of the principal point y-coordinate (in pixels). */
160  inline void cy(double val) { intrinsicParams(1,2)=val; }
161  /** Set the value of the focal length x-value (in pixels). */
162  inline void fx(double val) { intrinsicParams(0,0)=val; }
163  /** Set the value of the focal length y-value (in pixels). */
164  inline void fy(double val) { intrinsicParams(1,1)=val; }
165 
166  /** Get the value of the k1 distortion parameter. */
167  inline double k1() const { return dist[0]; }
168  /** Get the value of the k2 distortion parameter. */
169  inline double k2() const { return dist[1]; }
170  /** Get the value of the p1 distortion parameter. */
171  inline double p1() const { return dist[2]; }
172  /** Get the value of the p2 distortion parameter. */
173  inline double p2() const { return dist[3]; }
174  /** Get the value of the k3 distortion parameter. */
175  inline double k3() const { return dist[4]; }
176 
177  /** Get the value of the k1 distortion parameter. */
178  inline void k1(double val) { dist[0]=val; }
179  /** Get the value of the k2 distortion parameter. */
180  inline void k2(double val) { dist[1]=val; }
181  /** Get the value of the p1 distortion parameter. */
182  inline void p1(double val) { dist[2]=val; }
183  /** Get the value of the p2 distortion parameter. */
184  inline void p2(double val) { dist[3]=val; }
185  /** Get the value of the k3 distortion parameter. */
186  inline void k3(double val) { dist[4]=val; }
187  }; // end class TCamera
189 
190 
191  bool BASE_IMPEXP operator ==(const mrpt::utils::TCamera& a, const mrpt::utils::TCamera& b);
192  bool BASE_IMPEXP operator !=(const mrpt::utils::TCamera& a, const mrpt::utils::TCamera& b);
193 
194  } // End of namespace
195 } // end of namespace
196 #endif
void k1(double val)
Get the value of the k1 distortion parameter.
Definition: TCamera.h:178
std::vector< double > getDistortionParamsAsVector() const
Get a vector with the distortion params of the camera.
Definition: TCamera.h:113
void p1(double val)
Get the value of the p1 distortion parameter.
Definition: TCamera.h:182
double focalLengthMeters
The focal length of the camera, in meters (can be used among 'intrinsicParams' to determine the pixel...
Definition: TCamera.h:53
The virtual base class which provides a unified interface for all persistent objects in MRPT...
Definition: CSerializable.h:35
double p2() const
Get the value of the p2 distortion parameter.
Definition: TCamera.h:173
double k1() const
Get the value of the k1 distortion parameter.
Definition: TCamera.h:167
double k2() const
Get the value of the k2 distortion parameter.
Definition: TCamera.h:169
void setDistortionParamsVector(const VECTORLIKE &distParVector)
Set the whole vector of distortion params of the camera from a 4 or 5-vector.
Definition: TCamera.h:129
This class allows loading and storing values and vectors of different types from a configuration text...
double fy() const
Get the value of the focal length y-value (in pixels).
Definition: TCamera.h:155
A numeric matrix of compile-time fixed size.
void setDistortionParamsVector(const mrpt::math::CMatrixDouble15 &distParVector)
Set the whole vector of distortion params of the camera.
Definition: TCamera.h:121
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE(class_name, base_name)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
void fy(double val)
Set the value of the focal length y-value (in pixels).
Definition: TCamera.h:164
double k3() const
Get the value of the k3 distortion parameter.
Definition: TCamera.h:175
mrpt::math::CMatrixDouble33 intrinsicParams
Matrix of intrinsic parameters (containing the focal length and principal point coordinates) ...
Definition: TCamera.h:51
void p2(double val)
Get the value of the p2 distortion parameter.
Definition: TCamera.h:184
void getDistortionParamsVector(mrpt::math::CMatrixDouble15 &distParVector) const
Get the vector of distortion params of the camera.
Definition: TCamera.h:106
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
void k3(double val)
Get the value of the k3 distortion parameter.
Definition: TCamera.h:186
mrpt::math::CArrayDouble< 5 > dist
[k1 k2 t1 t2 k3] -> k_i: parameters of radial distortion, t_i: parameters of tangential distortion (d...
Definition: TCamera.h:52
void k2(double val)
Get the value of the k2 distortion parameter.
Definition: TCamera.h:180
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE(class_name, base_name)
uint32_t nrows
Camera resolution.
Definition: TCamera.h:50
#define ASSERT_(f)
void cx(double val)
Set the value of the principal point x-coordinate (in pixels).
Definition: TCamera.h:158
void fx(double val)
Set the value of the focal length x-value (in pixels).
Definition: TCamera.h:162
double fx() const
Get the value of the focal length x-value (in pixels).
Definition: TCamera.h:153
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:139
double p1() const
Get the value of the p1 distortion parameter.
Definition: TCamera.h:171
void cy(double val)
Set the value of the principal point y-coordinate (in pixels).
Definition: TCamera.h:160
double cx() const
Get the value of the principal point x-coordinate (in pixels).
Definition: TCamera.h:149
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:97
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:31
double cy() const
Get the value of the principal point y-coordinate (in pixels).
Definition: TCamera.h:151



Page generated by Doxygen 1.8.9.1 for MRPT 1.3.0 SVN: at Sun Sep 13 03:55:12 UTC 2015