testBearingFactor.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 #include <gtsam/geometry/Pose2.h>
21 #include <gtsam/geometry/Pose3.h>
26 
28 
29 using namespace std;
30 using namespace gtsam;
31 
32 Key poseKey(1);
33 Key pointKey(2);
34 
36 double measurement2D(10.0);
37 static SharedNoiseModel model2D(noiseModel::Isotropic::Sigma(1, 0.5));
39 
41 Unit3 measurement3D = Pose3().bearing(Point3(1, 0, 0)); // has to match values!
42 static SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(2, 0.5));
43 BearingFactor3D factor3D(poseKey, pointKey, measurement3D, model3D);
44 
45 /* ************************************************************************* */
46 // Export Noisemodels
47 // See http://www.boost.org/doc/libs/1_32_0/libs/serialization/doc/special.html
49 
50 /* ************************************************************************* */
51 TEST(BearingFactor, Serialization2D) {
55 }
56 
57 /* ************************************************************************* */
59  // Serialize the factor
60  std::string serialized = serializeXML(factor2D);
61 
62  // And de-serialize it
63  BearingFactor2D factor;
64  deserializeXML(serialized, factor);
65 
66  // Set the linearization point
67  Values values;
68  values.insert(poseKey, Pose2(1.0, 2.0, 0.57));
69  values.insert(pointKey, Point2(-4.0, 11.0));
70 
71  EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression({poseKey, pointKey}),
72  values, 1e-7, 1e-5);
73  EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5);
74 }
75 
76 /* ************************************************************************* */
77 TEST(BearingFactor, Serialization3D) {
81 }
82 
83 /* ************************************************************************* */
84 // TODO(frank): this test is disabled (for now) because the macros below are
85 // incompatible with the Unit3 localCoordinates. The issue is the following:
86 // For factors, we want to use Local(value, measured), because we need the error
87 // to be expressed in the tangent space of value. This surfaced in the Unit3 case
88 // where the tangent space can be radically didfferent from one value to the next.
89 // For derivatives, we want Local(constant, varying), because we need a derivative
90 // in a constant tangent space. But since the macros below call whitenedError
91 // which calls Local(value,measured), we actually call the reverse. This does not
92 // matter for types with a commutative Local, but matters a lot for Unit3.
93 // More thinking needed about what the right thing is, here...
94 //TEST(BearingFactor, 3D) {
95 // // Serialize the factor
96 // std::string serialized = serializeXML(factor3D);
97 //
98 // // And de-serialize it
99 // BearingFactor3D factor;
100 // deserializeXML(serialized, factor);
101 //
102 // // Set the linearization point
103 // Values values;
104 // values.insert(poseKey, Pose3());
105 // values.insert(pointKey, Point3(1, 0, 0));
106 //
107 // EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression({poseKey, pointKey}),
108 // values, 1e-7, 1e-5);
109 // EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5);
110 //}
111 
112 /* ************************************************************************* */
113 int main() {
114  TestResult tr;
115  return TestRegistry::runAllTests(tr);
116 }
117 /* ************************************************************************* */
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself=boost::none, OptionalJacobian< 2, 3 > Hpoint=boost::none) const
Definition: Pose3.cpp:360
BearingFactor< Pose3, Point3 > BearingFactor3D
static int runAllTests(TestResult &result)
void insert(Key j, const Value &val)
Definition: Values.cpp:140
BOOST_CLASS_EXPORT(gtsam::noiseModel::Isotropic)
Vector2 Point2
Definition: Point2.h:27
leaf::MyValues values
static SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(2, 0.5))
Definition: Half.h:150
double measurement2D(10.0)
Evaluate derivatives of a nonlinear factor numerically.
static SharedNoiseModel model2D(noiseModel::Isotropic::Sigma(1, 0.5))
Key pointKey(2)
BearingFactor3D factor3D(poseKey, pointKey, measurement3D, model3D)
#define EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by an expression against finite differences.
void deserializeXML(const std::string &serialized, T &output, const std::string &name="data")
deserializes from a string in XML
TEST(BearingFactor, Serialization2D)
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Key poseKey(1)
BearingFactor< Pose2, Point2 > BearingFactor2D
Test harness methods for expressions.
Unit3 measurement3D
Expression< T > expression(const typename Base::ArrayNKeys &keys) const override
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
int main()
BearingFactor2D factor2D(poseKey, pointKey, measurement2D, model2D)
traits
Definition: chartTesting.h:28
std::string serializeXML(const T &input, const std::string &name="data")
serializes to a string in XML
#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by a factor against finite differences.
Vector3 Point3
Definition: Point3.h:35
2D Pose
3D Pose
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734


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