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