Go to the documentation of this file.
29 using namespace gtsam;
30 using namespace std::placeholders;
34 std::make_shared<Cal3_S2>(1500, 1200, 0, 640, 480);
57 factor.evaluateError(
landmark, HActual);
59 Matrix HExpected = numericalDerivative11<Vector,Point3>(
67 TEST( triangulation, TriangulationFactorStereo ) {
81 factor.evaluateError(
landmark, HActual);
83 Matrix HExpected = numericalDerivative11<Vector, Point3>(
92 nullptr, std::placeholders::_2);
101 vector<Matrix> HActual1(1), HActual2(1);
102 Vector error1 = factor.unwhitenedError(
values, HActual1);
static int runAllTests(TestResult &result)
PinholeCamera< Cal3_S2 > camera1(pose1, *sharedCal)
const gtsam::Key pointKey
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static Point2 project2(const CalibratedCamera &camera, const Point3 &point)
#define EXPECT(condition)
static const Point3 landmark(5, 0.5, 1.2)
static const Rot3 upright
Functions for triangulation.
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
Some functions to compute numerical derivatives.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
TEST(triangulation, TriangulationFactor)
static const Line3 l(Rot3(), 1, 1)
Base class for all pinhole cameras.
std::shared_ptr< Cal3_S2Stereo > shared_ptr
void insert(Key j, const Vector &value)
static const std::shared_ptr< Cal3_S2 > sharedCal
noiseModel::Base::shared_ptr SharedNoiseModel
noiseModel::Diagonal::shared_ptr model
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
The most common 5DOF 3D->2D calibration, stereo version.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
static const Camera2 camera2(pose1, K2)
std::uint64_t Key
Integer nonlinear key type.
Expressions for Block Automatic Differentiation.
Calibration used by Bundler.
A Stereo Camera based on two Simple Cameras.
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:52