Go to the documentation of this file.
29 using namespace gtsam;
66 Vector expectedError = Vector::Zero(2);
68 expectedFs << -0.001, -1.00001, 0, -0.1, 0, -0.01, 0, 0, 0, 1, 0, 0, 0, -0.1,
71 expectedE << 0.1, 0, 0.01, 0, 0.1, 0;
85 :
Base(sharedNoiseModel) {}
static int runAllTests(TestResult &result)
Base class to create smart factors on poses or cameras.
TEST(SmartFactorBase, Stereo)
SmartFactorBase< StereoCamera > Base
std::array< PinholeCamera< Cal3_S2 >, 3 > cameras
Array< double, 1, 3 > e(1./3., 0.5, 2.)
#define EXPECT_LONGS_EQUAL(expected, actual)
#define EXPECT(condition)
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
A set of cameras, all with their own calibration.
std::shared_ptr< GaussianFactor > linearize(const Values &values) const override
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static shared_ptr Create(size_t dim)
Base class for all pinhole cameras.
noiseModel::Base::shared_ptr SharedNoiseModel
double error(const Values &values) const override
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Base class for smart factors. This base class has no internal point, but it has a measurement,...
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
StereoFactor(const SharedNoiseModel &sharedNoiseModel)
Calibration used by Bundler.
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
static Point2 measurement(323.0, 240.0)
static Unit3 unit3(1.0, 2.1, 3.4)
A Stereo Camera based on two Simple Cameras.
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:38