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 | #include <imgui.h> | ||
11 | |||
12 | #include "internal/FlowManager.hpp" | ||
13 | #include "internal/gui/widgets/HelpMarker.hpp" | ||
14 | #include "internal/gui/widgets/Matrix.hpp" | ||
15 | |||
16 | #include "Navigation/Transformations/CoordinateFrames.hpp" | ||
17 | #include "Navigation/Transformations/Units.hpp" | ||
18 | |||
19 | namespace | ||
20 | { | ||
21 | |||
22 | ✗ | void TrafoHelperMarker(const Eigen::Quaterniond& q) | |
23 | { | ||
24 | ✗ | if (NAV::gui::widgets::BeginHelpMarker()) | |
25 | { | ||
26 | ✗ | Eigen::Matrix3d dcm = q.toRotationMatrix(); | |
27 | |||
28 | ✗ | ImGui::BeginHorizontal("Tooltip Horizontal"); | |
29 | |||
30 | ✗ | ImGui::BeginVertical("Tooltip Vertical 1"); | |
31 | ✗ | ImGui::Spring(); | |
32 | ✗ | ImGui::TextUnformatted("(X Y Z)_b = "); | |
33 | ✗ | ImGui::Spring(); | |
34 | ✗ | ImGui::EndVertical(); | |
35 | |||
36 | ✗ | NAV::gui::widgets::MatrixView("quaternionAccel_bp", &dcm, GuiMatrixViewFlags_None, ImGuiTableFlags_Borders | ImGuiTableFlags_NoHostExtendX, "% -.1f"); | |
37 | |||
38 | ✗ | ImGui::BeginVertical("Tooltip Vertical 2"); | |
39 | ✗ | ImGui::Spring(); | |
40 | ✗ | ImGui::TextUnformatted(" * (X Y Z)_p"); | |
41 | ✗ | ImGui::Spring(); | |
42 | ✗ | ImGui::EndVertical(); | |
43 | |||
44 | ✗ | ImGui::EndHorizontal(); | |
45 | |||
46 | ✗ | NAV::gui::widgets::EndHelpMarker(); | |
47 | } | ||
48 | ✗ | } | |
49 | |||
50 | } // namespace | ||
51 | |||
52 | 1063 | NAV::Imu::Imu(std::string name) | |
53 |
2/4✓ Branch 3 taken 1063 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 1063 times.
✗ Branch 8 not taken.
|
1063 | : Node(std::move(name)) {} |
54 | |||
55 | ✗ | void NAV::Imu::guiConfig() | |
56 | { | ||
57 | ✗ | ImGui::SetNextItemOpen(false, ImGuiCond_Appearing); | |
58 | ✗ | if (ImGui::TreeNode(fmt::format("Imu Position & Rotation##{}", size_t(id)).c_str())) | |
59 | { | ||
60 | ✗ | ImGui::BeginDisabled(); // FIXME Not properly simulated and accounted for in the algorithms | |
61 | ✗ | std::array<float, 3> imuPos = { static_cast<float>(_imuPos.b_positionIMU_p().x()), static_cast<float>(_imuPos.b_positionIMU_p().y()), static_cast<float>(_imuPos.b_positionIMU_p().z()) }; | |
62 | ✗ | if (ImGui::InputFloat3(fmt::format("Position [m]##{}", size_t(id)).c_str(), imuPos.data())) | |
63 | { | ||
64 | ✗ | flow::ApplyChanges(); | |
65 | ✗ | _imuPos._b_positionIMU_p = Eigen::Vector3d(imuPos.at(0), imuPos.at(1), imuPos.at(2)); | |
66 | } | ||
67 | ✗ | ImGui::EndDisabled(); | |
68 | ✗ | ImGui::SameLine(); | |
69 | ✗ | gui::widgets::HelpMarker("Position of the IMU sensor relative to the vehicle center of mass in the body coordinate frame."); | |
70 | |||
71 | ✗ | Eigen::Vector3d eulerAngelsIMU = rad2deg(trafo::quat2eulerZYX(_imuPos.p_quat_b())); | |
72 | ✗ | std::array<float, 3> imuRot = { static_cast<float>(eulerAngelsIMU.x()), static_cast<float>(eulerAngelsIMU.y()), static_cast<float>(eulerAngelsIMU.z()) }; | |
73 | ✗ | if (ImGui::InputFloat3(fmt::format("Rotation [deg]##{}", size_t(id)).c_str(), imuRot.data())) | |
74 | { | ||
75 | // (-180:180] x (-90:90] x (-180:180] | ||
76 | ✗ | imuRot.at(0) = std::max(imuRot.at(0), -179.9999F); | |
77 | ✗ | imuRot.at(0) = std::min(imuRot.at(0), 180.0F); | |
78 | ✗ | imuRot.at(1) = std::max(imuRot.at(1), -89.9999F); | |
79 | ✗ | imuRot.at(1) = std::min(imuRot.at(1), 90.0F); | |
80 | ✗ | imuRot.at(2) = std::max(imuRot.at(2), -179.9999F); | |
81 | ✗ | imuRot.at(2) = std::min(imuRot.at(2), 180.0F); | |
82 | |||
83 | ✗ | flow::ApplyChanges(); | |
84 | ✗ | _imuPos._b_quat_p = trafo::b_Quat_p(deg2rad(imuRot.at(0)), deg2rad(imuRot.at(1)), deg2rad(imuRot.at(2))); | |
85 | } | ||
86 | ✗ | ImGui::SameLine(); | |
87 | ✗ | TrafoHelperMarker(_imuPos.b_quat_p()); | |
88 | |||
89 | ✗ | ImGui::TreePop(); | |
90 | } | ||
91 | ✗ | } | |
92 | |||
93 | ✗ | [[nodiscard]] json NAV::Imu::save() const | |
94 | { | ||
95 | LOG_TRACE("{}: called", nameId()); | ||
96 | |||
97 | ✗ | json j; | |
98 | |||
99 | ✗ | j["imuPos"] = _imuPos; | |
100 | |||
101 | ✗ | return j; | |
102 | ✗ | } | |
103 | |||
104 | 53 | void NAV::Imu::restore(json const& j) | |
105 | { | ||
106 | LOG_TRACE("{}: called", nameId()); | ||
107 | |||
108 |
1/2✓ Branch 1 taken 53 times.
✗ Branch 2 not taken.
|
53 | if (j.contains("imuPos")) |
109 | { | ||
110 | 53 | j.at("imuPos").get_to(_imuPos); | |
111 | } | ||
112 | 53 | } | |
113 |