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