forked from UAVGCSTeam/GCS
-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy pathdronecontroller.cpp
More file actions
795 lines (690 loc) · 25.8 KB
/
dronecontroller.cpp
File metadata and controls
795 lines (690 loc) · 25.8 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
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
#include "dronecontroller.h"
#include "droneclass.h"
#include "XbeeLink.h"
#include "MavlinkReceiver.h"
#include "MavlinkSender.h"
#include <QDebug>
#include <memory>
#include "MavlinkReceiver.h"
#include <QMetaType>
#include <QTimer>
#include <QJsonDocument>
#include <QJsonObject>
#include <QFile>
#include <QDir>
#include <QCoreApplication>
#include <QTextStream>
#include <QStandardPaths>
// 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
}
QList<QSharedPointer<DroneClass>> DroneController::droneList; // Define the static variable
DroneController::DroneController(DBManager &db, QObject *parent)
: QObject(parent), dbManager(db)
{
int index = 0;
// function loads all drones from the database on startup
qRegisterMetaType<mavlink_message_t>("mavlink_message_t");
QList<QVariantMap> droneRecords = dbManager.fetchAllDrones();
for (const QVariantMap &record : droneRecords)
{
QString name = record["drone_name"].toString();
QString role = record["drone_role"].toString();
QString xbeeID = record["xbee_id"].toString();
int sysID = -1;
int compID = -1;
QString xbeeAddress = record["xbee_address"].toString();
// Should? work with other fields like xbee_id or drone_id if needed
// existing table can have added columns for the lati and longi stuff and input here
// TODO: Change this, add xbee id?
if (index == 0) {
droneList.append(QSharedPointer<DroneClass>::create(name, role, xbeeID, xbeeAddress, 67, 34.06126372594308, -117.83284231468927, 10, nullptr));
} else if (index == 1) {
droneList.append(QSharedPointer<DroneClass>::create(name, role, xbeeID, xbeeAddress, 67, 34.06202196849312, -117.82905560740794, 10, nullptr));
} else if (index == 2) {
droneList.append(QSharedPointer<DroneClass>::create(name, role, xbeeID, xbeeAddress, 67, 34.06025272532348, -117.82775448760746, 10, nullptr));
} else {
droneList.append(QSharedPointer<DroneClass>::create(name, role, xbeeID, xbeeAddress, 67, 34.059174611493965, -117.82051240067321, 10, nullptr));
}
index++;
}
qDebug() << "Loaded" << droneList.size() << "drones from the database.";
// --- Simulated Drone Movement ---
connect(&simulationTimer, &QTimer::timeout, this, &DroneController::simulateDroneMovement);
simulationTimer.start(250); // Move once per second
qDebug() << "Simulation timer started for drone movement.";
}
// method so QML can retrieve the drone list.
QVariantList DroneController::getAllDrones() const
{
// qInfo() << "DEBUGGING" << Qt::endl;
// int index = 0;
QVariantList list;
for (const QSharedPointer<DroneClass> &drone : droneList)
{
QVariantMap droneMap;
// these method calls have to match our DroneClass interface
droneMap["name"] = drone->getName();
droneMap["role"] = drone->getRole(); // <-- we been using "drone type" in UI and everything but its called drone role in droneclass.h lul
droneMap["xbeeId"] = drone->getXbeeID();
droneMap["xbeeAddress"] = drone->getXbeeAddress();
// Adds placeholder values for status and battery and leave other fields blank
droneMap["status"] = drone->getBatteryLevel() > 0 ? "Connected" : "Not Connected";
droneMap["battery"] = drone->getBatteryLevel() > 0 ? QString::number(drone->getBatteryLevel()) + "%" : "Battery not received";
droneMap["latitude"] = drone->getLatitude();
droneMap["longitude"] = drone->getLongitude();
droneMap["altitude"] = drone->getAltitude();
droneMap["airspeed"] = drone->getAirspeed();
list.append(droneMap);
// index++;
}
return list;
}
DroneController::~DroneController()
{
}
// DroneClass updaters
// We're changing this here so that by default the DroneClass is
// not able to be updated from QML. Only C++ can update drones
// in the DroneController class
void DroneController::renameDrone(const QString &xbeeID, const QString &newName) {
for (auto &drone : droneList) {
if (drone->getXbeeID() == xbeeID) {
drone->setName(newName);
updateDrone(drone);
break;
}
}
}
void DroneController::setXbeeAddress(const QString &xbeeID, const QString &newXbeeAddress) {
for (auto &drone : droneList) {
if (drone->getXbeeID() == xbeeID) {
drone->setXbeeAddress(newXbeeAddress);
updateDrone(drone);
break;
}
}
}
void DroneController::setBatteryLevel(const QString &xbeeID, const double &newBattery) {
for (auto &drone : droneList) {
if (drone->getXbeeID() == xbeeID) {
drone->setBatteryLevel(newBattery);
updateDrone(drone);
break;
}
}
}
void DroneController::setRole(const QString &xbeeID, const QString &newRole) {
for (auto &drone : droneList) {
if (drone->getXbeeID() == xbeeID) {
drone->setRole(newRole);
updateDrone(drone);
break;
}
}
}
void DroneController::setXbeeID(const QString &xbeeID, const QString &newXbeeID) {
for (auto &drone : droneList) {
if (drone->getXbeeID() == xbeeID) {
drone->setXbeeID(newXbeeID);
updateDrone(drone);
break;
}
}
}
void DroneController::setPosition(const QString &xbeeID, const QVector3D &newPosition) {
for (auto &drone : droneList) {
if (drone->getXbeeID() == xbeeID) {
drone->setPosition(newPosition);
updateDrone(drone);
break;
}
}
}
void DroneController::setLatitude(const QString &xbeeID, const double &newLatitude) {
for (auto &drone : droneList) {
if (drone->getXbeeID() == xbeeID) {
drone->setLatitude(newLatitude);
updateDrone(drone);
break;
}
}
}
void DroneController::setLongitude(const QString &xbeeID, const double &newLongitude) {
for (auto &drone : droneList) {
if (drone->getXbeeID() == xbeeID) {
drone->setLongitude(newLongitude);
updateDrone(drone);
break;
}
}
}
void DroneController::setAltitude(const QString &xbeeID, const double &newAltitude) {
for (auto &drone : droneList) {
if (drone->getXbeeID() == xbeeID) {
drone->setAltitude(newAltitude);
updateDrone(drone);
break;
}
}
}
void DroneController::setVelocity(const QString &xbeeID, const QVector3D &newVelocity) {
for (auto &drone : droneList) {
if (drone->getXbeeID() == xbeeID) {
drone->setVelocity(newVelocity);
updateDrone(drone);
break;
}
}
}
void DroneController::setAirspeed(const QString &xbeeID, const double &newAirspeed) {
for (auto &drone : droneList) {
if (drone->getXbeeID() == xbeeID) {
drone->setAirspeed(newAirspeed);
updateDrone(drone);
break;
}
}
}
void DroneController::setOrientation(const QString &xbeeID, const QVector3D &newOrientation) {
for (auto &drone : droneList) {
if (drone->getXbeeID() == xbeeID) {
drone->setOrientation(newOrientation);
updateDrone(drone);
break;
}
}
}
// Steps in saving a drone.
/* User Clicks button to save drone information
* Saving Drone
* 1. Added To Database
* 2. Added as Drone Object ?
* 3. Added to a List of Drones from DroneManager
* 4. Automatically view
*
* Viewable Drone
*/
// new function so the QML can create a drone using strings
void DroneController::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)
{
auto drone = QSharedPointer<DroneClass>::create();
drone->setName(input_name);
drone->setRole(input_role);
drone->setXbeeID(input_xbeeID);
drone->setXbeeAddress(input_xbeeAddress);
drone->setBatteryLevel(input_batteryLevel);
drone->setLatitude(input_latitude);
drone->setLongitude(input_longitude);
drone->setAltitude(input_altitude);
saveDroneToDB(drone); // call the internal method
}
void DroneController::saveDroneToDB(const QSharedPointer<DroneClass> &drone)
{
// remmber to update db appropriately as well
if (!drone)
return;
qDebug() << "saveDroneToDB called with:" << drone->getName()
<< drone->getRole()
<< drone->getXbeeID()
<< drone->getXbeeAddress();
// Avoid duplicates
for (const auto &d : droneList)
{
if (d->getXbeeAddress() == drone->getXbeeAddress())
{
qDebug() << "Drone already exists with address:" << drone->getXbeeAddress();
return;
}
}
// Add Drone to Database
int newDroneID = -1;
if (dbManager.createDrone(drone->getName(),
drone->getRole(),
drone->getXbeeID(),
drone->getXbeeAddress(),
&newDroneID))
{
qDebug() << "Drone created in DB successfully with ID:" << newDroneID;
// Add to the in-memory list
droneList.push_back(drone);
emit droneAdded(drone); // right now this is not being used anywhere
emit dronesChanged();
// Adding update to the new QML list
rebuildVariant();
qDebug() << "dronesChanged signal emitted";
qDebug() << "Drone saved:" << drone->getName();
}
else
{
qWarning() << "Failed to save drone to DB:" << drone->getName();
}
}
void DroneController::updateDrone(const QSharedPointer<DroneClass> &drone)
{
// Find the drone in our list by its xbeeID (im assuming is unique)
if (!drone)
return;
for (int i = 0; i < droneList.size(); ++i)
{
if (droneList[i]->getXbeeID() == drone->getXbeeID())
{
// Update in-memory
droneList[i]->setName(drone->getName());
droneList[i]->setRole(drone->getRole());
droneList[i]->setXbeeID(drone->getXbeeID());
droneList[i]->setXbeeAddress(drone->getXbeeAddress());
// Update database
QSqlQuery query;
query.prepare("SELECT drone_id FROM drones WHERE xbee_id = :xbeeId");
query.bindValue(":xbeeId", drone->getXbeeID());
if (query.exec() && query.next())
{
int droneID = query.value(0).toInt();
dbManager.editDrone(droneID,
drone->getName(),
drone->getRole(),
drone->getXbeeID(),
drone->getXbeeAddress());
}
emit dronesChanged();
rebuildVariant();
qDebug() << "[DroneController] Drone updated:" << drone->getName();
break;
}
}
}
void DroneController::deleteDrone(const QString &input_xbeeID)
{
if (input_xbeeID.isEmpty())
{
qWarning() << "Drone Controller: xbeeID not passed by UI.";
return;
}
// Try to find and delete the drone from memory first
bool found = false;
for (int i = 0; i < droneList.size(); i++)
{
if (droneList[i]->getXbeeID() == input_xbeeID ||
droneList[i]->getXbeeAddress() == input_xbeeID)
{
droneList.removeAt(i);
found = true;
qDebug() << "Removed drone from memory with ID/address:" << input_xbeeID;
break;
}
}
// Now delete from database, even if not found in memory
if (dbManager.deleteDrone(input_xbeeID))
{
qDebug() << "Drone deleted successfully from database:" << input_xbeeID;
emit dronesChanged();
// Adding update to the new QML list
rebuildVariant();
}
else
{
qWarning() << "Failed to delete drone from database:" << input_xbeeID;
// If we removed from memory but failed to delete from DB, sync
if (found)
{
emit dronesChanged();
// Adding update to the new QML list
rebuildVariant();
}
}
}
// if we're being honest the slots being called by any function is in my head and i cant figure out if i need something rn
void DroneController::deleteALlDrones_UI()
{
if (dbManager.deleteAllDrones())
{
droneList.clear(); // also delete drones in C++ memory
qDebug() << "[dronecontroller.cpp]: All drones deleted successfully!";
// Adding update to the new QML list
rebuildVariant();
emit dronesChanged();
}
else
{
qWarning() << "Failed to delete all drones.";
}
}
// If want to query by name
QSharedPointer<DroneClass> DroneController::getDroneByName(const QString &name)
{
for (const auto &drone : droneList)
{
if (drone->getName() == name)
{
return drone;
}
}
return QSharedPointer<DroneClass>(); // Return null pointer if not found
}
// If want to query by address
QSharedPointer<DroneClass> DroneController::getDroneByXbeeAddress(const QString &address)
{
qDebug() << "Looking for drone with address:" << address;
// First try exact address match
for (const auto &drone : droneList)
{
if (drone->getXbeeAddress() == address)
{
qDebug() << "Found drone by address:" << drone->getName();
return drone;
}
}
// If not found, try xbeeID match
for (const auto &drone : droneList)
{
if (drone->getXbeeID() == address)
{
qDebug() << "Found drone by XBee ID:" << drone->getName();
return drone;
}
}
// Attempt a more flexible match (case insensitive, partial)
for (const auto &drone : droneList)
{
if (drone->getXbeeAddress().contains(address, Qt::CaseInsensitive) ||
address.contains(drone->getXbeeAddress(), Qt::CaseInsensitive))
{
qDebug() << "Found drone by partial address match:" << drone->getName();
return drone;
}
}
qDebug() << "No drone found with address:" << address;
return QSharedPointer<DroneClass>(); // Return null pointer if not found
}
// Gets drones, but is used to REBUILD the drone list; so it refreshes and keeps the drone list up to date
QVariantList DroneController::getDrones() const
{ // DOUBLE CHECK THIS BRANDON
QVariantList result;
// Ensure the database is open
if (!dbManager.isOpen())
{
qWarning() << "Database is not open!";
return result;
}
// Execute a simple SELECT query
QSqlQuery query("SELECT drone_id, drone_name, drone_role, xbee_id, xbee_address FROM drones");
if (query.exec())
{
while (query.next())
{
QVariantMap drone;
drone["id"] = query.value(0).toInt();
drone["name"] = query.value(1).toString();
drone["role"] = query.value(2).toString(); // Changed from "type" to "role"
drone["xbeeId"] = query.value(3).toString();
drone["xbeeAddress"] = query.value(4).toString();
result.append(drone);
}
qDebug() << "Found" << result.size() << "drones in database";
// Initialize droneList with database contents
droneList.clear();
for (const QVariant &droneVar : result)
{
QVariantMap droneMap = droneVar.toMap();
droneList.append(QSharedPointer<DroneClass>::create(
droneMap["name"].toString(),
droneMap["role"].toString(), // Changed from "type" to "role"
droneMap["xbeeId"].toString(),
droneMap["xbeeAddress"].toString()));
}
}
else
{
qWarning() << "Failed to fetch drones from database:" << query.lastError().text();
}
return result;
}
DroneClass *DroneController::getDrone(int index) const
{
if (index < 0 || index >= droneList.size())
{
qWarning() << "getDrone: index out of range" << index;
return nullptr;
}
// QSharedPointer::data() gives you the raw pointer, ownership stays with the list
return droneList.at(index).data();
}
bool DroneController::openXbee(const QString& port, int baud)
{
if (!xbee_) xbee_ = std::make_unique<XbeeLink>(this);
if (!mav_) mav_ = std::make_unique<MavlinkSender>(xbee_.get(), this);
// set up receiver & wire signals
if (!mavRx_) {
mavRx_ = std::make_unique<MavlinkReceiver>(this);
connect(xbee_.get(), &XbeeLink::bytesReceived,
mavRx_.get(), &MavlinkReceiver::onBytes);
connect(mavRx_.get(), &MavlinkReceiver::messageReceived,
this, &DroneController::onMavlinkMessage);
}
const bool ok = xbee_->open(port, baud);
if (!ok) {
qWarning() << "[DroneController] Failed to open XBee port" << port << "baud" << baud;
return false;
}
qInfo() << "[DroneController] XBee opened on" << port << "@" << baud;
return true;
}
bool DroneController::sendArm(const QString& droneKeyOrAddr, bool arm)
{
// Use your existing resolver so callers can pass either address or ID
QSharedPointer<DroneClass> drone = getDroneByXbeeAddress(droneKeyOrAddr);
if (drone.isNull()) {
qWarning() << "[DroneController] sendArm: unknown drone/address:" << droneKeyOrAddr;
return false;
}
if (!mav_) {
qWarning() << "[DroneController] MAVLink sender not ready; call openXbee() first";
return false;
}
// TODO: make these configurable or read from DB later
// targetSys and targetComp are both 0 when dealing with ArduPilot SITL
const uint8_t targetSys = 1;
const uint8_t targetComp = 1; // MAV_COMP_ID_AUTOPILOT1
const bool ok = mav_->sendArm(targetSys, targetComp, arm);
qInfo() << "[DroneController] ARM" << (arm ? "ON" : "OFF")
<< "->" << drone->getName() << drone->getXbeeAddress()
<< "sent=" << ok;
return ok;
}
// Helper: find (or lazily bind) a drone for a sysid.
// Header must have: QHash<uint8_t, QSharedPointer<DroneClass>> sysMap_;
QSharedPointer<DroneClass> droneForSysId_lazyBind(uint8_t sysid,
QList<QSharedPointer<DroneClass>>& list,
QHash<uint8_t, QSharedPointer<DroneClass>>& map)
{
if (map.contains(sysid)) return map.value(sysid);
if (!list.isEmpty()) {
// TEMP heuristic: bind first drone we have (until you provide a real mapping)
auto d = list.first();
map.insert(sysid, d);
qInfo() << "[DroneController] Bound sysid" << sysid << "to drone" << d->getName();
return d;
}
return {};
}
void DroneController::onMavlinkMessage(const RxMavlinkMsg& m)
{
// Rebuild a mavlink_message_t from the envelope so we can use decode helpers
mavlink_message_t msg{};
msg.sysid = m.sysid;
msg.compid = m.compid;
msg.msgid = static_cast<uint32_t>(m.msgid);
msg.len = static_cast<uint8_t>(m.payload.size());
memcpy(_MAV_PAYLOAD_NON_CONST(&msg), m.payload.constData(), msg.len);
uint8_t sysid = msg.sysid;
// qInfo() << "[onMavlinkMessage] received message";
// qInfo() << "[onMavlinkMessage] Orientation: " << droneList[0]->getOrientation();
switch (msg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT: {
// qInfo() << "Got a heartbeat";
mavlink_heartbeat_t hb;
mavlink_msg_heartbeat_decode(&msg, &hb);
updateDroneTelem(sysid, "connected", true);
updateDroneTelem(sysid, "base_mode", static_cast<int>(hb.base_mode));
updateDroneTelem(sysid, "custom_mode", static_cast<int>(hb.custom_mode));
break;
}
case MAVLINK_MSG_ID_SYS_STATUS: {
mavlink_sys_status_t s;
mavlink_msg_sys_status_decode(&msg, &s);
updateDroneTelem(sysid, "battery_v", s.voltage_battery/1000.0);
updateDroneTelem(sysid, "battery_pct", static_cast<int>(s.battery_remaining));
break;
}
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: {
mavlink_global_position_int_t p;
mavlink_msg_global_position_int_decode(&msg, &p);
updateDroneTelem(sysid, "lat", p.lat/1e7);
updateDroneTelem(sysid, "lon", p.lon/1e7);
// updateDroneTelem(sysid, "alt_m", p.alt/1000.0);
updateDroneTelem(sysid, "alt_m", p.relative_alt / 1000.0);
break;
}
case MAVLINK_MSG_ID_ATTITUDE: {
// qInfo() << "Got attitude";
mavlink_attitude_t a;
mavlink_msg_attitude_decode(&msg, &a);
updateDroneTelem(sysid, "roll", a.roll);
updateDroneTelem(sysid, "pitch", a.pitch);
updateDroneTelem(sysid, "yaw", a.yaw);
break;
}
case MAVLINK_MSG_ID_COMMAND_ACK: {
// qInfo() << "Got msg id ack";
mavlink_command_ack_t ack;
mavlink_msg_command_ack_decode(&msg, &ack);
qInfo().nospace()
<< "[MAVRX] COMMAND_ACK cmd=" << ack.command
<< " result=" << static_cast<int>(ack.result)
<< " (sysid=" << static_cast<int>(sysid)
<< ", compid=" << static_cast<int>(msg.compid) << ")";
updateDroneTelem(sysid, "last_command", static_cast<int>(ack.command));
updateDroneTelem(sysid, "last_result", static_cast<int>(ack.result));
break;
}
default:
break;
}
}
void DroneController::updateDroneTelem(uint8_t sysid, const QString& field, const QVariant& value)
{
// NOTE: add 'sysMap_' as a private member in your header:
// QHash<uint8_t, QSharedPointer<DroneClass>> sysMap_;
auto d = droneForSysId_lazyBind(sysid, droneList, sysMap_);
if (d.isNull()) return;
if (field == "connected") {
d->setConnected(value.toBool()); // if you have it
} else if (field == "battery_v") {
d->setBatteryVoltage(value.toDouble()); // or setBatteryLevel if that's what you track
} else if (field == "battery_pct") {
d->setBatteryLevel(value.toInt()); // 0–100
} else if (field == "lat") {
d->setLatitude(value.toDouble());
} else if (field == "lon") {
d->setLongitude(value.toDouble());
} else if (field == "alt_m") {
d->setAltitude(value.toDouble());
} else if (field == "roll") {
d->setRoll(value.toDouble()); // if you surface attitude
} else if (field == "pitch") {
d->setPitch(value.toDouble());
} else if (field == "yaw") {
d->setYaw(value.toDouble());
} else if (field == "base_mode" || field == "custom_mode") {
d->setModeField(field, value); // generic hook if you prefer
}
emit dronesChanged();
}
// Called when the droneList is updated
void DroneController::rebuildVariant()
{
m_dronesVariant.clear();
m_dronesVariant.reserve(droneList.size());
for (const auto &sp : droneList)
{
m_dronesVariant << QVariant::fromValue(static_cast<QObject *>(sp.data()));
}
}
// Telemetry update for ONE existing drone (same object pointer)
void DroneController::onTelemetry(const QString &name, double lat, double lon)
{
auto it = std::find_if(droneList.begin(), droneList.end(),
[&](const QSharedPointer<DroneClass> &d)
{ return d->getName() == name; });
if (it == droneList.end())
return;
(*it)->setLatitude(lat); // emits latitudeChanged → QML updates
(*it)->setLongitude(lon); // emits longitudeChanged
}
// Simple linear interpolation towards a target point
void moveDroneTowards(double &lat, double &lon, double targetLat, double targetLon, double step)
{
double dLat = targetLat - lat;
double dLon = targetLon - lon;
// Calculate distance
double distance = sqrt(dLat*dLat + dLon*dLon);
if (distance < 1e-6) return; // Already there
// Move by step, but don't overshoot
double ratio = step / distance;
if (ratio > 1.0) ratio = 1.0;
lat += dLat * ratio;
lon += dLon * ratio;
}
void DroneController::simulateDroneMovement()
{
double step = 0.00005; // small step toward waypoint
for (auto &drone : droneList)
{
if (!drone) continue;
double lat = drone->getLatitude();
double lon = drone->getLongitude();
// Get the next waypoint for this drone
QList<QVariantMap> wps;
if (droneWaypoints.contains(drone->getName()) && !droneWaypoints[drone->getName()].isEmpty())
{
wps = droneWaypoints[drone->getName()];
}
if (wps.size() < 2)
continue; // nothing to move toward
double targetLat = wps[1]["lat"].toDouble();
double targetLon = wps[1]["lon"].toDouble();
// Move towards it
moveDroneTowards(lat, lon, targetLat, targetLon, step);
// Update drone position
drone->setLatitude(lat);
drone->setLongitude(lon);
emit droneStateChanged(drone.data());
}
}
QObject* DroneController::getDroneByNameQML(const QString &name) const {
for (const auto &sp : droneList) { // QList<QSharedPointer<DroneClass>>
if (sp && sp->getName() == name) // use your getter names
return static_cast<QObject*>(sp.data()); // expose raw QObject* to QML
}
return nullptr;
}