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 
53  Matrix3 D_incrR_integratedOmega, Fr;
54  PreintegratedRotation::integrateMeasurement(measuredOmega,
55  biasHat_, deltaT, &D_incrR_integratedOmega, &Fr);
56 
57  // first order uncertainty propagation
58  // the deltaT allows to pass from continuous time noise to discrete time noise
59  preintMeasCov_ = Fr * preintMeasCov_ * Fr.transpose() + p().gyroscopeCovariance * deltaT;
60 }
61 
62 //------------------------------------------------------------------------------
63 Vector3 PreintegratedAhrsMeasurements::predict(const Vector3& bias,
64  OptionalJacobian<3,3> H) const {
65  const Vector3 biasOmegaIncr = bias - biasHat_;
66  const Rot3 biascorrected = biascorrectedDeltaRij(biasOmegaIncr, H);
67  Matrix3 D_omega_biascorrected;
68  const Vector3 omega = Rot3::Logmap(biascorrected, H ? &D_omega_biascorrected : 0);
69  if (H) (*H) = D_omega_biascorrected * (*H);
70  return omega;
71 }
72 //------------------------------------------------------------------------------
73 Vector PreintegratedAhrsMeasurements::DeltaAngles(
74  const Vector& msr_gyro_t, const double msr_dt,
75  const Vector3& delta_angles) {
76 
77  // Note: all delta terms refer to an IMU\sensor system at t0
78 
79  // Calculate the corrected measurements using the Bias object
80  Vector body_t_omega_body = msr_gyro_t;
81 
82  Rot3 R_t_to_t0 = Rot3::Expmap(delta_angles);
83 
84  R_t_to_t0 = R_t_to_t0 * Rot3::Expmap(body_t_omega_body * msr_dt);
85  return Rot3::Logmap(R_t_to_t0);
86 }
87 
88 //------------------------------------------------------------------------------
89 // AHRSFactor methods
90 //------------------------------------------------------------------------------
91 AHRSFactor::AHRSFactor(
92  Key rot_i, Key rot_j, Key bias,
93  const PreintegratedAhrsMeasurements& preintegratedMeasurements)
94  : Base(noiseModel::Gaussian::Covariance(
95  preintegratedMeasurements.preintMeasCov_),
96  rot_i, rot_j, bias),
97  _PIM_(preintegratedMeasurements) {}
98 
100 //------------------------------------------------------------------------------
101  return std::static_pointer_cast<gtsam::NonlinearFactor>(
103 }
104 
105 //------------------------------------------------------------------------------
106 void AHRSFactor::print(const string& s,
107  const KeyFormatter& keyFormatter) const {
108  cout << s << "AHRSFactor(" << keyFormatter(this->key<1>()) << ","
109  << keyFormatter(this->key<2>()) << "," << keyFormatter(this->key<3>()) << ",";
110  _PIM_.print(" preintegrated measurements:");
111  noiseModel_->print(" noise model: ");
112 }
113 
114 //------------------------------------------------------------------------------
115 bool AHRSFactor::equals(const NonlinearFactor& other, double tol) const {
116  const This *e = dynamic_cast<const This*>(&other);
117  return e != nullptr && Base::equals(*e, tol) && _PIM_.equals(e->_PIM_, tol);
118 }
119 
120 //------------------------------------------------------------------------------
122  const Vector3& bias, OptionalMatrixType H1,
123  OptionalMatrixType H2, OptionalMatrixType H3) const {
124 
125  // Do bias correction, if (H3) will contain 3*3 derivative used below
126  const Vector3 biascorrectedOmega = _PIM_.predict(bias, H3);
127 
128  // Coriolis term
130  const Vector3 correctedOmega = biascorrectedOmega - coriolis;
131 
132  // Prediction
133  const Rot3 correctedDeltaRij = Rot3::Expmap(correctedOmega);
134 
135  // Get error between actual and prediction
136  const Rot3 actualRij = Ri.between(Rj);
137  const Rot3 fRrot = correctedDeltaRij.between(actualRij);
138  Vector3 fR = Rot3::Logmap(fRrot);
139 
140  // Terms common to derivatives
141  const Matrix3 D_cDeltaRij_cOmega = Rot3::ExpmapDerivative(correctedOmega);
142  const Matrix3 D_fR_fRrot = Rot3::LogmapDerivative(fR);
143 
144  if (H1) {
145  // dfR/dRi
146  H1->resize(3, 3);
147  Matrix3 D_coriolis = -D_cDeltaRij_cOmega * skewSymmetric(coriolis);
148  (*H1)
149  << D_fR_fRrot * (-actualRij.transpose() - fRrot.transpose() * D_coriolis);
150  }
151 
152  if (H2) {
153  // dfR/dPosej
154  H2->resize(3, 3);
155  (*H2) << D_fR_fRrot;
156  }
157 
158  if (H3) {
159  // dfR/dBias, note H3 contains derivative of predict
160  const Matrix3 JbiasOmega = D_cDeltaRij_cOmega * (*H3);
161  H3->resize(3, 3);
162  (*H3) << D_fR_fRrot * (-fRrot.transpose() * JbiasOmega);
163  }
164 
165  Vector error(3);
166  error << fR;
167  return error;
168 }
169 
170 //------------------------------------------------------------------------------
171 Rot3 AHRSFactor::Predict(const Rot3& rot_i, const Vector3& bias,
172  const PreintegratedAhrsMeasurements& pim) {
173  const Vector3 biascorrectedOmega = pim.predict(bias);
174 
175  // Coriolis term
176  const Vector3 coriolis = pim.integrateCoriolis(rot_i);
177 
178  const Vector3 correctedOmega = biascorrectedOmega - coriolis;
179  const Rot3 correctedDeltaRij = Rot3::Expmap(correctedOmega);
180 
181  return rot_i.compose(correctedDeltaRij);
182 }
183 
184 //------------------------------------------------------------------------------
185 AHRSFactor::AHRSFactor(Key rot_i, Key rot_j, Key bias,
187  const Vector3& omegaCoriolis,
188  const std::optional<Pose3>& body_P_sensor)
189  : Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), rot_i, rot_j,
190  bias),
191  _PIM_(pim) {
192  auto p = std::make_shared<PreintegratedAhrsMeasurements::Params>(pim.p());
193  p->body_P_sensor = body_P_sensor;
194  _PIM_.p_ = p;
195 }
196 
197 //------------------------------------------------------------------------------
198 Rot3 AHRSFactor::predict(const Rot3& rot_i, const Vector3& bias,
200  const Vector3& omegaCoriolis,
201  const std::optional<Pose3>& body_P_sensor) {
202  auto p = std::make_shared<PreintegratedAhrsMeasurements::Params>(pim.p());
203  p->omegaCoriolis = omegaCoriolis;
204  p->body_P_sensor = body_P_sensor;
205  PreintegratedAhrsMeasurements newPim = pim;
206  newPim.p_ = p;
207  return Predict(rot_i, bias, newPim);
208 }
209 
210 } // namespace gtsam
Eigen::Vector3d Vector3
Definition: Vector.h:43
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
static Rot3 Predict(const Rot3 &rot_i, const Vector3 &bias, const PreintegratedAhrsMeasurements &pim)
Definition: AHRSFactor.cpp:171
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
Pose2_ Expmap(const Vector3_ &xi)
Definition: BFloat16.h:88
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
void print(const std::string &s="Preintegrated Measurements: ") const
print
Definition: AHRSFactor.cpp:30
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: AHRSFactor.cpp:106
Vector3 predict(const Vector3 &bias, OptionalJacobian< 3, 3 > H={}) const
Definition: AHRSFactor.cpp:63
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
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Definition: Rot3.h:374
AHRSFactor This
Definition: AHRSFactor.h:137
const SharedNoiseModel & noiseModel() const
access to the noise model
Matrix * OptionalMatrixType
Eigen::VectorXd Vector
Definition: Vector.h:38
static Matrix3 LogmapDerivative(const Vector3 &x)
Derivative of Logmap.
Definition: Rot3.cpp:241
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H={})
Definition: Rot3M.cpp:157
static Matrix3 ExpmapDerivative(const Vector3 &x)
Derivative of Expmap.
Definition: Rot3.cpp:236
static const double deltaT
bool equals(const PreintegratedAhrsMeasurements &, double tol=1e-9) const
equals
Definition: AHRSFactor.cpp:37
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: AHRSFactor.cpp:99
Vector::Scalar omega(const Vector &t, const Vector &s, RealScalar angle)
Definition: IDRS.h:36
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Class compose(const Class &g) const
Definition: Lie.h:48
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
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:80
Vector3 integrateCoriolis(const Rot3 &rot_i) const
Integrate coriolis correction in body frame rot_i.
traits
Definition: chartTesting.h:28
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:400
static const Vector3 measuredOmega(w, 0, 0)
SharedNoiseModel noiseModel_
double error(const Values &c) const override
std::function< Vector9(const NavState &, const bool &)> coriolis
bool equals(const NonlinearFactor &, double tol=1e-9) const override
equals
Definition: AHRSFactor.cpp:115
Class between(const Class &g) const
Definition: Lie.h:52
std::shared_ptr< This > shared_ptr
float * p
std::shared_ptr< Params > p_
Parameters.
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:198
const G double tol
Definition: Group.h:86
Vector3 biasHat_
Angular rate bias values used during preintegration.
Definition: AHRSFactor.h:40
Matrix3 transpose() const
Definition: Rot3M.cpp:143
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:121
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
PreintegratedAhrsMeasurements _PIM_
Definition: AHRSFactor.h:140


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:33:53