23 using namespace gtsam;
27 noiseModel::Isotropic::Sigma(1, 0.01);
51 Vector vA(
size_t i) {
return EssentialMatrix::Homogeneous(
pA(i)); }
52 Vector vB(
size_t i) {
return EssentialMatrix::Homogeneous(
pB(i)); }
58 expected << 0, 0, 0, 0, 0, -0.1, 0.1, 0, 0;
73 for (
size_t i = 0;
i < 5;
i++)
77 for (
size_t i = 0;
i < 5;
i++)
84 for (
size_t i = 0;
i < 5;
i++) {
102 for (
size_t i = 0;
i < 5;
i++) {
103 std::function<double(const EssentialMatrix &, OptionalJacobian<1, 5>)>
f =
119 vector<Matrix> Hactual(1);
128 for (
size_t i = 0;
i < 5;
i++) {
129 std::function<double(const EssentialMatrix &, OptionalJacobian<1, 5>)>
f =
152 vector<Matrix> Hactual(1);
168 for (
size_t i = 0;
i < 5;
i++)
180 initial.insert(1, initialE);
181 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) 200 for (
size_t i = 0;
i < 5;
i++)
206 for (
size_t i = 0;
i < 5;
i++) {
214 Matrix Hactual1, Hactual2;
215 double d(baseline / P1.z());
233 for (
size_t i = 0;
i < 5;
i++)
239 for (
size_t i = 0;
i < 5;
i++) {
241 truth.
insert(
i,
double(baseline / P1.z()));
254 for (
size_t i = 0;
i < 5;
i++)
271 for (
size_t i = 0;
i < 5;
i++) {
279 Matrix Hactual1, Hactual2;
280 double d(baseline / P1.z());
295 for (
size_t i = 0;
i < 5;
i++)
303 for (
size_t i = 0;
i < 5;
i++) {
305 truth.
insert(
i,
double(baseline / P1.z()));
318 for (
size_t i = 0;
i < 5;
i++)
329 for (
size_t i = 0;
i < 5;
i++) {
340 truth.
insert(keyK, trueK);
388 for (
size_t i = 0;
i < 5;
i++)
402 initial.insert(1, initialE);
403 initial.insert(2, trueK);
406 Vector5 priorNoiseModelSigma;
407 priorNoiseModelSigma << 10, 10, 10, 10, 10;
409 2,
trueK, noiseModel::Diagonal::Sigmas(priorNoiseModelSigma));
424 for (
size_t i = 0;
i < 5;
i++)
427 actualE.
error(EssentialMatrix::Homogeneous(actualK.calibrate(
pA(
i))),
428 EssentialMatrix::Homogeneous(actualK.calibrate(
pB(
i)))),
438 for (
size_t i = 0;
i < 7;
i++)
453 trueK.
retract((
Vector(5) << 0.1, -0.1, 0.0, -0.0, 0.0).finished());
454 initial.insert(1, initialE);
455 initial.insert(2, initialK);
458 Vector5 priorNoiseModelSigma;
459 priorNoiseModelSigma << 20, 20, 1, 1, 1;
461 2, initialK, noiseModel::Diagonal::Sigmas(priorNoiseModelSigma));
476 for (
size_t i = 0;
i < 7;
i++)
479 actualE.
error(EssentialMatrix::Homogeneous(actualK.calibrate(
pA(
i))),
480 EssentialMatrix::Homogeneous(actualK.calibrate(
pB(
i)))),
487 for (
size_t i = 0;
i < 5;
i++)
502 initial.insert(1, initialE);
503 initial.insert(2, initialK);
507 priorNoiseModelSigma << 0.1, 0.1, 0.1;
509 2,
trueK, noiseModel::Diagonal::Sigmas(priorNoiseModelSigma));
524 for (
size_t i = 0;
i < 5;
i++)
527 actualE.
error(EssentialMatrix::Homogeneous(actualK.calibrate(
pA(
i))),
528 EssentialMatrix::Homogeneous(actualK.calibrate(
pB(
i)))),
539 SfmData data = SfmData::FromBalFile(filename);
544 double baseline = 10;
550 std::shared_ptr<Cal3Bundler>
K = std::make_shared<Cal3Bundler>(
trueK);
555 return EssentialMatrix::Homogeneous(xy);
559 return EssentialMatrix::Homogeneous(xy);
567 for (
size_t i = 0;
i < 5;
i++)
579 initial.insert(1, initialE);
581 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) 600 for (
size_t i = 0;
i < 5;
i++)
606 for (
size_t i = 0;
i < 5;
i++) {
614 double d(baseline / P1.z());
641 truth.
insert(
i,
double(baseline / P1.z()));
666 for (
size_t i = 0;
i < 5;
i++) {
674 double d(baseline / P1.z());
const gtsam::Symbol key('X', 0)
virtual const Values & optimize()
Concept check for values that can be used in unit tests.
SfmData stores a bunch of SfmTracks.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
static int runAllTests(TestResult &result)
Factor Graph consisting of non-linear factors.
const ValueType at(Key j) const
GTSAM_EXPORT double error(const Vector3 &vA, const Vector3 &vB, OptionalJacobian< 1, 5 > H={}) const
epipolar error, algebraic
noiseModel::Unit::shared_ptr model2
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
std::shared_ptr< Cal3Bundler > K
gtsam::Point3 bX(1, 0, 0)
gtsam::Point3 bY(0, 1, 0)
std::shared_ptr< Unit > shared_ptr
Pose2_ Expmap(const Vector3_ &xi)
TEST(EssentialMatrixFactor3, extraTest)
Vector evaluateError(const EssentialMatrix &E, const double &d, OptionalMatrixType DE, OptionalMatrixType Dd) const override
EssentialMatrix trueE(trueRotation, trueDirection)
Evaluate derivatives of a nonlinear factor numerically.
PinholeCamera< Cal3Bundler > camera2(data.cameras[1].pose(), trueK)
NonlinearFactorGraph graph
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
noiseModel::Isotropic::shared_ptr model1
void g(const string &key, int i)
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.
#define EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by an expression against finite differences.
std::vector< SfmTrack > tracks
Sparse set of points.
Rot3 inverse() const
inverse of a rotation
EssentialMatrix retract(const Vector5 &xi) const
Retract delta to manifold.
Represents a 3D point on a unit sphere.
Vector evaluateError(const EssentialMatrix &E, const double &d, OptionalMatrixType DE, OptionalMatrixType Dd) const override
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Test harness methods for expressions.
Point2 calibrate(const Point2 &pi, OptionalJacobian< 2, 3 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
#define EXPECT(condition)
Data structure for dealing with Structure from Motion data.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::Point3 bZ(0, 0, 1)
The most common 5DOF 3D->2D calibration.
double error(const Values &values) const
std::shared_ptr< Isotropic > shared_ptr
static ConjugateGradientParameters parameters
Calibrated camera for which only pose is unknown.
static const Point3 P2(3.5,-8.2, 4.2)
Unit3 trueDirection(trueTranslation)
Cal3_S2 retract(const Vector &d) const
Given 5-dim tangent vector, create new calibration.
Matrix3 skewSymmetric(double wx, double wy, double wz)
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
std::vector< SfmCamera > cameras
Set of cameras.
Calibration used by Bundler.
#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by a factor against finite differences.
Point2(* Project)(const Point3 &, OptionalJacobian< 2, 3 >)
void insert(Key j, const Value &val)
Vector evaluateError(const EssentialMatrix &E, OptionalMatrixType H) const override
vector of errors returns 1D vector
size_t numberTracks() const
The number of reconstructed 3D points.
The matrix class, also used for vectors and row-vectors.
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
utility functions for loading datasets
std::uint64_t Key
Integer nonlinear key type.
The most common 5DOF 3D->2D calibration.