Newer
Older
/*===================================================================
======================================================================*/
/**
* @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(),
lipoFull(4.2f),
lipoEmpty(3.5f),
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),
paramDataModel(NULL),
// The protected members.
connectionLost(false),
lastVoltageWarning(0),
lastNonNullTime(0),
onboardTimeOffsetInvalidCount(0),
hilEnabled(false),
sensorHil(false),
lastSendTimeGPS(0),
lastSendTimeSensors(0),
blockHomePositionChanges(false)
{
for (unsigned int i = 0; i<255;++i)
{
componentID[i] = -1;
componentMulti[i] = false;
}
paramDataModel->setUASID(this->getUASID());
paramCommsMgr = new UASParameterCommsMgr(this,this);
// Store a list of available actions for this UAS.
// Basically everything exposted as a SLOT with no return value or arguments.
QAction* newAction = new QAction(tr("Arm"), this);
newAction->setToolTip(tr("Enable the UAS so that all actuators are online"));
connect(newAction, SIGNAL(triggered()), this, SLOT(armSystem()));
actions.append(newAction);
newAction = new QAction(tr("Disarm"), this);
newAction->setToolTip(tr("Disable the UAS so that all actuators are offline"));
connect(newAction, SIGNAL(triggered()), this, SLOT(disarmSystem()));
actions.append(newAction);
newAction = new QAction(tr("Toggle armed"), this);
newAction->setToolTip(tr("Toggle between armed and disarmed"));
connect(newAction, SIGNAL(triggered()), this, SLOT(toggleAutonomy()));
actions.append(newAction);
newAction = new QAction(tr("Go home"), this);
newAction->setToolTip(tr("Command the UAS to return to its home position"));
connect(newAction, SIGNAL(triggered()), this, SLOT(home()));
actions.append(newAction);
newAction = new QAction(tr("Land"), this);
newAction->setToolTip(tr("Command the UAS to land"));
connect(newAction, SIGNAL(triggered()), this, SLOT(land()));
actions.append(newAction);
newAction = new QAction(tr("Launch"), this);
newAction->setToolTip(tr("Command the UAS to launch itself and begin its mission"));
connect(newAction, SIGNAL(triggered()), this, SLOT(launch()));
actions.append(newAction);
newAction = new QAction(tr("Resume"), this);
newAction->setToolTip(tr("Command the UAS to continue its mission"));
connect(newAction, SIGNAL(triggered()), this, SLOT(go()));
actions.append(newAction);
newAction = new QAction(tr("Stop"), this);
Loading
Loading full blame...