AirframeComponentController.cc 5.47 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

10 11 12 13 14 15 16

/// @file
///     @author Don Gagne <don@thegagnes.com>

#include "AirframeComponentController.h"
#include "AirframeComponentAirframes.h"
#include "QGCMAVLink.h"
17
#include "MultiVehicleManager.h"
18 19 20 21 22 23 24
#include "QGCApplication.h"

#include <QVariant>
#include <QQmlProperty>

bool AirframeComponentController::_typesRegistered = false;

25
AirframeComponentController::AirframeComponentController(void) :
Don Gagne's avatar
Don Gagne committed
26
    _currentVehicleIndex(0),
27 28
    _autostartId(0),
    _showCustomConfigPanel(false)
29 30 31 32 33 34 35
{
    if (!_typesRegistered) {
        _typesRegistered = true;
        qmlRegisterUncreatableType<AirframeType>("QGroundControl.Controllers", 1, 0, "AiframeType", "Can only reference AirframeType");
        qmlRegisterUncreatableType<Airframe>("QGroundControl.Controllers", 1, 0, "Aiframe", "Can only reference Airframe");
    }
    
Don Gagne's avatar
Don Gagne committed
36 37 38
    QStringList usedParams;
    usedParams << "SYS_AUTOSTART" << "SYS_AUTOCONFIG";
    if (!_allParametersExists(FactSystem::defaultComponentId, usedParams)) {
39 40 41
        return;
    }
    
42 43 44
    // Load up member variables
    
    bool autostartFound = false;
Don Gagne's avatar
Don Gagne committed
45
    _autostartId = getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->rawValue().toInt();
46

47
    
48
    for (int tindex = 0; tindex < AirframeComponentAirframes::get().count(); tindex++) {
49

50
        const AirframeComponentAirframes::AirframeType_t* pType = AirframeComponentAirframes::get().values().at(tindex);
51

52 53
        AirframeType* airframeType = new AirframeType(pType->name, pType->imageResource, this);
        Q_CHECK_PTR(airframeType);
54

55 56 57
        for (int index = 0; index < pType->rgAirframeInfo.count(); index++) {
            const AirframeComponentAirframes::AirframeInfo_t* pInfo = pType->rgAirframeInfo.at(index);
            Q_CHECK_PTR(pInfo);
58

59
            if (_autostartId == pInfo->autostartId) {
DonLakeFlyer's avatar
DonLakeFlyer committed
60 61 62
                if (autostartFound) {
                    qWarning() << "AirframeComponentController::AirframeComponentController duplicate ids found:" << _autostartId;
                }
63 64 65 66 67 68 69 70 71 72
                autostartFound = true;
                _currentAirframeType = pType->name;
                _currentVehicleName = pInfo->name;
                _currentVehicleIndex = index;
            }
            airframeType->addAirframe(pInfo->name, pInfo->autostartId);
        }
        
        _airframeTypes.append(QVariant::fromValue(airframeType));
    }
73
    
74 75 76
    if (_autostartId != 0 && !autostartFound) {
        _showCustomConfigPanel = true;
        emit showCustomConfigPanelChanged(true);
Don Gagne's avatar
Don Gagne committed
77
    }
78 79 80 81 82 83 84 85 86
}

AirframeComponentController::~AirframeComponentController()
{

}

void AirframeComponentController::changeAutostart(void)
{
87
    if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count() > 1) {
88
        qgcApp()->showAppMessage(tr("You cannot change airframe configuration while connected to multiple vehicles."));
Don Gagne's avatar
Don Gagne committed
89 90 91
		return;
	}
	
92 93
    qgcApp()->setOverrideCursor(Qt::WaitCursor);
    
94 95
    Fact* sysAutoStartFact  = getParameterFact(-1, "SYS_AUTOSTART");
    Fact* sysAutoConfigFact = getParameterFact(-1, "SYS_AUTOCONFIG");
96
    
97 98 99 100
    // We need to wait for the vehicleUpdated signals to come back before we reboot
    _waitParamWriteSignalCount = 0;
    connect(sysAutoStartFact, &Fact::vehicleUpdated, this, &AirframeComponentController::_waitParamWriteSignal);
    connect(sysAutoConfigFact, &Fact::vehicleUpdated, this, &AirframeComponentController::_waitParamWriteSignal);
101
    
102
    // We use forceSetValue to params are sent even if the previous value is that same as the new value
Don Gagne's avatar
Don Gagne committed
103 104
    sysAutoStartFact->forceSetRawValue(_autostartId);
    sysAutoConfigFact->forceSetRawValue(1);
105 106 107 108 109
}

void AirframeComponentController::_waitParamWriteSignal(QVariant value)
{
    Q_UNUSED(value);
110
    
111 112 113 114 115
    _waitParamWriteSignalCount++;
    if (_waitParamWriteSignalCount == 2) {
        // Now that both params have made it to the vehicle we can reboot it. All these signals are flying
        // around on the main thread, so we need to allow the stack to unwind back to the event loop before
        // we reboot.
116
        QTimer::singleShot(800, this, &AirframeComponentController::_rebootAfterStackUnwind);
117 118 119 120 121
    }
}

void AirframeComponentController::_rebootAfterStackUnwind(void)
{    
122
    _vehicle->sendMavCommand(_vehicle->defaultComponentId(), MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, true /* showError */, 1.0f);
123
    qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
124 125 126 127
    for (unsigned i = 0; i < 2000; i++) {
        QGC::SLEEP::usleep(500);
        qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
    }
128
    qgcApp()->restoreOverrideCursor();
129
    qgcApp()->toolbox()->linkManager()->disconnectAll();
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
}

AirframeType::AirframeType(const QString& name, const QString& imageResource, QObject* parent) :
    QObject(parent),
    _name(name),
    _imageResource(imageResource)
{
    
}

AirframeType::~AirframeType()
{
    
}

void AirframeType::addAirframe(const QString& name, int autostartId)
{
    Airframe* airframe = new Airframe(name, autostartId);
    Q_CHECK_PTR(airframe);
    
    _airframes.append(QVariant::fromValue(airframe));
}

Airframe::Airframe(const QString& name, int autostartId, QObject* parent) :
    QObject(parent),
    _name(name),
    _autostartId(autostartId)
{
    
}

Airframe::~Airframe()
{
    
}