23 using namespace gtsam;
49 return data.
tracks[
i].measurements[0].second;
52 return data.
tracks[
i].measurements[1].second;
55 return EssentialMatrix::Homogeneous(
pA(i));
58 return EssentialMatrix::Homogeneous(
pB(i));
67 expected << 0, 0, 0, 0, 0, -0.1, 0.1, 0, 0;
82 for (
size_t i = 0;
i < 5;
i++)
86 for (
size_t i = 0;
i < 5;
i++)
93 for (
size_t i = 0;
i < 5;
i++) {
106 Hexpected = numericalDerivative11<Vector1, EssentialMatrix>(
107 boost::bind(&EssentialMatrixFactor::evaluateError, &factor, _1,
108 boost::none),
trueE);
118 for (
size_t i = 0;
i < 5;
i++) {
119 boost::function<double(const EssentialMatrix&, OptionalJacobian<1, 5>)>
f =
135 vector<Matrix> Hactual(1);
144 for (
size_t i = 0;
i < 5;
i++) {
145 boost::function<double(const EssentialMatrix&, OptionalJacobian<1, 5>)>
f =
147 boost::function<EssentialMatrix(const Rot3&, const Unit3&, OptionalJacobian<5, 3>,
165 vector<Matrix> Hactual(1);
181 for (
size_t i = 0;
i < 5;
i++)
192 (
Vector(5) << 0.1, -0.1, 0.1, 0.1, -0.1).finished());
193 initial.insert(1, initialE);
194 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) 213 for (
size_t i = 0;
i < 5;
i++)
220 for (
size_t i = 0;
i < 5;
i++) {
228 Matrix Hactual1, Hactual2;
229 double d(baseline / P1.z());
234 Matrix Hexpected1, Hexpected2;
235 boost::function<Vector(const EssentialMatrix&, double)>
f = boost::bind(
236 &EssentialMatrixFactor2::evaluateError, &factor, _1, _2, boost::none,
238 Hexpected1 = numericalDerivative21<Vector2, EssentialMatrix, double>(
f,
trueE,
d);
239 Hexpected2 = numericalDerivative22<Vector2, EssentialMatrix, double>(
f,
trueE,
d);
254 for (
size_t i = 0;
i < 5;
i++)
260 for (
size_t i = 0;
i < 5;
i++) {
262 truth.
insert(
i,
double(baseline / P1.z()));
275 for (
size_t i = 0;
i < 5;
i++)
293 for (
size_t i = 0;
i < 5;
i++) {
301 Matrix Hactual1, Hactual2;
302 double d(baseline / P1.z());
307 Matrix Hexpected1, Hexpected2;
308 boost::function<Vector(const EssentialMatrix&, double)>
f = boost::bind(
309 &EssentialMatrixFactor3::evaluateError, &factor, _1, _2, boost::none,
311 Hexpected1 = numericalDerivative21<Vector2, EssentialMatrix, double>(
f,
bodyE,
d);
312 Hexpected2 = numericalDerivative22<Vector2, EssentialMatrix, double>(
f,
bodyE,
d);
325 for (
size_t i = 0;
i < 5;
i++)
332 for (
size_t i = 0;
i < 5;
i++) {
334 truth.
insert(
i,
double(baseline / P1.z()));
347 for (
size_t i = 0;
i < 5;
i++)
367 double baseline = 10;
370 return data.
tracks[
i].measurements[0].second;
373 return data.
tracks[
i].measurements[1].second;
376 boost::shared_ptr<Cal3Bundler>
377 K = boost::make_shared<Cal3Bundler>(500, 0, 0);
382 return EssentialMatrix::Homogeneous(xy);
386 return EssentialMatrix::Homogeneous(xy);
394 for (
size_t i = 0;
i < 5;
i++)
405 (
Vector(5) << 0.1, -0.1, 0.1, 0.1, -0.1).finished());
406 initial.insert(1, initialE);
408 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) 427 for (
size_t i = 0;
i < 5;
i++)
434 for (
size_t i = 0;
i < 5;
i++) {
442 Matrix Hactual1, Hactual2;
443 double d(baseline / P1.z());
448 Matrix Hexpected1, Hexpected2;
449 boost::function<Vector(const EssentialMatrix&, double)>
f = boost::bind(
450 &EssentialMatrixFactor2::evaluateError, &factor, _1, _2, boost::none,
452 Hexpected1 = numericalDerivative21<Vector2, EssentialMatrix, double>(
f,
trueE,
d);
453 Hexpected2 = numericalDerivative22<Vector2, EssentialMatrix, double>(
f,
trueE,
d);
476 truth.
insert(
i,
double(baseline / P1.z()));
502 for (
size_t i = 0;
i < 5;
i++) {
510 Matrix Hactual1, Hactual2;
511 double d(baseline / P1.z());
516 Matrix Hexpected1, Hexpected2;
517 boost::function<Vector(const EssentialMatrix&, double)>
f = boost::bind(
518 &EssentialMatrixFactor3::evaluateError, &factor, _1, _2, boost::none,
520 Hexpected1 = numericalDerivative21<Vector2, EssentialMatrix, double>(
f,
bodyE,
d);
521 Hexpected2 = numericalDerivative22<Vector2, EssentialMatrix, double>(
f,
bodyE,
d);
boost::shared_ptr< Unit > shared_ptr
virtual const Values & optimize()
Concept check for values that can be used in unit tests.
Define the structure for SfM data.
static int runAllTests(TestResult &result)
Factor Graph consisting of non-linear factors.
Eigen::Matrix< double, 1, 1 > Vector1
void insert(Key j, const Value &val)
GTSAM_EXPORT double error(const Vector3 &vA, const Vector3 &vB, OptionalJacobian< 1, 5 > H=boost::none) const
epipolar error, algebraic
noiseModel::Unit::shared_ptr model2
gtsam::Point3 bX(1, 0, 0)
gtsam::Point3 bY(0, 1, 0)
TEST(EssentialMatrixFactor3, extraTest)
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
Vector evaluateError(const EssentialMatrix &E, const double &d, boost::optional< Matrix & > DE=boost::none, boost::optional< Matrix & > Dd=boost::none) const override
EssentialMatrix trueE(trueRotation, trueDirection)
Some functions to compute numerical derivatives.
EssentialMatrix retract(const Vector5 &xi) const
Retract delta to manifold.
NonlinearFactorGraph graph
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
noiseModel::Isotropic::shared_ptr model1
void g(const string &key, int i)
boost::shared_ptr< Cal3Bundler > K
Rot3 inverse() const
inverse of a rotation
#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.
string findExampleDataFile(const string &name)
PinholeCamera< Cal3_S2 > camera2(pose2,*sharedCal)
Represents a 3D point on a unit sphere.
size_t number_tracks() const
The number of reconstructed 3D points.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
const ValueType at(Key j) const
Test harness methods for expressions.
#define EXPECT(condition)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
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)
static ConjugateGradientParameters parameters
Calibrated camera for which only pose is unknown.
static const Point3 P2(3.5,-8.2, 4.2)
Unit3 trueDirection(trueTranslation)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Matrix3 skewSymmetric(double wx, double wy, double wz)
std::vector< SfmCamera > cameras
Set of cameras.
Point2(* Project)(const Point3 &, OptionalJacobian< 2, 3 >)
Vector evaluateError(const EssentialMatrix &E, const double &d, boost::optional< Matrix & > DE=boost::none, boost::optional< Matrix & > Dd=boost::none) const override
boost::shared_ptr< Isotropic > shared_ptr
double error(const Values &values) const
Vector evaluateError(const EssentialMatrix &E, boost::optional< Matrix & > H=boost::none) const override
vector of errors returns 1D vector
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.
bool readBAL(const string &filename, SfmData &data)
This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a SfmData...