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 <memory> | ||
10 | #if __linux__ || __APPLE__ | ||
11 | |||
12 | #include "mavlinkSend.hpp" | ||
13 | #include <array> | ||
14 | |||
15 | #include "internal/NodeManager.hpp" | ||
16 | namespace nm = NAV::NodeManager; | ||
17 | #include "internal/FlowManager.hpp" | ||
18 | |||
19 | #include "internal/gui/widgets/imgui_ex.hpp" | ||
20 | #include "internal/gui/widgets/HelpMarker.hpp" | ||
21 | #include "internal/gui/NodeEditorApplication.hpp" | ||
22 | |||
23 | #include "mavlink/common/mavlink.h" | ||
24 | #include "util/Vendor/MavLink/autopilot_interface.hpp" | ||
25 | |||
26 | #include "util/Logger.hpp" | ||
27 | |||
28 | 112 | NAV::MavlinkSend::MavlinkSend() | |
29 |
3/6✓ Branch 1 taken 112 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 112 times.
✗ Branch 5 not taken.
✓ Branch 9 taken 112 times.
✗ Branch 10 not taken.
|
112 | : Node(typeStatic()) |
30 | { | ||
31 | LOG_TRACE("{}: called", name); | ||
32 | 112 | _hasConfig = true; | |
33 | 112 | _guiConfigDefaultWindowSize = { 479.0, 197.0 }; | |
34 | |||
35 |
4/8✓ Branch 1 taken 112 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 112 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 112 times.
✓ Branch 9 taken 112 times.
✗ Branch 12 not taken.
✗ Branch 13 not taken.
|
336 | nm::CreateInputPin(this, "PosVelAtt", Pin::Type::Flow, { NAV::PosVelAtt::type() }, &MavlinkSend::receivePosVelAtt); |
36 | 224 | } | |
37 | |||
38 | 224 | NAV::MavlinkSend::~MavlinkSend() | |
39 | { | ||
40 | LOG_TRACE("{}: called", nameId()); | ||
41 | 224 | } | |
42 | |||
43 | 224 | std::string NAV::MavlinkSend::typeStatic() | |
44 | { | ||
45 |
1/2✓ Branch 1 taken 224 times.
✗ Branch 2 not taken.
|
448 | return "MavlinkSend"; |
46 | } | ||
47 | |||
48 | ✗ | std::string NAV::MavlinkSend::type() const | |
49 | { | ||
50 | ✗ | return typeStatic(); | |
51 | } | ||
52 | |||
53 | 112 | std::string NAV::MavlinkSend::category() | |
54 | { | ||
55 |
1/2✓ Branch 1 taken 112 times.
✗ Branch 2 not taken.
|
224 | return "Data Link"; |
56 | } | ||
57 | |||
58 | ✗ | void NAV::MavlinkSend::guiConfig() | |
59 | { | ||
60 | ✗ | float columnWidth = 140.0F * gui::NodeEditorApplication::windowFontRatio(); | |
61 | ✗ | ImGui::SetNextItemOpen(true, ImGuiCond_FirstUseEver); | |
62 | ✗ | if (ImGui::TreeNode("Transmission protocol")) | |
63 | { | ||
64 | ✗ | auto portType = static_cast<int>(_portType); | |
65 | ✗ | if (ImGui::RadioButton(fmt::format("UDP-Port##{}", size_t(id)).c_str(), &portType, static_cast<int>(PortType::UDP_Port))) | |
66 | { | ||
67 | ✗ | _portType = static_cast<decltype(_portType)>(portType); | |
68 | ✗ | LOG_DEBUG("{}: portType changed to {}", nameId(), fmt::underlying(_portType)); | |
69 | ✗ | flow::ApplyChanges(); | |
70 | } | ||
71 | ✗ | if (_portType == PortType::UDP_Port) | |
72 | { | ||
73 | ✗ | ImGui::Indent(); | |
74 | |||
75 | ✗ | ImGui::SetNextItemWidth(150 * gui::NodeEditorApplication::windowFontRatio()); | |
76 | ✗ | if (ImGui::InputInt4L(fmt::format("IPv4##{}", size_t(id)).c_str(), _ip.data(), IP_LIMITS[0], IP_LIMITS[1])) | |
77 | { | ||
78 | ✗ | flow::ApplyChanges(); | |
79 | } | ||
80 | ✗ | ImGui::SetNextItemWidth(150 * gui::NodeEditorApplication::windowFontRatio()); | |
81 | ✗ | if (ImGui::InputIntL(fmt::format("Port##{}", size_t(id)).c_str(), &_portNumber, PORT_LIMITS[0], PORT_LIMITS[1])) | |
82 | { | ||
83 | ✗ | flow::ApplyChanges(); | |
84 | } | ||
85 | |||
86 | ✗ | ImGui::Unindent(); | |
87 | } | ||
88 | |||
89 | ✗ | if (ImGui::RadioButton(fmt::format("Serial-Port##{}", size_t(id)).c_str(), &portType, static_cast<int>(PortType::Serial_Port))) | |
90 | { | ||
91 | ✗ | _portType = static_cast<decltype(_portType)>(portType); | |
92 | ✗ | LOG_DEBUG("{}: portType changed to {}", nameId(), fmt::underlying(_portType)); | |
93 | ✗ | flow::ApplyChanges(); | |
94 | } | ||
95 | ✗ | if (_portType == PortType::Serial_Port) | |
96 | { | ||
97 | ✗ | ImGui::Indent(); | |
98 | |||
99 | ✗ | ImGui::SetNextItemWidth(300 * gui::NodeEditorApplication::windowFontRatio()); | |
100 | ✗ | if (ImGui::InputTextWithHint("MavLinkPort", "/dev/ttyACM0", &_serialPort)) | |
101 | { | ||
102 | ✗ | LOG_DEBUG("{}: MavLinkPort changed to {}", nameId(), _serialPort); | |
103 | ✗ | flow::ApplyChanges(); | |
104 | ✗ | doDeinitialize(); | |
105 | } | ||
106 | ✗ | ImGui::SameLine(); | |
107 | ✗ | gui::widgets::HelpMarker("COM port where the MavLink device is attached to\n" | |
108 | "- \"COM1\" (Windows format for physical and virtual (USB) serial port)\n" | ||
109 | "- \"/dev/ttyS1\" (Linux format for physical serial port)\n" | ||
110 | "- \"/dev/ttyUSB0\" (Linux format for virtual (USB) serial port)\n" | ||
111 | "- \"/dev/tty.usbserial-FTXXXXXX\" (Mac OS X format for virtual (USB) serial port)\n" | ||
112 | "- \"/dev/ttyS0\" (CYGWIN format. Usually the Windows COM port number minus 1. This would connect to COM1)"); | ||
113 | |||
114 | ✗ | ImGui::SetNextItemWidth(150 * gui::NodeEditorApplication::windowFontRatio()); | |
115 | ✗ | if (ImGui::BeginCombo(fmt::format("Baudrate##{}", size_t(id)).c_str(), to_string(_baudrate))) | |
116 | { | ||
117 | ✗ | for (size_t i = 0; i < static_cast<size_t>(Baudrate::COUNT); i++) | |
118 | { | ||
119 | ✗ | const bool is_selected = (static_cast<size_t>(_baudrate) == i); | |
120 | ✗ | if (ImGui::Selectable(to_string(static_cast<Baudrate>(i)), is_selected)) | |
121 | { | ||
122 | ✗ | _baudrate = static_cast<Baudrate>(i); | |
123 | ✗ | LOG_DEBUG("{}: Baudrate changed to {}", nameId(), fmt::underlying(_baudrate)); | |
124 | ✗ | flow::ApplyChanges(); | |
125 | ✗ | doDeinitialize(); | |
126 | } | ||
127 | |||
128 | ✗ | if (is_selected) // Set the initial focus when opening the combo (scrolling + keyboard navigation focus) | |
129 | { | ||
130 | ✗ | ImGui::SetItemDefaultFocus(); | |
131 | } | ||
132 | } | ||
133 | ✗ | ImGui::EndCombo(); | |
134 | } | ||
135 | ✗ | ImGui::Unindent(); | |
136 | } | ||
137 | ✗ | if (NAV::MavlinkSend::isInitialized()) | |
138 | { | ||
139 | ✗ | doDeinitialize(); | |
140 | } | ||
141 | ✗ | ImGui::TreePop(); | |
142 | } | ||
143 | ✗ | if (ImGui::TreeNode("MavLink Messages")) | |
144 | { | ||
145 | ✗ | if (ImGui::Checkbox(fmt::format("Send GPS_INPUT (#232) ##{}", size_t(id)).c_str(), &_GPS_INPUT_Active)) | |
146 | { | ||
147 | ✗ | flow::ApplyChanges(); | |
148 | ✗ | LOG_DEBUG("{}: GPS_INPUT changed to {}", nameId(), _GPS_INPUT_Active); | |
149 | ✗ | autopilot_interface.setGPS_Active(_GPS_INPUT_Active); | |
150 | } | ||
151 | ✗ | if (_GPS_INPUT_Active) | |
152 | { | ||
153 | ✗ | ImGui::Indent(); | |
154 | ✗ | ImGui::SetNextItemWidth(columnWidth); | |
155 | ✗ | if (ImGui::InputDoubleL(fmt::format("GPS output rate##{}", size_t(id)).c_str(), &_GPS_INPUT_Frequency, 0, 100, 0, 0, "%.3f Hz")) | |
156 | { | ||
157 | ✗ | LOG_DEBUG("{}: GPS_INPUT_Frequency changed to {}", nameId(), _GPS_INPUT_Frequency); | |
158 | ✗ | autopilot_interface.setGPS_Frequency(_GPS_INPUT_Frequency); | |
159 | ✗ | flow::ApplyChanges(); | |
160 | } | ||
161 | ✗ | ImGui::Unindent(); | |
162 | } | ||
163 | |||
164 | ✗ | if (ImGui::Checkbox(fmt::format("Send ATT_POS_MOCAP (#138) ##{}", size_t(id)).c_str(), &_ATT_POS_MOCAP_Active)) | |
165 | { | ||
166 | ✗ | flow::ApplyChanges(); | |
167 | ✗ | LOG_DEBUG("{}: ATT_POS_MOCAP changed to {}", nameId(), _ATT_POS_MOCAP_Active); | |
168 | ✗ | autopilot_interface.setMOCAP_Active(_ATT_POS_MOCAP_Active); | |
169 | } | ||
170 | ✗ | if (_ATT_POS_MOCAP_Active) | |
171 | { | ||
172 | ✗ | ImGui::Indent(); | |
173 | ✗ | ImGui::SetNextItemWidth(columnWidth); | |
174 | ✗ | if (ImGui::InputDoubleL(fmt::format("MOCAP output rate##{}", size_t(id)).c_str(), &_ATT_POS_MOCAP_Frequency, 0, 10000, 0, 0, "%.3f Hz")) | |
175 | { | ||
176 | ✗ | LOG_DEBUG("{}: ATT_POS_MOCAP_Frequency changed to {}", nameId(), _ATT_POS_MOCAP_Frequency); | |
177 | ✗ | autopilot_interface.setMOCAP_Frequency(_ATT_POS_MOCAP_Frequency); | |
178 | ✗ | flow::ApplyChanges(); | |
179 | } | ||
180 | ✗ | ImGui::Unindent(); | |
181 | } | ||
182 | ✗ | ImGui::TreePop(); | |
183 | } | ||
184 | ✗ | } | |
185 | |||
186 | ✗ | bool NAV::MavlinkSend::resetNode() | |
187 | { | ||
188 | ✗ | return true; | |
189 | } | ||
190 | |||
191 | ✗ | json NAV::MavlinkSend::save() const | |
192 | { | ||
193 | LOG_TRACE("{}: called", nameId()); | ||
194 | |||
195 | ✗ | json j; | |
196 | |||
197 | ✗ | j["portType"] = _portType; | |
198 | |||
199 | ✗ | j["ip"] = _ip; | |
200 | ✗ | j["portNumber"] = _portNumber; | |
201 | |||
202 | ✗ | j["serialPort"] = _serialPort; | |
203 | ✗ | j["baudrate"] = _baudrate; | |
204 | |||
205 | ✗ | j["GPS_INPUT_Active"] = _GPS_INPUT_Active; | |
206 | ✗ | j["GPS_INPUT_Frequency"] = _GPS_INPUT_Frequency; | |
207 | |||
208 | ✗ | j["ATT_POS_MOCAP_Active"] = _ATT_POS_MOCAP_Active; | |
209 | ✗ | j["ATT_POS_MOCAP_Frequency"] = _ATT_POS_MOCAP_Frequency; | |
210 | ✗ | return j; | |
211 | ✗ | } | |
212 | |||
213 | ✗ | void NAV::MavlinkSend::restore(json const& j) | |
214 | { | ||
215 | LOG_TRACE("{}: called", nameId()); | ||
216 | |||
217 | ✗ | if (j.contains("portType")) | |
218 | { | ||
219 | ✗ | j.at("portType").get_to(_portType); | |
220 | } | ||
221 | |||
222 | ✗ | if (j.contains("ip")) | |
223 | { | ||
224 | ✗ | j.at("ip").get_to(_ip); | |
225 | } | ||
226 | ✗ | if (j.contains("portNumber")) | |
227 | { | ||
228 | ✗ | j.at("portNumber").get_to(_portNumber); | |
229 | } | ||
230 | |||
231 | ✗ | if (j.contains("serialPort")) | |
232 | { | ||
233 | ✗ | j.at("serialPort").get_to(_serialPort); | |
234 | } | ||
235 | ✗ | if (j.contains("baudrate")) | |
236 | { | ||
237 | ✗ | j.at("baudrate").get_to(_baudrate); | |
238 | } | ||
239 | |||
240 | ✗ | if (j.contains("GPS_INPUT_Active")) | |
241 | { | ||
242 | ✗ | j.at("GPS_INPUT_Active").get_to(_GPS_INPUT_Active); | |
243 | } | ||
244 | ✗ | if (j.contains("GPS_INPUT_Frequency")) | |
245 | { | ||
246 | ✗ | j.at("GPS_INPUT_Frequency").get_to(_GPS_INPUT_Frequency); | |
247 | } | ||
248 | |||
249 | ✗ | if (j.contains("ATT_POS_MOCAP_Active")) | |
250 | { | ||
251 | ✗ | j.at("ATT_POS_MOCAP_Active").get_to(_ATT_POS_MOCAP_Active); | |
252 | } | ||
253 | ✗ | if (j.contains("ATT_POS_MOCAP_Frequency")) | |
254 | { | ||
255 | ✗ | j.at("ATT_POS_MOCAP_Frequency").get_to(_ATT_POS_MOCAP_Frequency); | |
256 | } | ||
257 | ✗ | } | |
258 | |||
259 | ✗ | bool NAV::MavlinkSend::initialize() | |
260 | { | ||
261 | ✗ | if (_portType == PortType::UDP_Port) | |
262 | { | ||
263 | ✗ | port = std::make_shared<UDP_Port>(convertArrayToIPAddress(_ip).c_str(), _portNumber); | |
264 | } | ||
265 | ✗ | if (_portType == PortType::Serial_Port) | |
266 | { | ||
267 | ✗ | port = std::make_shared<Serial_Port>(_serialPort.c_str(), getBaudrateValue(_baudrate)); | |
268 | } | ||
269 | ✗ | autopilot_interface.setPort(port); | |
270 | ✗ | autopilot_interface.setGPS_Active(_GPS_INPUT_Active); | |
271 | ✗ | autopilot_interface.setMOCAP_Active(_ATT_POS_MOCAP_Active); | |
272 | ✗ | autopilot_interface.setGPS_Frequency(_GPS_INPUT_Frequency); | |
273 | ✗ | autopilot_interface.setMOCAP_Frequency(_ATT_POS_MOCAP_Frequency); | |
274 | try | ||
275 | { | ||
276 | ✗ | port->start(); // Open Port | |
277 | } | ||
278 | ✗ | catch (...) | |
279 | { | ||
280 | ✗ | LOG_ERROR("{} could not connect", nameId()); | |
281 | ✗ | return false; | |
282 | ✗ | } | |
283 | try | ||
284 | { | ||
285 | ✗ | autopilot_interface.start(); | |
286 | } | ||
287 | ✗ | catch (...) | |
288 | { | ||
289 | ✗ | port->stop(); // Close Port | |
290 | ✗ | LOG_ERROR("{} could not start autopilot_interface", nameId()); | |
291 | ✗ | return false; | |
292 | ✗ | } | |
293 | |||
294 | ✗ | return true; | |
295 | } | ||
296 | |||
297 | ✗ | void NAV::MavlinkSend::deinitialize() | |
298 | { | ||
299 | LOG_TRACE("{}: called", nameId()); | ||
300 | ✗ | autopilot_interface.stop(); | |
301 | ✗ | port->stop(); // Close Port | |
302 | ✗ | } | |
303 | |||
304 | ✗ | void NAV::MavlinkSend::receivePosVelAtt(NAV::InputPin::NodeDataQueue& queue, size_t /* pinIdx */) // NOLINT(readability-convert-member-functions-to-static) | |
305 | { | ||
306 | // de-initialize node if cable is pulled | ||
307 | ✗ | if (port->cabelCheck == 1) | |
308 | { | ||
309 | ✗ | doDeinitialize(); | |
310 | } | ||
311 | ✗ | auto posVelAtt = std::make_shared<PosVelAtt>(*std::static_pointer_cast<const PosVelAtt>(queue.extract_front())); | |
312 | |||
313 | // Mocap Message | ||
314 | ✗ | auto quat = posVelAtt->n_Quat_b(); | |
315 | ✗ | auto w = static_cast<float>(quat.w()); | |
316 | ✗ | auto x = static_cast<float>(quat.x()); | |
317 | ✗ | auto y = static_cast<float>(quat.y()); | |
318 | ✗ | auto z = static_cast<float>(quat.z()); | |
319 | ✗ | autopilot_interface.setMOCAP(w, x, y, z); | |
320 | |||
321 | // GPS Message | ||
322 | ✗ | auto lat_d = static_cast<int32_t>(((posVelAtt->latitude()) * 180.0 / std::numbers::pi_v<double>)*10000000); // Latitude (WGS84) (degE7) | |
323 | ✗ | auto lon_d = static_cast<int32_t>(((posVelAtt->longitude()) * 180.0 / std::numbers::pi_v<double>)*10000000); // Longitude (WGS84) (degE7) | |
324 | ✗ | auto alt = static_cast<float>(posVelAtt->altitude()); // Altitude (MSL) Positive for up (m) | |
325 | ✗ | auto time_week = static_cast<uint16_t>(posVelAtt->insTime.toGPSweekTow().gpsWeek); // GPS week number | |
326 | ✗ | auto time_week_ms = static_cast<uint32_t>((posVelAtt->insTime.toGPSweekTow().tow) / 1000); // GPS time (from start of GPS week) | |
327 | |||
328 | ✗ | auto vn = static_cast<float>(posVelAtt->n_velocity().x()); // GPS velocity in north direction in earth-fixed NED frame | |
329 | ✗ | auto ve = static_cast<float>(posVelAtt->n_velocity().y()); // GPS velocity in east direction in earth-fixed NED frame | |
330 | ✗ | auto vd = static_cast<float>(posVelAtt->n_velocity().z()); // GPS velocity in down direction in earth-fixed NED frame | |
331 | ✗ | autopilot_interface.setGPS(lat_d, lon_d, alt, vn, ve, vd, time_week_ms, time_week); | |
332 | ✗ | } | |
333 | |||
334 | ✗ | std::string NAV::MavlinkSend::convertArrayToIPAddress(const std::array<int, 4>& ipArray) | |
335 | { | ||
336 | ✗ | return fmt::format("{}", fmt::join(ipArray, ".")); | |
337 | } | ||
338 | |||
339 | ✗ | const char* NAV::MavlinkSend::to_string(Baudrate value) | |
340 | { | ||
341 | static const std::unordered_map<Baudrate, const char*> baudrateMap = { | ||
342 | { Baudrate::BAUDRATE_1200, "1200" }, | ||
343 | { Baudrate::BAUDRATE_2400, "2400" }, | ||
344 | { Baudrate::BAUDRATE_4800, "4800" }, | ||
345 | { Baudrate::BAUDRATE_9600, "9600" }, | ||
346 | { Baudrate::BAUDRATE_19200, "19200" }, | ||
347 | { Baudrate::BAUDRATE_38400, "38400" }, | ||
348 | { Baudrate::BAUDRATE_57600, "57600" }, | ||
349 | { Baudrate::BAUDRATE_111100, "111100" }, | ||
350 | { Baudrate::BAUDRATE_115200, "115200" }, | ||
351 | { Baudrate::BAUDRATE_230400, "230400" }, | ||
352 | { Baudrate::BAUDRATE_256000, "256000" }, | ||
353 | { Baudrate::BAUDRATE_460800, "460800" }, | ||
354 | { Baudrate::BAUDRATE_500000, "500000" }, | ||
355 | { Baudrate::BAUDRATE_921600, "921600" }, | ||
356 | { Baudrate::BAUDRATE_1500000, "1500000" }, | ||
357 | { Baudrate::COUNT, "" } | ||
358 | ✗ | }; | |
359 | ✗ | return baudrateMap.at(value); | |
360 | } | ||
361 | |||
362 | ✗ | int NAV::MavlinkSend::getBaudrateValue(Baudrate value) | |
363 | { | ||
364 | static const std::unordered_map<Baudrate, int> baudrateMap = { | ||
365 | { Baudrate::BAUDRATE_1200, 1200 }, | ||
366 | { Baudrate::BAUDRATE_2400, 2400 }, | ||
367 | { Baudrate::BAUDRATE_4800, 4800 }, | ||
368 | { Baudrate::BAUDRATE_9600, 9600 }, | ||
369 | { Baudrate::BAUDRATE_19200, 19200 }, | ||
370 | { Baudrate::BAUDRATE_38400, 38400 }, | ||
371 | { Baudrate::BAUDRATE_57600, 57600 }, | ||
372 | { Baudrate::BAUDRATE_111100, 111100 }, | ||
373 | { Baudrate::BAUDRATE_115200, 115200 }, | ||
374 | { Baudrate::BAUDRATE_230400, 230400 }, | ||
375 | { Baudrate::BAUDRATE_256000, 256000 }, | ||
376 | { Baudrate::BAUDRATE_460800, 460800 }, | ||
377 | { Baudrate::BAUDRATE_500000, 500000 }, | ||
378 | { Baudrate::BAUDRATE_921600, 921600 }, | ||
379 | { Baudrate::BAUDRATE_1500000, 1500000 } | ||
380 | ✗ | }; | |
381 | ✗ | return baudrateMap.at(value); | |
382 | } | ||
383 | #endif | ||
384 |