16#if __linux__ || __APPLE__
22 #include <mavlink/common/mavlink.h>
31class MavlinkSend :
public Node
37 ~MavlinkSend()
override;
39 MavlinkSend(
const MavlinkSend&) =
delete;
41 MavlinkSend(MavlinkSend&&) =
delete;
43 MavlinkSend& operator=(
const MavlinkSend&) =
delete;
45 MavlinkSend& operator=(MavlinkSend&&) =
delete;
48 [[nodiscard]]
static std::string typeStatic();
51 [[nodiscard]] std::string type()
const override;
54 [[nodiscard]]
static std::string category();
58 void guiConfig()
override;
61 [[nodiscard]]
json save()
const override;
65 void restore(
const json& j)
override;
68 bool resetNode()
override;
71 constexpr static size_t INPUT_PORT_INDEX_NODE_DATA = 0;
82 void receivePosVelAtt(InputPin::NodeDataQueue& queue,
size_t pinIdx);
85 enum class PortType : uint8_t
92 std::shared_ptr<Generic_Port> port;
95 Autopilot_Interface autopilot_interface;
98 PortType _portType = PortType::Serial_Port;
101 std::array<int, 4> _ip{ 127, 0, 0, 1 };
104 static std::string convertArrayToIPAddress(
const std::array<int, 4>& ipArray);
107 int _portNumber = 14540;
110 static constexpr std::array<int, 2> IP_LIMITS = { 0, 255 };
112 static constexpr std::array<int, 2> PORT_LIMITS = { 0, 65535 };
121 std::string _serialPort;
124 enum class Baudrate : uint8_t
146 static const char*
to_string(Baudrate value);
151 static int getBaudrateValue(Baudrate value);
154 Baudrate _baudrate = Baudrate::BAUDRATE_57600;
157 bool _GPS_INPUT_Active =
false;
160 double _GPS_INPUT_Frequency = 10;
163 bool _ATT_POS_MOCAP_Active =
false;
166 double _ATT_POS_MOCAP_Frequency = 10;
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.
nlohmann::json json
json namespace
Definition FlowManager.hpp:21
@ COUNT
Amount of items in the enum.
Position, Velocity and Attitude Storage Class.
Autopilot interface definition.
Serial interface definition.
UDP interface definition.