Skip to content
UAS.cc 96 KiB
Newer Older
/*===================================================================
======================================================================*/

/**
 * @file
 *   @brief Represents one unmanned aerial vehicle
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#include <QList>
#include <QTimer>
#include <QSettings>
#include <iostream>
#include <QDebug>
#include <cmath>
#include <qmath.h>
#include "UAS.h"
#include "LinkInterface.h"
#include "HomePositionManager.h"
#include "QGC.h"
#include "GAudioOutput.h"
#include "MAVLinkProtocol.h"
#include "QGCMAVLink.h"
#include "LinkManager.h"
dogmaphobic's avatar
dogmaphobic committed
#ifndef __ios__
#include "SerialLink.h"
dogmaphobic's avatar
dogmaphobic committed
#endif
#include <Eigen/Geometry>
Don Gagne's avatar
Don Gagne committed
#include "FirmwarePluginManager.h"
Don Gagne's avatar
Don Gagne committed
#include "QGCMessageBox.h"
#include "QGCLoggingCategory.h"
#include "Vehicle.h"
#include "Joystick.h"
QGC_LOGGING_CATEGORY(UASLog, "UASLog")
#define UAS_DEFAULT_BATTERY_WARNLEVEL 20

/**
* 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
UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle) : UASInterface(),
    lipoFull(4.2f),
    lipoEmpty(3.5f),
    uasId(vehicle->id()),
    unknownPackets(),
    mavlink(protocol),
    receiveDropRate(0),
    sendDropRate(0),

    name(""),
    type(MAV_TYPE_GENERIC),
    airframe(QGC_AIRFRAME_GENERIC),
    autopilot(vehicle->firmwareType()),
    base_mode(0),
    custom_mode(0),
    startVoltage(-1.0f),
    tickVoltage(10.5f),
    lastTickVoltageValue(13.0f),
    tickLowpassVoltage(12.0f),
    warnLevelPercent(UAS_DEFAULT_BATTERY_WARNLEVEL),
    currentVoltage(12.6f),
    lpVoltage(12.0f),
dongfang's avatar
dongfang committed
    currentCurrent(0.4f),
    lowBattAlarm(false),

    startTime(QGC::groundTimeMilliseconds()),
    onboardTimeOffset(0),
    controlRollManual(true),
    controlPitchManual(true),
    controlYawManual(true),
    controlThrustManual(true),
    manualRollAngle(0),
    manualPitchAngle(0),
    manualYawAngle(0),
    manualThrust(0),
    isLocalPositionKnown(false),
    isGlobalPositionKnown(false),

    localX(0.0),
    localY(0.0),
    localZ(0.0),
    altitudeAMSLFT(0.0),
    altitudeWGS84(0.0),
Don Gagne's avatar
Don Gagne committed
    globalEstimatorActive(false),

    latitude_gps(0.0),
    longitude_gps(0.0),
    altitude_gps(0.0),
Don Gagne's avatar
Don Gagne committed
    airSpeed(std::numeric_limits<double>::quiet_NaN()),
    groundSpeed(std::numeric_limits<double>::quiet_NaN()),
    fileManager(this, vehicle),
Don Gagne's avatar
Don Gagne committed

    attitudeKnown(false),
    attitudeStamped(false),
    lastAttitude(0),
    roll(0.0),
    pitch(0.0),
    yaw(0.0),

Don Gagne's avatar
Don Gagne committed
    imagePackets(0),    // We must initialize to 0, otherwise extended data packets maybe incorrectly thought to be images

Don Gagne's avatar
Don Gagne committed
    blockHomePositionChanges(false),
    receivedMode(false),

    // Initialize HIL sensor noise variances to 0.  If user wants corrupted sensor values they will need to set them
    // Note variances calculated from flight case from this log: http://dash.oznet.ch/view/MRjW8NUNYQSuSZkbn8dEjY
    // TODO: calibrate stand-still pixhawk variances
dogmaphobic's avatar
dogmaphobic committed
    xacc_var(1.2914f),
    yacc_var(0.7048f),
    zacc_var(1.9577f),
    rollspeed_var(0.8126f),
    pitchspeed_var(0.6145f),
    yawspeed_var(0.5852f),
    xmag_var(0.4786f),
    ymag_var(0.4566f),
    zmag_var(0.3333f),
    abs_pressure_var(1.1604f),
    diff_pressure_var(1.1604f),
    pressure_alt_var(1.1604f),
    temperature_var(1.4290f),
dogmaphobic's avatar
dogmaphobic committed
#ifndef __mobile__
dogmaphobic's avatar
dogmaphobic committed
#endif

    // The protected members.
    connectionLost(false),
    lastVoltageWarning(0),
    lastNonNullTime(0),
    onboardTimeOffsetInvalidCount(0),
    sensorHil(false),
    lastSendTimeGPS(0),
    lastSendTimeSensors(0),
    lastSendTimeOpticalFlow(0),
Don Gagne's avatar
Don Gagne committed
    _waypointManager(NULL),
    _vehicle(vehicle)
Don Gagne's avatar
Don Gagne committed
    if (!qgcApp()->useNewMissionEditor()) {
        _waypointManager = new UASWaypointManager(vehicle, this);
    }
    
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
    }
    connect(mavlink, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), &fileManager, SLOT(receiveMessage(LinkInterface*,mavlink_message_t)));

    color = UASInterface::getNextColor();
    connect(&statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
    statusTimeout.start(500);
}

/**
* Saves the settings of name, airframe, autopilot type and battery specifications
* by calling writeSettings.
*/
UAS::~UAS()
{
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
    if (simulation) {
        // wait for the simulator to exit
        simulation->wait();
        simulation->deleteLater();
Loading
Loading full blame...