25 using namespace gtsam;
41 boost::optional<Pose3> body_P_sensor = boost::none,
42 size_t expectedNumberCameras = 10)
43 : Base(sharedNoiseModel, body_P_sensor, expectedNumberCameras) {}
68 PinholeFactor::Cameras cameras;
72 Pose3 wTc = world_P_body * body_P_sensor;
78 f.
add(measurement, 1);
84 Vector expectedError = Vector::Zero(2);
86 expectedFs << -0.001, -1.00001, 0, -0.1, 0, -0.01, 0, 0, 0, 1, 0, 0, 0, -0.1, 0, 0, 0, 0;
88 expectedE << 0.1, 0, 0.01, 0, 0.1, 0;
SmartFactorBase< PinholeCamera< Cal3Bundler > > Base
PinholeFactor(const SharedNoiseModel &sharedNoiseModel, boost::optional< Pose3 > body_P_sensor=boost::none, size_t expectedNumberCameras=10)
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
void serialize(Archive &ar, Eigen::Matrix< Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_ > &m, const unsigned int version)
static int runAllTests(TestResult &result)
static SharedNoiseModel unit3(noiseModel::Unit::Create(3))
bool equalsObj(const T &input=T())
bool equalsXML(const T &input=T())
bool equalsBinary(const T &input=T())
Base class to create smart factors on poses or cameras.
Base class for all pinhole cameras.
Base class for smart factors This base class has no internal point, but it has a measurement, noise model and an optional sensor pose. This class mainly computes the derivatives and returns them as a variety of factors. The methods take a Cameras argument, which should behave like PinholeCamera, and the value of a point, which is kept in the base class.
TEST(SmartFactorBase, Pinhole)
double error(const Values &values) const override
#define EXPECT(condition)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
boost::shared_ptr< GaussianFactor > linearize(const Values &values) const override
static SharedNoiseModel unit2(noiseModel::Unit::Create(2))
StereoFactor(const SharedNoiseModel &sharedNoiseModel)
noiseModel::Diagonal::shared_ptr SharedDiagonal
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained,"gtsam_noiseModel_Constrained")
SmartFactorBase< StereoCamera > Base
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Pose3 body_P_sensor() const
A Stereo Camera based on two Simple Cameras.
#define EXPECT_LONGS_EQUAL(expected, actual)
size_t dim() const override
get the dimension (number of rows!) of the factor
void add(const Z &measured, const Key &key)
double error(const Values &values) const override
Vector unwhitenedError(const Cameras &cameras, const POINT &point, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
Calibration used by Bundler.
noiseModel::Base::shared_ptr SharedNoiseModel
boost::shared_ptr< GaussianFactor > linearize(const Values &values) const override