Line | Branch | Exec | Source |
---|---|---|---|
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 | |||
9 | #include "Imu.hpp" | ||
10 | |||
11 | #include "internal/FlowManager.hpp" | ||
12 | #include "internal/gui/widgets/HelpMarker.hpp" | ||
13 | #include "internal/gui/widgets/Matrix.hpp" | ||
14 | |||
15 | #include "Navigation/Transformations/CoordinateFrames.hpp" | ||
16 | #include "Navigation/Transformations/Units.hpp" | ||
17 | |||
18 | namespace | ||
19 | { | ||
20 | |||
21 | ✗ | void TrafoHelperMarker(const Eigen::Quaterniond& q) | |
22 | { | ||
23 | ✗ | if (NAV::gui::widgets::BeginHelpMarker()) | |
24 | { | ||
25 | ✗ | Eigen::Matrix3d dcm = q.toRotationMatrix(); | |
26 | |||
27 | ✗ | ImGui::BeginHorizontal("Tooltip Horizontal"); | |
28 | |||
29 | ✗ | ImGui::BeginVertical("Tooltip Vertical 1"); | |
30 | ✗ | ImGui::Spring(); | |
31 | ✗ | ImGui::TextUnformatted("(X Y Z)_b = "); | |
32 | ✗ | ImGui::Spring(); | |
33 | ✗ | ImGui::EndVertical(); | |
34 | |||
35 | ✗ | NAV::gui::widgets::MatrixView("quaternionAccel_bp", &dcm, GuiMatrixViewFlags_None, ImGuiTableFlags_Borders | ImGuiTableFlags_NoHostExtendX, "% -.1f"); | |
36 | |||
37 | ✗ | ImGui::BeginVertical("Tooltip Vertical 2"); | |
38 | ✗ | ImGui::Spring(); | |
39 | ✗ | ImGui::TextUnformatted(" * (X Y Z)_p"); | |
40 | ✗ | ImGui::Spring(); | |
41 | ✗ | ImGui::EndVertical(); | |
42 | |||
43 | ✗ | ImGui::EndHorizontal(); | |
44 | |||
45 | ✗ | NAV::gui::widgets::EndHelpMarker(); | |
46 | } | ||
47 | ✗ | } | |
48 | |||
49 | } // namespace | ||
50 | |||
51 | 1064 | NAV::Imu::Imu(std::string name) | |
52 |
2/4✓ Branch 3 taken 1064 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 1064 times.
✗ Branch 8 not taken.
|
1064 | : Node(std::move(name)) {} |
53 | |||
54 | ✗ | void NAV::Imu::guiConfig() | |
55 | { | ||
56 | ✗ | ImGui::SetNextItemOpen(false, ImGuiCond_Appearing); | |
57 | ✗ | if (ImGui::TreeNode(fmt::format("Imu Position & Rotation##{}", size_t(id)).c_str())) | |
58 | { | ||
59 | ✗ | std::array<float, 3> imuPosAccel = { static_cast<float>(_imuPos.b_positionAccel().x()), static_cast<float>(_imuPos.b_positionAccel().y()), static_cast<float>(_imuPos.b_positionAccel().z()) }; | |
60 | ✗ | if (ImGui::InputFloat3(fmt::format("Lever Accel [m]##{}", size_t(id)).c_str(), imuPosAccel.data())) | |
61 | { | ||
62 | ✗ | flow::ApplyChanges(); | |
63 | ✗ | _imuPos._b_positionAccel = Eigen::Vector3d(imuPosAccel.at(0), imuPosAccel.at(1), imuPosAccel.at(2)); | |
64 | } | ||
65 | ✗ | ImGui::SameLine(); | |
66 | ✗ | gui::widgets::HelpMarker("Position of the accelerometer sensor relative to the vehicle center of mass in the body coordinate frame."); | |
67 | |||
68 | ✗ | std::array<float, 3> imuPosGyro = { static_cast<float>(_imuPos.b_positionGyro().x()), static_cast<float>(_imuPos.b_positionGyro().y()), static_cast<float>(_imuPos.b_positionGyro().z()) }; | |
69 | ✗ | if (ImGui::InputFloat3(fmt::format("Lever Gyro [m]##{}", size_t(id)).c_str(), imuPosGyro.data())) | |
70 | { | ||
71 | ✗ | flow::ApplyChanges(); | |
72 | ✗ | _imuPos._b_positionGyro = Eigen::Vector3d(imuPosGyro.at(0), imuPosGyro.at(1), imuPosGyro.at(2)); | |
73 | } | ||
74 | ✗ | ImGui::SameLine(); | |
75 | ✗ | gui::widgets::HelpMarker("Position of the gyroscope sensor relative to the vehicle center of mass in the body coordinate frame."); | |
76 | |||
77 | ✗ | std::array<float, 3> imuPosMag = { static_cast<float>(_imuPos.b_positionMag().x()), static_cast<float>(_imuPos.b_positionMag().y()), static_cast<float>(_imuPos.b_positionMag().z()) }; | |
78 | ✗ | if (ImGui::InputFloat3(fmt::format("Lever Mag [m]##{}", size_t(id)).c_str(), imuPosMag.data())) | |
79 | { | ||
80 | ✗ | flow::ApplyChanges(); | |
81 | ✗ | _imuPos._b_positionMag = Eigen::Vector3d(imuPosMag.at(0), imuPosMag.at(1), imuPosMag.at(2)); | |
82 | } | ||
83 | ✗ | ImGui::SameLine(); | |
84 | ✗ | gui::widgets::HelpMarker("Position of the magnetometer sensor relative to the vehicle center of mass in the body coordinate frame."); | |
85 | |||
86 | ✗ | Eigen::Vector3d eulerAccel = rad2deg(trafo::quat2eulerZYX(_imuPos.p_quatAccel_b())); | |
87 | ✗ | std::array<float, 3> imuRotAccel = { static_cast<float>(eulerAccel.x()), static_cast<float>(eulerAccel.y()), static_cast<float>(eulerAccel.z()) }; | |
88 | ✗ | if (ImGui::InputFloat3(fmt::format("Rotation Accel [deg]##{}", size_t(id)).c_str(), imuRotAccel.data())) | |
89 | { | ||
90 | // (-180:180] x (-90:90] x (-180:180] | ||
91 | ✗ | imuRotAccel.at(0) = std::max(imuRotAccel.at(0), -179.9999F); | |
92 | ✗ | imuRotAccel.at(0) = std::min(imuRotAccel.at(0), 180.0F); | |
93 | ✗ | imuRotAccel.at(1) = std::max(imuRotAccel.at(1), -89.9999F); | |
94 | ✗ | imuRotAccel.at(1) = std::min(imuRotAccel.at(1), 90.0F); | |
95 | ✗ | imuRotAccel.at(2) = std::max(imuRotAccel.at(2), -179.9999F); | |
96 | ✗ | imuRotAccel.at(2) = std::min(imuRotAccel.at(2), 180.0F); | |
97 | |||
98 | ✗ | flow::ApplyChanges(); | |
99 | ✗ | _imuPos._b_quatAccel_p = trafo::b_Quat_p(deg2rad(imuRotAccel.at(0)), deg2rad(imuRotAccel.at(1)), deg2rad(imuRotAccel.at(2))); | |
100 | } | ||
101 | ✗ | ImGui::SameLine(); | |
102 | ✗ | TrafoHelperMarker(_imuPos.b_quatAccel_p()); | |
103 | |||
104 | ✗ | Eigen::Vector3d eulerGyro = rad2deg(trafo::quat2eulerZYX(_imuPos.p_quatGyro_b())); | |
105 | ✗ | std::array<float, 3> imuRotGyro = { static_cast<float>(eulerGyro.x()), static_cast<float>(eulerGyro.y()), static_cast<float>(eulerGyro.z()) }; | |
106 | ✗ | if (ImGui::InputFloat3(fmt::format("Rotation Gyro [deg]##{}", size_t(id)).c_str(), imuRotGyro.data())) | |
107 | { | ||
108 | // (-180:180] x (-90:90] x (-180:180] | ||
109 | ✗ | imuRotGyro.at(0) = std::max(imuRotGyro.at(0), -179.9999F); | |
110 | ✗ | imuRotGyro.at(0) = std::min(imuRotGyro.at(0), 180.0F); | |
111 | ✗ | imuRotGyro.at(1) = std::max(imuRotGyro.at(1), -89.9999F); | |
112 | ✗ | imuRotGyro.at(1) = std::min(imuRotGyro.at(1), 90.0F); | |
113 | ✗ | imuRotGyro.at(2) = std::max(imuRotGyro.at(2), -179.9999F); | |
114 | ✗ | imuRotGyro.at(2) = std::min(imuRotGyro.at(2), 180.0F); | |
115 | |||
116 | ✗ | flow::ApplyChanges(); | |
117 | ✗ | _imuPos._b_quatGyro_p = trafo::b_Quat_p(deg2rad(imuRotGyro.at(0)), deg2rad(imuRotGyro.at(1)), deg2rad(imuRotGyro.at(2))); | |
118 | } | ||
119 | ✗ | ImGui::SameLine(); | |
120 | ✗ | TrafoHelperMarker(_imuPos.b_quatGyro_p()); | |
121 | |||
122 | ✗ | Eigen::Vector3d eulerMag = rad2deg(trafo::quat2eulerZYX(_imuPos.p_quatMag_b())); | |
123 | ✗ | std::array<float, 3> imuRotMag = { static_cast<float>(eulerMag.x()), static_cast<float>(eulerMag.y()), static_cast<float>(eulerMag.z()) }; | |
124 | ✗ | if (ImGui::InputFloat3(fmt::format("Rotation Mag [deg]##{}", size_t(id)).c_str(), imuRotMag.data())) | |
125 | { | ||
126 | // (-180:180] x (-90:90] x (-180:180] | ||
127 | ✗ | imuRotMag.at(0) = std::max(imuRotMag.at(0), -179.9999F); | |
128 | ✗ | imuRotMag.at(0) = std::min(imuRotMag.at(0), 180.0F); | |
129 | ✗ | imuRotMag.at(1) = std::max(imuRotMag.at(1), -89.9999F); | |
130 | ✗ | imuRotMag.at(1) = std::min(imuRotMag.at(1), 90.0F); | |
131 | ✗ | imuRotMag.at(2) = std::max(imuRotMag.at(2), -179.9999F); | |
132 | ✗ | imuRotMag.at(2) = std::min(imuRotMag.at(2), 180.0F); | |
133 | |||
134 | ✗ | flow::ApplyChanges(); | |
135 | ✗ | _imuPos._b_quatMag_p = trafo::b_Quat_p(deg2rad(imuRotMag.at(0)), deg2rad(imuRotMag.at(1)), deg2rad(imuRotMag.at(2))); | |
136 | } | ||
137 | ✗ | ImGui::SameLine(); | |
138 | ✗ | TrafoHelperMarker(_imuPos.b_quatMag_p()); | |
139 | |||
140 | ✗ | ImGui::TreePop(); | |
141 | } | ||
142 | ✗ | } | |
143 | |||
144 | ✗ | [[nodiscard]] json NAV::Imu::save() const | |
145 | { | ||
146 | LOG_TRACE("{}: called", nameId()); | ||
147 | |||
148 | ✗ | json j; | |
149 | |||
150 | ✗ | j["imuPos"] = _imuPos; | |
151 | |||
152 | ✗ | return j; | |
153 | ✗ | } | |
154 | |||
155 | 54 | void NAV::Imu::restore(json const& j) | |
156 | { | ||
157 | LOG_TRACE("{}: called", nameId()); | ||
158 | |||
159 |
1/2✓ Branch 1 taken 54 times.
✗ Branch 2 not taken.
|
54 | if (j.contains("imuPos")) |
160 | { | ||
161 | 54 | j.at("imuPos").get_to(_imuPos); | |
162 | } | ||
163 | 54 | } | |
164 |