11 #include <gtsam/geometry/EssentialMatrix.h> 51 template<
class CALIBRATION>
61 virtual gtsam::NonlinearFactor::shared_ptr
clone()
const {
62 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
63 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));
67 virtual void print(
const std::string& s =
"",
68 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const {
70 std::cout <<
" EssentialMatrixFactor with measurements\n (" 71 << vA_.transpose() <<
")' and (" << vB_.transpose() <<
")'" 79 error << E.error(vA_, vB_, H);
84 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
125 template<
class CALIBRATION>
129 EssentialMatrix::Homogeneous(K->calibrate(pA))), pn_(K->calibrate(pB)) {
130 f_ = 0.5 * (K->fx() + K->fy());
134 virtual gtsam::NonlinearFactor::shared_ptr
clone()
const {
135 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
136 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));
140 virtual void print(
const std::string& s =
"",
141 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const {
143 std::cout <<
" EssentialMatrixFactor2 with measurements\n (" 144 << dP1_.transpose() <<
")' and (" << pn_.transpose()
145 <<
")'" << std::endl;
154 boost::optional<Matrix&> DE = boost::none, boost::optional<Matrix&> Dd =
170 Point3 _1T2 = E.direction().point3();
172 Point3 dP2 = E.rotation().unrotate(dP1_ - d1T2);
179 Matrix D_1T2_dir, DdP2_rot, DP2_point;
181 Point3 _1T2 = E.direction().point3(D_1T2_dir);
183 Point3 dP2 = E.rotation().unrotate(dP1_ - d1T2, DdP2_rot, DP2_point);
190 DdP2_E << DdP2_rot, -DP2_point * d * D_1T2_dir;
191 *DE = f_ * Dpn_dP2 * DdP2_E;
196 *Dd = -f_ * (Dpn_dP2 * (DP2_point * _1T2));
199 Point2 reprojectionError = pn - pn_;
200 return f_ * reprojectionError;
204 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
245 template<
class CALIBRATION>
248 boost::shared_ptr<CALIBRATION> K) :
253 virtual gtsam::NonlinearFactor::shared_ptr
clone()
const {
254 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
255 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));
259 virtual void print(
const std::string& s =
"",
260 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const {
262 std::cout <<
" EssentialMatrixFactor3 with rotation " << cRb_ << std::endl;
271 boost::optional<Matrix&> DE = boost::none, boost::optional<Matrix&> Dd =
280 Matrix D_e_cameraE, D_cameraE_E;
283 *DE = D_e_cameraE * D_cameraE_E;
289 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
virtual gtsam::NonlinearFactor::shared_ptr clone() const
Definition: EssentialMatrixFactor.h:253
This is the base class for all factor types.
Definition: Factor.h:54
A convenient base class for creating your own NoiseModelFactor with 2 variables.
Definition: NonlinearFactor.h:345
A simple camera class with a Cal3_S2 calibration.
static Vector3 Homogeneous(const Point2 &p)
Static function to convert Point2 to homogeneous coordinates.
Definition: EssentialMatrix.h:34
EssentialMatrixFactor2(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model)
Constructor.
Definition: EssentialMatrixFactor.h:110
Vector evaluateError(const EssentialMatrix &E, boost::optional< Matrix & > H=boost::none) const
vector of errors returns 1D vector
Definition: EssentialMatrixFactor.h:76
virtual void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Print.
Definition: NonlinearFactor.cpp:63
Binary factor that optimizes for E and inverse depth d: assumes measurement in image 2 is perfect,...
Definition: EssentialMatrixFactor.h:213
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
EssentialMatrixFactor(Key key, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model)
Constructor.
Definition: EssentialMatrixFactor.h:36
EssentialMatrixFactor2(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model, boost::shared_ptr< CALIBRATION > K)
Constructor.
Definition: EssentialMatrixFactor.h:126
virtual void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: EssentialMatrixFactor.h:67
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
A convenient base class for creating your own NoiseModelFactor with 1 variable.
Definition: NonlinearFactor.h:276
virtual gtsam::NonlinearFactor::shared_ptr clone() const
Definition: EssentialMatrixFactor.h:134
virtual void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: EssentialMatrixFactor.h:259
Key key1() const
methods to retrieve both keys
Definition: NonlinearFactor.h:377
Vector evaluateError(const EssentialMatrix &E, const double &d, boost::optional< Matrix & > DE=boost::none, boost::optional< Matrix & > Dd=boost::none) const
Override this method to finish implementing a binary factor.
Definition: EssentialMatrixFactor.h:270
EssentialMatrixFactor3(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const Rot3 &cRb, const SharedNoiseModel &model, boost::shared_ptr< CALIBRATION > K)
Constructor.
Definition: EssentialMatrixFactor.h:246
Vector evaluateError(const EssentialMatrix &E, const double &d, boost::optional< Matrix & > DE=boost::none, boost::optional< Matrix & > Dd=boost::none) const
Override this method to finish implementing a binary factor.
Definition: EssentialMatrixFactor.h:153
Binary factor that optimizes for E and inverse depth d: assumes measurement in image 2 is perfect,...
Definition: EssentialMatrixFactor.h:91
EssentialMatrixFactor3(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const Rot3 &cRb, const SharedNoiseModel &model)
Constructor.
Definition: EssentialMatrixFactor.h:231
Non-linear factor base classes.
EssentialMatrixFactor(Key key, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model, boost::shared_ptr< CALIBRATION > K)
Constructor.
Definition: EssentialMatrixFactor.h:52
Factor that evaluates epipolar error p'Ep for given essential matrix.
Definition: EssentialMatrixFactor.h:20
An essential matrix is like a Pose3, except with translation up to scale It is named after the 3*3 ma...
Definition: EssentialMatrix.h:26
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:1072
virtual void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: EssentialMatrixFactor.h:140
virtual gtsam::NonlinearFactor::shared_ptr clone() const
Definition: EssentialMatrixFactor.h:61
virtual double error(const Values &c) const
Calculate the error of the factor.
Definition: NonlinearFactor.cpp:97
static Point2 Project(const Point3 &pc, OptionalJacobian< 2, 3 > Dpoint=boost::none)
Project from 3D point in camera coordinates into image Does not throw a CheiralityException,...
Definition: CalibratedCamera.cpp:88