| 1 | /* ---------------------------------------------------------------------------- |
| 2 | |
| 3 | * GTSAM Copyright 2010, Georgia Tech Research Corporation, |
| 4 | * Atlanta, Georgia 30332-0415 |
| 5 | * All Rights Reserved |
| 6 | * Authors: Frank Dellaert, et al. (see THANKS for the full author list) |
| 7 | |
| 8 | * See LICENSE for the license information |
| 9 | |
| 10 | * -------------------------------------------------------------------------- */ |
| 11 | |
| 12 | /** |
| 13 | * @file Cal3DS2.h |
| 14 | * @brief Calibration of a camera with radial distortion, calculations in base |
| 15 | * class Cal3DS2_Base |
| 16 | * @date Feb 28, 2010 |
| 17 | * @author ydjian |
| 18 | * @autho Varun Agrawal |
| 19 | */ |
| 20 | |
| 21 | #pragma once |
| 22 | |
| 23 | #include <gtsam/geometry/Cal3DS2_Base.h> |
| 24 | #include <memory> |
| 25 | |
| 26 | namespace gtsam { |
| 27 | |
| 28 | /** |
| 29 | * @brief Calibration of a camera with radial distortion that also supports |
| 30 | * Lie-group behaviors for optimization. |
| 31 | * \sa Cal3DS2_Base |
| 32 | * @ingroup geometry |
| 33 | * \nosubgrouping |
| 34 | */ |
| 35 | class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base { |
| 36 | using Base = Cal3DS2_Base; |
| 37 | |
| 38 | public: |
| 39 | ///< shared pointer to stereo calibration object |
| 40 | using shared_ptr = std::shared_ptr<Cal3DS2>; |
| 41 | |
| 42 | /// @name Standard Constructors |
| 43 | /// @{ |
| 44 | |
| 45 | /// Default Constructor with only unit focal length |
| 46 | Cal3DS2() = default; |
| 47 | |
| 48 | Cal3DS2(double fx, double fy, double s, double u0, double v0, double k1, |
| 49 | double k2, double p1 = 0.0, double p2 = 0.0, double tol = 1e-5) |
| 50 | : Base(fx, fy, s, u0, v0, k1, k2, p1, p2, tol) {} |
| 51 | |
| 52 | ~Cal3DS2() override {} |
| 53 | |
| 54 | /// @} |
| 55 | /// @name Advanced Constructors |
| 56 | /// @{ |
| 57 | |
| 58 | Cal3DS2(const Vector9& v) : Base(v) {} |
| 59 | |
| 60 | /// @} |
| 61 | /// @name Testable |
| 62 | /// @{ |
| 63 | |
| 64 | /// Output stream operator |
| 65 | GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, |
| 66 | const Cal3DS2& cal); |
| 67 | |
| 68 | /// print with optional string |
| 69 | void print(const std::string& s = "" ) const override; |
| 70 | |
| 71 | /// assert equality up to a tolerance |
| 72 | bool equals(const Cal3DS2& K, double tol = 10e-9) const; |
| 73 | |
| 74 | /// @} |
| 75 | /// @name Manifold |
| 76 | /// @{ |
| 77 | |
| 78 | /// Given delta vector, update calibration |
| 79 | Cal3DS2 retract(const Vector& d) const; |
| 80 | |
| 81 | /// Given a different calibration, calculate update to obtain it |
| 82 | Vector localCoordinates(const Cal3DS2& T2) const; |
| 83 | |
| 84 | /// @} |
| 85 | /// @name Clone |
| 86 | /// @{ |
| 87 | |
| 88 | /// @return a deep copy of this object |
| 89 | std::shared_ptr<Base> clone() const override { |
| 90 | return std::shared_ptr<Base>(new Cal3DS2(*this)); |
| 91 | } |
| 92 | |
| 93 | /// @} |
| 94 | |
| 95 | private: |
| 96 | /// @name Advanced Interface |
| 97 | /// @{ |
| 98 | |
| 99 | #if GTSAM_ENABLE_BOOST_SERIALIZATION |
| 100 | /** Serialization function */ |
| 101 | friend class boost::serialization::access; |
| 102 | template <class Archive> |
| 103 | void serialize(Archive& ar, const unsigned int /*version*/) { |
| 104 | ar& boost::serialization::make_nvp( |
| 105 | n: "Cal3DS2" , v&: boost::serialization::base_object<Cal3DS2_Base>(d&: *this)); |
| 106 | } |
| 107 | #endif |
| 108 | |
| 109 | /// @} |
| 110 | }; |
| 111 | |
| 112 | template <> |
| 113 | struct traits<Cal3DS2> : public internal::Manifold<Cal3DS2> {}; |
| 114 | |
| 115 | template <> |
| 116 | struct traits<const Cal3DS2> : public internal::Manifold<Cal3DS2> {}; |
| 117 | } |
| 118 | |