19 using namespace gtsam;
41 Vector5 inv_landmark((
Vector(5) << 0., 0., 1., 0., 0.).finished());
44 double inv_depth(1./4);
virtual const Values & optimize()
static int runAllTests(TestResult &result)
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
static Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480))
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
NonlinearFactorGraph graph
static SharedNoiseModel sigma(noiseModel::Unit::Create(2))
static Point3 landmark(0, 0, 5)
NonlinearEquality< Pose3 > PoseConstraint
Base class for all pinhole cameras.
const ValueType at(Key j) const
#define EXPECT(condition)
PinholeCamera< Cal3_S2 > level_camera(level_pose,*K)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Inverse Depth Factor based on Civera09tro, Montiel06rss. Landmarks are initialized from the first cam...
TEST(InvDepthFactor, optimize)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
LevenbergMarquardtParams lmParams
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
boost::shared_ptr< Cal3_S2 > shared_ptr
InvDepthFactor3< Pose3, Vector5, double > InverseDepthFactor
noiseModel::Base::shared_ptr SharedNoiseModel
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))