CpiBase.h
Go to the documentation of this file.
1 #ifndef CPI_BASE_H
2 #define CPI_BASE_H
3 
4 /*
5  * MIT License
6  * Copyright (c) 2018 Kevin Eckenhoff
7  * Copyright (c) 2018 Patrick Geneva
8  * Copyright (c) 2018 Guoquan Huang
9  *
10  * Permission is hereby granted, free of charge, to any person obtaining a copy
11  * of this software and associated documentation files (the "Software"), to deal
12  * in the Software without restriction, including without limitation the rights
13  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
14  * copies of the Software, and to permit persons to whom the Software is
15  * furnished to do so, subject to the following conditions:
16  *
17  * The above copyright notice and this permission notice shall be included in all
18  * copies or substantial portions of the Software.
19  *
20  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
21  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
22  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
23  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
24  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
25  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
26  * SOFTWARE.
27  */
28 
29 #include "utils/quat_ops.h"
30 #include <Eigen/Dense>
31 
32 namespace ov_core {
33 
49 class CpiBase {
50 
51 public:
60  CpiBase(double sigma_w, double sigma_wb, double sigma_a, double sigma_ab, bool imu_avg_ = false) {
61  // Calculate our covariance matrix
62  Q_c.block(0, 0, 3, 3) = std::pow(sigma_w, 2) * eye3;
63  Q_c.block(3, 3, 3, 3) = std::pow(sigma_wb, 2) * eye3;
64  Q_c.block(6, 6, 3, 3) = std::pow(sigma_a, 2) * eye3;
65  Q_c.block(9, 9, 3, 3) = std::pow(sigma_ab, 2) * eye3;
66  imu_avg = imu_avg_;
67  // Calculate our unit vectors, and their skews (used in bias jacobian calcs)
68  e_1 << 1, 0, 0;
69  e_2 << 0, 1, 0;
70  e_3 << 0, 0, 1;
71  e_1x = skew_x(e_1);
72  e_2x = skew_x(e_2);
73  e_3x = skew_x(e_3);
74  }
75 
76  virtual ~CpiBase() {}
77 
88  void setLinearizationPoints(Eigen::Matrix<double, 3, 1> b_w_lin_, Eigen::Matrix<double, 3, 1> b_a_lin_,
89  Eigen::Matrix<double, 4, 1> q_k_lin_ = Eigen::Matrix<double, 4, 1>::Zero(),
90  Eigen::Matrix<double, 3, 1> grav_ = Eigen::Matrix<double, 3, 1>::Zero()) {
91  b_w_lin = b_w_lin_;
92  b_a_lin = b_a_lin_;
93  q_k_lin = q_k_lin_;
94  grav = grav_;
95  }
96 
109  virtual 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,
110  Eigen::Matrix<double, 3, 1> w_m_1 = Eigen::Matrix<double, 3, 1>::Zero(),
111  Eigen::Matrix<double, 3, 1> a_m_1 = Eigen::Matrix<double, 3, 1>::Zero()) = 0;
112 
113  // Flag if we should perform IMU averaging or not
114  // For version 1 we should average the measurement
115  // For version 2 we average the local true
116  bool imu_avg = false;
117 
118  // Measurement Means
119  double DT = 0;
120  Eigen::Matrix<double, 3, 1> alpha_tau = Eigen::Matrix<double, 3, 1>::Zero();
121  Eigen::Matrix<double, 3, 1> beta_tau = Eigen::Matrix<double, 3, 1>::Zero();
122  Eigen::Matrix<double, 4, 1> q_k2tau;
123  Eigen::Matrix<double, 3, 3> R_k2tau = Eigen::Matrix<double, 3, 3>::Identity();
124 
125  // Jacobians
126  Eigen::Matrix<double, 3, 3> J_q = Eigen::Matrix<double, 3, 3>::Zero();
127  Eigen::Matrix<double, 3, 3> J_a = Eigen::Matrix<double, 3, 3>::Zero();
128  Eigen::Matrix<double, 3, 3> J_b = Eigen::Matrix<double, 3, 3>::Zero();
129  Eigen::Matrix<double, 3, 3> H_a = Eigen::Matrix<double, 3, 3>::Zero();
130  Eigen::Matrix<double, 3, 3> H_b = Eigen::Matrix<double, 3, 3>::Zero();
131 
132  // Linearization points
133  Eigen::Matrix<double, 3, 1> b_w_lin;
134  Eigen::Matrix<double, 3, 1> b_a_lin;
135  Eigen::Matrix<double, 4, 1> q_k_lin;
136 
138  Eigen::Matrix<double, 3, 1> grav = Eigen::Matrix<double, 3, 1>::Zero();
139 
141  Eigen::Matrix<double, 12, 12> Q_c = Eigen::Matrix<double, 12, 12>::Zero();
142 
144  Eigen::Matrix<double, 15, 15> P_meas = Eigen::Matrix<double, 15, 15>::Zero();
145 
146  //==========================================================================
147  // HELPER VARIABLES
148  //==========================================================================
149 
150  // 3x3 identity matrix
151  Eigen::Matrix<double, 3, 3> eye3 = Eigen::Matrix<double, 3, 3>::Identity();
152 
153  // Simple unit vectors (used in bias jacobian calculations)
154  Eigen::Matrix<double, 3, 1> e_1; // = Eigen::Matrix<double,3,1>::Constant(1,0,0);
155  Eigen::Matrix<double, 3, 1> e_2; // = Eigen::Matrix<double,3,1>::Constant(0,1,0);
156  Eigen::Matrix<double, 3, 1> e_3; // = Eigen::Matrix<double,3,1>::Constant(0,0,1);
157 
158  // Calculate the skew-symetric of our unit vectors
159  Eigen::Matrix<double, 3, 3> e_1x; // = skew_x(e_1);
160  Eigen::Matrix<double, 3, 3> e_2x; // = skew_x(e_2);
161  Eigen::Matrix<double, 3, 3> e_3x; // = skew_x(e_3);
162 };
163 
164 } // namespace ov_core
165 
166 #endif /* CPI_BASE_H */
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
Base class for continuous preintegration integrators.
Definition: CpiBase.h:49
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::setLinearizationPoints
void setLinearizationPoints(Eigen::Matrix< double, 3, 1 > b_w_lin_, Eigen::Matrix< double, 3, 1 > b_a_lin_, Eigen::Matrix< double, 4, 1 > q_k_lin_=Eigen::Matrix< double, 4, 1 >::Zero(), Eigen::Matrix< double, 3, 1 > grav_=Eigen::Matrix< double, 3, 1 >::Zero())
Set linearization points of the integration.
Definition: CpiBase.h:88
ov_core::CpiBase::DT
double DT
measurement integration time
Definition: CpiBase.h:119
ov_core::CpiBase::feed_IMU
virtual 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())=0
Main function that will sequentially compute the preintegration measurement.
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::grav
Eigen::Matrix< double, 3, 1 > grav
Global gravity.
Definition: CpiBase.h:138
ov_core::CpiBase::e_3x
Eigen::Matrix< double, 3, 3 > e_3x
Definition: CpiBase.h:161
ov_core::CpiBase::beta_tau
Eigen::Matrix< double, 3, 1 > beta_tau
beta measurement mean
Definition: CpiBase.h:121
ov_core::CpiBase::q_k_lin
Eigen::Matrix< double, 4, 1 > q_k_lin
q_k linearization point (only model 2 uses)
Definition: CpiBase.h:135
ov_core::CpiBase::e_1
Eigen::Matrix< double, 3, 1 > e_1
Definition: CpiBase.h:154
ov_core::CpiBase::CpiBase
CpiBase(double sigma_w, double sigma_wb, double sigma_a, double sigma_ab, bool imu_avg_=false)
Default constructor.
Definition: CpiBase.h:60
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::~CpiBase
virtual ~CpiBase()
Definition: CpiBase.h:76
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