Newer
Older
/*===================================================================
======================================================================*/
/**
* @file
* @brief Represents one unmanned aerial vehicle
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QList>
#include <QMessageBox>
#include <QTimer>
#include "UAS.h"
#include "LinkInterface.h"
#include "UASManager.h"
#include "LinkManager.h"
#include "SerialLink.h"
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
uasId(id),
startTime(MG::TIME::getGroundTimeNow()),
commStatus(COMM_DISCONNECTED),
name(""),
autopilot(-1),
links(new QList<LinkInterface*>()),
unknownPackets(),
mavlink(protocol),
waypointManager(*this),
thrustSum(0),
thrustMax(10),
startVoltage(0),
currentVoltage(12.0f),
lpVoltage(12.0f),
batteryRemainingEstimateEnabled(false),
mode(-1),
status(-1),
navMode(-1),
onboardTimeOffset(0),
controlRollManual(true),
controlPitchManual(true),
controlYawManual(true),
controlThrustManual(true),
manualRollAngle(0),
manualPitchAngle(0),
manualYawAngle(0),
manualThrust(0),
receiveDropRate(0),
sendDropRate(0),
lowBattAlarm(false),
positionLock(false),
localX(0.0),
localY(0.0),
localZ(0.0),
latitude(0.0),
longitude(0.0),
altitude(0.0),
roll(0.0),
pitch(0.0),
yaw(0.0),
statusTimeout(new QTimer(this)),
paramsOnceRequested(false),
airframe(0)
color = UASInterface::getNextColor();
connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
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();
}
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"))
{
setBatterySpecs(settings.value("BATTERY_SPECS").toString());
}
settings.endGroup();
}
int UAS::getUASID() const
void UAS::updateState()
{
// Check if heartbeat timed out
quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
if (heartbeatInterval > timeoutIntervalHeartbeat)
{
emit heartbeatTimeout(heartbeatInterval);
emit heartbeatTimeout();
}
// Position lock is set by the MAVLink message handler
// if no position lock is available, indicate an error
if (positionLock)
{
positionLock = false;
}
else
{
{
GAudioOutput::instance()->notifyNegative();
}
}
}
if (UASManager::instance()->getActiveUAS() != this)
{
UASManager::instance()->setActiveUAS(this);
emit systemSelected(true);
}
}
bool UAS::getSelected() const
{
return (UASManager::instance()->getActiveUAS() == this);
void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
{
mavlink_named_value_float_t val;
mavlink_msg_named_value_float_decode(&message, &val);
QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
}
else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
{
mavlink_named_value_int_t val;
mavlink_msg_named_value_int_decode(&message, &val);
QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN);
emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
}
}
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
// qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
// else
// {
// qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
// }
// qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq;
if (message.sysid == uasId)
{
QString uasState;
QString stateDescription;
Loading
Loading full blame...