PreintegrationBase.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 
23 #include "PreintegrationBase.h"
25 #include <boost/make_shared.hpp>
26 
27 using namespace std;
28 
29 namespace gtsam {
30 
31 //------------------------------------------------------------------------------
32 PreintegrationBase::PreintegrationBase(const boost::shared_ptr<Params>& p,
33  const Bias& biasHat)
34  : p_(p), biasHat_(biasHat), deltaTij_(0.0) {
35 }
36 
37 //------------------------------------------------------------------------------
38 ostream& operator<<(ostream& os, const PreintegrationBase& pim) {
39  os << " deltaTij = " << pim.deltaTij_ << endl;
40  os << " deltaRij.ypr = (" << pim.deltaRij().ypr().transpose() << ")" << endl;
41  os << " deltaPij = " << pim.deltaPij().transpose() << endl;
42  os << " deltaVij = " << pim.deltaVij().transpose() << endl;
43  os << " gyrobias = " << pim.biasHat_.gyroscope().transpose() << endl;
44  os << " acc_bias = " << pim.biasHat_.accelerometer().transpose() << endl;
45  return os;
46 }
47 
48 //------------------------------------------------------------------------------
49 void PreintegrationBase::print(const string& s) const {
50  cout << (s.empty() ? s : s + "\n") << *this << endl;
51 }
52 
53 //------------------------------------------------------------------------------
55  biasHat_ = biasHat;
57 }
58 
59 //------------------------------------------------------------------------------
61  const Vector3& unbiasedAcc, const Vector3& unbiasedOmega,
62  OptionalJacobian<3, 3> correctedAcc_H_unbiasedAcc,
63  OptionalJacobian<3, 3> correctedAcc_H_unbiasedOmega,
64  OptionalJacobian<3, 3> correctedOmega_H_unbiasedOmega) const {
65  assert(p().body_P_sensor);
66 
67  // Compensate for sensor-body displacement if needed: we express the quantities
68  // (originally in the IMU frame) into the body frame
69  // Equations below assume the "body" frame is the CG
70 
71  // Get sensor to body rotation matrix
72  const Matrix3 bRs = p().body_P_sensor->rotation().matrix();
73 
74  // Convert angular velocity and acceleration from sensor to body frame
75  Vector3 correctedAcc = bRs * unbiasedAcc;
76  const Vector3 correctedOmega = bRs * unbiasedOmega;
77 
78  // Jacobians
79  if (correctedAcc_H_unbiasedAcc) *correctedAcc_H_unbiasedAcc = bRs;
80  if (correctedAcc_H_unbiasedOmega) *correctedAcc_H_unbiasedOmega = Z_3x3;
81  if (correctedOmega_H_unbiasedOmega) *correctedOmega_H_unbiasedOmega = bRs;
82 
83  // Centrifugal acceleration
84  const Vector3 b_arm = p().body_P_sensor->translation();
85  if (!b_arm.isZero()) {
86  // Subtract out the the centripetal acceleration from the unbiased one
87  // to get linear acceleration vector in the body frame:
88  const Matrix3 body_Omega_body = skewSymmetric(correctedOmega);
89  const Vector3 b_velocity_bs = body_Omega_body * b_arm; // magnitude: omega * arm
90  correctedAcc -= body_Omega_body * b_velocity_bs;
91 
92  // Update derivative: centrifugal causes the correlation between acc and omega!!!
93  if (correctedAcc_H_unbiasedOmega) {
94  double wdp = correctedOmega.dot(b_arm);
95  const Matrix3 diag_wdp = Vector3::Constant(wdp).asDiagonal();
96  *correctedAcc_H_unbiasedOmega = -( diag_wdp
97  + correctedOmega * b_arm.transpose()) * bRs.matrix()
98  + 2 * b_arm * unbiasedOmega.transpose();
99  }
100  }
101 
102  return make_pair(correctedAcc, correctedOmega);
103 }
104 
105 //------------------------------------------------------------------------------
107  const Vector3& measuredOmega, double dt) {
108  // NOTE(frank): integrateMeasurement always needs to compute the derivatives,
109  // even when not of interest to the caller. Provide scratch space here.
110  Matrix9 A;
111  Matrix93 B, C;
112  update(measuredAcc, measuredOmega, dt, &A, &B, &C);
113 }
114 
115 //------------------------------------------------------------------------------
118  OptionalJacobian<9, 6> H2) const {
119  Matrix96 D_biasCorrected_bias;
120  Vector9 biasCorrected = biasCorrectedDelta(bias_i,
121  H2 ? &D_biasCorrected_bias : nullptr);
122 
123  // Correct for initial velocity and gravity
124  Matrix9 D_delta_state, D_delta_biasCorrected;
125  Vector9 xi = state_i.correctPIM(biasCorrected, deltaTij_, p().n_gravity,
126  p().omegaCoriolis, p().use2ndOrderCoriolis, H1 ? &D_delta_state : nullptr,
127  H2 ? &D_delta_biasCorrected : nullptr);
128 
129  // Use retract to get back to NavState manifold
130  Matrix9 D_predict_state, D_predict_delta;
131  NavState state_j = state_i.retract(xi,
132  H1 ? &D_predict_state : nullptr,
133  H2 || H2 ? &D_predict_delta : nullptr);
134  if (H1)
135  *H1 = D_predict_state + D_predict_delta * D_delta_state;
136  if (H2)
137  *H2 = D_predict_delta * D_delta_biasCorrected * D_biasCorrected_bias;
138  return state_j;
139 }
140 
141 //------------------------------------------------------------------------------
143  const NavState& state_j,
144  const imuBias::ConstantBias& bias_i,
147  OptionalJacobian<9, 6> H3) const {
148  // Predict state at time j
149  Matrix9 D_predict_state_i;
150  Matrix96 D_predict_bias_i;
151  NavState predictedState_j = predict(
152  state_i, bias_i, H1 ? &D_predict_state_i : 0, H3 ? &D_predict_bias_i : 0);
153 
154  // Calculate error
155  Matrix9 D_error_state_j, D_error_predict;
156  Vector9 error =
157  state_j.localCoordinates(predictedState_j, H2 ? &D_error_state_j : 0,
158  H1 || H3 ? &D_error_predict : 0);
159 
160  if (H1) *H1 << D_error_predict* D_predict_state_i;
161  if (H2) *H2 << D_error_state_j;
162  if (H3) *H3 << D_error_predict* D_predict_bias_i;
163 
164  return error;
165 }
166 
167 //------------------------------------------------------------------------------
169  const Vector3& vel_i, const Pose3& pose_j, const Vector3& vel_j,
173 
174  // Note that derivative of constructors below is not identity for velocity, but
175  // a 9*3 matrix == Z_3x3, Z_3x3, state.R().transpose()
176  NavState state_i(pose_i, vel_i);
177  NavState state_j(pose_j, vel_j);
178 
179  // Predict state at time j
180  Matrix9 D_error_state_i, D_error_state_j;
181  Vector9 error = computeError(state_i, state_j, bias_i,
182  H1 || H2 ? &D_error_state_i : 0, H3 || H4 ? &D_error_state_j : 0, H5);
183 
184  // Separate out derivatives in terms of 5 arguments
185  // Note that doing so requires special treatment of velocities, as when treated as
186  // separate variables the retract applied will not be the semi-direct product in NavState
187  // Instead, the velocities in nav are updated using a straight addition
188  // This is difference is accounted for by the R().transpose calls below
189  if (H1) *H1 << D_error_state_i.leftCols<6>();
190  if (H2) *H2 << D_error_state_i.rightCols<3>() * state_i.R().transpose();
191  if (H3) *H3 << D_error_state_j.leftCols<6>();
192  if (H4) *H4 << D_error_state_j.rightCols<3>() * state_j.R().transpose();
193 
194  return error;
195 }
196 
197 //------------------------------------------------------------------------------
198 
199 } // namespace gtsam
const imuBias::ConstantBias & biasHat() const
Vector3 correctedAcc(const PreintegratedImuMeasurements &pim, const Vector3 &measuredAcc, const Vector3 &measuredOmega)
Vector9 correctPIM(const Vector9 &pim, double dt, const Vector3 &n_gravity, const boost::optional< Vector3 > &omegaCoriolis, bool use2ndOrderCoriolis=false, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 9 > H2=boost::none) const
Definition: NavState.cpp:258
Eigen::Vector3d Vector3
Definition: Vector.h:43
Vector9 localCoordinates(const NavState &g, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 9 > H2=boost::none) const
localCoordinates with optional derivatives
Definition: NavState.cpp:135
virtual void update(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C)=0
const Vector3 & accelerometer() const
Definition: ImuBias.h:59
Definition: Half.h:150
Some functions to compute numerical derivatives.
Vector3 ypr(OptionalJacobian< 3, 3 > H=boost::none) const
Definition: Rot3.cpp:184
Vector9 computeError(const NavState &state_i, const NavState &state_j, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1, OptionalJacobian< 9, 9 > H2, OptionalJacobian< 9, 6 > H3) const
Calculate error given navStates.
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
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
NavState predict(const NavState &state_i, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 6 > H2=boost::none) const
Predict state at time j.
const double dt
virtual Rot3 deltaRij() const =0
virtual Vector3 deltaPij() const =0
NavState retract(const Vector9 &v, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 9 > H2=boost::none) const
retract with optional derivatives
Definition: NavState.cpp:109
void resetIntegrationAndSetBias(const Bias &biasHat)
virtual void resetIntegration()=0
Params & p() const
const reference to params
RealScalar s
static const Vector3 measuredAcc
boost::optional< Pose3 > body_P_sensor
The pose of the sensor in the body frame.
double deltaTij_
Time interval from i to j.
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
const Vector3 & gyroscope() const
Definition: ImuBias.h:64
Vector xi
Definition: testPose2.cpp:150
virtual void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt)
Version without derivatives.
traits
Definition: chartTesting.h:28
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:404
static const Vector3 measuredOmega(w, 0, 0)
ofstream os("timeSchurFactors.csv")
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const PreintegrationBase &pim)
virtual Vector3 deltaVij() const =0
float * p
static double error
Definition: testRot3.cpp:39
Matrix3 R() const
Return rotation matrix. Induces computation in quaternion mode.
Definition: NavState.h:95
virtual Vector9 biasCorrectedDelta(const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H=boost::none) const =0
virtual void print(const std::string &s="") const
Vector9 computeErrorAndJacobians(const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H1=boost::none, OptionalJacobian< 9, 3 > H2=boost::none, OptionalJacobian< 9, 6 > H3=boost::none, OptionalJacobian< 9, 3 > H4=boost::none, OptionalJacobian< 9, 6 > H5=boost::none) const
Bias biasHat_
Acceleration and gyro bias used for preintegration.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:29