testSerializationNavigation.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 
28 
29 #include <fstream>
30 
31 using namespace std;
32 using namespace gtsam;
33 using namespace gtsam::serializationTestHelpers;
34 
35 BOOST_CLASS_EXPORT_GUID(noiseModel::Constrained, "gtsam_noiseModel_Constrained")
36 BOOST_CLASS_EXPORT_GUID(noiseModel::Diagonal, "gtsam_noiseModel_Diagonal")
37 BOOST_CLASS_EXPORT_GUID(noiseModel::Gaussian, "gtsam_noiseModel_Gaussian")
38 BOOST_CLASS_EXPORT_GUID(noiseModel::Unit, "gtsam_noiseModel_Unit")
39 BOOST_CLASS_EXPORT_GUID(noiseModel::Isotropic, "gtsam_noiseModel_Isotropic")
40 BOOST_CLASS_EXPORT_GUID(SharedNoiseModel, "gtsam_SharedNoiseModel")
41 BOOST_CLASS_EXPORT_GUID(SharedDiagonal, "gtsam_SharedDiagonal")
42 BOOST_CLASS_EXPORT_GUID(PreintegratedImuMeasurements, "gtsam_PreintegratedImuMeasurements")
43 BOOST_CLASS_EXPORT_GUID(PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams")
44 BOOST_CLASS_EXPORT_GUID(PreintegratedCombinedMeasurements, "gtsam_PreintegratedCombinedMeasurements")
45 
46 template <typename P>
48  // Create default parameters with Z-down and above noise paramaters
49  auto p = P::Params::MakeSharedD(9.81);
50  p->body_P_sensor = Pose3(Rot3::Ypr(0, 0, M_PI), Point3(0, 0, 0));
51  p->accelerometerCovariance = 1e-7 * I_3x3;
52  p->gyroscopeCovariance = 1e-8 * I_3x3;
53  p->integrationCovariance = 1e-9 * I_3x3;
54 
55  const double deltaT = 0.005;
56 
57  // Biases (acc, rot)
58  const imuBias::ConstantBias priorBias(Vector3(0, 0, 0), Vector3(0, 0.01, 0));
59 
60  P pim(p, priorBias);
61 
62  // measurements are needed for non-inf noise model, otherwise will throw error
63  // when deserialize
64  const Vector3 measuredOmega(0, 0.01, 0);
65  const Vector3 measuredAcc(0, 0, -9.81);
66 
67  for (int j = 0; j < 200; ++j)
68  pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
69 
70  return pim;
71 }
72 
73 /* ************************************************************************* */
74 TEST(ImuFactor, serialization) {
75  auto pim = getPreintegratedMeasurements<PreintegratedImuMeasurements>();
76 
77  EXPECT(equalsObj<PreintegratedImuMeasurements>(pim));
78  EXPECT(equalsXML<PreintegratedImuMeasurements>(pim));
79  EXPECT(equalsBinary<PreintegratedImuMeasurements>(pim));
80 
81  ImuFactor factor(1, 2, 3, 4, 5, pim);
82 
83  EXPECT(equalsObj<ImuFactor>(factor));
84  EXPECT(equalsXML<ImuFactor>(factor));
85  EXPECT(equalsBinary<ImuFactor>(factor));
86 }
87 
88 /* ************************************************************************* */
89 TEST(ImuFactor2, serialization) {
90  auto pim = getPreintegratedMeasurements<PreintegratedImuMeasurements>();
91 
92  ImuFactor2 factor(1, 2, 3, pim);
93 
94  EXPECT(equalsObj<ImuFactor2>(factor));
95  EXPECT(equalsXML<ImuFactor2>(factor));
96  EXPECT(equalsBinary<ImuFactor2>(factor));
97 }
98 
99 /* ************************************************************************* */
100 TEST(CombinedImuFactor, Serialization) {
101  auto pim = getPreintegratedMeasurements<PreintegratedCombinedMeasurements>();
102 
103  EXPECT(equalsObj<PreintegratedCombinedMeasurements>(pim));
104  EXPECT(equalsXML<PreintegratedCombinedMeasurements>(pim));
105  EXPECT(equalsBinary<PreintegratedCombinedMeasurements>(pim));
106 
107  const CombinedImuFactor factor(1, 2, 3, 4, 5, 6, pim);
108 
109  EXPECT(equalsObj<CombinedImuFactor>(factor));
110  EXPECT(equalsXML<CombinedImuFactor>(factor));
111  EXPECT(equalsBinary<CombinedImuFactor>(factor));
112 }
113 
114 /* ************************************************************************* */
115 TEST(Rot3AttitudeFactor, Serialization) {
116  Unit3 nDown(0, 0, -1);
117  SharedNoiseModel model = noiseModel::Isotropic::Sigma(2, 0.25);
118  Rot3AttitudeFactor factor(0, nDown, model);
119 
120  EXPECT(serializationTestHelpers::equalsObj(factor));
121  EXPECT(serializationTestHelpers::equalsXML(factor));
122  EXPECT(serializationTestHelpers::equalsBinary(factor));
123 }
124 
125 /* ************************************************************************* */
126 TEST(Pose3AttitudeFactor, Serialization) {
127  Unit3 nDown(0, 0, -1);
128  SharedNoiseModel model = noiseModel::Isotropic::Sigma(2, 0.25);
129  Pose3AttitudeFactor factor(0, nDown, model);
130 
131  EXPECT(serializationTestHelpers::equalsObj(factor));
132  EXPECT(serializationTestHelpers::equalsXML(factor));
133  EXPECT(serializationTestHelpers::equalsBinary(factor));
134 }
135 
136 /* ************************************************************************* */
137 int main() {
138  TestResult tr;
139  return TestRegistry::runAllTests(tr);
140 }
141 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
Gaussian
double Gaussian(double mu, double sigma, double z)
Gaussian density function.
Definition: testGaussianMixture.cpp:47
getPreintegratedMeasurements
P getPreintegratedMeasurements()
Definition: testSerializationNavigation.cpp:47
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
BOOST_CLASS_EXPORT_GUID
BOOST_CLASS_EXPORT_GUID(DecisionTreeFactor, "gtsam_DecisionTreeFactor")
main
int main()
Definition: testSerializationNavigation.cpp:137
gtsam::ImuFactor2
Definition: ImuFactor.h:264
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
gtsam::noiseModel::Constrained
Definition: NoiseModel.h:404
TEST
TEST(ImuFactor, serialization)
Definition: testSerializationNavigation.cpp:74
common::deltaT
static const double deltaT
Definition: testImuFactor.cpp:183
AttitudeFactor.h
Header file for Attitude factor.
biased_x_rotation::measuredOmega
const Vector3 measuredOmega
Definition: testPreintegratedRotation.cpp:35
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::Pose3
Definition: Pose3.h:37
gtsam::Rot3AttitudeFactor
Definition: AttitudeFactor.h:91
gtsam::PreintegratedImuMeasurements
Definition: ImuFactor.h:68
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:764
gtsam::Pose3AttitudeFactor
Definition: AttitudeFactor.h:167
gtsam::ImuFactor
Definition: ImuFactor.h:169
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
serializationTestHelpers.h
TestResult
Definition: TestResult.h:26
gtsam::CombinedImuFactor
Definition: CombinedImuFactor.h:205
gtsam::imuBias::ConstantBias
Definition: ImuBias.h:32
gtsam
traits
Definition: SFMdata.h:40
std
Definition: BFloat16.h:88
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Diagonal
static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix &covariance)
Definition: ScenarioRunner.h:27
P
static double P[]
Definition: ellpe.c:68
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
common::measuredAcc
static const Vector3 measuredAcc
Definition: testImuFactor.cpp:181
CombinedImuFactor.h
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
M_PI
#define M_PI
Definition: mconf.h:117
gtsam::PreintegrationCombinedParams
Definition: PreintegrationCombinedParams.h:36
gtsam::PreintegratedCombinedMeasurements
Definition: CombinedImuFactor.h:66
ImuFactor.h


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:29