12 using namespace gtsam;
19 Point3 noise(0.0, 0.0, 0.0);
35 Point3 noise(-1.0, 0.5, 0.3);
42 Vector expectedError = noise;
67 boost::none, boost::none);
68 Matrix numerical_H1 = numericalDerivative21<Vector, Pose3, Point3>(
f,
p,
l);
69 Matrix numerical_H2 = numericalDerivative22<Vector, Pose3, Point3>(
f,
p,
l);
static int runAllTests(TestResult &result)
Some functions to compute numerical derivatives.
static Rot3 RzRyRx(double x, double y, double z, OptionalJacobian< 3, 1 > Hx=boost::none, OptionalJacobian< 3, 1 > Hy=boost::none, OptionalJacobian< 3, 1 > Hz=boost::none)
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
static Pose3 identity()
identity for group operation
static const Line3 l(Rot3(), 1, 1)
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
Vector evaluateError(const Pose3 &wTwi, const Point3 &wPwp, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const
Error = wTwi.inverse()*wPwp - measured_.
#define EXPECT(condition)
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)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
TEST(LPInitSolver, InfiniteLoopSingleVar)
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Gaussian::shared_ptr SharedGaussian
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
All noise models live in the noiseModel namespace.