Commit f9d58d34 authored by Don Gagne's avatar Don Gagne

Merge pull request #2160 from DonLakeFlyer/UASCleanup

More works towards removing UAS completely
parents 2a3991e4 7c0a836c
......@@ -200,7 +200,6 @@ FORMS += \
src/ui/uas/UASQuickView.ui \
src/ui/uas/UASQuickViewItemSelect.ui \
src/ui/UASInfo.ui \
src/ui/UASRawStatusView.ui \
}
HEADERS += \
......@@ -317,7 +316,6 @@ HEADERS += \
src/ui/uas/UASQuickViewItem.h \
src/ui/uas/UASQuickViewItemSelect.h \
src/ui/uas/UASQuickViewTextItem.h \
src/ui/UASRawStatusView.h \
src/VehicleSetup/JoystickConfigController.h \
src/ViewWidgets/CustomCommandWidget.h \
src/ViewWidgets/CustomCommandWidgetController.h \
......@@ -423,7 +421,6 @@ SOURCES += \
src/ui/uas/UASQuickViewItem.cc \
src/ui/uas/UASQuickViewItemSelect.cc \
src/ui/uas/UASQuickViewTextItem.cc \
src/ui/UASRawStatusView.cpp \
src/VehicleSetup/JoystickConfigController.cc \
src/ViewWidgets/CustomCommandWidget.cc \
src/ViewWidgets/CustomCommandWidgetController.cc \
......
......@@ -27,8 +27,8 @@
#include "APMAirframeComponent.h"
#include "QGCQmlWidgetHolder.h"
APMAirframeComponent::APMAirframeComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) :
APMComponent(uas, autopilot, parent),
APMAirframeComponent::APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
APMComponent(vehicle, autopilot, parent),
_name(tr("Airframe"))
{
......
......@@ -31,7 +31,7 @@ class APMAirframeComponent : public APMComponent
Q_OBJECT
public:
APMAirframeComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
// Virtuals from APMComponent
virtual QStringList setupCompleteChangedTriggerList(void) const;
......
......@@ -48,7 +48,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
Q_ASSERT(_vehicle);
if (parametersReady()) {
_airframeComponent = new APMAirframeComponent(_vehicle->uas(), this);
_airframeComponent = new APMAirframeComponent(_vehicle, this);
Q_CHECK_PTR(_airframeComponent);
_airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
......
......@@ -28,10 +28,10 @@
#include "Fact.h"
#include "AutoPilotPlugin.h"
APMComponent::APMComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) :
VehicleComponent(uas, autopilot, parent)
APMComponent::APMComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
VehicleComponent(vehicle, autopilot, parent)
{
Q_ASSERT(uas);
Q_ASSERT(vehicle);
Q_ASSERT(autopilot);
}
......
......@@ -37,7 +37,7 @@ class APMComponent : public VehicleComponent
Q_OBJECT
public:
APMComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
/// @brief Returns an list of parameter names for which a change should cause the setupCompleteChanged
/// signal to be emitted. Last element is signalled by NULL.
......
......@@ -170,7 +170,7 @@ const QMap<int, QMap<QString, QStringList> >& AutoPilotPlugin::getGroupMap(void)
void AutoPilotPlugin::writeParametersToStream(QTextStream &stream)
{
_vehicle->getParameterLoader()->writeParametersToStream(stream, _vehicle->uas()->getUASName());
_vehicle->getParameterLoader()->writeParametersToStream(stream);
}
QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
......
......@@ -68,8 +68,8 @@ static const struct mavType mavTypeInfo[] = {
static size_t cMavTypes = sizeof(mavTypeInfo) / sizeof(mavTypeInfo[0]);
#endif
AirframeComponent::AirframeComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(uas, autopilot, parent),
AirframeComponent::AirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(vehicle, autopilot, parent),
_name(tr("Airframe"))
{
#if 0
......
......@@ -35,7 +35,7 @@ class AirframeComponent : public PX4Component
Q_OBJECT
public:
AirframeComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL);
AirframeComponent(Vehicle* vehicles, AutoPilotPlugin* autopilot, QObject* parent = NULL);
// Virtuals from PX4Component
virtual QStringList setupCompleteChangedTriggerList(void) const;
......
......@@ -43,8 +43,8 @@ static const SwitchListItem switchList[] = {
};
static const size_t cSwitchList = sizeof(switchList) / sizeof(switchList[0]);
FlightModesComponent::FlightModesComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(uas, autopilot, parent),
FlightModesComponent::FlightModesComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(vehicle, autopilot, parent),
_name(tr("Flight Modes"))
{
}
......
......@@ -35,7 +35,7 @@ class FlightModesComponent : public PX4Component
Q_OBJECT
public:
FlightModesComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL);
FlightModesComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
// Virtuals from PX4Component
virtual QStringList setupCompleteChangedTriggerList(void) const;
......
......@@ -66,7 +66,7 @@ FlightModesComponentController::~FlightModesComponentController()
void FlightModesComponentController::_init(void)
{
// FIXME: What about VTOL? That confuses the whole Flight Mode naming scheme
_fixedWing = _uas->getSystemType() == MAV_TYPE_FIXED_WING;
_fixedWing = _vehicle->vehicleType() == MAV_TYPE_FIXED_WING;
// We need to know min and max for channel in order to calculate percentage range
for (int channel=0; channel<_chanMax; channel++) {
......
......@@ -94,32 +94,32 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
Q_ASSERT(_vehicle);
if (parametersReady()) {
_airframeComponent = new AirframeComponent(_vehicle->uas(), this);
_airframeComponent = new AirframeComponent(_vehicle, this);
Q_CHECK_PTR(_airframeComponent);
_airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
_radioComponent = new RadioComponent(_vehicle->uas(), this);
_radioComponent = new RadioComponent(_vehicle, this);
Q_CHECK_PTR(_radioComponent);
_radioComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_radioComponent));
_flightModesComponent = new FlightModesComponent(_vehicle->uas(), this);
_flightModesComponent = new FlightModesComponent(_vehicle, this);
Q_CHECK_PTR(_flightModesComponent);
_flightModesComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_flightModesComponent));
_sensorsComponent = new SensorsComponent(_vehicle->uas(), this);
_sensorsComponent = new SensorsComponent(_vehicle, this);
Q_CHECK_PTR(_sensorsComponent);
_sensorsComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_sensorsComponent));
_powerComponent = new PowerComponent(_vehicle->uas(), this);
_powerComponent = new PowerComponent(_vehicle, this);
Q_CHECK_PTR(_powerComponent);
_powerComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_powerComponent));
_safetyComponent = new SafetyComponent(_vehicle->uas(), this);
_safetyComponent = new SafetyComponent(_vehicle, this);
Q_CHECK_PTR(_safetyComponent);
_safetyComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent));
......
......@@ -28,10 +28,10 @@
#include "Fact.h"
#include "AutoPilotPlugin.h"
PX4Component::PX4Component(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) :
VehicleComponent(uas, autopilot, parent)
PX4Component::PX4Component(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
VehicleComponent(vehicle, autopilot, parent)
{
Q_ASSERT(uas);
Q_ASSERT(vehicle);
Q_ASSERT(autopilot);
}
......
......@@ -37,7 +37,7 @@ class PX4Component : public VehicleComponent
Q_OBJECT
public:
PX4Component(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL);
PX4Component(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
/// @brief Returns an list of parameter names for which a change should cause the setupCompleteChanged
/// signal to be emitted. Last element is signalled by NULL.
......
......@@ -28,8 +28,8 @@
#include "QGCQmlWidgetHolder.h"
#include "PX4AutoPilotPlugin.h"
PowerComponent::PowerComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(uas, autopilot, parent),
PowerComponent::PowerComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(vehicle, autopilot, parent),
_name(tr("Power"))
{
}
......
......@@ -35,7 +35,7 @@ class PowerComponent : public PX4Component
Q_OBJECT
public:
PowerComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL);
PowerComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
// Virtuals from PX4Component
virtual QStringList setupCompleteChangedTriggerList(void) const;
......
......@@ -28,8 +28,8 @@
#include "QGCQmlWidgetHolder.h"
#include "PX4AutoPilotPlugin.h"
RadioComponent::RadioComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(uas, autopilot, parent),
RadioComponent::RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(vehicle, autopilot, parent),
_name(tr("Radio"))
{
}
......
......@@ -36,7 +36,7 @@ class RadioComponent : public PX4Component
Q_OBJECT
public:
RadioComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL);
RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
// Virtuals from PX4Component
virtual QStringList setupCompleteChangedTriggerList(void) const;
......
......@@ -28,8 +28,8 @@
#include "QGCQmlWidgetHolder.h"
#include "PX4AutoPilotPlugin.h"
SafetyComponent::SafetyComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(uas, autopilot, parent),
SafetyComponent::SafetyComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(vehicle, autopilot, parent),
_name(tr("Safety"))
{
}
......
......@@ -36,7 +36,7 @@ class SafetyComponent : public PX4Component
Q_OBJECT
public:
SafetyComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL);
SafetyComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
// Virtuals from PX4Component
virtual QStringList setupCompleteChangedTriggerList(void) const;
......
......@@ -31,8 +31,8 @@
// These two list must be kept in sync
SensorsComponent::SensorsComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(uas, autopilot, parent),
SensorsComponent::SensorsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
PX4Component(vehicle, autopilot, parent),
_name(tr("Sensors"))
{
......@@ -87,11 +87,15 @@ QStringList SensorsComponent::setupCompleteChangedTriggerList(void) const
QStringList triggers;
triggers << "CAL_MAG0_ID" << "CAL_GYRO0_ID" << "CAL_ACC0_ID";
if (_uas->getSystemType() == MAV_TYPE_FIXED_WING ||
_uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR ||
_uas->getSystemType() == MAV_TYPE_VTOL_QUADROTOR ||
_uas->getSystemType() == MAV_TYPE_VTOL_TILTROTOR) {
triggers << "SENS_DPRES_OFF";
switch (_vehicle->vehicleType()) {
case MAV_TYPE_FIXED_WING:
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
triggers << "SENS_DPRES_OFF";
break;
default:
break;
}
return triggers;
......@@ -115,13 +119,16 @@ QUrl SensorsComponent::summaryQmlSource(void) const
{
QString summaryQml;
if (_uas->getSystemType() == MAV_TYPE_FIXED_WING ||
_uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR ||
_uas->getSystemType() == MAV_TYPE_VTOL_QUADROTOR ||
_uas->getSystemType() == MAV_TYPE_VTOL_TILTROTOR) {
summaryQml = "qrc:/qml/SensorsComponentSummaryFixedWing.qml";
} else {
summaryQml = "qrc:/qml/SensorsComponentSummary.qml";
switch (_vehicle->vehicleType()) {
case MAV_TYPE_FIXED_WING:
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
summaryQml = "qrc:/qml/SensorsComponentSummaryFixedWing.qml";
break;
default:
summaryQml = "qrc:/qml/SensorsComponentSummary.qml";
break;
}
return QUrl::fromUserInput(summaryQml);
......
......@@ -35,7 +35,7 @@ class SensorsComponent : public PX4Component
Q_OBJECT
public:
SensorsComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL);
SensorsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
// Virtuals from PX4Component
virtual QStringList setupCompleteChangedTriggerList(void) const;
......
......@@ -445,12 +445,15 @@ void SensorsComponentController::_refreshParams(void)
bool SensorsComponentController::fixedWing(void)
{
UASInterface* uas = _autopilot->vehicle()->uas();
Q_ASSERT(uas);
return uas->getSystemType() == MAV_TYPE_FIXED_WING ||
uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR ||
uas->getSystemType() == MAV_TYPE_VTOL_QUADROTOR ||
uas->getSystemType() == MAV_TYPE_VTOL_TILTROTOR;
switch (_vehicle->vehicleType()) {
case MAV_TYPE_FIXED_WING:
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
return true;
default:
return false;
}
}
void SensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show)
......
......@@ -708,9 +708,9 @@ QString ParameterLoader::readParametersFromStream(QTextStream& stream)
return errors;
}
void ParameterLoader::writeParametersToStream(QTextStream &stream, const QString& name)
void ParameterLoader::writeParametersToStream(QTextStream &stream)
{
stream << "# Onboard parameters for system " << name << "\n";
stream << "# Onboard parameters for vehicle " << _vehicle->id() << "\n";
stream << "#\n";
stream << "# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT)\n";
......
......@@ -85,7 +85,7 @@ public:
/// Returns error messages from loading
QString readParametersFromStream(QTextStream& stream);
void writeParametersToStream(QTextStream &stream, const QString& name);
void writeParametersToStream(QTextStream &stream);
signals:
/// Signalled when the full set of facts are ready
......
......@@ -117,62 +117,7 @@ void HomePositionManager::_loadSettings(void)
if (_homePositions.count() == 0) {
_homePositions.append(new HomePosition("ETH Campus", QGeoCoordinate(47.3769, 8.549444, 470.0), this));
}
// Deprecated settings for old editor
settings.beginGroup("QGC_UASMANAGER");
bool changed = setHomePosition(settings.value("HOMELAT", homeLat).toDouble(),
settings.value("HOMELON", homeLon).toDouble(),
settings.value("HOMEALT", homeAlt).toDouble());
// Make sure to fire the change - this will
// make sure widgets get the signal once
if (!changed)
{
emit homePositionChanged(homeLat, homeLon, homeAlt);
}
settings.endGroup();
}
bool HomePositionManager::setHomePosition(double lat, double lon, double alt)
{
// Checking for NaN and infitiny
// and checking for borders
bool changed = false;
if (!isnan(lat) && !isnan(lon) && !isnan(alt)
&& !isinf(lat) && !isinf(lon) && !isinf(alt)
&& lat <= 90.0 && lat >= -90.0 && lon <= 180.0 && lon >= -180.0)
{
if (fabs(homeLat - lat) > 1e-7) changed = true;
if (fabs(homeLon - lon) > 1e-7) changed = true;
if (fabs(homeAlt - alt) > 0.5f) changed = true;
if (changed)
{
homeLat = lat;
homeLon = lon;
homeAlt = alt;
emit homePositionChanged(homeLat, homeLon, homeAlt);
}
}
return changed;
}
bool HomePositionManager::setHomePositionAndNotify(double lat, double lon, double alt)
{
// Checking for NaN and infitiny
// and checking for borders
bool changed = setHomePosition(lat, lon, alt);
if (changed) {
qgcApp()->toolbox()->multiVehicleManager()->setHomePositionForAllVehicles(homeLat, homeLon, homeAlt);
}
return changed;
}
}
void HomePositionManager::updateHomePosition(const QString& name, const QGeoCoordinate& coordinate)
......
......@@ -112,21 +112,6 @@ public:
return homeAlt;
}
public slots:
// Deprecated methods
/** @brief Set the current home position, but do not change it on the UAVs */
bool setHomePosition(double lat, double lon, double alt);
/** @brief Set the current home position on all UAVs*/
bool setHomePositionAndNotify(double lat, double lon, double alt);
signals:
/** @brief Current home position changed */
void homePositionChanged(double lat, double lon, double alt);
protected:
double homeLat;
double homeLon;
......
......@@ -212,13 +212,6 @@ void MultiVehicleManager::_autopilotParametersReadyChanged(bool parametersReady)
}
}
void MultiVehicleManager::setHomePositionForAllVehicles(double lat, double lon, double alt)
{
for (int i=0; i< _vehicles.count(); i++) {
qobject_cast<Vehicle*>(_vehicles[i])->uas()->setHomePosition(lat, lon, alt);
}
}
void MultiVehicleManager::saveSetting(const QString &name, const QString& value)
{
QSettings settings;
......
......@@ -65,8 +65,6 @@ public:
Q_INVOKABLE Vehicle* getVehicleById(int vehicleId);
void setHomePositionForAllVehicles(double lat, double lon, double alt);
UAS* activeUas(void) { return _activeVehicle ? _activeVehicle->uas() : NULL; }
QList<Vehicle*> vehicles(void);
......
......@@ -90,8 +90,6 @@ Vehicle::Vehicle(LinkInterface* link,
, _batteryPercent(0.0)
, _batteryConsumed(-1.0)
, _currentHeartbeatTimeout(0)
, _waypointDistance(0.0)
, _currentWaypoint(0)
, _satelliteCount(-1)
, _satelliteLock(0)
, _updateCount(0)
......@@ -154,15 +152,12 @@ Vehicle::Vehicle(LinkInterface* link,
connect(_mav, &UASInterface::heartbeatTimeout, this, &Vehicle::_heartbeatTimeout);
connect(_mav, &UASInterface::batteryChanged, this, &Vehicle::_updateBatteryRemaining);
connect(_mav, &UASInterface::batteryConsumedChanged, this, &Vehicle::_updateBatteryConsumedChanged);
connect(_mav, &UASInterface::nameChanged, this, &Vehicle::_updateName);
connect(_mav, &UASInterface::systemTypeSet, this, &Vehicle::_setSystemType);
connect(_mav, &UASInterface::localizationChanged, this, &Vehicle::_setSatLoc);
UAS* pUas = dynamic_cast<UAS*>(_mav);
if(pUas) {
_setSatelliteCount(pUas->getSatelliteCount(), QString(""));
connect(pUas, &UAS::satelliteCountChanged, this, &Vehicle::_setSatelliteCount);
}
_setSystemType(_mav, _mav->getSystemType());
_loadSettings();
......@@ -188,8 +183,6 @@ Vehicle::Vehicle(LinkInterface* link,
Vehicle::~Vehicle()
{
qDebug() << "~Vehicle";
delete _missionManager;
_missionManager = NULL;
......@@ -519,12 +512,6 @@ void Vehicle::_updateNavigationControllerData(UASInterface *uas, float, float, f
* Internal
*/
bool Vehicle::_isAirplane() {
if (_mav)
return _mav->isAirplane();
return false;
}
void Vehicle::_addChange(int id)
{
if(!_changes.contains(id)) {
......@@ -639,86 +626,6 @@ void Vehicle::_updateState(UASInterface*, QString name, QString)
}
}
void Vehicle::_updateName(const QString& name)
{
if (_systemName != name) {
_systemName = name;
emit systemNameChanged();
}
}
/**
* The current system type is represented through the system icon.
*
* @param uas Source system, has to be the same as this->uas
* @param systemType type ID, following the MAVLink system type conventions
* @see http://pixhawk.ethz.ch/software/mavlink
*/
void Vehicle::_setSystemType(UASInterface*, unsigned int systemType)
{
_systemPixmap = "qrc:/res/mavs/";
switch (systemType) {
case MAV_TYPE_GENERIC:
_systemPixmap += "Generic";
break;
case MAV_TYPE_FIXED_WING:
_systemPixmap += "FixedWing";
break;
case MAV_TYPE_QUADROTOR:
_systemPixmap += "QuadRotor";
break;
case MAV_TYPE_COAXIAL:
_systemPixmap += "Coaxial";
break;
case MAV_TYPE_HELICOPTER:
_systemPixmap += "Helicopter";
break;
case MAV_TYPE_ANTENNA_TRACKER:
_systemPixmap += "AntennaTracker";
break;
case MAV_TYPE_GCS:
_systemPixmap += "Groundstation";
break;
case MAV_TYPE_AIRSHIP:
_systemPixmap += "Airship";
break;
case MAV_TYPE_FREE_BALLOON:
_systemPixmap += "FreeBalloon";
break;
case MAV_TYPE_ROCKET:
_systemPixmap += "Rocket";
break;
case MAV_TYPE_GROUND_ROVER:
_systemPixmap += "GroundRover";
break;
case MAV_TYPE_SURFACE_BOAT:
_systemPixmap += "SurfaceBoat";
break;
case MAV_TYPE_SUBMARINE:
_systemPixmap += "Submarine";
break;
case MAV_TYPE_HEXAROTOR:
_systemPixmap += "HexaRotor";
break;
case MAV_TYPE_OCTOROTOR:
_systemPixmap += "OctoRotor";
break;
case MAV_TYPE_TRICOPTER:
_systemPixmap += "TriCopter";
break;
case MAV_TYPE_FLAPPING_WING:
_systemPixmap += "FlappingWing";
break;
case MAV_TYPE_KITE:
_systemPixmap += "Kite";
break;
default:
_systemPixmap += "Unknown";
break;
}
emit systemPixmapChanged();
}
void Vehicle::_heartbeatTimeout(bool timeout, unsigned int ms)
{
unsigned int elapsed = ms;
......@@ -756,39 +663,6 @@ void Vehicle::_setSatLoc(UASInterface*, int fix)
}
}
void Vehicle::_updateWaypointDistance(double distance)
{
if (_waypointDistance != distance) {
_waypointDistance = distance;
emit waypointDistanceChanged();
}
}
void Vehicle::_updateCurrentWaypoint(quint16 id)
{
if (_currentWaypoint != id) {
_currentWaypoint = id;
emit currentWaypointChanged();
}
}
void Vehicle::_updateWaypointViewOnly(int, MissionItem* /*wp*/)
{
/*
bool changed = false;
for(int i = 0; i < _waypoints.count(); i++) {
if(_waypoints[i].sequenceNumber() == wp->sequenceNumber()) {
_waypoints[i] = *wp;
changed = true;
break;
}
}
if(changed) {
emit waypointListChanged();
}
*/
}
void Vehicle::_handleTextMessage(int newCount)
{
// Reset?
......
This diff is collapsed.
......@@ -27,12 +27,12 @@
#include "VehicleComponent.h"
#include "AutoPilotPlugin.h"
VehicleComponent::VehicleComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) :
VehicleComponent::VehicleComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
QObject(parent),
_uas(uas),
_vehicle(vehicle),
_autopilot(autopilot)
{
Q_ASSERT(uas);
Q_ASSERT(vehicle);
Q_ASSERT(autopilot);
}
......
......@@ -31,7 +31,7 @@
#include <QQmlContext>
#include <QQuickItem>
#include "UASInterface.h"
#include "Vehicle.h"