Newer
Older
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
// NO NEW CODE HERE
// UASInterface, UAS.h/cc are deprecated. All new functionality should go into Vehicle.h/cc
//
#include <QList>
#include <QTimer>
#include <QSettings>
#include <iostream>
#include <QDebug>
#include <cmath>
#include <qmath.h>
#include <limits>
#include <cstdlib>
#include "UAS.h"
#include "LinkInterface.h"
#include "QGC.h"
#include "GAudioOutput.h"
#include "MAVLinkProtocol.h"
#include "QGCMAVLink.h"
#include "LinkManager.h"
#include "SerialLink.h"
#include "QGCLoggingCategory.h"
#include "QGCApplication.h"
QGC_LOGGING_CATEGORY(UASLog, "UASLog")
// THIS CLASS IS DEPRECATED. ALL NEW FUNCTIONALITY SHOULD GO INTO Vehicle class
UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * firmwarePluginManager) : UASInterface(),
lipoFull(4.2f),
lipoEmpty(3.5f),
unknownPackets(),
mavlink(protocol),
receiveDropRate(0),
sendDropRate(0),
status(-1),
startTime(QGC::groundTimeMilliseconds()),
onboardTimeOffset(0),
controlRollManual(true),
controlPitchManual(true),
controlYawManual(true),
controlThrustManual(true),
manualRollAngle(0),
manualPitchAngle(0),
manualYawAngle(0),
manualThrust(0),
attitudeKnown(false),
attitudeStamped(false),
lastAttitude(0),
roll(0.0),
pitch(0.0),
yaw(0.0),
imagePackets(0), // We must initialize to 0, otherwise extended data packets maybe incorrectly thought to be images
// Note variances calculated from flight case from this log: http://dash.oznet.ch/view/MRjW8NUNYQSuSZkbn8dEjY
// TODO: calibrate stand-still pixhawk variances
xacc_var(0.6457f),
zacc_var(0.97885f),
rollspeed_var(0.8126f),
pitchspeed_var(0.6145f),
yawspeed_var(0.5852f),
xmag_var(0.2393f),
ymag_var(0.2283f),
zmag_var(0.1665f),
abs_pressure_var(0.5802f),
diff_pressure_var(0.5802f),
pressure_alt_var(0.5802f),
temperature_var(0.7145f),
Lorenz Meier
committed
/*
xacc_var(0.0f),
yacc_var(0.0f),
zacc_var(0.0f),
rollspeed_var(0.0f),
pitchspeed_var(0.0f),
yawspeed_var(0.0f),
xmag_var(0.0f),
ymag_var(0.0f),
zmag_var(0.0f),
abs_pressure_var(0.0f),
diff_pressure_var(0.0f),
pressure_alt_var(0.0f),
temperature_var(0.0f),
Lorenz Meier
committed
*/
// The protected members.
connectionLost(false),
lastVoltageWarning(0),
lastNonNullTime(0),
onboardTimeOffsetInvalidCount(0),
hilEnabled(false),
sensorHil(false),
lastSendTimeGPS(0),
_vehicle(vehicle),
_firmwarePluginManager(firmwarePluginManager)
for (unsigned int i = 0; i<255;++i)
{
componentID[i] = -1;
componentMulti[i] = false;
}
connect(_vehicle, &Vehicle::mavlinkMessageReceived, &fileManager, &FileManager::receiveMessage);
color = UASInterface::getNextColor();
}
/**
* @ return the id of the uas
*/
int UAS::getUASID() const
{
return uasId;
}
void UAS::receiveMessage(mavlink_message_t message)
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
{
if (!components.contains(message.compid))
{
QString componentName;
switch (message.compid)
{
case MAV_COMP_ID_ALL:
{
componentName = "ANONYMOUS";
break;
}
case MAV_COMP_ID_IMU:
{
componentName = "IMU #1";
break;
}
case MAV_COMP_ID_CAMERA:
{
componentName = "CAMERA";
break;
}
case MAV_COMP_ID_MISSIONPLANNER:
{
componentName = "MISSIONPLANNER";
break;
}
}
components.insert(message.compid, componentName);
}
// qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq;
// Only accept messages from this system (condition 1)
// and only then if a) attitudeStamped is disabled OR b) attitudeStamped is enabled
// and we already got one attitude packet
if (message.sysid == uasId && (!attitudeStamped || (attitudeStamped && (lastAttitude != 0)) || message.msgid == MAVLINK_MSG_ID_ATTITUDE))
{
QString uasState;
QString stateDescription;
bool multiComponentSourceDetected = false;
bool wrongComponent = false;
Loading
Loading full blame...