21 using namespace gtsam;
43 double theta =
atan2(landmark_p1.x(), landmark_p1.z());
44 double phi =
atan2(landmark_p1.y(),
sqrt(landmark_p1.x()*landmark_p1.x()+landmark_p1.z()*landmark_p1.z()));
45 double rho = 1./landmark_p1.norm();
58 NonlinearFactor::shared_ptr factor4(
new InvDepthFactorVariant3b(poseKey1, poseKey2, landmarkKey, pixel2, K, sigma));
67 values.
insert(poseKey1, pose1.
retract((
Vector(6) << +0.01, -0.02, +0.03, -0.10, +0.20, -0.30).finished()));
68 values.
insert(poseKey2, pose2.
retract((
Vector(6) << +0.01, +0.02, -0.03, -0.10, +0.20, +0.30).finished()));
virtual const Values & optimize()
static int runAllTests(TestResult &result)
Factor Graph consisting of non-linear factors.
const ValueType at(Key j) const
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 K(500, 500, 0.1, 640/2, 480/2)
NonlinearFactorGraph graph
TEST(InvDepthFactorVariant3, optimize)
static const SmartProjectionParams params
static Point3 landmark(0, 0, 5)
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
std::shared_ptr< Cal3_S2 > shared_ptr
#define EXPECT(condition)
static const Camera2 camera2(pose1, K2)
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 parameterized as (theta...
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
AnnoyingScalar atan2(const AnnoyingScalar &y, const AnnoyingScalar &x)
static Key poseKey1(X(1))
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Point3 transformTo(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in world coordinates and transforms it to Pose coordinates
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
static const double sigma
void insert(Key j, const Value &val)
Jet< T, N > sqrt(const Jet< T, N > &f)
static Key poseKey2(X(2))
PinholeCamera< Cal3_S2 > camera1(pose1, *sharedCal)
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.