Newer
Older
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
/*===================================================================
======================================================================*/
/**
* @file
* @brief Represents one unmanned aerial vehicle
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QList>
#include <QMessageBox>
#include <QTimer>
#include <QSettings>
#include <iostream>
#include <QDebug>
#include <cmath>
#include <qmath.h>
#include "UAS.h"
#include "LinkInterface.h"
#include "UASManager.h"
#include "QGC.h"
#include "GAudioOutput.h"
#include "MAVLinkProtocol.h"
#include "QGCMAVLink.h"
#include "LinkManager.h"
#include "SerialLink.h"
#ifdef QGC_PROTOBUF_ENABLED
#include <google/protobuf/descriptor.h>
#endif
/**
* Gets the settings from the previous UAS (name, airframe, autopilot, battery specs)
* by calling readSettings. This means the new UAS will have the same settings
* as the previous one created unless one calls deleteSettings in the code after
* creating the UAS.
*/
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
uasId(id),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
commStatus(COMM_DISCONNECTED),
receiveDropRate(0),
sendDropRate(0),
statusTimeout(new QTimer(this)),
name(""),
type(MAV_TYPE_GENERIC),
airframe(QGC_AIRFRAME_GENERIC),
autopilot(-1),
systemIsArmed(false),
mode(-1),
// custom_mode not initialized
navMode(-1),
status(-1),
// shortModeText not initialized
// shortStateText not initialized
// actuatorValues not initialized
// actuatorNames not initialized
// motorValues not initialized
// motorNames mnot initialized
thrustSum(0),
thrustMax(10),
// batteryType not initialized
// cells not initialized
// fullVoltage not initialized
// emptyVoltage not initialized
startVoltage(-1.0f),
tickVoltage(10.5f),
lastTickVoltageValue(13.0f),
tickLowpassVoltage(12.0f),
warnVoltage(9.5f),
warnLevelPercent(20.0f),
currentVoltage(12.6f),
lpVoltage(12.0f),
batteryRemainingEstimateEnabled(true),
// chargeLevel not initialized
// timeRemaining not initialized
lowBattAlarm(false),
startTime(QGC::groundTimeMilliseconds()),
onboardTimeOffset(0),
controlRollManual(true),
controlPitchManual(true),
controlYawManual(true),
controlThrustManual(true),
manualRollAngle(0),
manualPitchAngle(0),
manualYawAngle(0),
manualThrust(0),
positionLock(false),
isLocalPositionKnown(false),
isGlobalPositionKnown(false),
localX(0.0),
localY(0.0),
localZ(0.0),
globalEstimatorActive(false),
latitude_gps(0.0),
longitude_gps(0.0),
altitude_gps(0.0),
nedPosGlobalOffset(0,0,0),
nedAttGlobalOffset(0,0,0),
waypointManager(this),
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
receivedOverlayTimestamp(0.0),
receivedObstacleListTimestamp(0.0),
receivedPathTimestamp(0.0),
receivedPointCloudTimestamp(0.0),
receivedRGBDImageTimestamp(0.0),
#endif
attitudeKnown(false),
attitudeStamped(false),
lastAttitude(0),
paramsOnceRequested(false),
paramManager(NULL),
// The protected members.
connectionLost(false),
lastVoltageWarning(0),
lastNonNullTime(0),
onboardTimeOffsetInvalidCount(0),
hilEnabled(false),
sensorHil(false),
lastSendTimeGPS(0),
lastSendTimeSensors(0)
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
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
{
for (unsigned int i = 0; i<255;++i)
{
componentID[i] = -1;
componentMulti[i] = false;
}
color = UASInterface::getNextColor();
setBatterySpecs(QString("9V,9.5V,12.6V"));
connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
statusTimeout->start(500);
readSettings();
// Initial signals
emit disarmed();
emit armingChanged(false);
}
/**
* Saves the settings of name, airframe, autopilot type and battery specifications
* by calling writeSettings.
*/
UAS::~UAS()
{
writeSettings();
delete links;
delete statusTimeout;
delete simulation;
}
/**
* Saves the settings of name, airframe, autopilot type and battery specifications
* for the next instantiation of UAS.
*/
void UAS::writeSettings()
{
QSettings settings;
settings.beginGroup(QString("MAV%1").arg(uasId));
settings.setValue("NAME", this->name);
settings.setValue("AIRFRAME", this->airframe);
settings.setValue("AP_TYPE", this->autopilot);
settings.setValue("BATTERY_SPECS", getBatterySpecs());
settings.endGroup();
settings.sync();
}
/**
* Reads in the settings: name, airframe, autopilot type, and battery specifications
* for the new UAS.
*/
void UAS::readSettings()
{
QSettings settings;
settings.beginGroup(QString("MAV%1").arg(uasId));
this->name = settings.value("NAME", this->name).toString();
this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
if (settings.contains("BATTERY_SPECS"))
{
Loading
Loading full blame...