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 SphericalCamera.h
14 * @brief Calibrated camera with spherical projection
15 * @date Aug 26, 2021
16 * @author Luca Carlone
17 */
18
19#pragma once
20
21#include <gtsam/base/Manifold.h>
22#include <gtsam/base/ThreadsafeException.h>
23#include <gtsam/base/concepts.h>
24#include <gtsam/dllexport.h>
25#include <gtsam/geometry/BearingRange.h>
26#include <gtsam/geometry/Pose3.h>
27#include <gtsam/geometry/Unit3.h>
28
29#if GTSAM_ENABLE_BOOST_SERIALIZATION
30#include <boost/serialization/nvp.hpp>
31#endif
32
33namespace gtsam {
34
35/**
36 * Empty calibration. Only needed to play well with other cameras
37 * (e.g., when templating functions wrt cameras), since other cameras
38 * have constuctors in the form ‘camera(pose,calibration)’
39 * @ingroup geometry
40 * \nosubgrouping
41 */
42class GTSAM_EXPORT EmptyCal {
43 public:
44 inline constexpr static auto dimension = 0;
45 EmptyCal() {}
46 virtual ~EmptyCal() = default;
47 using shared_ptr = std::shared_ptr<EmptyCal>;
48
49 /// return DOF, dimensionality of tangent space
50 inline static size_t Dim() { return 0; }
51 size_t dim() const { return 0; }
52
53 void print(const std::string& s) const {
54 std::cout << "empty calibration: " << s << std::endl;
55 }
56
57 private:
58#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
59 /// Serialization function
60 friend class boost::serialization::access;
61 template <class Archive>
62 void serialize(Archive& ar, const unsigned int /*version*/) {
63 ar& boost::serialization::make_nvp(
64 n: "EmptyCal", v&: boost::serialization::base_object<EmptyCal>(d&: *this));
65 }
66#endif
67};
68
69/**
70 * A spherical camera class that has a Pose3 and measures bearing vectors.
71 * The camera has an ‘Empty’ calibration and the only 6 dof are the pose
72 * @ingroup geometry
73 * \nosubgrouping
74 */
75class GTSAM_EXPORT SphericalCamera {
76 public:
77 inline constexpr static auto dimension = 6;
78
79 using Measurement = Unit3;
80 using MeasurementVector = std::vector<Unit3>;
81 using CalibrationType = EmptyCal;
82
83 private:
84 Pose3 pose_; ///< 3D pose of camera
85
86 protected:
87 EmptyCal::shared_ptr emptyCal_;
88
89 public:
90 /// @name Standard Constructors
91 /// @{
92
93 /// Default constructor
94 SphericalCamera()
95 : pose_(Pose3()), emptyCal_(std::make_shared<EmptyCal>()) {}
96
97 /// Constructor with pose
98 explicit SphericalCamera(const Pose3& pose)
99 : pose_(pose), emptyCal_(std::make_shared<EmptyCal>()) {}
100
101 /// Constructor with empty intrinsics (needed for smart factors)
102 explicit SphericalCamera(const Pose3& pose,
103 const EmptyCal::shared_ptr& cal)
104 : pose_(pose), emptyCal_(cal) {}
105
106 /// @}
107 /// @name Advanced Constructors
108 /// @{
109 explicit SphericalCamera(const Vector& v) : pose_(Pose3::Expmap(xi: v)) {}
110
111 /// Default destructor
112 virtual ~SphericalCamera() = default;
113
114 /// return shared pointer to calibration
115 const EmptyCal::shared_ptr& sharedCalibration() const {
116 return emptyCal_;
117 }
118
119 /// return calibration
120 const EmptyCal& calibration() const { return *emptyCal_; }
121
122 /// @}
123 /// @name Testable
124 /// @{
125
126 /// assert equality up to a tolerance
127 bool equals(const SphericalCamera& camera, double tol = 1e-9) const;
128
129 /// print
130 virtual void print(const std::string& s = "SphericalCamera") const;
131
132 /// @}
133 /// @name Standard Interface
134 /// @{
135
136 /// return pose, constant version
137 const Pose3& pose() const { return pose_; }
138
139 /// get rotation
140 const Rot3& rotation() const { return pose_.rotation(); }
141
142 /// get translation
143 const Point3& translation() const { return pose_.translation(); }
144
145 // /// return pose, with derivative
146 // const Pose3& getPose(OptionalJacobian<6, 6> H) const;
147
148 /// @}
149 /// @name Transformations and measurement functions
150 /// @{
151
152 /// Project a point into the image and check depth
153 std::pair<Unit3, bool> projectSafe(const Point3& pw) const;
154
155 /** Project point into the image
156 * (note: there is no CheiralityException for a spherical camera)
157 * @param point 3D point in world coordinates
158 * @return the intrinsic coordinates of the projected point
159 */
160 Unit3 project2(const Point3& pw, OptionalJacobian<2, 6> Dpose = {},
161 OptionalJacobian<2, 3> Dpoint = {}) const;
162
163 /** Project point into the image
164 * (note: there is no CheiralityException for a spherical camera)
165 * @param point 3D direction in world coordinates
166 * @return the intrinsic coordinates of the projected point
167 */
168 Unit3 project2(const Unit3& pwu, OptionalJacobian<2, 6> Dpose = {},
169 OptionalJacobian<2, 2> Dpoint = {}) const;
170
171 /// backproject a 2-dimensional point to a 3-dimensional point at given depth
172 Point3 backproject(const Unit3& p, const double depth) const;
173
174 /// backproject point at infinity
175 Unit3 backprojectPointAtInfinity(const Unit3& p) const;
176
177 /** Project point into the image
178 * (note: there is no CheiralityException for a spherical camera)
179 * @param point 3D point in world coordinates
180 * @return the intrinsic coordinates of the projected point
181 */
182 Unit3 project(const Point3& point, OptionalJacobian<2, 6> Dpose = {},
183 OptionalJacobian<2, 3> Dpoint = {}) const;
184
185 /** Compute reprojection error for a given 3D point in world coordinates
186 * @param point 3D point in world coordinates
187 * @return the tangent space error between the projection and the measurement
188 */
189 Vector2 reprojectionError(const Point3& point, const Unit3& measured,
190 OptionalJacobian<2, 6> Dpose = {},
191 OptionalJacobian<2, 3> Dpoint = {}) const;
192 /// @}
193
194 /// move a cameras according to d
195 SphericalCamera retract(const Vector6& d) const {
196 return SphericalCamera(pose().retract(v: d));
197 }
198
199 /// return canonical coordinate
200 Vector6 localCoordinates(const SphericalCamera& p) const {
201 return pose().localCoordinates(g: p.pose());
202 }
203
204 /// for Canonical
205 static SphericalCamera Identity() {
206 return SphericalCamera(
207 Pose3::Identity()); // assumes that the default constructor is valid
208 }
209
210 /// for Linear Triangulation
211 Matrix34 cameraProjectionMatrix() const {
212 return Matrix34(pose_.inverse().matrix().block(startRow: 0, startCol: 0, blockRows: 3, blockCols: 4));
213 }
214
215 /// for Nonlinear Triangulation
216 Vector defaultErrorWhenTriangulatingBehindCamera() const {
217 return Eigen::Matrix<double, traits<Point2>::dimension, 1>::Constant(value: 0.0);
218 }
219
220 size_t dim() const { return 6; }
221
222 static size_t Dim() { return 6; }
223
224 private:
225#if GTSAM_ENABLE_BOOST_SERIALIZATION
226 /** Serialization function */
227 friend class boost::serialization::access;
228 template <class Archive>
229 void serialize(Archive& ar, const unsigned int /*version*/) {
230 ar& BOOST_SERIALIZATION_NVP(pose_);
231 }
232#endif
233
234 public:
235 GTSAM_MAKE_ALIGNED_OPERATOR_NEW
236};
237// end of class SphericalCamera
238
239template <>
240struct traits<SphericalCamera> : public internal::Manifold<SphericalCamera> {};
241
242template <>
243struct traits<const SphericalCamera> : public internal::Manifold<SphericalCamera> {};
244
245} // namespace gtsam
246