28 #include <boost/assign.hpp> 29 #include <boost/assign/std/vector.hpp> 32 using namespace gtsam;
37 boost::make_shared<Cal3_S2>(1500, 1200, 0, 640, 480);
56 Factor factor(
camera1, z1, model, pointKey);
60 factor.evaluateError(
landmark, HActual);
62 Matrix HExpected = numericalDerivative11<Vector,Point3>(
63 boost::bind(&Factor::evaluateError, &factor, _1, boost::none),
landmark);
70 TEST( triangulation, TriangulationFactorStereo ) {
80 Factor factor(camera2, z2, model, pointKey);
84 factor.evaluateError(
landmark, HActual);
86 Matrix HExpected = numericalDerivative11<Vector,Point3>(
87 boost::bind(&Factor::evaluateError, &factor, _1, boost::none),
landmark);
102 vector<Matrix> HActual1(1), HActual2(1);
103 Vector error1 = factor.unwhitenedError(values, HActual1);
static Point2 project2(const CalibratedCamera &camera, const Point3 &point)
static int runAllTests(TestResult &result)
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
static const Rot3 upright
static const Point3 landmark(5, 0.5, 1.2)
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
Some functions to compute numerical derivatives.
const gtsam::Key pointKey
TEST(triangulation, TriangulationFactor)
Expressions for Block Automatic Differentiation.
PinholeCamera< Cal3_S2 > camera2(pose2,*sharedCal)
Base class for all pinhole cameras.
boost::shared_ptr< Cal3_S2Stereo > shared_ptr
#define EXPECT(condition)
Functions for triangulation.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
A Stereo Camera based on two Simple Cameras.
StereoPoint2 project(const Point3 &point) const
Project 3D point to StereoPoint2 (uL,uR,v)
PinholeCamera< Cal3_S2 > camera1(pose1,*sharedCal)
std::uint64_t Key
Integer nonlinear key type.
Calibration used by Bundler.
static const boost::shared_ptr< Cal3_S2 > sharedCal
noiseModel::Base::shared_ptr SharedNoiseModel