TangentPreintegration.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 
18 #include "TangentPreintegration.h"
20 #include <boost/make_shared.hpp>
21 
22 using namespace std;
23 
24 namespace gtsam {
25 
26 //------------------------------------------------------------------------------
27 TangentPreintegration::TangentPreintegration(const boost::shared_ptr<Params>& p,
28  const Bias& biasHat) :
29  PreintegrationBase(p, biasHat) {
31 }
32 
33 //------------------------------------------------------------------------------
35  deltaTij_ = 0.0;
36  preintegrated_.setZero();
39 }
40 
41 //------------------------------------------------------------------------------
43  double tol) const {
44  return p_->equals(*other.p_, tol) && std::abs(deltaTij_ - other.deltaTij_) < tol
45  && biasHat_.equals(other.biasHat_, tol)
48  other.preintegrated_H_biasAcc_, tol)
50  other.preintegrated_H_biasOmega_, tol);
51 }
52 
53 //------------------------------------------------------------------------------
54 // See extensive discussion in ImuFactor.lyx
56  const Vector3& w_body, double dt, const Vector9& preintegrated,
59  const auto theta = preintegrated.segment<3>(0);
60  const auto position = preintegrated.segment<3>(3);
61  const auto velocity = preintegrated.segment<3>(6);
62 
63  // This functor allows for saving computation when exponential map and its
64  // derivatives are needed at the same location in so<3>
65  so3::DexpFunctor local(theta);
66 
67  // Calculate exact mean propagation
68  Matrix3 w_tangent_H_theta, invH;
69  const Vector3 w_tangent = // angular velocity mapped back to tangent space
70  local.applyInvDexp(w_body, A ? &w_tangent_H_theta : 0, C ? &invH : 0);
71  const Rot3 R(local.expmap()); // nRb: rotation of body in nav frame
72  const Vector3 a_nav = R * a_body;
73  const double dt22 = 0.5 * dt * dt;
74 
75  Vector9 preintegratedPlus;
76  preintegratedPlus << // new preintegrated vector:
77  theta + w_tangent * dt, // theta
78  position + velocity * dt + a_nav * dt22, // position
79  velocity + a_nav * dt; // velocity
80 
81  if (A) {
82  // Exact derivative of R*a with respect to theta:
83  const Matrix3 a_nav_H_theta = R.matrix() * skewSymmetric(-a_body) * local.dexp();
84 
85  A->setIdentity();
86  A->block<3, 3>(0, 0).noalias() += w_tangent_H_theta * dt; // theta
87  A->block<3, 3>(3, 0) = a_nav_H_theta * dt22; // position wrpt theta...
88  A->block<3, 3>(3, 6) = I_3x3 * dt; // .. and velocity
89  A->block<3, 3>(6, 0) = a_nav_H_theta * dt; // velocity wrpt theta
90  }
91  if (B) {
92  B->block<3, 3>(0, 0) = Z_3x3;
93  B->block<3, 3>(3, 0) = R.matrix() * dt22;
94  B->block<3, 3>(6, 0) = R.matrix() * dt;
95  }
96  if (C) {
97  C->block<3, 3>(0, 0) = invH * dt;
98  C->block<3, 3>(3, 0) = Z_3x3;
99  C->block<3, 3>(6, 0) = Z_3x3;
100  }
101 
102  return preintegratedPlus;
103 }
104 
105 //------------------------------------------------------------------------------
107  const Vector3& measuredOmega, const double dt, Matrix9* A, Matrix93* B,
108  Matrix93* C) {
109  // Correct for bias in the sensor frame
110  Vector3 acc = biasHat_.correctAccelerometer(measuredAcc);
111  Vector3 omega = biasHat_.correctGyroscope(measuredOmega);
112 
113  // Possibly correct for sensor pose by converting to body frame
114  Matrix3 D_correctedAcc_acc, D_correctedAcc_omega, D_correctedOmega_omega;
115  if (p().body_P_sensor)
116  boost::tie(acc, omega) = correctMeasurementsBySensorPose(acc, omega,
117  D_correctedAcc_acc, D_correctedAcc_omega, D_correctedOmega_omega);
118 
119  // Do update
120  deltaTij_ += dt;
121  preintegrated_ = UpdatePreintegrated(acc, omega, dt, preintegrated_, A, B, C);
122 
123  if (p().body_P_sensor) {
124  // More complicated derivatives in case of non-trivial sensor pose
125  *C *= D_correctedOmega_omega;
126  if (!p().body_P_sensor->translation().isZero())
127  *C += *B * D_correctedAcc_omega;
128  *B *= D_correctedAcc_acc; // NOTE(frank): needs to be last
129  }
130 
131  // new_H_biasAcc = new_H_old * old_H_biasAcc + new_H_acc * acc_H_biasAcc
132  // where acc_H_biasAcc = -I_3x3, hence
133  // new_H_biasAcc = new_H_old * old_H_biasAcc - new_H_acc
135 
136  // new_H_biasOmega = new_H_old * old_H_biasOmega + new_H_omega * omega_H_biasOmega
137  // where omega_H_biasOmega = -I_3x3, hence
138  // new_H_biasOmega = new_H_old * old_H_biasOmega - new_H_omega
140 }
141 
142 //------------------------------------------------------------------------------
144  const imuBias::ConstantBias& bias_i, OptionalJacobian<9, 6> H) const {
145  // We correct for a change between bias_i and the biasHat_ used to integrate
146  // This is a simple linear correction with obvious derivatives
147  const imuBias::ConstantBias biasIncr = bias_i - biasHat_;
148  const Vector9 biasCorrected = preintegrated()
150  + preintegrated_H_biasOmega_ * biasIncr.gyroscope();
151 
152  if (H) {
154  }
155  return biasCorrected;
156 }
157 
158 //------------------------------------------------------------------------------
159 // sugar for derivative blocks
160 #define D_R_R(H) (H)->block<3,3>(0,0)
161 #define D_R_t(H) (H)->block<3,3>(0,3)
162 #define D_R_v(H) (H)->block<3,3>(0,6)
163 #define D_t_R(H) (H)->block<3,3>(3,0)
164 #define D_t_t(H) (H)->block<3,3>(3,3)
165 #define D_t_v(H) (H)->block<3,3>(3,6)
166 #define D_v_R(H) (H)->block<3,3>(6,0)
167 #define D_v_t(H) (H)->block<3,3>(6,3)
168 #define D_v_v(H) (H)->block<3,3>(6,6)
169 
170 //------------------------------------------------------------------------------
171 Vector9 TangentPreintegration::Compose(const Vector9& zeta01,
172  const Vector9& zeta12, double deltaT12, OptionalJacobian<9, 9> H1,
174  const auto t01 = zeta01.segment<3>(0);
175  const auto p01 = zeta01.segment<3>(3);
176  const auto v01 = zeta01.segment<3>(6);
177 
178  const auto t12 = zeta12.segment<3>(0);
179  const auto p12 = zeta12.segment<3>(3);
180  const auto v12 = zeta12.segment<3>(6);
181 
182  Matrix3 R01_H_t01, R12_H_t12;
183  const Rot3 R01 = Rot3::Expmap(t01, R01_H_t01);
184  const Rot3 R12 = Rot3::Expmap(t12, R12_H_t12);
185 
186  Matrix3 R02_H_R01, R02_H_R12; // NOTE(frank): R02_H_R12 == Identity
187  const Rot3 R02 = R01.compose(R12, R02_H_R01, R02_H_R12);
188 
189  Matrix3 t02_H_R02;
190  Vector9 zeta02;
191  const Matrix3 R = R01.matrix();
192  zeta02 << Rot3::Logmap(R02, t02_H_R02), // theta
193  p01 + v01 * deltaT12 + R * p12, // position
194  v01 + R * v12; // velocity
195 
196  if (H1) {
197  H1->setIdentity();
198  D_R_R(H1) = t02_H_R02 * R02_H_R01 * R01_H_t01;
199  D_t_R(H1) = R * skewSymmetric(-p12) * R01_H_t01;
200  D_t_v(H1) = I_3x3 * deltaT12;
201  D_v_R(H1) = R * skewSymmetric(-v12) * R01_H_t01;
202  }
203 
204  if (H2) {
205  H2->setZero();
206  D_R_R(H2) = t02_H_R02 * R02_H_R12 * R12_H_t12;
207  D_t_t(H2) = R;
208  D_v_v(H2) = R;
209  }
210 
211  return zeta02;
212 }
213 
214 //------------------------------------------------------------------------------
216  Matrix9* H1, Matrix9* H2) {
217  if (!matchesParamsWith(pim12)) {
218  throw std::domain_error(
219  "Cannot merge pre-integrated measurements with different params");
220  }
221 
222  if (params()->body_P_sensor) {
223  throw std::domain_error(
224  "Cannot merge pre-integrated measurements with sensor pose yet");
225  }
226 
227  const double t01 = deltaTij();
228  const double t12 = pim12.deltaTij();
229  deltaTij_ = t01 + t12;
230 
231  const Vector9 zeta01 = preintegrated();
232  Vector9 zeta12 = pim12.preintegrated(); // will be modified.
233 
234  const imuBias::ConstantBias bias_incr_for_12 = biasHat() - pim12.biasHat();
235  zeta12 += pim12.preintegrated_H_biasOmega_ * bias_incr_for_12.gyroscope()
236  + pim12.preintegrated_H_biasAcc_ * bias_incr_for_12.accelerometer();
237 
238  preintegrated_ = TangentPreintegration::Compose(zeta01, zeta12, t12, H1, H2);
239 
241  + (*H2) * pim12.preintegrated_H_biasAcc_;
242 
244  + (*H2) * pim12.preintegrated_H_biasOmega_;
245 }
246 
247 //------------------------------------------------------------------------------
248 
249 }// namespace gtsam
const imuBias::ConstantBias & biasHat() const
Vector9 biasCorrectedDelta(const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H=boost::none) const override
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
Eigen::Vector3d Vector3
Definition: Vector.h:43
static Vector9 Compose(const Vector9 &zeta01, const Vector9 &zeta12, double deltaT12, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 9 > H2=boost::none)
Matrix93 preintegrated_H_biasAcc_
Jacobian of preintegrated_ w.r.t. acceleration bias.
Rot2 R(Rot2::fromAngle(0.1))
const Vector3 & accelerometer() const
Definition: ImuBias.h:59
boost::shared_ptr< Params > p_
Definition: Half.h:150
Some functions to compute numerical derivatives.
Matrix3 matrix() const
Definition: Rot3M.cpp:219
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
Matrix93 preintegrated_H_biasOmega_
Jacobian of preintegrated_ w.r.t. angular rate bias.
std::pair< Vector3, Vector3 > correctMeasurementsBySensorPose(const Vector3 &unbiasedAcc, const Vector3 &unbiasedOmega, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedAcc=boost::none, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedOmega=boost::none, OptionalJacobian< 3, 3 > correctedOmega_H_unbiasedOmega=boost::none) const
#define D_R_R(H)
#define D_t_v(H)
const double dt
bool equals(const TangentPreintegration &other, double tol) const
Class compose(const Class &g) const
Definition: Lie.h:47
#define D_v_R(H)
SO3 expmap() const
Rodrigues formula.
Definition: SO3.cpp:83
static Vector9 UpdatePreintegrated(const Vector3 &a_body, const Vector3 &w_body, const double dt, const Vector9 &preintegrated, OptionalJacobian< 9, 9 > A=boost::none, OptionalJacobian< 9, 3 > B=boost::none, OptionalJacobian< 9, 3 > C=boost::none)
Vector3 correctAccelerometer(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Definition: ImuBias.h:69
Params & p() const
const reference to params
bool equals(const ConstantBias &expected, double tol=1e-5) const
Definition: ImuBias.h:98
static const Vector3 measuredAcc
double deltaTij_
Time interval from i to j.
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3.h:377
const Vector9 & preintegrated() const
Velocity3_ velocity(const NavState_ &X)
#define D_v_v(H)
const Matrix3 & dexp() const
Definition: SO3.h:170
#define D_t_t(H)
void update(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C) override
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:84
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
const Vector3 & gyroscope() const
Definition: ImuBias.h:64
traits
Definition: chartTesting.h:28
void mergeWith(const TangentPreintegration &pim, Matrix9 *H1, Matrix9 *H2)
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:404
static const Vector3 measuredOmega(w, 0, 0)
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3M.cpp:158
Functor that implements Exponential map and its derivatives.
Definition: SO3.h:155
bool matchesParamsWith(const PreintegrationBase &other) const
check parameters equality: checks whether shared pointer points to same Params object.
Point3_ position(const NavState_ &X)
GTSAM_EXPORT Vector3 applyInvDexp(const Vector3 &v, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Multiplies with dexp().inverse(), with optional derivatives.
Definition: SO3.cpp:120
float * p
const boost::shared_ptr< Params > & params() const
shared pointer to params
Vector3 correctGyroscope(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Definition: ImuBias.h:78
#define D_t_R(H)
const G double tol
Definition: Group.h:83
#define abs(x)
Definition: datatypes.h:17
Bias biasHat_
Acceleration and gyro bias used for preintegration.


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