23 #include <gtsam/geometry/EssentialMatrix.h> 69 template <
class CALIBRATION>
72 std::shared_ptr<CALIBRATION> K)
80 gtsam::NonlinearFactor::shared_ptr
clone()
const override {
82 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));
87 const std::string& s =
"",
88 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
90 std::cout <<
" EssentialMatrixFactor with measurements\n (" 91 << vA_.transpose() <<
")' and (" << vB_.transpose() <<
")'" 99 error << E.
error(vA_, vB_, H);
135 : Base(model, key1, key2),
150 template <
class CALIBRATION>
153 std::shared_ptr<CALIBRATION> K)
154 : Base(model, key1, key2),
156 pn_(K->calibrate(pB)) {
157 f_ = 0.5 * (K->fx() + K->fy());
161 gtsam::NonlinearFactor::shared_ptr
clone()
const override {
163 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));
168 const std::string& s =
"",
169 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
171 std::cout <<
" EssentialMatrixFactor2 with measurements\n (" 172 << dP1_.transpose() <<
")' and (" << pn_.transpose() <<
")'" 204 Matrix D_1T2_dir, DdP2_rot, DP2_point;
215 DdP2_E << DdP2_rot, -DP2_point * d * D_1T2_dir;
216 *DE = f_ * Dpn_dP2 * DdP2_E;
221 *Dd = -f_ * (Dpn_dP2 * (DP2_point * _1T2));
223 Point2 reprojectionError = pn - pn_;
224 return f_ * reprojectionError;
270 template <
class CALIBRATION>
273 std::shared_ptr<CALIBRATION> K)
277 gtsam::NonlinearFactor::shared_ptr
clone()
const override {
279 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));
284 const std::string& s =
"",
285 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
287 std::cout <<
" EssentialMatrixFactor3 with rotation " << cRb_ << std::endl;
305 Matrix D_e_cameraE, D_cameraE_E;
310 *DE = D_e_cameraE * D_cameraE_E;
333 template <
class CALIBRATION>
343 typedef Eigen::Matrix<double, 2, DimK> JacobianCalibration;
361 : Base(model, keyE, keyK), pA_(pA), pB_(pB) {}
364 gtsam::NonlinearFactor::shared_ptr
clone()
const override {
366 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));
371 const std::string& s =
"",
372 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
374 std::cout <<
" EssentialMatrixFactor4 with measurements\n (" 375 << pA_.transpose() <<
")' and (" << pB_.transpose() <<
")'" 392 JacobianCalibration cA_H_K;
393 JacobianCalibration cB_H_K;
408 *H2 = vB.transpose() * E.
matrix().transpose().leftCols<2>() * cA_H_K +
409 vA.transpose() * E.
matrix().leftCols<2>() * cB_H_K;
413 error << E.
error(vA, vB, H1);
Definition: NonlinearFactor.h:431
double error(const Values &c) const override
GTSAM_EXPORT EssentialMatrix rotate(const Rot3 &cRb, OptionalJacobian< 5, 5 > HE={}, OptionalJacobian< 5, 3 > HR={}) const
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: EssentialMatrixFactor.h:161
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: EssentialMatrixFactor.h:370
Definition: EssentialMatrixFactor.h:237
const Unit3 & direction() const
Direction.
Definition: EssentialMatrix.h:115
Vector2 Point2
Definition: Point2.h:32
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:161
Key key() const
Definition: NonlinearFactor.h:582
Definition: NonlinearFactor.h:68
EssentialMatrixFactor3(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const Rot3 &cRb, const SharedNoiseModel &model, std::shared_ptr< CALIBRATION > K)
Definition: EssentialMatrixFactor.h:271
static Point2 Project(const Point3 &pc, OptionalJacobian< 2, 3 > Dpoint={})
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
Vector evaluateError(const EssentialMatrix &E, const CALIBRATION &K, OptionalMatrixType H1, OptionalMatrixType H2) const override
Calculate the algebraic epipolar error pA' (K^-1)' E K pB.
Definition: EssentialMatrixFactor.h:388
static Vector3 Homogeneous(const Point2 &p)
Static function to convert Point2 to homogeneous coordinates.
Definition: EssentialMatrix.h:34
#define OptionalNone
Definition: NonlinearFactor.h:49
Base class for all pinhole cameras.
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: EssentialMatrixFactor.h:277
EssentialMatrixFactor(Key key, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model, std::shared_ptr< CALIBRATION > K)
Definition: EssentialMatrixFactor.h:70
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
rotate point from world to rotated frame
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: EssentialMatrixFactor.h:283
EssentialMatrixFactor(Key key, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model)
Definition: EssentialMatrixFactor.h:53
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: EssentialMatrixFactor.h:80
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: EssentialMatrixFactor.h:86
EssentialMatrixFactor2(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model, std::shared_ptr< CALIBRATION > K)
Definition: EssentialMatrixFactor.h:151
const Rot3 & rotation() const
Rotation.
Definition: EssentialMatrix.h:110
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
Definition: EssentialMatrixFactor.h:34
EssentialMatrixFactor3(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const Rot3 &cRb, const SharedNoiseModel &model)
Definition: EssentialMatrixFactor.h:257
Definition: chartTesting.h:28
Definition: EssentialMatrix.h:26
EssentialMatrixFactor4(Key keyE, Key keyK, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model)
Definition: EssentialMatrixFactor.h:359
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Non-linear factor base classes.
Definition: EssentialMatrixFactor.h:111
const Matrix3 & matrix() const
Return 3*3 matrix representation.
Definition: EssentialMatrix.h:120
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: EssentialMatrixFactor.h:364
Vector evaluateError(const EssentialMatrix &E, OptionalMatrixType H) const override
vector of errors returns 1D vector
Definition: EssentialMatrixFactor.h:96
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:284
Point3 point3(OptionalJacobian< 3, 2 > H={}) const
Return unit-norm Point3.
Vector3 Point3
Definition: Point3.h:38
Definition: EssentialMatrixFactor.h:334
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: EssentialMatrixFactor.h:167
GTSAM_EXPORT double error(const Vector3 &vA, const Vector3 &vB, OptionalJacobian< 1, 5 > H={}) const
epipolar error, algebraic
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
EssentialMatrixFactor2(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model)
Definition: EssentialMatrixFactor.h:133