CpiV1.cpp
Go to the documentation of this file.
1 
2 /*
3  * MIT License
4  * Copyright (c) 2018 Kevin Eckenhoff
5  * Copyright (c) 2018 Patrick Geneva
6  * Copyright (c) 2018 Guoquan Huang
7  *
8  * Permission is hereby granted, free of charge, to any person obtaining a copy
9  * of this software and associated documentation files (the "Software"), to deal
10  * in the Software without restriction, including without limitation the rights
11  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
12  * copies of the Software, and to permit persons to whom the Software is
13  * furnished to do so, subject to the following conditions:
14  *
15  * The above copyright notice and this permission notice shall be included in all
16  * copies or substantial portions of the Software.
17  *
18  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
19  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
20  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
21  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
22  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
23  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
24  * SOFTWARE.
25  */
26 
27 #include "CpiV1.h"
28 
29 #include "utils/quat_ops.h"
30 
31 using namespace ov_core;
32 
33 void CpiV1::feed_IMU(double t_0, double t_1, Eigen::Matrix<double, 3, 1> w_m_0, Eigen::Matrix<double, 3, 1> a_m_0,
34  Eigen::Matrix<double, 3, 1> w_m_1, Eigen::Matrix<double, 3, 1> a_m_1) {
35 
36  // Get time difference
37  double delta_t = t_1 - t_0;
38  DT += delta_t;
39 
40  // If no time has passed do nothing
41  if (delta_t == 0) {
42  return;
43  }
44 
45  // Get estimated imu readings
46  Eigen::Matrix<double, 3, 1> w_hat = w_m_0 - b_w_lin;
47  Eigen::Matrix<double, 3, 1> a_hat = a_m_0 - b_a_lin;
48 
49  // If averaging, average
50  if (imu_avg) {
51  w_hat += w_m_1 - b_w_lin;
52  w_hat = 0.5 * w_hat;
53  a_hat += a_m_1 - b_a_lin;
54  a_hat = .5 * a_hat;
55  }
56 
57  // Get angle change w*dt
58  Eigen::Matrix<double, 3, 1> w_hatdt = w_hat * delta_t;
59 
60  // Get entries of w_hat
61  double w_1 = w_hat(0, 0);
62  double w_2 = w_hat(1, 0);
63  double w_3 = w_hat(2, 0);
64 
65  // Get magnitude of w and wdt
66  double mag_w = w_hat.norm();
67  double w_dt = mag_w * delta_t;
68 
69  // Threshold to determine if equations will be unstable
70  bool small_w = (mag_w < 0.008726646);
71 
72  // Get some of the variables used in the preintegration equations
73  double dt_2 = pow(delta_t, 2);
74  double cos_wt = cos(w_dt);
75  double sin_wt = sin(w_dt);
76 
77  Eigen::Matrix<double, 3, 3> w_x = skew_x(w_hat);
78  Eigen::Matrix<double, 3, 3> a_x = skew_x(a_hat);
79  Eigen::Matrix<double, 3, 3> w_tx = skew_x(w_hatdt);
80  Eigen::Matrix<double, 3, 3> w_x_2 = w_x * w_x;
81 
82  //==========================================================================
83  // MEASUREMENT MEANS
84  //==========================================================================
85 
86  // Get relative rotation
87  Eigen::Matrix<double, 3, 3> R_tau2tau1 = small_w ? eye3 - delta_t * w_x + (pow(delta_t, 2) / 2) * w_x_2
88  : eye3 - (sin_wt / mag_w) * w_x + ((1.0 - cos_wt) / (pow(mag_w, 2.0))) * w_x_2;
89 
90  // Updated rotation and its transpose
91  Eigen::Matrix<double, 3, 3> R_k2tau1 = R_tau2tau1 * R_k2tau;
92  Eigen::Matrix<double, 3, 3> R_tau12k = R_k2tau1.transpose();
93 
94  // Intermediate variables for evaluating the measurement/bias Jacobian update
95  double f_1;
96  double f_2;
97  double f_3;
98  double f_4;
99 
100  if (small_w) {
101  f_1 = -(pow(delta_t, 3) / 3);
102  f_2 = (pow(delta_t, 4) / 8);
103  f_3 = -(pow(delta_t, 2) / 2);
104  f_4 = (pow(delta_t, 3) / 6);
105  } else {
106  f_1 = (w_dt * cos_wt - sin_wt) / (pow(mag_w, 3));
107  f_2 = (pow(w_dt, 2) - 2 * cos_wt - 2 * w_dt * sin_wt + 2) / (2 * pow(mag_w, 4));
108  f_3 = -(1 - cos_wt) / pow(mag_w, 2);
109  f_4 = (w_dt - sin_wt) / pow(mag_w, 3);
110  }
111 
112  // Compute the main part of our analytical means
113  Eigen::Matrix<double, 3, 3> alpha_arg = ((dt_2 / 2.0) * eye3 + f_1 * w_x + f_2 * w_x_2);
114  Eigen::Matrix<double, 3, 3> Beta_arg = (delta_t * eye3 + f_3 * w_x + f_4 * w_x_2);
115 
116  // Matrices that will multiply the a_hat in the update expressions
117  Eigen::MatrixXd H_al = R_tau12k * alpha_arg;
118  Eigen::MatrixXd H_be = R_tau12k * Beta_arg;
119 
120  // Update the measurement means
121  alpha_tau += beta_tau * delta_t + H_al * a_hat;
122  beta_tau += H_be * a_hat;
123 
124  //==========================================================================
125  // BIAS JACOBIANS (ANALYTICAL)
126  //==========================================================================
127 
128  // Get right Jacobian
129  Eigen::Matrix<double, 3, 3> J_r_tau1 =
130  small_w ? eye3 - .5 * w_tx + (1.0 / 6.0) * w_tx * w_tx
131  : eye3 - ((1 - cos_wt) / (pow((w_dt), 2.0))) * w_tx + ((w_dt - sin_wt) / (pow(w_dt, 3.0))) * w_tx * w_tx;
132 
133  // Update orientation in respect to gyro bias Jacobians
134  J_q = R_tau2tau1 * J_q + J_r_tau1 * delta_t;
135 
136  // Update alpha and beta in respect to accel bias Jacobians
137  H_a -= H_al;
138  H_a += delta_t * H_b;
139  H_b -= H_be;
140 
141  // Derivatives of R_tau12k wrt bias_w entries
142  Eigen::MatrixXd d_R_bw_1 = -R_tau12k * skew_x(J_q * e_1);
143  Eigen::MatrixXd d_R_bw_2 = -R_tau12k * skew_x(J_q * e_2);
144  Eigen::MatrixXd d_R_bw_3 = -R_tau12k * skew_x(J_q * e_3);
145 
146  // Now compute the gyro bias Jacobian terms
147  double df_1_dbw_1;
148  double df_1_dbw_2;
149  double df_1_dbw_3;
150 
151  double df_2_dbw_1;
152  double df_2_dbw_2;
153  double df_2_dbw_3;
154 
155  double df_3_dbw_1;
156  double df_3_dbw_2;
157  double df_3_dbw_3;
158 
159  double df_4_dbw_1;
160  double df_4_dbw_2;
161  double df_4_dbw_3;
162 
163  if (small_w) {
164  double df_1_dw_mag = -(pow(delta_t, 5) / 15);
165  df_1_dbw_1 = w_1 * df_1_dw_mag;
166  df_1_dbw_2 = w_2 * df_1_dw_mag;
167  df_1_dbw_3 = w_3 * df_1_dw_mag;
168 
169  double df_2_dw_mag = (pow(delta_t, 6) / 72);
170  df_2_dbw_1 = w_1 * df_2_dw_mag;
171  df_2_dbw_2 = w_2 * df_2_dw_mag;
172  df_2_dbw_3 = w_3 * df_2_dw_mag;
173 
174  double df_3_dw_mag = -(pow(delta_t, 4) / 12);
175  df_3_dbw_1 = w_1 * df_3_dw_mag;
176  df_3_dbw_2 = w_2 * df_3_dw_mag;
177  df_3_dbw_3 = w_3 * df_3_dw_mag;
178 
179  double df_4_dw_mag = (pow(delta_t, 5) / 60);
180  df_4_dbw_1 = w_1 * df_4_dw_mag;
181  df_4_dbw_2 = w_2 * df_4_dw_mag;
182  df_4_dbw_3 = w_3 * df_4_dw_mag;
183  } else {
184  double df_1_dw_mag = (pow(w_dt, 2) * sin_wt - 3 * sin_wt + 3 * w_dt * cos_wt) / pow(mag_w, 5);
185  df_1_dbw_1 = w_1 * df_1_dw_mag;
186  df_1_dbw_2 = w_2 * df_1_dw_mag;
187  df_1_dbw_3 = w_3 * df_1_dw_mag;
188 
189  double df_2_dw_mag = (pow(w_dt, 2) - 4 * cos_wt - 4 * w_dt * sin_wt + pow(w_dt, 2) * cos_wt + 4) / (pow(mag_w, 6));
190  df_2_dbw_1 = w_1 * df_2_dw_mag;
191  df_2_dbw_2 = w_2 * df_2_dw_mag;
192  df_2_dbw_3 = w_3 * df_2_dw_mag;
193 
194  double df_3_dw_mag = (2 * (cos_wt - 1) + w_dt * sin_wt) / (pow(mag_w, 4));
195  df_3_dbw_1 = w_1 * df_3_dw_mag;
196  df_3_dbw_2 = w_2 * df_3_dw_mag;
197  df_3_dbw_3 = w_3 * df_3_dw_mag;
198 
199  double df_4_dw_mag = (2 * w_dt + w_dt * cos_wt - 3 * sin_wt) / (pow(mag_w, 5));
200  df_4_dbw_1 = w_1 * df_4_dw_mag;
201  df_4_dbw_2 = w_2 * df_4_dw_mag;
202  df_4_dbw_3 = w_3 * df_4_dw_mag;
203  }
204 
205  // Update alpha and beta gyro bias Jacobians
206  J_a += J_b * delta_t;
207  J_a.block(0, 0, 3, 1) +=
208  (d_R_bw_1 * alpha_arg + R_tau12k * (df_1_dbw_1 * w_x - f_1 * e_1x + df_2_dbw_1 * w_x_2 - f_2 * (e_1x * w_x + w_x * e_1x))) * a_hat;
209  J_a.block(0, 1, 3, 1) +=
210  (d_R_bw_2 * alpha_arg + R_tau12k * (df_1_dbw_2 * w_x - f_1 * e_2x + df_2_dbw_2 * w_x_2 - f_2 * (e_2x * w_x + w_x * e_2x))) * a_hat;
211  J_a.block(0, 2, 3, 1) +=
212  (d_R_bw_3 * alpha_arg + R_tau12k * (df_1_dbw_3 * w_x - f_1 * e_3x + df_2_dbw_3 * w_x_2 - f_2 * (e_3x * w_x + w_x * e_3x))) * a_hat;
213  J_b.block(0, 0, 3, 1) +=
214  (d_R_bw_1 * Beta_arg + R_tau12k * (df_3_dbw_1 * w_x - f_3 * e_1x + df_4_dbw_1 * w_x_2 - f_4 * (e_1x * w_x + w_x * e_1x))) * a_hat;
215  J_b.block(0, 1, 3, 1) +=
216  (d_R_bw_2 * Beta_arg + R_tau12k * (df_3_dbw_2 * w_x - f_3 * e_2x + df_4_dbw_2 * w_x_2 - f_4 * (e_2x * w_x + w_x * e_2x))) * a_hat;
217  J_b.block(0, 2, 3, 1) +=
218  (d_R_bw_3 * Beta_arg + R_tau12k * (df_3_dbw_3 * w_x - f_3 * e_3x + df_4_dbw_3 * w_x_2 - f_4 * (e_3x * w_x + w_x * e_3x))) * a_hat;
219 
220  //==========================================================================
221  // MEASUREMENT COVARIANCE
222  //==========================================================================
223 
224  // Going to need orientation at intermediate time i.e. at .5*dt;
225  Eigen::Matrix<double, 3, 3> R_mid =
226  small_w ? eye3 - .5 * delta_t * w_x + (pow(.5 * delta_t, 2) / 2) * w_x_2
227  : eye3 - (sin(mag_w * .5 * delta_t) / mag_w) * w_x + ((1.0 - cos(mag_w * .5 * delta_t)) / (pow(mag_w, 2.0))) * w_x_2;
228  R_mid = R_mid * R_k2tau;
229 
230  // Compute covariance (in this implementation, we use RK4)
231  // k1-------------------------------------------------------------------------------------------------
232 
233  // Build state Jacobian
234  Eigen::Matrix<double, 15, 15> F_k1 = Eigen::Matrix<double, 15, 15>::Zero();
235  F_k1.block(0, 0, 3, 3) = -w_x;
236  F_k1.block(0, 3, 3, 3) = -eye3;
237  F_k1.block(6, 0, 3, 3) = -R_k2tau.transpose() * a_x;
238  F_k1.block(6, 9, 3, 3) = -R_k2tau.transpose();
239  F_k1.block(12, 6, 3, 3) = eye3;
240 
241  // Build noise Jacobian
242  Eigen::Matrix<double, 15, 12> G_k1 = Eigen::Matrix<double, 15, 12>::Zero();
243  G_k1.block(0, 0, 3, 3) = -eye3;
244  G_k1.block(3, 3, 3, 3) = eye3;
245  G_k1.block(6, 6, 3, 3) = -R_k2tau.transpose();
246  G_k1.block(9, 9, 3, 3) = eye3;
247 
248  // Get covariance derivative
249  Eigen::Matrix<double, 15, 15> P_dot_k1 = F_k1 * P_meas + P_meas * F_k1.transpose() + G_k1 * Q_c * G_k1.transpose();
250 
251  // k2-------------------------------------------------------------------------------------------------
252 
253  // Build state Jacobian
254  Eigen::Matrix<double, 15, 15> F_k2 = Eigen::Matrix<double, 15, 15>::Zero();
255  F_k2.block(0, 0, 3, 3) = -w_x;
256  F_k2.block(0, 3, 3, 3) = -eye3;
257  F_k2.block(6, 0, 3, 3) = -R_mid.transpose() * a_x;
258  F_k2.block(6, 9, 3, 3) = -R_mid.transpose();
259  F_k2.block(12, 6, 3, 3) = eye3;
260 
261  // Build noise Jacobian
262  Eigen::Matrix<double, 15, 12> G_k2 = Eigen::Matrix<double, 15, 12>::Zero();
263  G_k2.block(0, 0, 3, 3) = -eye3;
264  G_k2.block(3, 3, 3, 3) = eye3;
265  G_k2.block(6, 6, 3, 3) = -R_mid.transpose();
266  G_k2.block(9, 9, 3, 3) = eye3;
267 
268  // Get covariance derivative
269  Eigen::Matrix<double, 15, 15> P_k2 = P_meas + P_dot_k1 * delta_t / 2.0;
270  Eigen::Matrix<double, 15, 15> P_dot_k2 = F_k2 * P_k2 + P_k2 * F_k2.transpose() + G_k2 * Q_c * G_k2.transpose();
271 
272  // k3-------------------------------------------------------------------------------------------------
273 
274  // Our state and noise Jacobians are the same as k2
275  // Since k2 and k3 correspond to the same estimates for the midpoint
276  Eigen::Matrix<double, 15, 15> F_k3 = F_k2;
277  Eigen::Matrix<double, 15, 12> G_k3 = G_k2;
278 
279  // Get covariance derivative
280  Eigen::Matrix<double, 15, 15> P_k3 = P_meas + P_dot_k2 * delta_t / 2.0;
281  Eigen::Matrix<double, 15, 15> P_dot_k3 = F_k3 * P_k3 + P_k3 * F_k3.transpose() + G_k3 * Q_c * G_k3.transpose();
282 
283  // k4-------------------------------------------------------------------------------------------------
284 
285  // Build state Jacobian
286  Eigen::Matrix<double, 15, 15> F_k4 = Eigen::Matrix<double, 15, 15>::Zero();
287  F_k4.block(0, 0, 3, 3) = -w_x;
288  F_k4.block(0, 3, 3, 3) = -eye3;
289  F_k4.block(6, 0, 3, 3) = -R_k2tau1.transpose() * a_x;
290  F_k4.block(6, 9, 3, 3) = -R_k2tau1.transpose();
291  F_k4.block(12, 6, 3, 3) = eye3;
292 
293  // Build noise Jacobian
294  Eigen::Matrix<double, 15, 12> G_k4 = Eigen::Matrix<double, 15, 12>::Zero();
295  G_k4.block(0, 0, 3, 3) = -eye3;
296  G_k4.block(3, 3, 3, 3) = eye3;
297  G_k4.block(6, 6, 3, 3) = -R_k2tau1.transpose();
298  G_k4.block(9, 9, 3, 3) = eye3;
299 
300  // Get covariance derivative
301  Eigen::Matrix<double, 15, 15> P_k4 = P_meas + P_dot_k3 * delta_t;
302  Eigen::Matrix<double, 15, 15> P_dot_k4 = F_k4 * P_k4 + P_k4 * F_k4.transpose() + G_k4 * Q_c * G_k4.transpose();
303 
304  // done-------------------------------------------------------------------------------------------------
305 
306  // Collect covariance solution
307  // Ensure it is positive definite
308  P_meas += (delta_t / 6.0) * (P_dot_k1 + 2.0 * P_dot_k2 + 2.0 * P_dot_k3 + P_dot_k4);
309  P_meas = 0.5 * (P_meas + P_meas.transpose());
310 
311  // Update rotation mean
312  // Note we had to wait to do this, since we use the old orientation in our covariance calculation
313  R_k2tau = R_k2tau1;
315 }
ov_core::CpiBase::H_a
Eigen::Matrix< double, 3, 3 > H_a
alpha Jacobian wrt b_a
Definition: CpiBase.h:129
ov_core::skew_x
Eigen::Matrix< double, 3, 3 > skew_x(const Eigen::Matrix< double, 3, 1 > &w)
Skew-symmetric matrix from a given 3x1 vector.
Definition: quat_ops.h:135
ov_core::CpiBase::b_a_lin
Eigen::Matrix< double, 3, 1 > b_a_lin
b_a linearization point (accelerometer)
Definition: CpiBase.h:134
ov_core::CpiBase::Q_c
Eigen::Matrix< double, 12, 12 > Q_c
Our continous-time measurement noise matrix (computed from contructor noise values)
Definition: CpiBase.h:141
ov_core::CpiBase::alpha_tau
Eigen::Matrix< double, 3, 1 > alpha_tau
alpha measurement mean
Definition: CpiBase.h:120
ov_core::CpiBase::R_k2tau
Eigen::Matrix< double, 3, 3 > R_k2tau
orientation measurement mean
Definition: CpiBase.h:123
ov_core::CpiBase::e_2
Eigen::Matrix< double, 3, 1 > e_2
Definition: CpiBase.h:155
ov_core::CpiBase::DT
double DT
measurement integration time
Definition: CpiBase.h:119
ov_core::CpiBase::J_q
Eigen::Matrix< double, 3, 3 > J_q
orientation Jacobian wrt b_w
Definition: CpiBase.h:126
ov_core::CpiBase::J_a
Eigen::Matrix< double, 3, 3 > J_a
alpha Jacobian wrt b_w
Definition: CpiBase.h:127
ov_core::CpiBase::q_k2tau
Eigen::Matrix< double, 4, 1 > q_k2tau
orientation measurement mean
Definition: CpiBase.h:122
ov_core::CpiBase::e_2x
Eigen::Matrix< double, 3, 3 > e_2x
Definition: CpiBase.h:160
ov_core::CpiBase::e_3x
Eigen::Matrix< double, 3, 3 > e_3x
Definition: CpiBase.h:161
CpiV1.h
ov_core::CpiBase::beta_tau
Eigen::Matrix< double, 3, 1 > beta_tau
beta measurement mean
Definition: CpiBase.h:121
ov_core::CpiV1::feed_IMU
void feed_IMU(double t_0, double t_1, Eigen::Matrix< double, 3, 1 > w_m_0, Eigen::Matrix< double, 3, 1 > a_m_0, Eigen::Matrix< double, 3, 1 > w_m_1=Eigen::Matrix< double, 3, 1 >::Zero(), Eigen::Matrix< double, 3, 1 > a_m_1=Eigen::Matrix< double, 3, 1 >::Zero())
Our precompound function for Model 1.
Definition: CpiV1.cpp:33
ov_core::CpiBase::e_1
Eigen::Matrix< double, 3, 1 > e_1
Definition: CpiBase.h:154
ov_core::rot_2_quat
Eigen::Matrix< double, 4, 1 > rot_2_quat(const Eigen::Matrix< double, 3, 3 > &rot)
Returns a JPL quaternion from a rotation matrix.
Definition: quat_ops.h:88
ov_core::CpiBase::e_3
Eigen::Matrix< double, 3, 1 > e_3
Definition: CpiBase.h:156
ov_core::CpiBase::eye3
Eigen::Matrix< double, 3, 3 > eye3
Definition: CpiBase.h:151
ov_core::CpiBase::P_meas
Eigen::Matrix< double, 15, 15 > P_meas
Our final measurement covariance.
Definition: CpiBase.h:144
ov_core::CpiBase::imu_avg
bool imu_avg
Definition: CpiBase.h:116
quat_ops.h
ov_core::CpiBase::b_w_lin
Eigen::Matrix< double, 3, 1 > b_w_lin
b_w linearization point (gyroscope)
Definition: CpiBase.h:133
ov_core
Core algorithms for OpenVINS.
Definition: CamBase.h:30
ov_core::CpiBase::e_1x
Eigen::Matrix< double, 3, 3 > e_1x
Definition: CpiBase.h:159
ov_core::CpiBase::H_b
Eigen::Matrix< double, 3, 3 > H_b
beta Jacobian wrt b_a
Definition: CpiBase.h:130
ov_core::CpiBase::J_b
Eigen::Matrix< double, 3, 3 > J_b
beta Jacobian wrt b_w
Definition: CpiBase.h:128


ov_core
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Jan 22 2024 03:08:17