0.3.0
Loading...
Searching...
No Matches
ImuObs.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 "NodeData/NodeData.hpp"
17
18#include "ImuPos.hpp"
19#include "util/Eigen.hpp"
20
21namespace NAV
22{
24class ImuObs : public NodeData
25{
26 public:
29 explicit ImuObs(const ImuPos& imuPos)
30 : imuPos(imuPos) {}
31
34 [[nodiscard]] static std::string type()
35 {
36 return "ImuObs";
37 }
38
41 [[nodiscard]] std::string getType() const override { return type(); }
42
45 [[nodiscard]] static std::vector<std::string> parentTypes()
46 {
47 return { NodeData::type() };
48 }
49
51 [[nodiscard]] static std::vector<std::string> GetStaticDataDescriptors()
52 {
53 return {
54 "Time since startup [ns]",
55 "Accel X [m/s^2]",
56 "Accel Y [m/s^2]",
57 "Accel Z [m/s^2]",
58 "Gyro X [rad/s]",
59 "Gyro Y [rad/s]",
60 "Gyro Z [rad/s]",
61 "Mag X [Gauss]",
62 "Mag Y [Gauss]",
63 "Mag Z [Gauss]",
64 "Temperature [°C]",
65 };
66 }
67
69 [[nodiscard]] static constexpr size_t GetStaticDescriptorCount() { return 11; }
70
72 [[nodiscard]] std::vector<std::string> staticDataDescriptors() const override { return GetStaticDataDescriptors(); }
73
75 [[nodiscard]] size_t staticDescriptorCount() const override { return GetStaticDescriptorCount(); }
76
80 [[nodiscard]] std::optional<double> getValueAt(size_t idx) const override
81 {
83 switch (idx)
84 {
85 case 0: // Time since startup [ns]
86 if (timeSinceStartup.has_value()) { return static_cast<double>(timeSinceStartup.value()); }
87 break;
88 case 1: // Accel X [m/s^2]
89 return p_acceleration.x();
90 case 2: // Accel Y [m/s^2]
91 return p_acceleration.y();
92 case 3: // Accel Z [m/s^2]
93 return p_acceleration.z();
94 case 4: // Gyro X [rad/s]
95 return p_angularRate.x();
96 case 5: // Gyro Y [rad/s]
97 return p_angularRate.y();
98 case 6: // Gyro Z [rad/s]
99 return p_angularRate.z();
100 case 7: // Mag X [Gauss]
101 if (p_magneticField.has_value()) { return p_magneticField->x(); }
102 break;
103 case 8: // Mag Y [Gauss]
104 if (p_magneticField.has_value()) { return p_magneticField->y(); }
105 break;
106 case 9: // Mag Z [Gauss]
107 if (p_magneticField.has_value()) { return p_magneticField->z(); }
108 break;
109 case 10: // Temperature [°C]
110 return temperature;
111 default:
112 return std::nullopt;
113 }
114 return std::nullopt;
115 }
116
121 [[nodiscard]] bool setValueAt(size_t idx, double value) override
122 {
124
125 switch (idx)
126 {
127 case 0: // Time since startup [ns]
128 if (value >= 0.0)
129 {
130 timeSinceStartup = static_cast<size_t>(value);
131 return true;
132 }
133 break;
134 case 1: // Accel X [m/s^2]
135 p_acceleration.x() = value;
136 return true;
137 case 2: // Accel Y [m/s^2]
138 p_acceleration.y() = value;
139 return true;
140 case 3: // Accel Z [m/s^2]
141 p_acceleration.z() = value;
142 return true;
143 case 4: // Gyro X [rad/s]
144 p_angularRate.x() = value;
145 return true;
146 case 5: // Gyro Y [rad/s]
147 p_angularRate.y() = value;
148 return true;
149 case 6: // Gyro Z [rad/s]
150 p_angularRate.z() = value;
151 return true;
152 case 7: // Mag X [Gauss]
153 if (p_magneticField.has_value())
154 {
155 p_magneticField->x() = value;
156 return true;
157 }
158 break;
159 case 8: // Mag Y [Gauss]
160 if (p_magneticField.has_value())
161 {
162 p_magneticField->y() = value;
163 return true;
164 }
165 break;
166 case 9: // Mag Z [Gauss]
167 if (p_magneticField.has_value())
168 {
169 p_magneticField->z() = value;
170 return true;
171 }
172 break;
173 case 10: // Temperature [°C]
174 temperature = value;
175 return true;
176 default:
177 return false;
178 }
179
180 return false;
181 }
182
185
187 std::optional<uint64_t> timeSinceStartup;
188
190 Eigen::Vector3d p_acceleration;
192 Eigen::Vector3d p_angularRate;
193
195 std::optional<Eigen::Vector3d> p_magneticField;
197 std::optional<double> temperature = 0.0;
198};
199
200} // namespace NAV
#define INS_ASSERT(_EXPR)
Assert function wrapper.
Definition Assert.h:19
Vector space operations.
Imu Position Data.
Abstract NodeData Class.
IMU Observation storage class.
Definition ImuObs.hpp:25
Eigen::Vector3d p_acceleration
The IMU acceleration measured in units of [m/s^2], given in the platform frame.
Definition ImuObs.hpp:190
std::optional< double > temperature
The IMU temperature measured in units of [Celsius].
Definition ImuObs.hpp:197
bool setValueAt(size_t idx, double value) override
Set the value at the index.
Definition ImuObs.hpp:121
static std::string type()
Returns the type of the data class.
Definition ImuObs.hpp:34
Eigen::Vector3d p_angularRate
The IMU angular rate measured in units of [rad/s], given in the platform frame.
Definition ImuObs.hpp:192
std::optional< uint64_t > timeSinceStartup
The system time since startup measured in [nano seconds].
Definition ImuObs.hpp:187
std::vector< std::string > staticDataDescriptors() const override
Returns a vector of data descriptors.
Definition ImuObs.hpp:72
static std::vector< std::string > parentTypes()
Returns the parent types of the data class.
Definition ImuObs.hpp:45
static std::vector< std::string > GetStaticDataDescriptors()
Returns a vector of data descriptors.
Definition ImuObs.hpp:51
std::string getType() const override
Returns the type of the data class.
Definition ImuObs.hpp:41
static constexpr size_t GetStaticDescriptorCount()
Get the amount of descriptors.
Definition ImuObs.hpp:69
std::optional< double > getValueAt(size_t idx) const override
Get the value at the index.
Definition ImuObs.hpp:80
ImuObs(const ImuPos &imuPos)
Constructor.
Definition ImuObs.hpp:29
size_t staticDescriptorCount() const override
Get the amount of descriptors.
Definition ImuObs.hpp:75
const ImuPos & imuPos
Position and rotation information for conversion from platform to body frame.
Definition ImuObs.hpp:184
std::optional< Eigen::Vector3d > p_magneticField
The IMU magnetic field measured in units of [Gauss], given in the platform frame.
Definition ImuObs.hpp:195
IMU Position.
Definition ImuPos.hpp:26
Parent class for all data transmitted over Flow pins.
Definition NodeData.hpp:28
static std::string type()
Returns the type of the data class.
Definition NodeData.hpp:45