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


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:12:46