0.2.0
Loading...
Searching...
No Matches
ImuPos.hpp
Go to the documentation of this file.
1// This file is part of INSTINCT, the INS Toolkit for Integrated
2// Navigation Concepts and Training by the Institute of Navigation of
3// the University of Stuttgart, Germany.
4//
5// This Source Code Form is subject to the terms of the Mozilla Public
6// License, v. 2.0. If a copy of the MPL was not distributed with this
7// file, You can obtain one at https://mozilla.org/MPL/2.0/.
8
13
14#pragma once
15
16#include "util/Eigen.hpp"
17
18namespace NAV
19{
20// Forward declarations
21class Imu;
22class MultiImuFile;
23
25class ImuPos
26{
27 public:
29 [[nodiscard]] const Eigen::Vector3d& b_positionAccel() const
30 {
31 return _b_positionAccel;
32 }
34 [[nodiscard]] const Eigen::Vector3d& b_positionGyro() const
35 {
36 return _b_positionGyro;
37 }
39 [[nodiscard]] const Eigen::Vector3d& b_positionMag() const
40 {
41 return _b_positionMag;
42 }
43
45 [[nodiscard]] const Eigen::Quaterniond& b_quatAccel_p() const
46 {
47 return _b_quatAccel_p;
48 }
50 [[nodiscard]] Eigen::Quaterniond p_quatAccel_b() const
51 {
52 return _b_quatAccel_p.conjugate();
53 }
54
56 [[nodiscard]] const Eigen::Quaterniond& b_quatGyro_p() const
57 {
58 return _b_quatGyro_p;
59 }
61 [[nodiscard]] Eigen::Quaterniond p_quatGyro_b() const
62 {
63 return _b_quatGyro_p.conjugate();
64 }
65
67 [[nodiscard]] const Eigen::Quaterniond& b_quatMag_p() const
68 {
69 return _b_quatMag_p;
70 }
72 [[nodiscard]] Eigen::Quaterniond p_quatMag_b() const
73 {
74 return _b_quatMag_p.conjugate();
75 }
76
77 private:
79 Eigen::Vector3d _b_positionAccel = { 0, 0, 0 };
81 Eigen::Vector3d _b_positionGyro = { 0, 0, 0 };
83 Eigen::Vector3d _b_positionMag = { 0, 0, 0 };
84
86 Eigen::Quaterniond _b_quatAccel_p = Eigen::Quaterniond::Identity();
88 Eigen::Quaterniond _b_quatGyro_p = { 1, 0, 0, 0 };
90 Eigen::Quaterniond _b_quatMag_p = { 1, 0, 0, 0 };
91
92 friend class Imu;
93 friend class MultiImuFile;
94 friend void from_json(const json& j, ImuPos& pos);
95};
96
100void to_json(json& j, const ImuPos& pos);
104void from_json(const json& j, ImuPos& pos);
105
106} // namespace NAV
Vector space operations.
nlohmann::json json
json namespace
Definition FlowManager.hpp:21
void from_json(const json &j, ImColor &color)
Converts the provided json object into a color.
void to_json(json &j, const ImColor &color)
Converts the provided color into a json object.
IMU Position.
Definition ImuPos.hpp:26
const Eigen::Vector3d & b_positionGyro() const
Gyroscope position in body frame coordinates in [m].
Definition ImuPos.hpp:34
friend void from_json(const json &j, ImuPos &pos)
Read info from a json object.
const Eigen::Vector3d & b_positionMag() const
Magnetometer position in body frame coordinates in [m].
Definition ImuPos.hpp:39
Eigen::Quaterniond p_quatAccel_b() const
Quaternion from body frame to accelerometer platform frame.
Definition ImuPos.hpp:50
const Eigen::Quaterniond & b_quatGyro_p() const
Quaternion from gyroscope platform frame to body frame.
Definition ImuPos.hpp:56
Eigen::Quaterniond p_quatMag_b() const
Quaternion from body frame to magnetometer platform frame.
Definition ImuPos.hpp:72
const Eigen::Vector3d & b_positionAccel() const
Accelerometer position in body frame coordinates in [m].
Definition ImuPos.hpp:29
const Eigen::Quaterniond & b_quatMag_p() const
Quaternion from magnetometer platform frame to body frame.
Definition ImuPos.hpp:67
const Eigen::Quaterniond & b_quatAccel_p() const
Quaternion from accelerometer platform frame to body frame.
Definition ImuPos.hpp:45
Eigen::Quaterniond p_quatGyro_b() const
Quaternion from body frame to gyroscope platform frame.
Definition ImuPos.hpp:61