28 using namespace gtsam;
45 Rot3::RzRyRx(0.179693265735950, 0.002945368776519, 0.102274823253840),
46 Point3(-3.37493895, 6.14660244, -8.93650986));
53 Matrix expectedH1 = numericalDerivative11<Vector5,Pose3>(
54 boost::bind(&EssentialMatrixConstraint::evaluateError, &factor, _1, pose2,
55 boost::none, boost::none),
pose1);
56 Matrix expectedH2 = numericalDerivative11<Vector5,Pose3>(
57 boost::bind(&EssentialMatrixConstraint::evaluateError, &factor, pose1, _1,
58 boost::none, boost::none),
pose2);
Provides additional testing facilities for common data structures.
static int runAllTests(TestResult &result)
noiseModel::Diagonal::shared_ptr model
Some functions to compute numerical derivatives.
Point3 trueTranslation(0.1, 0, 0)
Vector evaluateError(const Pose3 &p1, const Pose3 &p2, boost::optional< Matrix & > Hp1=boost::none, boost::optional< Matrix & > Hp2=boost::none) const override
TEST(EssentialMatrixConstraint, test)
Represents a 3D point on a unit sphere.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
Unit3 trueDirection(trueTranslation)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel