51 template<
class CALIBRATION>
67 void print(
const std::string&
s =
"",
70 std::cout <<
" EssentialMatrixFactor with measurements\n (" 71 << vA_.transpose() <<
")' and (" << vB_.transpose() <<
")'" 77 boost::none)
const override {
79 error << E.
error(vA_, vB_,
H);
112 Base(model, key1, key2), dP1_(
EssentialMatrix::Homogeneous(pA)), pn_(pB) {
125 template<
class CALIBRATION>
128 Base(model, key1, key2), dP1_(
129 EssentialMatrix::Homogeneous(K->calibrate(pA))), pn_(K->calibrate(pB)) {
130 f_ = 0.5 * (K->fx() + K->fy());
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 =
155 boost::none)
const override {
179 Matrix D_1T2_dir, 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;
245 template<
class CALIBRATION>
248 boost::shared_ptr<CALIBRATION>
K) :
262 std::cout <<
" EssentialMatrixFactor3 with rotation " << cRb_ << std::endl;
271 boost::optional<Matrix&> DE = boost::none, boost::optional<Matrix&> Dd =
272 boost::none)
const override {
280 Matrix D_e_cameraE, D_cameraE_E;
283 *DE = D_e_cameraE * D_cameraE_E;
EssentialMatrixFactor2 This
double error(const Values &c) const override
EssentialMatrixFactor2(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model, boost::shared_ptr< CALIBRATION > K)
gtsam::NonlinearFactor::shared_ptr clone() const override
noiseModel::Diagonal::shared_ptr model
GTSAM_EXPORT double error(const Vector3 &vA, const Vector3 &vB, OptionalJacobian< 1, 5 > H=boost::none) const
epipolar error, algebraic
virtual Vector evaluateError(const X &x, boost::optional< Matrix & > H=boost::none) const =0
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
rotate point from world to rotated frame
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Vector evaluateError(const EssentialMatrix &E, const double &d, boost::optional< Matrix & > DE=boost::none, boost::optional< Matrix & > Dd=boost::none) const override
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
static const KeyFormatter DefaultKeyFormatter
Vector3 vB_
Homogeneous versions, in ideal coordinates.
static Vector3 Homogeneous(const Point2 &p)
Static function to convert Point2 to homogeneous coordinates.
const Symbol key1('v', 1)
const Unit3 & direction() const
Direction.
Base class for all pinhole cameras.
gtsam::NonlinearFactor::shared_ptr clone() const override
NoiseModelFactor1< EssentialMatrix > Base
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
EssentialMatrixFactor(Key key, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model)
Point2 pn_
Measurement in image 2, in ideal coordinates.
GTSAM_EXPORT EssentialMatrix rotate(const Rot3 &cRb, OptionalJacobian< 5, 5 > HE=boost::none, OptionalJacobian< 5, 3 > HR=boost::none) const
Point3 dP1_
3D point corresponding to measurement in image 1
gtsam::NonlinearFactor::shared_ptr clone() const override
boost::shared_ptr< This > shared_ptr
EssentialMatrixFactor This
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
GTSAM_EXPORT Point3 point3(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Point3.
EssentialMatrixFactor3(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const Rot3 &cRb, const SharedNoiseModel &model)
EssentialMatrixFactor2 Base
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Non-linear factor base classes.
const Rot3 & rotation() const
Rotation.
const Symbol key2('v', 2)
static Point2 Project(const Point3 &pc, OptionalJacobian< 2, 3 > Dpoint=boost::none)
Vector evaluateError(const EssentialMatrix &E, const double &d, boost::optional< Matrix & > DE=boost::none, boost::optional< Matrix & > Dd=boost::none) const override
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
NoiseModelFactor2< EssentialMatrix, double > Base
EssentialMatrixFactor(Key key, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model, boost::shared_ptr< CALIBRATION > K)
EssentialMatrixFactor3(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const Rot3 &cRb, const SharedNoiseModel &model, boost::shared_ptr< CALIBRATION > K)
Vector evaluateError(const EssentialMatrix &E, boost::optional< Matrix & > H=boost::none) const override
vector of errors returns 1D vector
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Rot3 cRb_
Rotation from body to camera frame.
double f_
approximate conversion factor for error scaling
std::uint64_t Key
Integer nonlinear key type.
EssentialMatrixFactor3 This
noiseModel::Base::shared_ptr SharedNoiseModel
EssentialMatrixFactor2(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model)