-
Notifications
You must be signed in to change notification settings - Fork 3
Expand file tree
/
Copy pathDroneController.h
More file actions
368 lines (325 loc) · 15.1 KB
/
DroneController.h
File metadata and controls
368 lines (325 loc) · 15.1 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
#ifndef DRONECONTROLLER_H
#define DRONECONTROLLER_H
#include <QList>
#include <QCoreApplication>
#include <QStandardPaths>
#include <QJsonDocument>
#include <QJsonObject>
#include <QSharedPointer>
#include <QSharedMemory>
#include <QMetaType>
#include <QFile>
#include <QTextStream>
#include <QHash>
#include <QByteArray>
#include <QMetaObject>
#include <cstdint>
#include "DroneClass.h"
#include "backend/dbmanager.h"
#include "MAVLinkReceiver.h"
#include "MAVLinkSender.h"
#include "UARTLink.h"
#include "UDPLink.h"
#include "unknowndroneclass.h"
// For randomly generating battery levels
#include <QRandomGenerator>
// DATA PATH
#ifdef _WIN32
// Try both the original path and the user's temp directory
#define DEFAULT_DATA_FILE_PATH "C:/tmp/xbee_data.json" // Windows path
#else
#define DEFAULT_DATA_FILE_PATH "/tmp/xbee_data.json" // Unix/Mac path
#endif
extern "C" {
#if __has_include(<mavlink/common/mavlink.h>)
#include <mavlink/common/mavlink.h>
#else
#include <common/mavlink.h>
#endif
}
/*
* Qt uses Slots and Signals to create responsive UI/GUI applications.
* It allows for communication between QML and C++.
* https://doc.qt.io/qt-6/signalsandslots.html
*/
/*
* Button Press:
* 1. DroneController -- Saves Drone to update on UI
* 2. DroneManager -- Holds the list of Drone C++ objects and modifies it. -- vectorList
* 3. DroneClass - Is the data model that can take real time updates
* 4. DBManager -- Connects Drone Database
*/
// Drone Controller will notify UI
// Serves as a middle man from UI and backend.
class UARTLink;
class UDPLink;
class MAVLinkSender;
class MAVLinkReceiver;
class DroneController : public QObject
{
Q_OBJECT
Q_PROPERTY(QVariantList drones READ drones NOTIFY dronesChanged)
Q_PROPERTY(QVariantList unknownDrones READ unknownDrones NOTIFY unknownDronesChanged)
public:
// idk how to pass the parent function
explicit DroneController(DBManager &gcsdb_in, QObject *parent = nullptr);
~DroneController();
Q_INVOKABLE QVariantList getDrones() const;
/**
* function openUART()
* @brief Initializes and opens a UART connection for MAVLink communication.
*
* This function sets up the required UART transport and MAVLink components,
* including the UARTLink, MAVLinkSender, and MAVLinkReceiver. It also establishes
* a signal-slot connection to process incoming serial byte streams and convert
* them into MAVLink messages.
*
* If a previous UART-to-MAVLink connection exists, it is disconnected before
* creating a new one to prevent duplicate signal handling.
*
* @param port The serial port identifier (e.g., "/dev/ttyUSB0", "COM3").
* @param baud The baud rate for the UART connection.
*
* @return true if the UART connection was successfully opened.
* @return false if the serial port failed to open.
*/
Q_INVOKABLE bool openUART(const QString &port, int baud = 57600);
/**
* function openUDP()
* @brief Initializes and opens a UDP connection for MAVLink communication.
*
* Incoming UDP data is forwarded to the MAVLinkReceiver for parsing. Valid
* MAVLink messages are then passed to onMavlinkMessage() along with the sender's
* port information.
*
* If a previous UDP-to-MAVLink connection exists, it is disconnected before
* creating a new one to prevent duplicate signal handling.
*
* @param localPort The local UDP port to bind and listen on.
* @param remoteHost The target remote host address (IP or hostname).
* @param remotePort The target remote UDP port for outgoing messages.
*
* @return true if the UDP connection was successfully opened.
* @return false if the UDP socket failed to bind or initialize.
*
* @note The sender port is captured via a lambda and passed along with parsed
* MAVLink messages, keeping transport-layer details separate from the
* MAVLinkReceiver.
*/
Q_INVOKABLE bool openUDP(uint16_t localPort,
const QString &remoteHost = QStringLiteral("127.0.0.1"),
uint16_t remotePort = 14550);
/**
* function sendArm()
* @brief Sends an arm or disarm command to a drone via MAVLink.
*
* Resolves the specified drone using its XBee address (or key), constructs
* a MAV_CMD_COMPONENT_ARM_DISARM command, and transmits it over the active
* MAVLink/XBee link.
*
* @param droneKeyOrAddr The drone identifier or XBee address used to resolve
* the target drone.
* @param arm If true, sends an ARM command; if false, sends DISARM.
*
* @return true if the command was successfully written to the MAVLink link;
* false if the drone could not be resolved, the MAVLink sender is not
* initialized, the link is not open, or transmission fails.
*
* @note Requires a valid and open MAVLink link (openUART() must be called first).
*/
Q_INVOKABLE bool sendArm(const QString &droneKeyOrAddr, bool arm = true);
/**
* function sendTakeoffCmd()
* @brief Sends a MAVLink takeoff command to the specified drone.
*
* This function issues a MAV_CMD_NAV_TAKEOFF command to the target drone,
* instructing it to take off to a predefined altitude (5 meters above home).
* The drone is identified using the provided key or XBee address.
*
* Behavior:
* - If @p takeoff is false, the function performs no action and returns true.
* - If the drone cannot be resolved, a warning is logged and false is returned.
* - If the MAVLink transmitter is not initialized or the link is not open,
* a warning is logged and false is returned.
* - Otherwise, a takeoff command is sent via MAVLink.
*
* Command parameters:
* - pitch = 0.0f
* - yaw = 0.0f
* - latitude/longitude = 0.0f (use current position for ArduCopter)
* - altitude = 5.0f (meters above home position)
*
* @param droneKeyOrAddr Identifier used to locate the drone (e.g., XBee address).
* @param takeoff If true, a takeoff command is sent. If false,
* no command is sent and the function returns true.
*
* @return true if:
* - @p takeoff is false, or
* - the takeoff command was successfully queued/sent.
* Returns false if the drone was not found, the link is not open,
* or the send operation failed.
*
* @note Requires a valid and open MAVLink transport (e.g., openUDP() or openUART()).
* @note The altitude is hardcoded to 5 meters AGL (above home).
*
* @warning No pre-arm checks or flight mode validation are performed here.
* The flight controller must be armed and in a mode that permits takeoff.
*/
Q_INVOKABLE bool sendTakeoffCmd(const QString &droneKeyOrAddr, bool takeoff);
Q_INVOKABLE bool sendToCoord(const QString droneName, float lat, float lon);
Q_INVOKABLE bool sendToCoordByUavID(const QString uavID, float lat, float lon);
/**
* function sendGuidedMode()
* @brief Sends a MAVLink command to set the target drone to Guided mode.
*
* This function resolves a drone instance using the provided identifier
* (XBeeAddress or key), verifies that the MAVLink transmission interface
* is ready, and sends a MAV_CMD_DO_SET_MODE command to the target system.
*
* The command is sent with:
* - param1 = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
* - param2 = 4.0f (custom mode value corresponding to GUIDED)
*
* If the drone cannot be found or the MAVLink sender is not initialized
* or open, the function logs a warning and returns false.
*
* @param droneKeyOrAddr Identifier used to locate the drone (e.g., XBee address).
* @param enableGuidedMode Boolean flag indicating intent to enable or disable
* Guided mode. Currently not used in command construction;
* the function always sends a request to enable GUIDED mode.
*
* @return true if the command was successfully queued/sent by the MAVLink
* transmitter; false if the drone was not found, the link is not open,
* or the send operation failed.
*
* @note Requires a valid and open MAVLink transport (e.g., openUDP() or openUART()).
* @note The GUIDED mode value (4.0f) assumes ArduPilot-compatible custom modes.
* Mode mappings may differ across firmware types.
*
* @warning The @p enableGuidedMode parameter is not currently used to toggle
* modes and does not disable Guided mode when false.
*/
Q_INVOKABLE bool sendGuidedMode(const QString& droneKeyOrAddr, bool enableGuidedMode);
/**
* function requestTelem()
* @brief Requests periodic telemetry messages (streamed) from the target vehicle.
*
* Sends MAV_CMD_SET_MESSAGE_INTERVAL commands to configure the autopilot
* to stream selected MAVLink telemetry messages at 2 Hz (500,000 µs interval).
*
* Each message is requested using COMMAND_LONG with:
* param1 = message ID
* param2 = interval in microseconds
*
* @param targetSysID MAVLink system ID of the target vehicle.
* @param targetCompID MAVLink component ID (typically MAV_COMP_ID_AUTOPILOT1).
*
* @return true if all message interval requests were successfully written
* to the link; false if the link is null, not open, or any write fails.
*
* @note Requires a valid and open MAVLink link.
* @note The vehicle will continue streaming messages at the requested rate
* until the interval is changed or the vehicle reboots.
*/
Q_INVOKABLE bool requestTelem(QSharedPointer<DroneClass> drone);
Q_INVOKABLE DroneClass *getDrone(int index) const;
// Declaration for retrieving the drone list
Q_INVOKABLE QVariantList getAllDrones() const;
QVariantList drones() const { return m_dronesVariant; }
void rebuildVariant();
// unknowndronelist
QVariantList unknownDrones() const { return m_unknownDronesVariant; }
Q_INVOKABLE void loadUnknownDrones();
Q_INVOKABLE void setUnknownDroneIgnored(const QString &uid, bool ignored);
Q_INVOKABLE void acceptUnknownDrone(const QString &uid);
Q_INVOKABLE void removeUnknownDrones(const QString &uid);
void rebuildUnknownVariant();
Q_INVOKABLE void renameDrone(const QString &xbeeID, const QString &newName);
Q_INVOKABLE void setXbeeAddress(const QString &xbeeID, const QString &newXbeeAddress);
Q_INVOKABLE void setBatteryLevel(const QString &xbeeID, const double &newBattery);
Q_INVOKABLE void setRole(const QString &xbeeID, const QString &newRole);
Q_INVOKABLE void setXbeeID(const QString &xbeeID, const QString &newXbeeID);
Q_INVOKABLE void setPosition(const QString &xbeeID, const QVector3D &newPosition);
Q_INVOKABLE void setLatitude(const QString &xbeeID, const double &newLatitude);
Q_INVOKABLE void setLongitude(const QString &xbeeID, const double &newLongitude);
Q_INVOKABLE void setAltitude(const QString &xbeeID, const double &newAltitude);
Q_INVOKABLE void setVelocity(const QString &xbeeID, const QVector3D &newVelocity);
Q_INVOKABLE void setAirspeed(const QString &xbeeID, const double &newAirspeed);
Q_INVOKABLE void setOrientation(const QString &xbeeID, const QVector3D &newOrientation);
public slots:
void saveDroneToDB(const QSharedPointer<DroneClass> &drone);
void createDrone(const QString &input_name,
const QString &input_role,
const QString &input_xbeeID,
const QString &input_xbeeAddress,
double input_batteryLevel,
double input_latitude,
double input_longitude,
double input_altitude,
QObject *parent);
void createAndAddDroneToUI(const QString &input_name,
const uint8_t &input_sysID,
const uint8_t &input_compID,
const uint16_t senderUDPPort,
const QObject *parent);
bool updateDrone(const QSharedPointer<DroneClass> &drone);
void deleteDrone(const QString &xbeeid);
void deleteALlDrones_UI();
// Functions for serial / MAVLink connections
void onMavlinkMessage(const RxMavlinkMsg& msg, uint16_t senderUDPPort);
signals:
void droneAdded(const QSharedPointer<DroneClass> &drone);
void droneDeleted(const QSharedPointer<DroneClass> &drone);
void droneStateChanged(const DroneClass *drone);
void dronesChanged();
void commandAcknowledged(const QString &message, bool success);
void unknownDronesChanged();
private:
bool checkHeartBeat = false;
DBManager &dbManager;
std::unique_ptr<UARTLink> uartDevice_;
std::unique_ptr<UDPLink> udp_;
std::unique_ptr<MAVLinkSender> mavTx_;
std::unique_ptr<MAVLinkReceiver> mavRx_;
QMetaObject::Connection udpMavlinkBytesConn_; // Holds functor-based connects so openUDP can replace wiring without duplicates.
QMetaObject::Connection uartMavlinkBytesConn_; // Holds functor-based connects so openUART can replace wiring without duplicates.
QHash<uint32_t, QSharedPointer<DroneClass>> m_drone_map;
static QList<QSharedPointer<DroneClass>> droneList;
static QList<QSharedPointer<UnknownDroneClass>> unknownDroneList;
QSharedPointer<DroneClass> getDroneByName(const QString &name);
QSharedPointer<DroneClass> getDroneByXbeeAddress(const QString &address);
/**
* function getDroneBySysID()
*
* @warning inefficient due to looping
* @todo implement map structure in DroneController class (checkout m_drone_map)
*/
QSharedPointer<DroneClass> getDroneBySysID(uint8_t sysID);
void updateDroneTelem(QSharedPointer<DroneClass> drone, const QString& field, const QVariant& value);
/**
* function onUdpBytesReceived()
* @brief FOR DEBUGGING: Handles raw UDP payloads received from the active link.
*
* This function is invoked when a UDP datagram is received. It logs
* the total number of bytes received and prints a hexadecimal preview
* of the payload (up to the first 32 bytes) for diagnostic purposes.
*
* Behavior:
* - Computes the total payload size.
* - Extracts up to the first 32 bytes.
* - Converts the preview portion to a space-separated hexadecimal string.
* - Emits a debug log entry containing the size and preview data.
*
* @param bytes Raw UDP datagram payload.
*
* @note This function performs logging only and does not parse or process
* the payload contents.
* @note Logging large volumes of UDP traffic may impact performance
* when debug output is enabled.
*/
void onUdpBytesReceived(const QByteArray& bytes);
// Trying out caching QVariantList for QML property usage
QVariantList m_dronesVariant; // cached QObject* view for QML
QVariantList m_unknownDronesVariant; // cached QObject* view for QML
};
#endif // DRONECONTROLLER_H