10#if __linux__ || __APPLE__
21 #include "mavlink/common/mavlink.h"
26NAV::MavlinkSend::MavlinkSend()
31 _guiConfigDefaultWindowSize = { 479.0, 197.0 };
33 CreateInputPin(
"PosVelAtt", Pin::Type::Flow, {
NAV::PosVelAtt::type() }, &MavlinkSend::receivePosVelAtt);
36NAV::MavlinkSend::~MavlinkSend()
41std::string NAV::MavlinkSend::typeStatic()
46std::string NAV::MavlinkSend::type()
const
51std::string NAV::MavlinkSend::category()
56void NAV::MavlinkSend::guiConfig()
58 float columnWidth = 140.0F * gui::NodeEditorApplication::windowFontRatio();
59 ImGui::SetNextItemOpen(
true, ImGuiCond_FirstUseEver);
60 if (ImGui::TreeNode(
"Transmission protocol"))
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)))
65 _portType =
static_cast<decltype(_portType)
>(portType);
66 LOG_DEBUG(
"{}: portType changed to {}", nameId(), fmt::underlying(_portType));
69 if (_portType == PortType::UDP_Port)
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]))
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]))
87 if (ImGui::RadioButton(fmt::format(
"Serial-Port##{}",
size_t(
id)).c_str(), &portType,
static_cast<int>(PortType::Serial_Port)))
89 _portType =
static_cast<decltype(_portType)
>(portType);
90 LOG_DEBUG(
"{}: portType changed to {}", nameId(), fmt::underlying(_portType));
93 if (_portType == PortType::Serial_Port)
97 ImGui::SetNextItemWidth(300 * gui::NodeEditorApplication::windowFontRatio());
98 if (ImGui::InputTextWithHint(
"MavLinkPort",
"/dev/ttyACM0", &_serialPort))
100 LOG_DEBUG(
"{}: MavLinkPort changed to {}", nameId(), _serialPort);
101 flow::ApplyChanges();
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)");
112 ImGui::SetNextItemWidth(150 * gui::NodeEditorApplication::windowFontRatio());
113 if (ImGui::BeginCombo(fmt::format(
"Baudrate##{}",
size_t(
id)).c_str(),
to_string(_baudrate)))
115 for (
size_t i = 0; i < static_cast<size_t>(Baudrate::COUNT); i++)
117 const bool is_selected = (
static_cast<size_t>(_baudrate) == i);
118 if (ImGui::Selectable(
to_string(
static_cast<Baudrate
>(i)), is_selected))
120 _baudrate =
static_cast<Baudrate
>(i);
121 LOG_DEBUG(
"{}: Baudrate changed to {}", nameId(), fmt::underlying(_baudrate));
122 flow::ApplyChanges();
128 ImGui::SetItemDefaultFocus();
135 if (NAV::MavlinkSend::isInitialized())
141 if (ImGui::TreeNode(
"MavLink Messages"))
143 if (ImGui::Checkbox(fmt::format(
"Send GPS_INPUT (#232) ##{}",
size_t(
id)).c_str(), &_GPS_INPUT_Active))
145 flow::ApplyChanges();
146 LOG_DEBUG(
"{}: GPS_INPUT changed to {}", nameId(), _GPS_INPUT_Active);
147 autopilot_interface.setGPS_Active(_GPS_INPUT_Active);
149 if (_GPS_INPUT_Active)
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"))
155 LOG_DEBUG(
"{}: GPS_INPUT_Frequency changed to {}", nameId(), _GPS_INPUT_Frequency);
156 autopilot_interface.setGPS_Frequency(_GPS_INPUT_Frequency);
157 flow::ApplyChanges();
162 if (ImGui::Checkbox(fmt::format(
"Send ATT_POS_MOCAP (#138) ##{}",
size_t(
id)).c_str(), &_ATT_POS_MOCAP_Active))
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);
168 if (_ATT_POS_MOCAP_Active)
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"))
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();
184bool NAV::MavlinkSend::resetNode()
189json NAV::MavlinkSend::save()
const
195 j[
"portType"] = _portType;
198 j[
"portNumber"] = _portNumber;
200 j[
"serialPort"] = _serialPort;
201 j[
"baudrate"] = _baudrate;
203 j[
"GPS_INPUT_Active"] = _GPS_INPUT_Active;
204 j[
"GPS_INPUT_Frequency"] = _GPS_INPUT_Frequency;
206 j[
"ATT_POS_MOCAP_Active"] = _ATT_POS_MOCAP_Active;
207 j[
"ATT_POS_MOCAP_Frequency"] = _ATT_POS_MOCAP_Frequency;
211void NAV::MavlinkSend::restore(
json const& j)
215 if (j.contains(
"portType"))
217 j.at(
"portType").get_to(_portType);
220 if (j.contains(
"ip"))
222 j.at(
"ip").get_to(_ip);
224 if (j.contains(
"portNumber"))
226 j.at(
"portNumber").get_to(_portNumber);
229 if (j.contains(
"serialPort"))
231 j.at(
"serialPort").get_to(_serialPort);
233 if (j.contains(
"baudrate"))
235 j.at(
"baudrate").get_to(_baudrate);
238 if (j.contains(
"GPS_INPUT_Active"))
240 j.at(
"GPS_INPUT_Active").get_to(_GPS_INPUT_Active);
242 if (j.contains(
"GPS_INPUT_Frequency"))
244 j.at(
"GPS_INPUT_Frequency").get_to(_GPS_INPUT_Frequency);
247 if (j.contains(
"ATT_POS_MOCAP_Active"))
249 j.at(
"ATT_POS_MOCAP_Active").get_to(_ATT_POS_MOCAP_Active);
251 if (j.contains(
"ATT_POS_MOCAP_Frequency"))
253 j.at(
"ATT_POS_MOCAP_Frequency").get_to(_ATT_POS_MOCAP_Frequency);
257bool NAV::MavlinkSend::initialize()
259 if (_portType == PortType::UDP_Port)
261 port = std::make_shared<UDP_Port>(convertArrayToIPAddress(_ip).c_str(), _portNumber);
263 if (_portType == PortType::Serial_Port)
265 port = std::make_shared<Serial_Port>(_serialPort.c_str(), getBaudrateValue(_baudrate));
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);
278 LOG_ERROR(
"{} could not connect", nameId());
283 autopilot_interface.start();
288 LOG_ERROR(
"{} could not start autopilot_interface", nameId());
295void NAV::MavlinkSend::deinitialize()
298 autopilot_interface.stop();
305 if (port->cabelCheck == 1)
309 auto posVelAtt = std::make_shared<PosVelAtt>(*std::static_pointer_cast<const PosVelAtt>(queue.
extract_front()));
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);
320 auto lat_d =
static_cast<int32_t
>(((posVelAtt->latitude()) * 180.0 / std::numbers::pi_v<double>)*10000000);
321 auto lon_d =
static_cast<int32_t
>(((posVelAtt->longitude()) * 180.0 / std::numbers::pi_v<double>)*10000000);
322 auto alt =
static_cast<float>(posVelAtt->altitude());
323 auto time_week =
static_cast<uint16_t
>(posVelAtt->insTime.toGPSweekTow().gpsWeek);
324 auto time_week_ms =
static_cast<uint32_t
>((posVelAtt->insTime.toGPSweekTow().tow) / 1000);
326 auto vn =
static_cast<float>(posVelAtt->n_velocity().x());
327 auto ve =
static_cast<float>(posVelAtt->n_velocity().y());
328 auto vd =
static_cast<float>(posVelAtt->n_velocity().z());
329 autopilot_interface.setGPS(lat_d, lon_d, alt,
vn, ve, vd, time_week_ms, time_week);
332std::string NAV::MavlinkSend::convertArrayToIPAddress(
const std::array<int, 4>& ipArray)
334 return fmt::format(
"{}", fmt::join(ipArray,
"."));
337const char* NAV::MavlinkSend::to_string(Baudrate value)
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,
"" }
357 return baudrateMap.at(value);
360int NAV::MavlinkSend::getBaudrateValue(Baudrate value)
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 }
379 return baudrateMap.at(value);
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)
#define LOG_ERROR
Error occurred, which stops part of the program to work, but not everything.
#define LOG_TRACE
Detailled info to trace the execution of the program. Should not be called on functions which receive...
Autopilot interface definition.
static std::string type()
Returns the type of the data class.
auto extract_front()
Returns a copy of the first element in the container and removes it from the container.
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'.
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]'.
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'.
const char * to_string(gui::widgets::PositionWithFrame::ReferenceFrame refFrame)
Converts the enum to a string.