0.4.1
Loading...
Searching...
No Matches
mavlinkSend.hpp
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/// @file mavlinkSend.hpp
10/// @brief Sends a navigation solution via the MAVLink protocol
11/// @author M. Maier (marcel.maier@ins.uni-stuttgart.de)
12/// @date 2023-11-20
13
14#pragma once
15
16#if __linux__ || __APPLE__
17
18 #include "internal/Node/Node.hpp"
19
21
22 #include <mavlink/common/mavlink.h>
23
27
28namespace NAV
29{
30/// @brief MavLink Send node
31class MavlinkSend : public Node
32{
33 public:
34 /// @brief Default constructor
35 MavlinkSend();
36 /// @brief Destructor
37 ~MavlinkSend() override;
38 /// @brief Copy constructor
39 MavlinkSend(const MavlinkSend&) = delete;
40 /// @brief Move constructor
41 MavlinkSend(MavlinkSend&&) = delete;
42 /// @brief Copy assignment operator
43 MavlinkSend& operator=(const MavlinkSend&) = delete;
44 /// @brief Move assignment operator
45 MavlinkSend& operator=(MavlinkSend&&) = delete;
46
47 /// @brief String representation of the Class Type
48 [[nodiscard]] static std::string typeStatic();
49
50 /// @brief String representation of the Class Type
51 [[nodiscard]] std::string type() const override;
52
53 /// @brief String representation of the Class Category
54 [[nodiscard]] static std::string category();
55
56 /// @brief ImGui config window which is shown on double click
57 /// @attention Don't forget to set _hasConfig to true in the constructor of the node
58 void guiConfig() override;
59
60 /// @brief Saves the node into a json object
61 [[nodiscard]] json save() const override;
62
63 /// @brief Restores the node from a json object
64 /// @param[in] j Json object with the node state
65 void restore(const json& j) override;
66
67 /// @brief Resets the node. Moves the read cursor to the start
68 bool resetNode() override;
69
70 private:
71 constexpr static size_t INPUT_PORT_INDEX_NODE_DATA = 0; ///< @brief Object (NodeData)
72
73 /// @brief Initialize the node
74 bool initialize() override;
75
76 /// @brief Deinitialize the node
77 void deinitialize() override;
78
79 /// @brief Callback when receiving data on a port
80 /// @param[in] queue Queue with all the received data messages
81 /// @param[in] pinIdx Index of the pin the data is received on
82 void receivePosVelAtt(InputPin::NodeDataQueue& queue, size_t pinIdx);
83
84 /// Available PortTypes
85 enum class PortType : uint8_t
86 {
87 Serial_Port, ///< Serial_Port
88 UDP_Port, ///< UDP_Port
89 };
90
91 /// Serial or UDP port
92 std::shared_ptr<Generic_Port> port;
93
94 /// Autopilot interface
95 Autopilot_Interface autopilot_interface;
96
97 /// Port type
98 PortType _portType = PortType::Serial_Port;
99
100 /// IPv4 address
101 std::array<int, 4> _ip{ 127, 0, 0, 1 };
102
103 /// @brief Helper function
104 static std::string convertArrayToIPAddress(const std::array<int, 4>& ipArray);
105
106 /// UDP port number
107 int _portNumber = 14540;
108
109 /// Range an IPv4 address can be in [0, 2^8-1]
110 static constexpr std::array<int, 2> IP_LIMITS = { 0, 255 };
111 /// Range a port can be in [0, 2^16-1]
112 static constexpr std::array<int, 2> PORT_LIMITS = { 0, 65535 };
113
114 /// COM port where the MavLink device is attached to
115 ///
116 /// - "COM1" (Windows format for physical and virtual (USB) serial port)
117 /// - "/dev/ttyS1" (Linux format for physical serial port)
118 /// - "/dev/ttyUSB0" (Linux format for virtual (USB) serial port)
119 /// - "/dev/tty.usbserial-FTXXXXXX" (Mac OS X format for virtual (USB) serial port)
120 /// - "/dev/ttyS0" (CYGWIN format. Usually the Windows COM port number minus 1. This would connect to COM1)
121 std::string _serialPort;
122
123 /// Available Baudrates
124 enum class Baudrate : uint8_t
125 {
126 BAUDRATE_1200, ///< Baudrate with 1200 symbols per second [Baud]
127 BAUDRATE_2400, ///< Baudrate with 2400 symbols per second [Baud]
128 BAUDRATE_4800, ///< Baudrate with 4800 symbols per second [Baud]
129 BAUDRATE_9600, ///< Baudrate with 9600 symbols per second [Baud]
130 BAUDRATE_19200, ///< Baudrate with 19200 symbols per second [Baud]
131 BAUDRATE_38400, ///< Baudrate with 38400 symbols per second [Baud]
132 BAUDRATE_57600, ///< Baudrate with 57600 symbols per second [Baud]
133 BAUDRATE_111100, ///< Baudrate with 111100 symbols per second [Baud]
134 BAUDRATE_115200, ///< Baudrate with 115200 symbols per second [Baud]
135 BAUDRATE_230400, ///< Baudrate with 230400 symbols per second [Baud]
136 BAUDRATE_256000, ///< Baudrate with 256000 symbols per second [Baud]
137 BAUDRATE_460800, ///< Baudrate with 460800 symbols per second [Baud]
138 BAUDRATE_500000, ///< Baudrate with 500000 symbols per second [Baud]
139 BAUDRATE_921600, ///< Baudrate with 921600 symbols per second [Baud]
140 BAUDRATE_1500000, ///< Baudrate with 1500000 symbols per second [Baud]
141 COUNT /// Count Variable
142 };
143 /// @brief Converts the enum to a string
144 /// @param[in] value Enum value to convert into text
145 /// @return String representation of the enum
146 static const char* to_string(Baudrate value);
147
148 /// @brief Converts the enum to int
149 /// @param[in] value Enum value to convert into int
150 /// @return int representation of the enum
151 static int getBaudrateValue(Baudrate value);
152
153 /// Selected Baudrate for the Serialport in the GUI
154 Baudrate _baudrate = Baudrate::BAUDRATE_57600;
155
156 /// Determines whether the Mavlink message "GPS_INPUT (#232)" is sent
157 bool _GPS_INPUT_Active = false;
158
159 /// Determines how often the Mavlink message "GPS_INPUT (#232)" is sent
160 double _GPS_INPUT_Frequency = 10;
161
162 /// Determines whether the Mavlink message "ATT_POS_MOCAP (#138)" is sent
163 bool _ATT_POS_MOCAP_Active = false;
164
165 /// Determines how often the Mavlink message "ATT_POS_MOCAP (#138)" is sent
166 double _ATT_POS_MOCAP_Frequency = 10;
167};
168} // namespace NAV
169#endif
nlohmann::json json
json namespace
Node Class.
Position, Velocity and Attitude Storage Class.
Autopilot interface definition.
Abstract parent class for all nodes.
Definition Node.hpp:92
void initialize()
Initializes the config manager. Call this function before using other functions.
void deinitialize()
Deinitializes the config manager. Call this if you want to Fetch config again.
@ COUNT
Amount of items in the enum.
const char * to_string(gui::widgets::PositionWithFrame::ReferenceFrame refFrame)
Converts the enum to a string.
Serial interface definition.
UDP interface definition.