gtsam 4.2
gtsam
Loading...
Searching...
No Matches
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
17
18#pragma once
19
24#include <gtsam_unstable/dllexport.h>
25
26#include <boost/optional.hpp>
27
28namespace gtsam {
29
43
44class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter
45 : public NoiseModelFactorN<Pose3, Pose3, Point3> {
46 protected:
47 // Keep a copy of measurement and calibration for I/O
49 double alpha_;
51 boost::shared_ptr<Cal3_S2> K_;
52 boost::optional<Pose3>
54
55 // verbosity handling for Cheirality Exceptions
60
61 public:
64
67
69 typedef boost::shared_ptr<This> shared_ptr;
70
77
92 const Point2& measured, double alpha, const SharedNoiseModel& model,
93 Key poseKey_a, Key poseKey_b, Key pointKey,
94 const boost::shared_ptr<Cal3_S2>& K,
95 boost::optional<Pose3> body_P_sensor = boost::none)
96 : Base(model, poseKey_a, poseKey_b, pointKey),
99 K_(K),
100 body_P_sensor_(body_P_sensor),
101 throwCheirality_(false),
102 verboseCheirality_(false) {}
103
122 const Point2& measured, double alpha, const SharedNoiseModel& model,
123 Key poseKey_a, Key poseKey_b, Key pointKey,
124 const boost::shared_ptr<Cal3_S2>& K, bool throwCheirality,
126 boost::optional<Pose3> body_P_sensor = boost::none)
127 : Base(model, poseKey_a, poseKey_b, pointKey),
129 alpha_(alpha),
130 K_(K),
131 body_P_sensor_(body_P_sensor),
134
137
139 gtsam::NonlinearFactor::shared_ptr clone() const override {
140 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
141 gtsam::NonlinearFactor::shared_ptr(new This(*this)));
142 }
143
149 void print(
150 const std::string& s = "",
151 const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
152 std::cout << s << "ProjectionFactorRollingShutter, z = ";
154 std::cout << " rolling shutter interpolation param = " << alpha_;
155 if (this->body_P_sensor_)
156 this->body_P_sensor_->print(" sensor pose in body frame: ");
157 Base::print("", keyFormatter);
158 }
159
161 bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
162 const This* e = dynamic_cast<const This*>(&p);
163 return e && Base::equals(p, tol) && (alpha_ == e->alpha()) &&
164 traits<Point2>::Equals(this->measured_, e->measured_, tol) &&
165 this->K_->equals(*e->K_, tol) &&
166 (this->throwCheirality_ == e->throwCheirality_) &&
167 (this->verboseCheirality_ == e->verboseCheirality_) &&
168 ((!body_P_sensor_ && !e->body_P_sensor_) ||
170 body_P_sensor_->equals(*e->body_P_sensor_)));
171 }
172
174 Vector evaluateError(
175 const Pose3& pose_a, const Pose3& pose_b, const Point3& point,
176 boost::optional<Matrix&> H1 = boost::none,
177 boost::optional<Matrix&> H2 = boost::none,
178 boost::optional<Matrix&> H3 = boost::none) const override;
179
181 const Point2& measured() const { return measured_; }
182
184 inline const boost::shared_ptr<Cal3_S2> calibration() const { return K_; }
185
187 inline double alpha() const { return alpha_; }
188
190 inline bool verboseCheirality() const { return verboseCheirality_; }
191
193 inline bool throwCheirality() const { return throwCheirality_; }
194
195 private:
197 friend class boost::serialization::access;
198 template <class ARCHIVE>
199 void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
200 ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
201 ar& BOOST_SERIALIZATION_NVP(measured_);
202 ar& BOOST_SERIALIZATION_NVP(alpha_);
203 ar& BOOST_SERIALIZATION_NVP(K_);
204 ar& BOOST_SERIALIZATION_NVP(body_P_sensor_);
205 ar& BOOST_SERIALIZATION_NVP(throwCheirality_);
206 ar& BOOST_SERIALIZATION_NVP(verboseCheirality_);
207 }
208
209 public:
210 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
211};
212
214template <>
216 : public Testable<ProjectionFactorRollingShutter> {};
217
218} // 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
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
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:36
noiseModel::Base::shared_ptr SharedNoiseModel
Aliases.
Definition NoiseModel.h:724
std::uint64_t Key
Integer nonlinear key type.
Definition types.h:100
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
A 3D pose (R,t) : (Rot3,Point3).
Definition Pose3.h:37
virtual void print(const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
print
Definition Factor.cpp:29
bool equals(const This &other, double tol=1e-9) const
check equality
Definition Factor.cpp:42
Nonlinear factor base class.
Definition NonlinearFactor.h:42
NoiseModelFactorN()
Definition NonlinearFactor.h:469
Non-linear factor for 2D projection measurement obtained using a rolling shutter camera.
Definition ProjectionFactorRollingShutter.h:45
boost::optional< Pose3 > body_P_sensor_
The pose of the sensor in the body frame.
Definition ProjectionFactorRollingShutter.h:53
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition ProjectionFactorRollingShutter.h:149
const boost::shared_ptr< Cal3_S2 > calibration() const
return the calibration object
Definition ProjectionFactorRollingShutter.h:184
bool throwCheirality() const
return flag for throwing cheirality exceptions
Definition ProjectionFactorRollingShutter.h:193
const Point2 & measured() const
return the measurement
Definition ProjectionFactorRollingShutter.h:181
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition ProjectionFactorRollingShutter.h:139
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:91
ProjectionFactorRollingShutter This
shorthand for this class
Definition ProjectionFactorRollingShutter.h:66
bool verboseCheirality() const
return verbosity
Definition ProjectionFactorRollingShutter.h:190
boost::shared_ptr< Cal3_S2 > K_
shared pointer to calibration object
Definition ProjectionFactorRollingShutter.h:51
ProjectionFactorRollingShutter()
Default constructor.
Definition ProjectionFactorRollingShutter.h:72
double alpha() const
returns the rolling shutter interp param
Definition ProjectionFactorRollingShutter.h:187
Point2 measured_
2D measurement
Definition ProjectionFactorRollingShutter.h:48
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:121
double alpha_
interpolation parameter in [0,1] corresponding to the point2 measurement
Definition ProjectionFactorRollingShutter.h:49
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false).
Definition ProjectionFactorRollingShutter.h:56
NoiseModelFactorN< Pose3, Pose3, Point3 > Base
shorthand for base class type
Definition ProjectionFactorRollingShutter.h:63
virtual ~ProjectionFactorRollingShutter()
Virtual destructor.
Definition ProjectionFactorRollingShutter.h:136
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition ProjectionFactorRollingShutter.h:69
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false).
Definition ProjectionFactorRollingShutter.h:58
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition ProjectionFactorRollingShutter.h:161