10#include <QtCore/QThread>
11#include <QtCore/QVariant>
12#include <QtGui/QCursor>
14bool AirframeComponentController::_typesRegistered =
false;
17 _currentVehicleIndex(0),
19 _showCustomConfigPanel(false)
21 if (!_typesRegistered) {
22 _typesRegistered =
true;
25 QStringList usedParams;
26 usedParams <<
"SYS_AUTOSTART" <<
"SYS_AUTOCONFIG";
33 bool autostartFound =
false;
35 _currentVehicleName = QString::number(_autostartId);
42 Q_CHECK_PTR(airframeType);
44 for (
int index = 0; index < pType->
rgAirframeInfo.count(); index++) {
50 qWarning() <<
"AirframeComponentController::AirframeComponentController duplicate ids found:" << _autostartId;
52 autostartFound =
true;
53 _currentAirframeType = pType->
name;
54 _currentVehicleName = pInfo->
name;
55 _currentVehicleIndex = index;
60 _airframeTypes.append(QVariant::fromValue(airframeType));
63 if (_autostartId != 0 && !autostartFound) {
64 _showCustomConfigPanel =
true;
74void AirframeComponentController::changeAutostart(
void)
76 if (MultiVehicleManager::instance()->vehicles()->count() > 1) {
77 qgcApp()->showAppMessage(tr(
"You cannot change airframe configuration while connected to multiple vehicles."));
81 QGuiApplication::setOverrideCursor(QCursor(Qt::WaitCursor));
83 Fact* sysAutoStartFact = getParameterFact(-1,
"SYS_AUTOSTART");
84 Fact* sysAutoConfigFact = getParameterFact(-1,
"SYS_AUTOCONFIG");
87 _waitParamWriteSignalCount = 0;
88 connect(sysAutoStartFact, &
Fact::vehicleUpdated,
this, &AirframeComponentController::_waitParamWriteSignal);
89 connect(sysAutoConfigFact, &
Fact::vehicleUpdated,
this, &AirframeComponentController::_waitParamWriteSignal);
92 sysAutoStartFact->forceSetRawValue(_autostartId);
93 sysAutoConfigFact->forceSetRawValue(1);
96void AirframeComponentController::_waitParamWriteSignal(QVariant value)
100 _waitParamWriteSignalCount++;
101 if (_waitParamWriteSignalCount == 2) {
105 QTimer::singleShot(800,
this, &AirframeComponentController::_rebootAfterStackUnwind);
109void AirframeComponentController::_rebootAfterStackUnwind(
void)
112 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
113 for (
unsigned i = 0; i < 2000; i++) {
114 QThread::usleep(500);
115 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
117 QGuiApplication::restoreOverrideCursor();
118 LinkManager::instance()->disconnectAll();
124 _imageResource(imageResource)
134void AirframeType::addAirframe(
const QString& name,
int autostartId)
137 Q_CHECK_PTR(airframe);
139 _airframes.append(QVariant::fromValue(airframe));
145 _autostartId(autostartId)
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)
AirframeComponentController(void)
~AirframeComponentController()
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.
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)
int defaultComponentId() const
QList< AirframeInfo_t * > rgAirframeInfo