QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
AirframeComponentController.cc
Go to the documentation of this file.
4#include "QGCApplication.h"
5#include "LinkManager.h"
6#include "Fact.h"
7#include "Vehicle.h"
8#include "ParameterManager.h"
9
10#include <QtCore/QThread>
11#include <QtCore/QVariant>
12#include <QtGui/QCursor>
13
14bool AirframeComponentController::_typesRegistered = false;
15
17 _currentVehicleIndex(0),
18 _autostartId(0),
19 _showCustomConfigPanel(false)
20{
21 if (!_typesRegistered) {
22 _typesRegistered = true;
23 }
24
25 QStringList usedParams;
26 usedParams << "SYS_AUTOSTART" << "SYS_AUTOCONFIG";
28 return;
29 }
30
31 // Load up member variables
32
33 bool autostartFound = false;
34 _autostartId = getParameterFact(ParameterManager::defaultComponentId, "SYS_AUTOSTART")->rawValue().toInt();
35 _currentVehicleName = QString::number(_autostartId); // Temp val. Replaced with actual vehicle name if found
36
37 for (int tindex = 0; tindex < AirframeComponentAirframes::get().count(); tindex++) {
38
40
41 AirframeType* airframeType = new AirframeType(pType->name, pType->imageResource, this);
42 Q_CHECK_PTR(airframeType);
43
44 for (int index = 0; index < pType->rgAirframeInfo.count(); index++) {
45 const AirframeComponentAirframes::AirframeInfo_t* pInfo = pType->rgAirframeInfo.at(index);
46 Q_CHECK_PTR(pInfo);
47
48 if (_autostartId == pInfo->autostartId) {
49 if (autostartFound) {
50 qWarning() << "AirframeComponentController::AirframeComponentController duplicate ids found:" << _autostartId;
51 }
52 autostartFound = true;
53 _currentAirframeType = pType->name;
54 _currentVehicleName = pInfo->name;
55 _currentVehicleIndex = index;
56 }
57 airframeType->addAirframe(pInfo->name, pInfo->autostartId);
58 }
59
60 _airframeTypes.append(QVariant::fromValue(airframeType));
61 }
62
63 if (_autostartId != 0 && !autostartFound) {
64 _showCustomConfigPanel = true;
66 }
67}
68
73
74void AirframeComponentController::changeAutostart(void)
75{
76 if (MultiVehicleManager::instance()->vehicles()->count() > 1) {
77 qgcApp()->showAppMessage(tr("You cannot change airframe configuration while connected to multiple vehicles."));
78 return;
79 }
80
81 QGuiApplication::setOverrideCursor(QCursor(Qt::WaitCursor));
82
83 Fact* sysAutoStartFact = getParameterFact(-1, "SYS_AUTOSTART");
84 Fact* sysAutoConfigFact = getParameterFact(-1, "SYS_AUTOCONFIG");
85
86 // We need to wait for the vehicleUpdated signals to come back before we reboot
87 _waitParamWriteSignalCount = 0;
88 connect(sysAutoStartFact, &Fact::vehicleUpdated, this, &AirframeComponentController::_waitParamWriteSignal);
89 connect(sysAutoConfigFact, &Fact::vehicleUpdated, this, &AirframeComponentController::_waitParamWriteSignal);
90
91 // We use forceSetValue to ensure params are sent even if the previous value is that same as the new value
92 sysAutoStartFact->forceSetRawValue(_autostartId);
93 sysAutoConfigFact->forceSetRawValue(1);
94}
95
96void AirframeComponentController::_waitParamWriteSignal(QVariant value)
97{
98 Q_UNUSED(value);
99
100 _waitParamWriteSignalCount++;
101 if (_waitParamWriteSignalCount == 2) {
102 // Now that both params have made it to the vehicle we can reboot it. All these signals are flying
103 // around on the main thread, so we need to allow the stack to unwind back to the event loop before
104 // we reboot.
105 QTimer::singleShot(800, this, &AirframeComponentController::_rebootAfterStackUnwind);
106 }
107}
108
109void AirframeComponentController::_rebootAfterStackUnwind(void)
110{
111 _vehicle->sendMavCommand(_vehicle->defaultComponentId(), MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, true /* showError */, 1.0f);
112 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
113 for (unsigned i = 0; i < 2000; i++) {
114 QThread::usleep(500);
115 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
116 }
117 QGuiApplication::restoreOverrideCursor();
118 LinkManager::instance()->disconnectAll();
119}
120
121AirframeType::AirframeType(const QString& name, const QString& imageResource, QObject* parent) :
122 QObject(parent),
123 _name(name),
124 _imageResource(imageResource)
125{
126
127}
128
133
134void AirframeType::addAirframe(const QString& name, int autostartId)
135{
136 Airframe* airframe = new Airframe(name, autostartId);
137 Q_CHECK_PTR(airframe);
138
139 _airframes.append(QVariant::fromValue(airframe));
140}
141
142Airframe::Airframe(const QString& name, int autostartId, QObject* parent) :
143 QObject(parent),
144 _name(name),
145 _autostartId(autostartId)
146{
147
148}
149
151{
152
153}
#define qgcApp()
static QMap< QString, AirframeComponentAirframes::AirframeType_t * > & get()
bool showCustomConfigPanel MEMBER _showCustomConfigPanel NOTIFY showCustomConfigPanelChanged(QVariantList airframeTypes MEMBER _airframeTypes CONSTANT) 1(QString currentAirframeType MEMBER _currentAirframeType CONSTANT) 1(QString currentVehicleName MEMBER _currentVehicleName CONSTANT) 1(int currentVehicleIndex MEMBER _currentVehicleIndex CONSTANT) 1(int autostartId MEMBER _autostartId NOTIFY autostartIdChanged) 1 void changeAutostart(void)
AirframeType(const QString &name, const QString &imageResource, QObject *parent=nullptr)
QString name MEMBER _name int autostartId
Airframe(const QString &name, int autostartId, QObject *parent=nullptr)
bool _allParametersExists(int componentId, const QStringList &names) const
A Fact is used to hold a single value within the system.
Definition Fact.h:19
void vehicleUpdated(const QVariant &value)
Signalled when the param write ack comes back from the vehicle.
static constexpr int defaultComponentId
void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Definition Vehicle.cc:2309
int defaultComponentId() const
Definition Vehicle.h:711