3#include <QtGui/QGuiApplication>
12#include <QtCore/QThread>
13#include <QtCore/QVariant>
14#include <QtGui/QCursor>
16bool AirframeComponentController::_typesRegistered =
false;
19 _currentVehicleIndex(0),
21 _showCustomConfigPanel(false)
23 if (!_typesRegistered) {
24 _typesRegistered =
true;
27 QStringList usedParams;
28 usedParams <<
"SYS_AUTOSTART" <<
"SYS_AUTOCONFIG";
35 bool autostartFound =
false;
37 _currentVehicleName = QString::number(_autostartId);
44 Q_CHECK_PTR(airframeType);
46 for (
int index = 0; index < pType->
rgAirframeInfo.count(); index++) {
52 qWarning() <<
"AirframeComponentController::AirframeComponentController duplicate ids found:" << _autostartId;
54 autostartFound =
true;
55 _currentAirframeType = pType->
name;
56 _currentVehicleName = pInfo->
name;
57 _currentVehicleIndex = index;
62 _airframeTypes.append(QVariant::fromValue(airframeType));
65 if (_autostartId != 0 && !autostartFound) {
66 _showCustomConfigPanel =
true;
79 QGC::showAppMessage(tr(
"You cannot change airframe configuration while connected to multiple vehicles."));
83 QGuiApplication::setOverrideCursor(QCursor(Qt::WaitCursor));
89 _waitParamWriteSignalCount = 0;
90 connect(sysAutoStartFact, &
Fact::vehicleUpdated,
this, &AirframeComponentController::_waitParamWriteSignal);
91 connect(sysAutoConfigFact, &
Fact::vehicleUpdated,
this, &AirframeComponentController::_waitParamWriteSignal);
98void AirframeComponentController::_waitParamWriteSignal(QVariant value)
102 _waitParamWriteSignalCount++;
103 if (_waitParamWriteSignalCount == 2) {
107 QTimer::singleShot(800,
this, &AirframeComponentController::_rebootAfterStackUnwind);
111void AirframeComponentController::_rebootAfterStackUnwind(
void)
114 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
115 for (
unsigned i = 0; i < 2000; i++) {
116 QThread::usleep(500);
117 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
119 QGuiApplication::restoreOverrideCursor();
126 _imageResource(imageResource)
139 Q_CHECK_PTR(airframe);
141 _airframes.append(QVariant::fromValue(airframe));
147 _autostartId(autostartId)
static QMap< QString, AirframeComponentAirframes::AirframeType_t * > & get()
void showCustomConfigPanelChanged(bool show)
AirframeComponentController(void)
Q_INVOKABLE void changeAutostart(void)
~AirframeComponentController()
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.
void forceSetRawValue(const QVariant &value)
Sets and sends new value to vehicle even if value is the same.
void vehicleUpdated(const QVariant &value)
Signalled when the param write ack comes back from the vehicle.
QVariant rawValue() const
Value after translation.
static LinkManager * instance()
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)
int defaultComponentId() const
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
QList< AirframeInfo_t * > rgAirframeInfo