30 using namespace gtsam;
43 const InverseDepthFactor& factor) {
57 Vector5 inv_landmark((
Vector(5) << 0., 0., 1., 0., 0.).finished());
60 double inv_depth(1./4);
111 TEST( InvDepthFactor, Jacobian3D ) {
121 const auto [inv_landmark, inv_depth] = inv_camera.
backproject(expected_uv, 5);
122 Vector5 expected_inv_landmark((
Vector(5) << 0., 0., 1., 0., 0.).finished());
129 Symbol invDepthKey(
'd',1);
130 InverseDepthFactor factor(expected_uv,
sigma, poseKey, pointKey, invDepthKey,
K);
132 std::vector<Matrix> actualHs(3);
138 const Matrix& H1Actual = actualHs.at(0);
139 const Matrix& H2Actual = actualHs.at(1);
140 const Matrix& H3Actual = actualHs.at(2);
143 Matrix H1Expected, H2Expected, H3Expected;
145 std::function<Matrix(const Pose3 &, const Vector5 &, const double &)>
146 func = std::bind(&
factorError, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, factor);
virtual const Values & optimize()
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
PinholeCamera< Cal3_S2 > level_camera(level_pose, *K)
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
static Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480))
Some functions to compute numerical derivatives.
NonlinearFactorGraph graph
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
const gtsam::Key pointKey
static SharedNoiseModel sigma(noiseModel::Unit::Create(2))
static Point3 landmark(0, 0, 5)
NonlinearEquality< Pose3 > PoseConstraint
Base class for all pinhole cameras.
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
internal::FixedSizeMatrix< Y, X3 >::type numericalDerivative33(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Matrix factorError(const Pose3 &pose, const Vector5 &point, double invDepth, const InverseDepthFactor &factor)
std::shared_ptr< Cal3_S2 > shared_ptr
std::pair< Vector5, double > backproject(const gtsam::Point2 &pi, const double depth) const
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
#define EXPECT(condition)
LevenbergMarquardtParams lmParams
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
The most common 5DOF 3D->2D calibration.
Inverse Depth Factor based on Civera09tro, Montiel06rss. Landmarks are initialized from the first cam...
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
GenericValue< T > genericValue(const T &v)
TEST(InvDepthFactor, optimize)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
void insert(Key j, const Value &val)
Vector evaluateError(const POSE &pose, const Vector5 &point, const INVDEPTH &invDepth, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override
Evaluate error h(x)-z and optionally derivatives.
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
InvDepthFactor3< Pose3, Vector5, double > InverseDepthFactor
noiseModel::Base::shared_ptr SharedNoiseModel