Go to the documentation of this file.
21 using namespace std::placeholders;
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++) {
105 std::placeholders::_2);
120 vector<Matrix> actualH(1);
129 for (
size_t i = 0;
i < 5;
i++) {
132 std::placeholders::_2);
154 vector<Matrix> actualH(1);
170 for (
size_t i = 0;
i < 5;
i++)
183 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS)
202 for (
size_t i = 0;
i < 5;
i++)
208 for (
size_t i = 0;
i < 5;
i++) {
216 Matrix actualH1, actualH2;
235 for (
size_t i = 0;
i < 5;
i++)
241 for (
size_t i = 0;
i < 5;
i++) {
256 for (
size_t i = 0;
i < 5;
i++)
273 for (
size_t i = 0;
i < 5;
i++) {
281 Matrix actualH1, actualH2;
297 for (
size_t i = 0;
i < 5;
i++)
305 for (
size_t i = 0;
i < 5;
i++) {
320 for (
size_t i = 0;
i < 5;
i++)
331 for (
size_t i = 0;
i < 5;
i++) {
390 for (
size_t i = 0;
i < 5;
i++)
408 Vector5 priorNoiseModelSigma;
409 priorNoiseModelSigma << 10, 10, 10, 10, 10;
411 2,
trueK, noiseModel::Diagonal::Sigmas(priorNoiseModelSigma));
426 for (
size_t i = 0;
i < 5;
i++)
429 actualE.
error(EssentialMatrix::Homogeneous(actualK.calibrate(
pA(
i))),
430 EssentialMatrix::Homogeneous(actualK.calibrate(
pB(
i)))),
440 for (
size_t i = 0;
i < 7;
i++)
460 Vector5 priorNoiseModelSigma;
461 priorNoiseModelSigma << 20, 20, 1, 1, 1;
463 2, initialK, noiseModel::Diagonal::Sigmas(priorNoiseModelSigma));
478 for (
size_t i = 0;
i < 7;
i++)
481 actualE.
error(EssentialMatrix::Homogeneous(actualK.calibrate(
pA(
i))),
482 EssentialMatrix::Homogeneous(actualK.calibrate(
pB(
i)))),
489 for (
size_t i = 0;
i < 5;
i++)
509 priorNoiseModelSigma << 0.1, 0.1, 0.1;
511 2,
trueK, noiseModel::Diagonal::Sigmas(priorNoiseModelSigma));
526 for (
size_t i = 0;
i < 5;
i++)
529 actualE.
error(EssentialMatrix::Homogeneous(actualK.calibrate(
pA(
i))),
530 EssentialMatrix::Homogeneous(actualK.calibrate(
pB(
i)))),
536 Key keyE(1), keyKa(2), keyKb(3);
537 for (
size_t i = 0;
i < 5;
i++) {
559 Key keyE(1), keyK(2);
560 for (
size_t i = 0;
i < 5;
i++) {
594 std::shared_ptr<Cal3Bundler>
K = std::make_shared<Cal3Bundler>(
trueK);
599 return EssentialMatrix::Homogeneous(
xy);
603 return EssentialMatrix::Homogeneous(
xy);
611 for (
size_t i = 0;
i < 5;
i++)
625 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS)
644 for (
size_t i = 0;
i < 5;
i++)
650 for (
size_t i = 0;
i < 5;
i++) {
710 for (
size_t i = 0;
i < 5;
i++) {
static int runAllTests(TestResult &result)
Cal3Bundler retract(const Vector &d) const
Update calibration with tangent space delta.
PinholeCamera< Cal3Bundler > camera2(data.cameras[1].pose(), trueK)
virtual const Values & optimize()
#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by a factor against finite differences.
Vector evaluateError(const EssentialMatrix &E, const CALIBRATION &Ka, const CALIBRATION &Kb, OptionalMatrixType HE, OptionalMatrixType HKa, OptionalMatrixType HKb) const override
Calculate the algebraic epipolar error pA' (Ka^-1)' E Kb pB.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const double d[K][N]
Concept check for values that can be used in unit tests.
#define EXPECT(condition)
GTSAM_EXPORT double error(const Vector3 &vA, const Vector3 &vB, OptionalJacobian< 1, 5 > H={}) const
epipolar error, algebraic
The most common 5DOF 3D->2D calibration.
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
noiseModel::Unit::shared_ptr model2
Vector evaluateError(const EssentialMatrix &E, const CALIBRATION &K, OptionalMatrixType HE, OptionalMatrixType HK) const override
Calculate the algebraic epipolar error pA' (K^-1)' E K pB.
std::shared_ptr< Unit > shared_ptr
Unit3 trueDirection(trueTranslation)
TEST(EssentialMatrixFactor3, extraTest)
Matrix3 skewSymmetric(double wx, double wy, double wz)
Calibrated camera for which only pose is unknown.
EssentialMatrix retract(const Vector5 &xi) const
Retract delta to manifold.
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
SfmData stores a bunch of SfmTracks.
DecisionTreeFactor factor(D &C &B &A, "0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 " "0.0 0.0 0.99995287 1.0 1.0 1.0 1.0")
gtsam::Point3 bX(1, 0, 0)
double error(const Values &values) const
Pose2_ Expmap(const Vector3_ &xi)
std::vector< SfmTrack > tracks
Sparse set of points.
const ValueType at(Key j) const
utility functions for loading datasets
gtsam::Point3 bY(0, 1, 0)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static ConjugateGradientParameters parameters
Calibration used by Bundler.
Evaluate derivatives of a nonlinear factor numerically.
void insert(Key j, const Vector &value)
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Rot3 inverse() const
inverse of a rotation
void g(const string &key, int i)
Test harness methods for expressions.
const gtsam::Symbol key('X', 0)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Data structure for dealing with Structure from Motion data.
std::shared_ptr< Cal3Bundler > K
Factor Graph consisting of non-linear factors.
std::vector< SfmCamera > cameras
Set of cameras.
void insert(Key j, const Value &val)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
gtsam::Point3 bZ(0, 0, 1)
The most common 5DOF 3D->2D calibration.
The matrix class, also used for vectors and row-vectors.
EssentialMatrix trueE(trueRotation, trueDirection)
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
#define EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by an expression against finite differences.
std::shared_ptr< Isotropic > shared_ptr
Point2 calibrate(const Point2 &pi, OptionalJacobian< 2, 3 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
Represents a 3D point on a unit sphere.
Point2(* Project)(const Point3 &, OptionalJacobian< 2, 3 >)
NonlinearFactorGraph graph
noiseModel::Isotropic::shared_ptr model1
std::uint64_t Key
Integer nonlinear key type.
size_t numberTracks() const
The number of reconstructed 3D points.
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:16:15