gtsam 4.1.1
gtsam
ProjectionFactorRollingShutter.h
Go to the documentation of this file.
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
18#pragma once
19
24
25#include <boost/optional.hpp>
26
27namespace gtsam {
28
44 : public NoiseModelFactor3<Pose3, Pose3, Point3> {
45 protected:
46 // Keep a copy of measurement and calibration for I/O
48 double alpha_;
50 boost::shared_ptr<Cal3_S2> K_;
51 boost::optional<Pose3>
53
54 // verbosity handling for Cheirality Exceptions
59
60 public:
63
66
68 typedef boost::shared_ptr<This> shared_ptr;
69
72 : measured_(0, 0),
73 alpha_(0),
74 throwCheirality_(false),
75 verboseCheirality_(false) {}
76
91 const Point2& measured, double alpha, const SharedNoiseModel& model,
92 Key poseKey_a, Key poseKey_b, Key pointKey,
93 const boost::shared_ptr<Cal3_S2>& K,
94 boost::optional<Pose3> body_P_sensor = boost::none)
95 : Base(model, poseKey_a, poseKey_b, pointKey),
98 K_(K),
99 body_P_sensor_(body_P_sensor),
100 throwCheirality_(false),
101 verboseCheirality_(false) {}
102
121 const Point2& measured, double alpha, const SharedNoiseModel& model,
122 Key poseKey_a, Key poseKey_b, Key pointKey,
123 const boost::shared_ptr<Cal3_S2>& K, bool throwCheirality,
125 boost::optional<Pose3> body_P_sensor = boost::none)
126 : Base(model, poseKey_a, poseKey_b, pointKey),
128 alpha_(alpha),
129 K_(K),
130 body_P_sensor_(body_P_sensor),
133
136
138 gtsam::NonlinearFactor::shared_ptr clone() const override {
139 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
140 gtsam::NonlinearFactor::shared_ptr(new This(*this)));
141 }
142
148 void print(
149 const std::string& s = "",
150 const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
151 std::cout << s << "ProjectionFactorRollingShutter, z = ";
153 std::cout << " rolling shutter interpolation param = " << alpha_;
154 if (this->body_P_sensor_)
155 this->body_P_sensor_->print(" sensor pose in body frame: ");
156 Base::print("", keyFormatter);
157 }
158
160 bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
161 const This* e = dynamic_cast<const This*>(&p);
162 return e && Base::equals(p, tol) && (alpha_ == e->alpha()) &&
163 traits<Point2>::Equals(this->measured_, e->measured_, tol) &&
164 this->K_->equals(*e->K_, tol) &&
165 (this->throwCheirality_ == e->throwCheirality_) &&
166 (this->verboseCheirality_ == e->verboseCheirality_) &&
167 ((!body_P_sensor_ && !e->body_P_sensor_) ||
168 (body_P_sensor_ && e->body_P_sensor_ &&
169 body_P_sensor_->equals(*e->body_P_sensor_)));
170 }
171
173 Vector evaluateError(
174 const Pose3& pose_a, const Pose3& pose_b, const Point3& point,
175 boost::optional<Matrix&> H1 = boost::none,
176 boost::optional<Matrix&> H2 = boost::none,
177 boost::optional<Matrix&> H3 = boost::none) const override;
178
180 const Point2& measured() const { return measured_; }
181
183 inline const boost::shared_ptr<Cal3_S2> calibration() const { return K_; }
184
186 inline double alpha() const { return alpha_; }
187
189 inline bool verboseCheirality() const { return verboseCheirality_; }
190
192 inline bool throwCheirality() const { return throwCheirality_; }
193
194 private:
197 template <class ARCHIVE>
198 void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
199 ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
200 ar& BOOST_SERIALIZATION_NVP(measured_);
201 ar& BOOST_SERIALIZATION_NVP(alpha_);
202 ar& BOOST_SERIALIZATION_NVP(K_);
203 ar& BOOST_SERIALIZATION_NVP(body_P_sensor_);
204 ar& BOOST_SERIALIZATION_NVP(throwCheirality_);
205 ar& BOOST_SERIALIZATION_NVP(verboseCheirality_);
206 }
207
208 public:
209 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
210};
211
213template <>
215 : public Testable<ProjectionFactorRollingShutter> {};
216
217} // namespace gtsam
The most common 5DOF 3D->2D calibration.
Calibrated camera for which only pose is unknown.
Base class for all pinhole cameras.
Non-linear factor base classes.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Vector2 Point2
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point2 to Vector2...
Definition: Point2.h:27
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition: Point3.h:35
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:736
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:69
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:151
Definition: Pose3.h:37
This is the base class for all factor types.
Definition: Factor.h:56
Nonlinear factor base class.
Definition: NonlinearFactor.h:43
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Check if two factors are equal.
Definition: NonlinearFactor.cpp:71
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Print.
Definition: NonlinearFactor.cpp:63
A convenient base class for creating your own NoiseModelFactor with 3 variables.
Definition: NonlinearFactor.h:444
Definition: ProjectionFactorRollingShutter.h:44
boost::optional< Pose3 > body_P_sensor_
The pose of the sensor in the body frame.
Definition: ProjectionFactorRollingShutter.h:52
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: ProjectionFactorRollingShutter.h:148
const boost::shared_ptr< Cal3_S2 > calibration() const
return the calibration object
Definition: ProjectionFactorRollingShutter.h:183
bool throwCheirality() const
return flag for throwing cheirality exceptions
Definition: ProjectionFactorRollingShutter.h:192
const Point2 & measured() const
return the measurement
Definition: ProjectionFactorRollingShutter.h:180
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: ProjectionFactorRollingShutter.h:138
NoiseModelFactor3< Pose3, Pose3, Point3 > Base
shorthand for base class type
Definition: ProjectionFactorRollingShutter.h:62
ProjectionFactorRollingShutter(const Point2 &measured, double alpha, const SharedNoiseModel &model, Key poseKey_a, Key poseKey_b, Key pointKey, const boost::shared_ptr< Cal3_S2 > &K, boost::optional< Pose3 > body_P_sensor=boost::none)
Constructor.
Definition: ProjectionFactorRollingShutter.h:90
ProjectionFactorRollingShutter This
shorthand for this class
Definition: ProjectionFactorRollingShutter.h:65
Vector evaluateError(const Pose3 &pose_a, const Pose3 &pose_b, const Point3 &point, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const override
Evaluate error h(x)-z and optionally derivatives.
Definition: ProjectionFactorRollingShutter.cpp:22
bool verboseCheirality() const
return verbosity
Definition: ProjectionFactorRollingShutter.h:189
boost::shared_ptr< Cal3_S2 > K_
shared pointer to calibration object
Definition: ProjectionFactorRollingShutter.h:50
ProjectionFactorRollingShutter()
Default constructor.
Definition: ProjectionFactorRollingShutter.h:71
double alpha() const
returns the rolling shutter interp param
Definition: ProjectionFactorRollingShutter.h:186
Point2 measured_
2D measurement
Definition: ProjectionFactorRollingShutter.h:47
ProjectionFactorRollingShutter(const Point2 &measured, double alpha, const SharedNoiseModel &model, Key poseKey_a, Key poseKey_b, Key pointKey, const boost::shared_ptr< Cal3_S2 > &K, bool throwCheirality, bool verboseCheirality, boost::optional< Pose3 > body_P_sensor=boost::none)
Constructor with exception-handling flags.
Definition: ProjectionFactorRollingShutter.h:120
double alpha_
interpolation parameter in [0,1] corresponding to the point2 measurement
Definition: ProjectionFactorRollingShutter.h:48
friend class boost::serialization::access
Serialization function.
Definition: ProjectionFactorRollingShutter.h:196
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
Definition: ProjectionFactorRollingShutter.h:55
virtual ~ProjectionFactorRollingShutter()
Virtual destructor.
Definition: ProjectionFactorRollingShutter.h:135
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: ProjectionFactorRollingShutter.h:68
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
Definition: ProjectionFactorRollingShutter.h:57
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: ProjectionFactorRollingShutter.h:160