testPoseToPointFactor.h
Go to the documentation of this file.
1 
11 
12 using namespace gtsam;
13 using namespace gtsam::noiseModel;
14 
16 TEST(PoseToPointFactor, errorNoiseless) {
18  Point3 point(1.0, 2.0, 3.0);
19  Point3 noise(0.0, 0.0, 0.0);
20  Point3 measured = t + noise;
21 
22  Key pose_key(1);
23  Key point_key(2);
24  PoseToPointFactor factor(pose_key, point_key, measured,
25  Isotropic::Sigma(3, 0.05));
26  Vector expectedError = Vector3(0.0, 0.0, 0.0);
27  Vector actualError = factor.evaluateError(pose, point);
28  EXPECT(assert_equal(expectedError, actualError, 1E-5));
29 }
30 
32 TEST(PoseToPointFactor, errorNoise) {
34  Point3 point(1.0, 2.0, 3.0);
35  Point3 noise(-1.0, 0.5, 0.3);
36  Point3 measured = t + noise;
37 
38  Key pose_key(1);
39  Key point_key(2);
40  PoseToPointFactor factor(pose_key, point_key, measured,
41  Isotropic::Sigma(3, 0.05));
42  Vector expectedError = noise;
43  Vector actualError = factor.evaluateError(pose, point);
44  EXPECT(assert_equal(expectedError, actualError, 1E-5));
45 }
46 
48 TEST(PoseToPointFactor, jacobian) {
49  // Measurement
50  gtsam::Point3 l_meas = gtsam::Point3(1, 2, 3);
51 
52  // Linearisation point
53  gtsam::Point3 p_t = gtsam::Point3(-5, 12, 2);
54  gtsam::Rot3 p_R = gtsam::Rot3::RzRyRx(1.5 * M_PI, -0.3 * M_PI, 0.4 * M_PI);
55  Pose3 p(p_R, p_t);
56 
57  gtsam::Point3 l = gtsam::Point3(3, 0, 5);
58 
59  // Factor
60  Key pose_key(1);
61  Key point_key(2);
62  SharedGaussian noise = noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 0.1));
63  PoseToPointFactor factor(pose_key, point_key, l_meas, noise);
64 
65  // Calculate numerical derivatives
66  auto f = boost::bind(&PoseToPointFactor::evaluateError, factor, _1, _2,
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);
70 
71  // Use the factor to calculate the derivative
72  Matrix actual_H1;
73  Matrix actual_H2;
74  factor.evaluateError(p, l, actual_H1, actual_H2);
75 
76  // Verify we get the expected error
77  EXPECT_TRUE(assert_equal(numerical_H1, actual_H1, 1e-8));
78  EXPECT_TRUE(assert_equal(numerical_H2, actual_H2, 1e-8));
79 }
80 
81 /* ************************************************************************* */
82 int main() {
83  TestResult tr;
84  return TestRegistry::runAllTests(tr);
85 }
86 /* ************************************************************************* */
Key E(std::uint64_t j)
int main()
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
#define M_PI
Definition: main.h:78
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.
Definition: Rot3M.cpp:85
Point3 point(10, 0,-5)
static Pose3 identity()
identity for group operation
Definition: Pose3.h:103
static const Line3 l(Rot3(), 1, 1)
Eigen::VectorXd Vector
Definition: Vector.h:38
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)
Definition: Test.h:151
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270
float * p
TEST(LPInitSolver, InfiniteLoopSingleVar)
Vector3 Point3
Definition: Point3.h:35
Point3 measured
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Gaussian::shared_ptr SharedGaussian
Definition: NoiseModel.h:735
Point2 t(10, 10)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:567
All noise models live in the noiseModel namespace.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:48:48