16 using namespace gtsam;
26 Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3);
41 Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3);
56 Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3);
69 std::function<Vector(const Pose3&, const Point3&)>
f = [&factor](
const Pose3&
pose,
const Point3& bias) {
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
static int runAllTests(TestResult &result)
TEST(BiasedGPSFactor, errorNoiseless)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Rot2 R(Rot2::fromAngle(0.1))
Some functions to compute numerical derivatives.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
#define EXPECT(condition)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector evaluateError(const Pose3 &pose, const Point3 &bias, OptionalMatrixType H1, OptionalMatrixType H2) const override
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
All noise models live in the noiseModel namespace.