IMU.h
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #ifndef OV_TYPE_TYPE_IMU_H
23 #define OV_TYPE_TYPE_IMU_H
24 
25 #include "PoseJPL.h"
26 #include "utils/quat_ops.h"
27 
28 namespace ov_type {
29 
37 class IMU : public Type {
38 
39 public:
40  IMU() : Type(15) {
41 
42  // Create all the sub-variables
43  _pose = std::shared_ptr<PoseJPL>(new PoseJPL());
44  _v = std::shared_ptr<Vec>(new Vec(3));
45  _bg = std::shared_ptr<Vec>(new Vec(3));
46  _ba = std::shared_ptr<Vec>(new Vec(3));
47 
48  // Set our default state value
49  Eigen::VectorXd imu0 = Eigen::VectorXd::Zero(16, 1);
50  imu0(3) = 1.0;
51  set_value_internal(imu0);
52  set_fej_internal(imu0);
53  }
54 
55  ~IMU() {}
56 
64  void set_local_id(int new_id) override {
65  _id = new_id;
66  _pose->set_local_id(new_id);
67  _v->set_local_id(_pose->id() + ((new_id != -1) ? _pose->size() : 0));
68  _bg->set_local_id(_v->id() + ((new_id != -1) ? _v->size() : 0));
69  _ba->set_local_id(_bg->id() + ((new_id != -1) ? _bg->size() : 0));
70  }
71 
78  void update(const Eigen::VectorXd &dx) override {
79 
80  assert(dx.rows() == _size);
81 
82  Eigen::Matrix<double, 16, 1> newX = _value;
83 
84  Eigen::Matrix<double, 4, 1> dq;
85  dq << .5 * dx.block(0, 0, 3, 1), 1.0;
86  dq = ov_core::quatnorm(dq);
87 
88  newX.block(0, 0, 4, 1) = ov_core::quat_multiply(dq, quat());
89  newX.block(4, 0, 3, 1) += dx.block(3, 0, 3, 1);
90 
91  newX.block(7, 0, 3, 1) += dx.block(6, 0, 3, 1);
92  newX.block(10, 0, 3, 1) += dx.block(9, 0, 3, 1);
93  newX.block(13, 0, 3, 1) += dx.block(12, 0, 3, 1);
94 
95  set_value(newX);
96  }
97 
102  void set_value(const Eigen::MatrixXd &new_value) override { set_value_internal(new_value); }
103 
108  void set_fej(const Eigen::MatrixXd &new_value) override { set_fej_internal(new_value); }
109 
110  std::shared_ptr<Type> clone() override {
111  auto Clone = std::shared_ptr<Type>(new IMU());
112  Clone->set_value(value());
113  Clone->set_fej(fej());
114  return Clone;
115  }
116 
117  std::shared_ptr<Type> check_if_subvariable(const std::shared_ptr<Type> check) override {
118  if (check == _pose) {
119  return _pose;
120  } else if (check == _pose->check_if_subvariable(check)) {
121  return _pose->check_if_subvariable(check);
122  } else if (check == _v) {
123  return _v;
124  } else if (check == _bg) {
125  return _bg;
126  } else if (check == _ba) {
127  return _ba;
128  }
129  return nullptr;
130  }
131 
133  Eigen::Matrix<double, 3, 3> Rot() const { return _pose->Rot(); }
134 
136  Eigen::Matrix<double, 3, 3> Rot_fej() const { return _pose->Rot_fej(); }
137 
139  Eigen::Matrix<double, 4, 1> quat() const { return _pose->quat(); }
140 
142  Eigen::Matrix<double, 4, 1> quat_fej() const { return _pose->quat_fej(); }
143 
145  Eigen::Matrix<double, 3, 1> pos() const { return _pose->pos(); }
146 
148  Eigen::Matrix<double, 3, 1> pos_fej() const { return _pose->pos_fej(); }
149 
151  Eigen::Matrix<double, 3, 1> vel() const { return _v->value(); }
152 
153  // FEJ velocity access
154  Eigen::Matrix<double, 3, 1> vel_fej() const { return _v->fej(); }
155 
157  Eigen::Matrix<double, 3, 1> bias_g() const { return _bg->value(); }
158 
160  Eigen::Matrix<double, 3, 1> bias_g_fej() const { return _bg->fej(); }
161 
163  Eigen::Matrix<double, 3, 1> bias_a() const { return _ba->value(); }
164 
165  // FEJ accel bias access
166  Eigen::Matrix<double, 3, 1> bias_a_fej() const { return _ba->fej(); }
167 
169  std::shared_ptr<PoseJPL> pose() { return _pose; }
170 
172  std::shared_ptr<JPLQuat> q() { return _pose->q(); }
173 
175  std::shared_ptr<Vec> p() { return _pose->p(); }
176 
178  std::shared_ptr<Vec> v() { return _v; }
179 
181  std::shared_ptr<Vec> bg() { return _bg; }
182 
184  std::shared_ptr<Vec> ba() { return _ba; }
185 
186 protected:
188  std::shared_ptr<PoseJPL> _pose;
189 
191  std::shared_ptr<Vec> _v;
192 
194  std::shared_ptr<Vec> _bg;
195 
197  std::shared_ptr<Vec> _ba;
198 
203  void set_value_internal(const Eigen::MatrixXd &new_value) {
204 
205  assert(new_value.rows() == 16);
206  assert(new_value.cols() == 1);
207 
208  _pose->set_value(new_value.block(0, 0, 7, 1));
209  _v->set_value(new_value.block(7, 0, 3, 1));
210  _bg->set_value(new_value.block(10, 0, 3, 1));
211  _ba->set_value(new_value.block(13, 0, 3, 1));
212 
213  _value = new_value;
214  }
215 
220  void set_fej_internal(const Eigen::MatrixXd &new_value) {
221 
222  assert(new_value.rows() == 16);
223  assert(new_value.cols() == 1);
224 
225  _pose->set_fej(new_value.block(0, 0, 7, 1));
226  _v->set_fej(new_value.block(7, 0, 3, 1));
227  _bg->set_fej(new_value.block(10, 0, 3, 1));
228  _ba->set_fej(new_value.block(13, 0, 3, 1));
229 
230  _fej = new_value;
231  }
232 };
233 
234 } // namespace ov_type
235 
236 #endif // OV_TYPE_TYPE_IMU_H
ov_type::IMU::set_value_internal
void set_value_internal(const Eigen::MatrixXd &new_value)
Sets the value of the estimate.
Definition: IMU.h:203
ov_type::IMU::quat
Eigen::Matrix< double, 4, 1 > quat() const
Rotation access quaternion.
Definition: IMU.h:139
check
ROSCPP_DECL bool check()
ov_type::IMU::pos_fej
Eigen::Matrix< double, 3, 1 > pos_fej() const
FEJ position access.
Definition: IMU.h:148
ov_type::IMU::_bg
std::shared_ptr< Vec > _bg
Gyroscope bias subvariable.
Definition: IMU.h:194
ov_type::IMU::pose
std::shared_ptr< PoseJPL > pose()
Pose type access.
Definition: IMU.h:169
ov_type::IMU::set_fej_internal
void set_fej_internal(const Eigen::MatrixXd &new_value)
Sets the value of the first estimate.
Definition: IMU.h:220
ov_type::IMU::_pose
std::shared_ptr< PoseJPL > _pose
Pose subvariable.
Definition: IMU.h:188
ov_type::IMU::~IMU
~IMU()
Definition: IMU.h:55
ov_type::Type::_size
int _size
Dimension of error state.
Definition: Type.h:132
ov_type::IMU::pos
Eigen::Matrix< double, 3, 1 > pos() const
Position access.
Definition: IMU.h:145
ov_type::IMU::p
std::shared_ptr< Vec > p()
Position type access.
Definition: IMU.h:175
ov_core::quat_multiply
Eigen::Matrix< double, 4, 1 > quat_multiply(const Eigen::Matrix< double, 4, 1 > &q, const Eigen::Matrix< double, 4, 1 > &p)
Multiply two JPL quaternions.
Definition: quat_ops.h:180
ov_type::IMU::bias_g
Eigen::Matrix< double, 3, 1 > bias_g() const
Gyro bias access.
Definition: IMU.h:157
ov_type::IMU::_ba
std::shared_ptr< Vec > _ba
Acceleration bias subvariable.
Definition: IMU.h:197
ov_type::IMU::bias_a_fej
Eigen::Matrix< double, 3, 1 > bias_a_fej() const
Definition: IMU.h:166
ov_type::IMU::bias_g_fej
Eigen::Matrix< double, 3, 1 > bias_g_fej() const
FEJ gyro bias access.
Definition: IMU.h:160
ov_type::IMU::set_fej
void set_fej(const Eigen::MatrixXd &new_value) override
Sets the value of the first estimate.
Definition: IMU.h:108
ov_type::IMU::vel
Eigen::Matrix< double, 3, 1 > vel() const
Velocity access.
Definition: IMU.h:151
ov_type::IMU::clone
std::shared_ptr< Type > clone() override
Create a clone of this variable.
Definition: IMU.h:110
ov_type::IMU
Derived Type class that implements an IMU state.
Definition: IMU.h:37
ov_type::IMU::vel_fej
Eigen::Matrix< double, 3, 1 > vel_fej() const
Definition: IMU.h:154
ov_type::Type::_id
int _id
Location of error state in covariance.
Definition: Type.h:129
ov_type::Type::value
virtual const Eigen::MatrixXd & value() const
Access variable's estimate.
Definition: Type.h:79
ov_type::IMU::_v
std::shared_ptr< Vec > _v
Velocity subvariable.
Definition: IMU.h:191
ov_type::IMU::quat_fej
Eigen::Matrix< double, 4, 1 > quat_fej() const
FEJ Rotation access quaternion.
Definition: IMU.h:142
ov_type::IMU::ba
std::shared_ptr< Vec > ba()
Acceleration bias access.
Definition: IMU.h:184
ov_type::IMU::bg
std::shared_ptr< Vec > bg()
Gyroscope bias access.
Definition: IMU.h:181
ov_type::IMU::set_local_id
void set_local_id(int new_id) override
Sets id used to track location of variable in the filter covariance.
Definition: IMU.h:64
ov_type::IMU::Rot
Eigen::Matrix< double, 3, 3 > Rot() const
Rotation access.
Definition: IMU.h:133
ov_type::IMU::set_value
void set_value(const Eigen::MatrixXd &new_value) override
Sets the value of the estimate.
Definition: IMU.h:102
PoseJPL.h
ov_type::IMU::q
std::shared_ptr< JPLQuat > q()
Quaternion type access.
Definition: IMU.h:172
ov_type::IMU::check_if_subvariable
std::shared_ptr< Type > check_if_subvariable(const std::shared_ptr< Type > check) override
Determine if pass variable is a sub-variable.
Definition: IMU.h:117
ov_type
Dynamic type system types.
ov_core::quatnorm
Eigen::Matrix< double, 4, 1 > quatnorm(Eigen::Matrix< double, 4, 1 > q_t)
Normalizes a quaternion to make sure it is unit norm.
Definition: quat_ops.h:496
ov_type::IMU::v
std::shared_ptr< Vec > v()
Velocity type access.
Definition: IMU.h:178
ov_type::IMU::update
void update(const Eigen::VectorXd &dx) override
Performs update operation using JPLQuat update for orientation, then vector updates for position,...
Definition: IMU.h:78
ov_type::PoseJPL
Derived Type class that implements a 6 d.o.f pose.
Definition: PoseJPL.h:37
ov_type::Type::fej
virtual const Eigen::MatrixXd & fej() const
Access variable's first-estimate.
Definition: Type.h:84
ov_type::Type::_fej
Eigen::MatrixXd _fej
First-estimate.
Definition: Type.h:123
ov_type::Type::_value
Eigen::MatrixXd _value
Current best estimate.
Definition: Type.h:126
ov_type::IMU::Rot_fej
Eigen::Matrix< double, 3, 3 > Rot_fej() const
FEJ Rotation access.
Definition: IMU.h:136
quat_ops.h
ov_type::IMU::bias_a
Eigen::Matrix< double, 3, 1 > bias_a() const
Accel bias access.
Definition: IMU.h:163
ov_type::Vec
Derived Type class that implements vector variables.
Definition: Vec.h:32
ov_type::IMU::IMU
IMU()
Definition: IMU.h:40
ov_type::Type
Base class for estimated variables.
Definition: Type.h:37


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