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
177
/*=====================================================================
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 "AutoPilotPlugin.h"
#include "QGCApplication.h"
#include "ParameterLoader.h"
#include "UAS.h"
#include "FirmwarePlugin.h"
AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent)
: QObject(parent)
, _vehicle(vehicle)
, _firmwarePlugin(vehicle->firmwarePlugin())
, _parametersReady(false)
, _missingParameters(false)
, _setupComplete(false)
{
Q_ASSERT(vehicle);
connect(_vehicle->uas(), &UASInterface::disconnected, this, &AutoPilotPlugin::_uasDisconnected);
connect(this, &AutoPilotPlugin::parametersReadyChanged, this, &AutoPilotPlugin::_parametersReadyChanged);
}
AutoPilotPlugin::~AutoPilotPlugin()
{
}
void AutoPilotPlugin::_uasDisconnected(void)
{
_parametersReady = false;
emit parametersReadyChanged(_parametersReady);
}
void AutoPilotPlugin::_parametersReadyChanged(bool parametersReady)
{
if (parametersReady) {
_recalcSetupComplete();
if (!_setupComplete) {
qgcApp()->showMessage("One or more vehicle components require setup prior to flight.");
// Take the user to Vehicle Summary
qgcApp()->showSetupView();
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
}
}
}
void AutoPilotPlugin::_recalcSetupComplete(void)
{
bool newSetupComplete = true;
foreach(const QVariant componentVariant, vehicleComponents()) {
VehicleComponent* component = qobject_cast<VehicleComponent*>(qvariant_cast<QObject *>(componentVariant));
Q_ASSERT(component);
if (!component->setupComplete()) {
newSetupComplete = false;
break;
}
}
if (_setupComplete != newSetupComplete) {
_setupComplete = newSetupComplete;
emit setupCompleteChanged(_setupComplete);
}
}
bool AutoPilotPlugin::setupComplete(void)
{
Q_ASSERT(_parametersReady);
return _setupComplete;
}
void AutoPilotPlugin::resetAllParametersToDefaults(void)
{
mavlink_message_t msg;
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->uas()->getUASID(), 0, MAV_CMD_PREFLIGHT_STORAGE, 0, 2, -1, 0, 0, 0, 0, 0);
_vehicle->sendMessage(msg);
}
void AutoPilotPlugin::refreshAllParameters(unsigned char componentID)
{
_vehicle->getParameterLoader()->refreshAllParameters((uint8_t)componentID);
}
void AutoPilotPlugin::refreshParameter(int componentId, const QString& name)
{
_vehicle->getParameterLoader()->refreshParameter(componentId, name);
}
void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& namePrefix)
{
_vehicle->getParameterLoader()->refreshParametersPrefix(componentId, namePrefix);
}
bool AutoPilotPlugin::parameterExists(int componentId, const QString& name)
{
return _vehicle->getParameterLoader()->parameterExists(componentId, name);
}
Fact* AutoPilotPlugin::getParameterFact(int componentId, const QString& name)
{
return _vehicle->getParameterLoader()->getFact(componentId, name);
}
bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name)
{
switch (provider) {
case FactSystem::ParameterProvider:
return _vehicle->getParameterLoader()->parameterExists(componentId, name);
// Other providers will go here once they come online
}
Q_ASSERT(false);
return false;
}
Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, const QString& name)
{
switch (provider) {
case FactSystem::ParameterProvider:
return _vehicle->getParameterLoader()->getFact(componentId, name);
// Other providers will go here once they come online
}
Q_ASSERT(false);
return NULL;
}
QStringList AutoPilotPlugin::parameterNames(int componentId)
{
return _vehicle->getParameterLoader()->parameterNames(componentId);
}
const QMap<int, QMap<QString, QStringList> >& AutoPilotPlugin::getGroupMap(void)
{
return _vehicle->getParameterLoader()->getGroupMap();
}
void AutoPilotPlugin::writeParametersToStream(QTextStream &stream)
{
_vehicle->getParameterLoader()->writeParametersToStream(stream);
}
QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
{
return _vehicle->getParameterLoader()->readParametersFromStream(stream);
}