ekf_cal  0.4.0
A Kalman filter-based sensor calibration package
types.hpp
1 // Copyright 2023 Jacob Hartzer
2 //
3 // This program is free software: you can redistribute it and/or modify
4 // it under the terms of the GNU General Public License as published by
5 // the Free Software Foundation, either version 3 of the License, or
6 // (at your option) any later version.
7 //
8 // This program is distributed in the hope that it will be useful,
9 // but WITHOUT ANY WARRANTY; without even the implied warranty of
10 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 // GNU General Public License for more details.
12 //
13 // You should have received a copy of the GNU General Public License
14 // along with this program. If not, see <https://www.gnu.org/licenses/>.
15 
16 #ifndef EKF__TYPES_HPP_
17 #define EKF__TYPES_HPP_
18 
19 #include <eigen3/Eigen/Eigen>
20 
21 #include <map>
22 #include <vector>
23 
24 #include "ekf/constants.hpp"
25 
26 #include <opencv2/opencv.hpp>
27 
28 enum class SensorType
29 {
30  IMU,
31  Camera,
32  Tracker,
33  GPS
34 };
35 
36 enum class AugmentationType
37 {
38  NONE, // No camera frames are augmented (fiducial detection only)
39  ALL, // All camera frames are augmented
40  PRIMARY, // Only the primary camera frames are augmented
41  TIME, // Time-based frame augmentation
42  ERROR // Linear Error-based frame augmentation
43 };
44 
49 {
50 public:
51  Intrinsics() {}
52 
57  cv::Mat ToCameraMatrix() const;
58 
63  cv::Mat ToDistortionVector() const;
64 
66  double f_x {0.01};
67  double f_y {0.01};
68  double k_1 {0.0};
69  double k_2 {0.0};
70  double p_1 {0.0};
71  double p_2 {0.0};
72  double width {1920};
73  double height {1080};
74  double pixel_size {5.0e-6};
75 };
76 
80 class BodyState
81 {
82 public:
86  BodyState() {}
87 
92  Eigen::VectorXd ToVector() const;
93 
98  void SetState(const Eigen::VectorXd & state);
99 
100  Eigen::Vector3d pos_b_in_l{0.0, 0.0, 0.0};
101  Eigen::Vector3d vel_b_in_l{0.0, 0.0, 0.0};
102  Eigen::Vector3d acc_b_in_l{g_gravity};
103  Eigen::Quaterniond ang_b_to_l{1.0, 0.0, 0.0, 0.0};
104  Eigen::Vector3d ang_vel_b_in_l{0.0, 0.0, 0.0};
105  Eigen::Vector3d ang_acc_b_in_l{0.0, 0.0, 0.0};
106  unsigned int size{g_body_state_size};
107  unsigned int index{0};
108 };
109 
113 class ImuState
114 {
115 public:
116  ImuState() {}
117 
122  Eigen::VectorXd ToVector() const;
123 
128  bool GetIsExtrinsic() const;
133  bool GetIsIntrinsic() const;
138  void SetIsExtrinsic(bool extrinsic);
143  void SetIsIntrinsic(bool intrinsic);
148  void SetExtrinsicState(const Eigen::VectorXd & state);
153  void SetIntrinsicState(const Eigen::VectorXd & state);
154 
155  double pos_stability {1e-9};
156  double ang_stability {1e-9};
157  double acc_bias_stability {1e-9};
158  double omg_bias_stability {1e-9};
159  Eigen::Vector3d pos_i_in_b{0.0, 0.0, 0.0};
160  Eigen::Quaterniond ang_i_to_b{1.0, 0.0, 0.0, 0.0};
161  Eigen::Vector3d acc_bias{0.0, 0.0, 0.0};
162  Eigen::Vector3d omg_bias{0.0, 0.0, 0.0};
163  unsigned int size{0};
164  unsigned int index{0};
165  unsigned int index_intrinsic{0};
166  unsigned int index_extrinsic{0};
167 
168 private:
169  void refresh_size();
170  bool is_extrinsic{false};
171  bool is_intrinsic{false};
172 };
173 
177 class GpsState
178 {
179 public:
180  GpsState() {}
181 
186  Eigen::VectorXd ToVector() const;
187 
192  bool GetIsExtrinsic() const;
197  void SetIsExtrinsic(bool extrinsic);
198 
199  Eigen::Vector3d pos_a_in_b{0.0, 0.0, 0.0};
200  double pos_stability {1e-9};
201  unsigned int size{0};
202  unsigned int index{0};
203 
204 private:
205  void refresh_size();
206  bool is_extrinsic{false};
207 };
208 
212 class AugState
213 {
214 public:
215  AugState() {}
216 
221  Eigen::VectorXd ToVector() const;
222 
223  unsigned int frame_id{0};
224  double time {0.0};
225  Eigen::Vector3d pos_b_in_l{0.0, 0.0, 0.0};
226  Eigen::Quaterniond ang_b_to_l{1.0, 0.0, 0.0, 0.0};
227  unsigned int size{g_aug_state_size};
228  unsigned int index{0};
229  double alpha {0.0};
230 };
231 
235 class CamState
236 {
237 public:
238  CamState() {}
239 
244  Eigen::VectorXd ToVector() const;
245 
250  bool GetIsExtrinsic() const;
255  void SetIsExtrinsic(bool extrinsic);
260  void SetState(const Eigen::VectorXd & state);
261 
262  double pos_stability {1e-9};
263  double ang_stability {1e-9};
264  Eigen::Vector3d pos_c_in_b{0.0, 0.0, 0.0};
265  Eigen::Quaterniond ang_c_to_b{1.0, 0.0, 0.0, 0.0};
267  double rate{1.0};
268  unsigned int size{0};
269  unsigned int index{0};
270 
271 private:
272  void refresh_size();
273  bool is_extrinsic{false};
274 };
275 
279 typedef struct FeaturePoint
280 {
281  unsigned int frame_id;
282  double frame_time;
283  cv::KeyPoint key_point;
284 } FeaturePoint;
285 
289 typedef struct FeatureTrack
290 {
291  std::vector<FeaturePoint> track;
293  Eigen::Vector3d true_feature_position;
294 } FeatureTrack;
295 
299 typedef std::vector<FeatureTrack> FeatureTracks;
300 
304 typedef struct BoardDetection
305 {
306  unsigned int frame_id{0};
307  double frame_time{-1.0};
308  Eigen::Vector3d pos_f_in_c;
309  Eigen::Quaterniond ang_f_to_c;
310  Eigen::Vector3d pos_error{1e-9, 1e-9, 1e-9};
311  Eigen::Vector3d ang_error{1e-9, 1e-9, 1e-9};
313 
317 class FidState
318 {
319 public:
320  FidState() {}
321 
326  Eigen::VectorXd ToVector() const;
327 
332  bool GetIsExtrinsic() const;
337  void SetIsExtrinsic(bool extrinsic);
342  void SetState(const Eigen::VectorXd & state);
343 
344  unsigned int frame_id{0};
345  Eigen::Vector3d pos_f_in_l;
346  Eigen::Quaterniond ang_f_to_l;
347  double pos_stability {1e-9};
348  double ang_stability {1e-9};
349  unsigned int size{0};
350  unsigned int index{0};
351  unsigned int id{0};
352 
353 private:
354  void refresh_size();
355  bool is_extrinsic{false};
356 };
357 
362 class State
363 {
364 public:
368  State() {}
369 
374  Eigen::VectorXd ToVector() const;
375 
380  void SetState(const Eigen::VectorXd & state);
381 
386  unsigned int GetStateSize() const;
387 
389  std::map<unsigned int, ImuState> imu_states{};
390  std::map<unsigned int, GpsState> gps_states{};
391  std::map<unsigned int, CamState> cam_states{};
392  std::map<unsigned int, FidState> fid_states{};
393  std::map<unsigned int, std::vector<AugState>> aug_states{};
394 };
395 
396 BodyState & operator+=(BodyState & l_body_state, const BodyState & r_body_state);
397 BodyState & operator+=(BodyState & l_body_state, const Eigen::VectorXd & r_vector);
398 ImuState & operator+=(ImuState & l_imu_state, const Eigen::VectorXd & r_vector);
399 std::map<unsigned int, ImuState> & operator+=(
400  std::map<unsigned int, ImuState> & l_imu_state, const Eigen::VectorXd & r_vector);
401 std::map<unsigned int, GpsState> & operator+=(
402  std::map<unsigned int, GpsState> & l_gps_state, const Eigen::VectorXd & r_vector);
403 std::map<unsigned int, CamState> & operator+=(
404  std::map<unsigned int, CamState> & l_cam_state, const Eigen::VectorXd & r_vector);
405 std::map<unsigned int, FidState> & operator+=(
406  std::map<unsigned int, FidState> & l_fid_state, const Eigen::VectorXd & r_vector);
407 std::vector<AugState> & operator+=(
408  std::vector<AugState> & l_aug_state, const Eigen::VectorXd & r_vector);
409 
410 State & operator+=(State & l_state, State & r_state);
411 State & operator+=(State & l_state, const Eigen::VectorXd & r_vector);
412 
413 enum class GpsInitType
414 {
415  CONSTANT,
416  BASELINE_DIST,
417  ERROR_THRESHOLD
418 };
419 
420 #endif // EKF__TYPES_HPP_
AugState structure.
Definition: types.hpp:213
double time
Augmented frame ID.
Definition: types.hpp:224
Eigen::Quaterniond ang_b_to_l
Augmented IMU orientation.
Definition: types.hpp:226
double alpha
Interpolation Factor.
Definition: types.hpp:229
Eigen::Vector3d pos_b_in_l
Augmented IMU position.
Definition: types.hpp:225
unsigned int index
State index.
Definition: types.hpp:228
unsigned int frame_id
Augmented frame ID.
Definition: types.hpp:223
unsigned int size
State size.
Definition: types.hpp:227
Eigen::VectorXd ToVector() const
Get augmented state as a vector.
Definition: types.cpp:244
BodyState structure.
Definition: types.hpp:81
Eigen::Vector3d ang_vel_b_in_l
Body angular velocity.
Definition: types.hpp:104
void SetState(const Eigen::VectorXd &state)
Function to set state using vector.
Definition: types.cpp:290
Eigen::Vector3d ang_acc_b_in_l
Body angular acceleration.
Definition: types.hpp:105
unsigned int size
State size.
Definition: types.hpp:106
unsigned int index
State index.
Definition: types.hpp:107
Eigen::Vector3d vel_b_in_l
Body velocity.
Definition: types.hpp:101
Eigen::Vector3d pos_b_in_l
Body position.
Definition: types.hpp:100
BodyState()
EKF State constructor.
Definition: types.hpp:86
Eigen::Vector3d acc_b_in_l
Body acceleration.
Definition: types.hpp:102
Eigen::VectorXd ToVector() const
Get EKF state as a vector.
Definition: types.cpp:220
Eigen::Quaterniond ang_b_to_l
Body orientation.
Definition: types.hpp:103
CamState structure.
Definition: types.hpp:236
void SetIsExtrinsic(bool extrinsic)
is_extrinsic setter function
Definition: types.cpp:465
Eigen::Vector3d pos_c_in_b
Camera state position.
Definition: types.hpp:264
double rate
Frame rate.
Definition: types.hpp:267
double ang_stability
Extrinsic orientation stability.
Definition: types.hpp:263
Eigen::Quaterniond ang_c_to_b
Camera state orientation.
Definition: types.hpp:265
Intrinsics intrinsics
Camera Intrinsics.
Definition: types.hpp:266
unsigned int index
State index.
Definition: types.hpp:269
unsigned int size
State size.
Definition: types.hpp:268
double pos_stability
Extrinsic position stability.
Definition: types.hpp:262
Eigen::VectorXd ToVector() const
Get camera state as a vector.
Definition: types.cpp:234
bool GetIsExtrinsic() const
is_extrinsic getter function
Definition: types.cpp:444
void SetState(const Eigen::VectorXd &state)
Setter for state values.
Definition: types.cpp:471
Camera Sensor Class.
Definition: camera.hpp:41
Fiducial state structure.
Definition: types.hpp:318
Eigen::Vector3d pos_f_in_l
Fiducial position in the local frame.
Definition: types.hpp:345
double ang_stability
Fiducial orientation stability.
Definition: types.hpp:348
unsigned int index
State index.
Definition: types.hpp:350
Eigen::VectorXd ToVector() const
Get fiducial state as a vector.
Definition: types.cpp:278
bool GetIsExtrinsic() const
is_extrinsic getter function
Definition: types.cpp:454
unsigned int size
State size.
Definition: types.hpp:349
double pos_stability
Fiducial position stability.
Definition: types.hpp:347
void SetState(const Eigen::VectorXd &state)
Setter for state values.
Definition: types.cpp:514
Eigen::Quaterniond ang_f_to_l
Fiducial position in the local frame.
Definition: types.hpp:346
void SetIsExtrinsic(bool extrinsic)
is_extrinsic setter function
Definition: types.cpp:508
unsigned int frame_id
Fiducial board ID.
Definition: types.hpp:344
GPS Sensor Class.
Definition: gps.hpp:36
GpsState structure.
Definition: types.hpp:178
double pos_stability
Antenna position stability.
Definition: types.hpp:200
void SetIsExtrinsic(bool extrinsic)
is_extrinsic setter function
Definition: types.cpp:477
Eigen::Vector3d pos_a_in_b
Antenna position in body frame.
Definition: types.hpp:199
bool GetIsExtrinsic() const
is_extrinsic getter function
Definition: types.cpp:449
Eigen::VectorXd ToVector() const
Get GPS state as a vector.
Definition: types.cpp:273
unsigned int index
State index.
Definition: types.hpp:202
unsigned int size
State size.
Definition: types.hpp:201
IMU Sensor Class.
Definition: imu.hpp:33
ImuState structure.
Definition: types.hpp:114
void SetIsExtrinsic(bool extrinsic)
is_extrinsic setter function
Definition: types.cpp:459
bool GetIsExtrinsic() const
is_extrinsic getter function
Definition: types.cpp:434
bool GetIsIntrinsic() const
is_intrinsic getter function
Definition: types.cpp:439
unsigned int index
State index.
Definition: types.hpp:164
Eigen::Vector3d omg_bias
Angular rate bias.
Definition: types.hpp:162
Eigen::Vector3d pos_i_in_b
Position.
Definition: types.hpp:159
double ang_stability
Extrinsic orientation stability.
Definition: types.hpp:156
void SetIsIntrinsic(bool intrinsic)
is_intrinsic setter function
Definition: types.cpp:483
double acc_bias_stability
Accelerometer bias stability.
Definition: types.hpp:157
unsigned int size
State size.
Definition: types.hpp:163
Eigen::VectorXd ToVector() const
Get IMU state as a vector.
Definition: types.cpp:254
Eigen::Quaterniond ang_i_to_b
Orientation.
Definition: types.hpp:160
Eigen::Vector3d acc_bias
Acceleration bias.
Definition: types.hpp:161
void SetIntrinsicState(const Eigen::VectorXd &state)
Setter for intrinsic state values.
Definition: types.cpp:428
unsigned int index_intrinsic
Intrinsic state index.
Definition: types.hpp:165
double pos_stability
Extrinsic position stability.
Definition: types.hpp:155
unsigned int index_extrinsic
Extrinsic state index.
Definition: types.hpp:166
double omg_bias_stability
Gyroscope bias stability.
Definition: types.hpp:158
void SetExtrinsicState(const Eigen::VectorXd &state)
Setter for extrinsic state values.
Definition: types.cpp:422
Camera intrinsics data structure.
Definition: types.hpp:49
double p_1
Tangential coefficient 1.
Definition: types.hpp:70
double p_2
Tangential coefficient 1.
Definition: types.hpp:71
cv::Mat ToDistortionVector() const
Generate distortion vector from intrinsics.
Definition: types.cpp:539
double k_1
Radial coefficient 1.
Definition: types.hpp:68
cv::Mat ToCameraMatrix() const
Generate camera matrix from intrinsics.
Definition: types.cpp:526
double width
Image width [px].
Definition: types.hpp:72
double f_y
Y focal length [px].
Definition: types.hpp:67
double f_x
X focal length [px].
Definition: types.hpp:66
double height
Image height [px].
Definition: types.hpp:73
double k_2
Radial coefficient 2.
Definition: types.hpp:69
double pixel_size
Pixel size [mm].
Definition: types.hpp:74
EKF State Class.
Definition: types.hpp:363
std::map< unsigned int, std::vector< AugState > > aug_states
Fiducial states.
Definition: types.hpp:393
unsigned int GetStateSize() const
Get EKF state size.
Definition: types.cpp:386
void SetState(const Eigen::VectorXd &state)
Function to set state using vector.
Definition: types.cpp:347
std::map< unsigned int, CamState > cam_states
Camera states.
Definition: types.hpp:391
std::map< unsigned int, ImuState > imu_states
IMU states.
Definition: types.hpp:389
State()
EKF State constructor.
Definition: types.hpp:368
std::map< unsigned int, GpsState > gps_states
GPS states.
Definition: types.hpp:390
Eigen::VectorXd ToVector() const
Get EKF state as a vector.
Definition: types.cpp:301
BodyState body_state
Body state.
Definition: types.hpp:388
std::map< unsigned int, FidState > fid_states
Fiducial states.
Definition: types.hpp:392
Tracker Class.
Definition: tracker.hpp:31
BoardDetection structure.
Definition: types.hpp:305
unsigned int frame_id
Image frame ID.
Definition: types.hpp:306
Eigen::Vector3d pos_f_in_c
Rotation vector of the board.
Definition: types.hpp:308
Eigen::Vector3d pos_error
Position detection error.
Definition: types.hpp:310
double frame_time
Feature frame time.
Definition: types.hpp:307
Eigen::Vector3d ang_error
Orientation detection error.
Definition: types.hpp:311
Eigen::Quaterniond ang_f_to_c
Translation vector of the board.
Definition: types.hpp:309
FeaturePoint structure.
Definition: types.hpp:280
cv::KeyPoint key_point
Feature track key point.
Definition: types.hpp:283
unsigned int frame_id
Feature track frame ID.
Definition: types.hpp:281
double frame_time
Feature frame time.
Definition: types.hpp:282
FeatureTrack structure.
Definition: types.hpp:290
std::vector< FeaturePoint > track
Vector of tracked feature keypoints.
Definition: types.hpp:291
Eigen::Vector3d true_feature_position
True feature position (sim only)
Definition: types.hpp:293