AHRSFactor.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 
21 #include <iostream>
22 
23 using namespace std;
24 
25 namespace gtsam {
26 
27 //------------------------------------------------------------------------------
28 // Inner class PreintegratedMeasurements
29 //------------------------------------------------------------------------------
30 void PreintegratedAhrsMeasurements::print(const string& s) const {
32  cout << "biasHat [" << biasHat_.transpose() << "]" << endl;
33  cout << " PreintMeasCov [ " << preintMeasCov_ << " ]" << endl;
34 }
35 
36 //------------------------------------------------------------------------------
37 bool PreintegratedAhrsMeasurements::equals(
38  const PreintegratedAhrsMeasurements& other, double tol) const {
39  return PreintegratedRotation::equals(other, tol) &&
40  equal_with_abs_tol(biasHat_, other.biasHat_, tol);
41 }
42 
43 //------------------------------------------------------------------------------
44 void PreintegratedAhrsMeasurements::resetIntegration() {
45  PreintegratedRotation::resetIntegration();
46  preintMeasCov_.setZero();
47 }
48 
49 //------------------------------------------------------------------------------
50 void PreintegratedAhrsMeasurements::integrateMeasurement(
51  const Vector3& measuredOmega, double deltaT) {
52  Matrix3 Fr;
53  PreintegratedRotation::integrateGyroMeasurement(measuredOmega, biasHat_,
54  deltaT, &Fr);
55 
56  // First order uncertainty propagation
57  // The deltaT allows to pass from continuous time noise to discrete time
58  // noise. Comparing with the IMUFactor.cpp implementation, the latter is an
59  // approximation for C * (wCov / dt) * C.transpose(), with C \approx I * dt.
60  preintMeasCov_ = Fr * preintMeasCov_ * Fr.transpose() + p().gyroscopeCovariance * deltaT;
61 }
62 
63 //------------------------------------------------------------------------------
64 Vector3 PreintegratedAhrsMeasurements::predict(const Vector3& bias,
65  OptionalJacobian<3,3> H) const {
66  const Vector3 biasOmegaIncr = bias - biasHat_;
67  const Rot3 biascorrected = biascorrectedDeltaRij(biasOmegaIncr, H);
68  Matrix3 D_omega_biascorrected;
69  const Vector3 omega = Rot3::Logmap(biascorrected, H ? &D_omega_biascorrected : 0);
70  if (H) (*H) = D_omega_biascorrected * (*H);
71  return omega;
72 }
73 //------------------------------------------------------------------------------
74 Vector PreintegratedAhrsMeasurements::DeltaAngles(
75  const Vector& msr_gyro_t, const double msr_dt,
76  const Vector3& delta_angles) {
77 
78  // Note: all delta terms refer to an IMU\sensor system at t0
79 
80  // Calculate the corrected measurements using the Bias object
81  Vector body_t_omega_body = msr_gyro_t;
82 
83  Rot3 R_t_to_t0 = Rot3::Expmap(delta_angles);
84 
85  R_t_to_t0 = R_t_to_t0 * Rot3::Expmap(body_t_omega_body * msr_dt);
86  return Rot3::Logmap(R_t_to_t0);
87 }
88 
89 //------------------------------------------------------------------------------
90 // AHRSFactor methods
91 //------------------------------------------------------------------------------
92 AHRSFactor::AHRSFactor(
93  Key rot_i, Key rot_j, Key bias,
94  const PreintegratedAhrsMeasurements& preintegratedMeasurements)
95  : Base(noiseModel::Gaussian::Covariance(
96  preintegratedMeasurements.preintMeasCov_),
97  rot_i, rot_j, bias),
98  _PIM_(preintegratedMeasurements) {}
99 
101 //------------------------------------------------------------------------------
102  return std::static_pointer_cast<gtsam::NonlinearFactor>(
104 }
105 
106 //------------------------------------------------------------------------------
107 void AHRSFactor::print(const string& s,
108  const KeyFormatter& keyFormatter) const {
109  cout << s << "AHRSFactor(" << keyFormatter(this->key<1>()) << ","
110  << keyFormatter(this->key<2>()) << "," << keyFormatter(this->key<3>()) << ",";
111  _PIM_.print(" preintegrated measurements:");
112  noiseModel_->print(" noise model: ");
113 }
114 
115 //------------------------------------------------------------------------------
116 bool AHRSFactor::equals(const NonlinearFactor& other, double tol) const {
117  const This *e = dynamic_cast<const This*>(&other);
118  return e != nullptr && Base::equals(*e, tol) && _PIM_.equals(e->_PIM_, tol);
119 }
120 
121 //------------------------------------------------------------------------------
123  const Vector3& bias, OptionalMatrixType H1,
124  OptionalMatrixType H2, OptionalMatrixType H3) const {
125 
126  // Do bias correction, if (H3) will contain 3*3 derivative used below
127  const Vector3 biascorrectedOmega = _PIM_.predict(bias, H3);
128 
129  // Coriolis term
131  const Vector3 correctedOmega = biascorrectedOmega - coriolis;
132 
133  // Prediction
134  const Rot3 correctedDeltaRij = Rot3::Expmap(correctedOmega);
135 
136  // Get error between actual and prediction
137  const Rot3 actualRij = Ri.between(Rj);
138  const Rot3 fRrot = correctedDeltaRij.between(actualRij);
139  Vector3 fR = Rot3::Logmap(fRrot);
140 
141  // Terms common to derivatives
142  const Matrix3 D_cDeltaRij_cOmega = Rot3::ExpmapDerivative(correctedOmega);
143  const Matrix3 D_fR_fRrot = Rot3::LogmapDerivative(fR);
144 
145  if (H1) {
146  // dfR/dRi
147  H1->resize(3, 3);
148  Matrix3 D_coriolis = -D_cDeltaRij_cOmega * skewSymmetric(coriolis);
149  (*H1)
150  << D_fR_fRrot * (-actualRij.transpose() - fRrot.transpose() * D_coriolis);
151  }
152 
153  if (H2) {
154  // dfR/dPosej
155  H2->resize(3, 3);
156  (*H2) << D_fR_fRrot;
157  }
158 
159  if (H3) {
160  // dfR/dBias, note H3 contains derivative of predict
161  const Matrix3 JbiasOmega = D_cDeltaRij_cOmega * (*H3);
162  H3->resize(3, 3);
163  (*H3) << D_fR_fRrot * (-fRrot.transpose() * JbiasOmega);
164  }
165 
166  Vector error(3);
167  error << fR;
168  return error;
169 }
170 
171 //------------------------------------------------------------------------------
172 Rot3 AHRSFactor::Predict(const Rot3& rot_i, const Vector3& bias,
173  const PreintegratedAhrsMeasurements& pim) {
174  const Vector3 biascorrectedOmega = pim.predict(bias);
175 
176  // Coriolis term
177  const Vector3 coriolis = pim.integrateCoriolis(rot_i);
178 
179  const Vector3 correctedOmega = biascorrectedOmega - coriolis;
180  const Rot3 correctedDeltaRij = Rot3::Expmap(correctedOmega);
181 
182  return rot_i.compose(correctedDeltaRij);
183 }
184 
185 //------------------------------------------------------------------------------
188  const Vector3& omegaCoriolis,
189  const std::optional<Pose3>& body_P_sensor)
190  : Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), rot_i, rot_j,
191  bias),
192  _PIM_(pim) {
193  auto p = std::make_shared<PreintegratedAhrsMeasurements::Params>(pim.p());
194  p->body_P_sensor = body_P_sensor;
195  _PIM_.p_ = p;
196 }
197 
198 //------------------------------------------------------------------------------
199 Rot3 AHRSFactor::predict(const Rot3& rot_i, const Vector3& bias,
201  const Vector3& omegaCoriolis,
202  const std::optional<Pose3>& body_P_sensor) {
203  auto p = std::make_shared<PreintegratedAhrsMeasurements::Params>(pim.p());
204  p->omegaCoriolis = omegaCoriolis;
205  p->body_P_sensor = body_P_sensor;
206  PreintegratedAhrsMeasurements newPim = pim;
207  newPim.p_ = p;
208  return Predict(rot_i, bias, newPim);
209 }
210 
211 } // namespace gtsam
Gaussian
double Gaussian(double mu, double sigma, double z)
Gaussian density function.
Definition: testGaussianMixture.cpp:47
gtsam::AHRSFactor::predict
static Rot3 predict(const Rot3 &rot_i, const Vector3 &bias, const PreintegratedAhrsMeasurements &pim, const Vector3 &omegaCoriolis, const std::optional< Pose3 > &body_P_sensor={})
Definition: AHRSFactor.cpp:199
gtsam::LieGroup::between
Class between(const Class &g) const
Definition: Lie.h:52
H
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
Definition: gnuplot_common_settings.hh:74
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:78
Eigen::internal::print
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Definition: NEON/PacketMath.h:3115
gtsam::AHRSFactor::AHRSFactor
AHRSFactor()
Definition: AHRSFactor.h:143
gtsam::AHRSFactor::print
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: AHRSFactor.cpp:107
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::NoiseModelFactor::error
double error(const Values &c) const override
Definition: NonlinearFactor.cpp:136
AHRSFactor.h
gtsam::AHRSFactor::equals
bool equals(const NonlinearFactor &, double tol=1e-9) const override
equals
Definition: AHRSFactor.cpp:116
gtsam::LieGroup::compose
Class compose(const Class &g) const
Definition: Lie.h:48
biased_x_rotation::bias
const Vector3 bias(1, 2, 3)
gtsam::equal_with_abs_tol
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:80
gtsam::Factor
Definition: Factor.h:70
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
gtsam::NoiseModelFactor::noiseModel_
SharedNoiseModel noiseModel_
Definition: NonlinearFactor.h:205
body_P_sensor
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::skewSymmetric
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:400
gtsam::PreintegratedAhrsMeasurements::predict
Vector3 predict(const Vector3 &bias, OptionalJacobian< 3, 3 > H={}) const
Definition: AHRSFactor.cpp:64
gtsam::Rot3::LogmapDerivative
static Matrix3 LogmapDerivative(const Vector3 &x)
Derivative of Logmap.
Definition: Rot3.cpp:241
gtsam::AHRSFactor::evaluateError
Vector evaluateError(const Rot3 &rot_i, const Rot3 &rot_j, const Vector3 &bias, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override
vector of errors
Definition: AHRSFactor.cpp:122
gtsam::AHRSFactor::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: AHRSFactor.cpp:100
gtsam::PreintegratedAhrsMeasurements::equals
bool equals(const PreintegratedAhrsMeasurements &, double tol=1e-9) const
equals
Definition: AHRSFactor.cpp:37
biased_x_rotation::omega
const double omega
Definition: testPreintegratedRotation.cpp:32
common::deltaT
static const double deltaT
Definition: testImuFactor.cpp:183
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
biased_x_rotation::measuredOmega
const Vector3 measuredOmega
Definition: testPreintegratedRotation.cpp:35
gtsam::PreintegratedRotation::integrateCoriolis
Vector3 integrateCoriolis(const Rot3 &rot_i) const
Integrate coriolis correction in body frame rot_i.
Definition: PreintegratedRotation.cpp:139
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::PreintegratedAhrsMeasurements
Definition: AHRSFactor.h:36
gtsam::KeyFormatter
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
gtsam::NoiseModelFactorN< Rot3, Rot3, Vector3 >
gtsam::AHRSFactor::_PIM_
PreintegratedAhrsMeasurements _PIM_
Definition: AHRSFactor.h:140
gtsam::NoiseModelFactor::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: NonlinearFactor.cpp:80
gtsam::AHRSFactor::This
AHRSFactor This
Definition: AHRSFactor.h:137
gtsam
traits
Definition: SFMdata.h:40
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::PreintegratedAhrsMeasurements::p
Params & p() const
Definition: AHRSFactor.h:80
gtsam::Rot3::ExpmapDerivative
static Matrix3 ExpmapDerivative(const Vector3 &x)
Derivative of Expmap.
Definition: Rot3.cpp:236
std
Definition: BFloat16.h:88
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:68
gtsam::Rot3::Expmap
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Definition: Rot3.h:374
p
float * p
Definition: Tutorial_Map_using.cpp:9
coriolis
std::function< Vector9(const NavState &, const bool &)> coriolis
Definition: testNavState.cpp:174
gtsam::Rot3::transpose
Matrix3 transpose() const
Definition: Rot3M.cpp:143
gtsam::AHRSFactor::Predict
static Rot3 Predict(const Rot3 &rot_i, const Vector3 &bias, const PreintegratedAhrsMeasurements &pim)
Definition: AHRSFactor.cpp:172
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Rot3::Logmap
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H={})
Definition: Rot3M.cpp:157
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
gtsam::PreintegratedAhrsMeasurements::print
void print(const std::string &s="Preintegrated Measurements: ") const
print
Definition: AHRSFactor.cpp:30
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::PreintegratedRotation::p_
std::shared_ptr< Params > p_
Parameters.
Definition: PreintegratedRotation.h:123


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:01:48