1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
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
165
166
167
168
169
170
171
172
173
174
175
176
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "AirframeComponentController.h"
#include "AirframeComponentAirframes.h"
#include "QGCMAVLink.h"
#include "MultiVehicleManager.h"
#include "AutoPilotPluginManager.h"
#include "QGCApplication.h"
#include <QVariant>
#include <QQmlProperty>
bool AirframeComponentController::_typesRegistered = false;
AirframeComponentController::AirframeComponentController(void) :
_currentVehicleIndex(0),
_autostartId(0),
_showCustomConfigPanel(false)
{
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");
}
QStringList usedParams;
usedParams << "SYS_AUTOSTART" << "SYS_AUTOCONFIG";
if (!_allParametersExists(FactSystem::defaultComponentId, usedParams)) {
return;
}
// Load up member variables
bool autostartFound = false;
_autostartId = getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->rawValue().toInt();
for (int tindex = 0; tindex < AirframeComponentAirframes::get().count(); tindex++) {
const AirframeComponentAirframes::AirframeType_t* pType = AirframeComponentAirframes::get().values().at(tindex);
AirframeType* airframeType = new AirframeType(pType->name, pType->imageResource, this);
Q_CHECK_PTR(airframeType);
for (int index = 0; index < pType->rgAirframeInfo.count(); index++) {
const AirframeComponentAirframes::AirframeInfo_t* pInfo = pType->rgAirframeInfo.at(index);
Q_CHECK_PTR(pInfo);
if (_autostartId == pInfo->autostartId) {
Q_ASSERT(!autostartFound);
autostartFound = true;
_currentAirframeType = pType->name;
_currentVehicleName = pInfo->name;
_currentVehicleIndex = index;
}
airframeType->addAirframe(pInfo->name, pInfo->autostartId);
}
_airframeTypes.append(QVariant::fromValue(airframeType));
}
if (_autostartId != 0 && !autostartFound) {
_showCustomConfigPanel = true;
emit showCustomConfigPanelChanged(true);
}
}
AirframeComponentController::~AirframeComponentController()
{
}
void AirframeComponentController::changeAutostart(void)
{
if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count() > 1) {
qgcApp()->showMessage("You cannot change airframe configuration while connected to multiple vehicles.");
return;
}
qgcApp()->setOverrideCursor(Qt::WaitCursor);
Fact* sysAutoStartFact = getParameterFact(-1, "SYS_AUTOSTART");
Fact* sysAutoConfigFact = getParameterFact(-1, "SYS_AUTOCONFIG");
// 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);
// We use forceSetValue to params are sent even if the previous value is that same as the new value
sysAutoStartFact->forceSetRawValue(_autostartId);
sysAutoConfigFact->forceSetRawValue(1);
}
void AirframeComponentController::_waitParamWriteSignal(QVariant value)
{
Q_UNUSED(value);
_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.
QTimer::singleShot(800, this, &AirframeComponentController::_rebootAfterStackUnwind);
}
}
void AirframeComponentController::_rebootAfterStackUnwind(void)
{
_uas->executeCommand(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
for (unsigned i = 0; i < 2000; i++) {
QGC::SLEEP::usleep(500);
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
}
qgcApp()->toolbox()->linkManager()->disconnectAll();
qgcApp()->restoreOverrideCursor();
}
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()
{
}