diff --git a/src/lib/CMakeLists.txt b/src/lib/CMakeLists.txt index b229dc1..772fcfc 100644 --- a/src/lib/CMakeLists.txt +++ b/src/lib/CMakeLists.txt @@ -1,109 +1,112 @@ ecm_setup_version(PROJECT VARIABLE_PREFIX KIROGI PACKAGE_VERSION_FILE "${CMAKE_CURRENT_BINARY_DIR}/KirogiCoreConfigVersion.cmake" SOVERSION ${KIROGI_VERSION_STRING} ) set(kirogicore_SRCS abstractvehicle.cpp vehiclesupportplugin.cpp vehiclesupportpluginmodel.cpp ) ecm_qt_declare_logging_category(kirogicore_SRCS HEADER debug.h IDENTIFIER KIROGI_CORE CATEGORY_NAME "kirogi.core" ) ecm_generate_headers(Kirogi_CamelCase_HEADERS HEADER_NAMES AbstractVehicle VehicleSupportPlugin VehicleSupportPluginModel REQUIRED_HEADERS Kirogi_HEADERS PREFIX kirogi ) add_subdirectory(positionsource) +add_subdirectory(vehicleparameters) add_library(kirogicore SHARED ${kirogicore_SRCS} ${Kirogi_HEADERS}) add_library(KirogiCore ALIAS kirogicore) generate_export_header(kirogicore BASE_NAME Kirogi EXPORT_FILE_NAME kirogicore_export.h) target_include_directories(kirogicore INTERFACE "$") target_link_libraries(kirogicore PRIVATE Qt5::Core Qt5::Positioning Qt5::Qml Qt5::Quick KF5::CoreAddons positionsource + vehicleparameters ) set_target_properties(kirogicore PROPERTIES VERSION ${KIROGI_VERSION_STRING} SOVERSION ${KIROGI_SOVERSION} EXPORT_NAME KirogiCore OUTPUT_NAME kirogicore ) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") target_compile_options(kirogicore PRIVATE -pedantic) endif() install(TARGETS kirogicore EXPORT kirogicoreLibraryTargets ${KDE_INSTALL_TARGETS_DEFAULT_ARGS}) install(FILES ${Kirogi_HEADERS} ${CMAKE_CURRENT_BINARY_DIR}/kirogicore_export.h DESTINATION ${KDE_INSTALL_INCLUDEDIR}/Kirogi/kirogi COMPONENT Devel) install(FILES ${Kirogi_CamelCase_HEADERS} DESTINATION ${KDE_INSTALL_INCLUDEDIR}/Kirogi/Kirogi COMPONENT Devel) write_basic_config_version_file(${CMAKE_CURRENT_BINARY_DIR}/KirogiCoreConfigVersion.cmake VERSION "${PROJECT_VERSION}" COMPATIBILITY AnyNewerVersion) set(CMAKECONFIG_INSTALL_DIR ${KDE_INSTALL_LIBDIR}/cmake/KirogiCore) configure_package_config_file(KirogiCoreConfig.cmake.in "${CMAKE_CURRENT_BINARY_DIR}/KirogiCoreConfig.cmake" INSTALL_DESTINATION ${CMAKECONFIG_INSTALL_DIR}) install(FILES ${CMAKE_CURRENT_BINARY_DIR}/KirogiCoreConfig.cmake ${CMAKE_CURRENT_BINARY_DIR}/KirogiCoreConfigVersion.cmake DESTINATION ${CMAKECONFIG_INSTALL_DIR}) install(EXPORT kirogicoreLibraryTargets DESTINATION ${CMAKECONFIG_INSTALL_DIR} FILE KirogiCoreLibraryTargets.cmake) install(FILES kirogivehiclesupportplugin.desktop DESTINATION ${KDE_INSTALL_KSERVICETYPES5DIR}) install(FILES kirogi.categories DESTINATION ${KDE_INSTALL_CONFDIR}) if(NOT BUILD_QT_QUICK_LIB) return() endif() add_library(kirogiqtquickplugin SHARED qtquickplugin.cpp) target_link_libraries(kirogiqtquickplugin Qt5::Positioning Qt5::Qml Qt5::Quick KirogiCore positionsource + vehicleparameters ) install(TARGETS kirogiqtquickplugin DESTINATION ${KDE_INSTALL_QMLDIR}/org/kde/kirogi) install(FILES qmldir DESTINATION ${KDE_INSTALL_QMLDIR}/org/kde/kirogi) diff --git a/src/lib/abstractvehicle.cpp b/src/lib/abstractvehicle.cpp index 09de7a2..2c6b9dc 100644 --- a/src/lib/abstractvehicle.cpp +++ b/src/lib/abstractvehicle.cpp @@ -1,506 +1,514 @@ /* * Copyright 2019 Eike Hein * * This library is free software; you can redistribute it and/or * modify it under the terms of the GNU Lesser General Public * License as published by the Free Software Foundation; either * version 2.1 of the License, or (at your option) version 3, or any * later version accepted by the membership of KDE e.V. (or its * successor approved by the membership of KDE e.V.), which shall * act as a proxy defined in Section 6 of version 3 of the license. * * This library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU * Lesser General Public License for more details. * * You should have received a copy of the GNU Lesser General Public * License along with this library. If not, see . */ #include "abstractvehicle.h" #include "debug.h" +#include "parametermodel.h" #include #include namespace Kirogi { class Q_DECL_HIDDEN AbstractVehicle::Private { public: Private(AbstractVehicle *q); ~Private(); static int s_availableId; int id; AbstractVehicle::ConnectionState connectionState = AbstractVehicle::Disconnected; AbstractVehicle::FlyingState flyingState = AbstractVehicle::Unknown; QElapsedTimer *flightTime = nullptr; QTimer *flightTimeTimer = nullptr; + ParameterModel parameters; + private: AbstractVehicle *q; }; int AbstractVehicle::Private::s_availableId = 0; AbstractVehicle::Private::Private(AbstractVehicle *q) : q(q) { id = s_availableId; ++s_availableId; } AbstractVehicle::Private::~Private() { delete flightTime; } AbstractVehicle::AbstractVehicle(QObject *parent) : QObject(parent) , d(new Private(this)) { } AbstractVehicle::~AbstractVehicle() { } int AbstractVehicle::id() const { return d->id; } QString AbstractVehicle::iconName() const { return QLatin1String("uav"); } Kirogi::AbstractVehicle::VehicleType AbstractVehicle::vehicleType() const { return UnknownVehicleType; } AbstractVehicle::ConnectionState AbstractVehicle::connectionState() const { return d->connectionState; } void Kirogi::AbstractVehicle::setConnectionState(Kirogi::AbstractVehicle::ConnectionState state) { if (connectionState() != state) { qCDebug(KIROGI_CORE) << name() << "changed connection state to:" << state; d->connectionState = state; emit connectionStateChanged(); } } Kirogi::AbstractVehicle::FlyingState AbstractVehicle::flyingState() const { return d->flyingState; } void Kirogi::AbstractVehicle::setFlyingState(Kirogi::AbstractVehicle::FlyingState state) { if (flyingState() != state) { qCDebug(KIROGI_CORE) << name() << "changed flying state to:" << state; d->flyingState = state; emit flyingStateChanged(); if (state > Landed) { if (!d->flightTime) { d->flightTime = new QElapsedTimer(); } if (!d->flightTimeTimer) { d->flightTimeTimer = new QTimer(this); QObject::connect(d->flightTimeTimer, &QTimer::timeout, this, &AbstractVehicle::flightTimeChanged); d->flightTimeTimer->setTimerType(Qt::PreciseTimer); d->flightTimeTimer->setInterval(1000); } d->flightTime->start(); d->flightTimeTimer->start(); } else { if (d->flightTime) { d->flightTime->invalidate(); } if (d->flightTimeTimer) { d->flightTimeTimer->stop(); } } } } bool AbstractVehicle::connected() const { return connectionState() >= Connected; } bool AbstractVehicle::ready() const { return connectionState() >= Ready; } bool AbstractVehicle::flying() const { return flyingState() >= TakingOff; } QList AbstractVehicle::supportedActions() const { return QList(); } bool AbstractVehicle::isActionSupported(Kirogi::AbstractVehicle::VehicleAction action) const { return supportedActions().contains(action); } bool AbstractVehicle::piloting() const { return false; } void AbstractVehicle::setPiloting(bool piloting) { Q_UNUSED(piloting) } int AbstractVehicle::flightTime() const { if (d->flightTime && d->flightTime->isValid()) { return d->flightTime->elapsed() / 1000; } return 0; } Kirogi::AbstractVehicle::PerformanceMode AbstractVehicle::performanceMode() const { return CustomPerformance; } void AbstractVehicle::requestPerformanceMode(Kirogi::AbstractVehicle::PerformanceMode mode) { Q_UNUSED(mode) } float AbstractVehicle::maxRollSpeed() const { return 0.0; } void AbstractVehicle::requestMaxRollSpeed(float speed) { Q_UNUSED(speed) } float AbstractVehicle::maxRollSpeedMin() const { return 0.0; } float AbstractVehicle::maxRollSpeedMax() const { return 0.0; } float AbstractVehicle::maxPitchSpeed() const { return 0.0; } void AbstractVehicle::requestMaxPitchSpeed(float speed) { Q_UNUSED(speed) } float AbstractVehicle::maxPitchSpeedMin() const { return 0.0; } float AbstractVehicle::maxPitchSpeedMax() const { return 0.0; } float AbstractVehicle::maxYawSpeed() const { return 0.0; } void AbstractVehicle::requestMaxYawSpeed(float speed) { Q_UNUSED(speed) } float AbstractVehicle::maxYawSpeedMin() const { return 0.0; } float AbstractVehicle::maxYawSpeedMax() const { return 0.0; } float AbstractVehicle::maxGazSpeed() const { return 0.0; } void AbstractVehicle::requestMaxGazSpeed(float speed) { Q_UNUSED(speed) } float AbstractVehicle::maxGazSpeedMin() const { return 0.0; } float AbstractVehicle::maxGazSpeedMax() const { return 0.0; } float AbstractVehicle::maxTilt() const { return 0.0; } void AbstractVehicle::requestMaxTilt(float tilt) { Q_UNUSED(tilt) } float AbstractVehicle::maxTiltMin() const { return 0.0; } float AbstractVehicle::maxTiltMax() const { return 0.0; } bool AbstractVehicle::bankedTurns() const { return false; } void AbstractVehicle::requestEnableBankedTurns(bool enable) { Q_UNUSED(enable) } bool AbstractVehicle::geofence() const { return false; } void AbstractVehicle::requestEnableGeofence(bool enable) { Q_UNUSED(enable) } float AbstractVehicle::maxAltitude() const { return 0.0; } void AbstractVehicle::requestMaxAltitude(float altitude) { Q_UNUSED(altitude) } float AbstractVehicle::maxAltitudeMin() const { return 0.0; } float AbstractVehicle::maxAltitudeMax() const { return 0.0; } float AbstractVehicle::maxDistance() const { return 0.0; } void AbstractVehicle::requestMaxDistance(float distance) { Q_UNUSED(distance) } float AbstractVehicle::maxDistanceMin() const { return 0.0; } float AbstractVehicle::maxDistanceMax() const { return 0.0; } void AbstractVehicle::requestAction(Kirogi::AbstractVehicle::VehicleAction action) { if (!ready()) { qCWarning(KIROGI_CORE) << name() << "Requested an action while not ready, aborting. Current connection state:" << connectionState(); return; } qCDebug(KIROGI_CORE) << name() << "No implementation for action:" << action; } void AbstractVehicle::requestTakeOff() { if (flying()) { qCWarning(KIROGI_CORE) << name() << "Requested to take off while flying, aborting. Current flying state:" << flyingState(); return; } requestAction(TakeOff); } void AbstractVehicle::requestLand() { if (!flying()) { qCWarning(KIROGI_CORE) << name() << "Requested to land while not flying, aborting. Current flying state:" << flyingState(); return; } requestAction(Land); } void AbstractVehicle::pilot(qint8 roll, qint8 pitch, qint8 yaw, qint8 gaz) { Q_UNUSED(roll) Q_UNUSED(pitch) Q_UNUSED(yaw) Q_UNUSED(gaz) } void AbstractVehicle::requestMoveTo(QGeoCoordinate destination) { Q_UNUSED(destination) } float AbstractVehicle::roll() const { return 0.0; } float AbstractVehicle::pitch() const { return 0.0; } float AbstractVehicle::yaw() const { return 0.0; } int AbstractVehicle::signalStrength() const { return -1; } int AbstractVehicle::batteryLevel() const { return -1; } bool AbstractVehicle::gpsSupported() const { return false; } bool AbstractVehicle::gpsFix() const { return false; } QGeoCoordinate AbstractVehicle::gpsPosition() const { return QGeoCoordinate(); } float AbstractVehicle::altitude() const { return 0.0; } float AbstractVehicle::distance() const { return -1.0; } void AbstractVehicle::setControllerGpsPosition(const QGeoCoordinate &position) { Q_UNUSED(position) } void AbstractVehicle::requestReturnHome() { } float AbstractVehicle::speed() const { return 0.0; } QString AbstractVehicle::videoSource() const { return QString(); } bool AbstractVehicle::videoStreamEnabled() const { return false; } void AbstractVehicle::requestEnableVideoStream(bool enable) { Q_UNUSED(enable) qCWarning(KIROGI_CORE) << name() << "Enabling video streaming is not supported."; } bool AbstractVehicle::videoStabilization() const { return false; } void AbstractVehicle::requestEnableVideoStabilization(bool enable) { Q_UNUSED(enable) } bool AbstractVehicle::canTakePicture() const { return false; } bool AbstractVehicle::isRecordingVideo() const { return false; } quint16 AbstractVehicle::numberOfFlights() const { return 0; } quint16 AbstractVehicle::lastFlightDuration() const { return 0; } +ParameterModel *AbstractVehicle::parameters() +{ + return &d->parameters; +} + } diff --git a/src/lib/abstractvehicle.h b/src/lib/abstractvehicle.h index 2c5111a..5312042 100644 --- a/src/lib/abstractvehicle.h +++ b/src/lib/abstractvehicle.h @@ -1,345 +1,353 @@ /* * Copyright 2019 Eike Hein * * This library is free software; you can redistribute it and/or * modify it under the terms of the GNU Lesser General Public * License as published by the Free Software Foundation; either * version 2.1 of the License, or (at your option) version 3, or any * later version accepted by the membership of KDE e.V. (or its * successor approved by the membership of KDE e.V.), which shall * act as a proxy defined in Section 6 of version 3 of the license. * * This library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU * Lesser General Public License for more details. * * You should have received a copy of the GNU Lesser General Public * License along with this library. If not, see . */ #pragma once #include #include #include #include "kirogicore_export.h" +class ParameterModel; + namespace Kirogi { class KIROGI_EXPORT AbstractVehicle : public QObject { Q_OBJECT Q_PROPERTY(int id READ id CONSTANT) Q_PROPERTY(QString name READ name NOTIFY nameChanged) Q_PROPERTY(QString iconName READ iconName NOTIFY iconNameChanged) Q_PROPERTY(VehicleType vehicleType READ vehicleType CONSTANT) Q_PROPERTY(ConnectionState connectionState READ connectionState NOTIFY connectionStateChanged) Q_PROPERTY(FlyingState flyingState READ flyingState NOTIFY flyingStateChanged) Q_PROPERTY(bool connected READ connected NOTIFY connectionStateChanged) Q_PROPERTY(bool ready READ ready NOTIFY connectionStateChanged) Q_PROPERTY(bool flying READ flying NOTIFY flyingStateChanged) Q_PROPERTY(QList supportedActions READ supportedActions CONSTANT) Q_PROPERTY(bool piloting READ piloting WRITE setPiloting NOTIFY pilotingChanged) Q_PROPERTY(int flightTime READ flightTime NOTIFY flightTimeChanged) Q_PROPERTY(PerformanceMode performanceMode READ performanceMode NOTIFY performanceModeChanged) Q_PROPERTY(float maxRollSpeed READ maxRollSpeed NOTIFY maxRollSpeedChanged) Q_PROPERTY(float maxRollSpeedMin READ maxRollSpeedMin NOTIFY maxRollSpeedMinChanged) Q_PROPERTY(float maxRollSpeedMax READ maxRollSpeedMax NOTIFY maxRollSpeedMaxChanged) Q_PROPERTY(float maxPitchSpeed READ maxPitchSpeed NOTIFY maxPitchSpeedChanged) Q_PROPERTY(float maxPitchSpeedMin READ maxPitchSpeedMin NOTIFY maxPitchSpeedMinChanged) Q_PROPERTY(float maxPitchSpeedMax READ maxPitchSpeedMax NOTIFY maxPitchSpeedMaxChanged) Q_PROPERTY(float maxYawSpeed READ maxYawSpeed NOTIFY maxYawSpeedChanged) Q_PROPERTY(float maxYawSpeedMin READ maxYawSpeedMin NOTIFY maxYawSpeedMinChanged) Q_PROPERTY(float maxYawSpeedMax READ maxYawSpeedMax NOTIFY maxYawSpeedMaxChanged) Q_PROPERTY(float maxGazSpeed READ maxGazSpeed NOTIFY maxGazSpeedChanged) Q_PROPERTY(float maxGazSpeedMin READ maxGazSpeedMin NOTIFY maxGazSpeedMinChanged) Q_PROPERTY(float maxGazSpeedMax READ maxGazSpeedMax NOTIFY maxGazSpeedMaxChanged) Q_PROPERTY(float maxTilt READ maxTilt NOTIFY maxTiltChanged) Q_PROPERTY(float maxTiltMin READ maxTiltMin NOTIFY maxTiltMinChanged) Q_PROPERTY(float maxTiltMax READ maxTiltMax NOTIFY maxTiltMaxChanged) Q_PROPERTY(bool bankedTurns READ bankedTurns NOTIFY bankedTurnsChanged) Q_PROPERTY(bool geofence READ geofence NOTIFY geofenceChanged) Q_PROPERTY(float maxAltitude READ maxAltitude NOTIFY maxAltitudeChanged) Q_PROPERTY(float maxAltitudeMin READ maxAltitudeMin NOTIFY maxAltitudeMinChanged) Q_PROPERTY(float maxAltitudeMax READ maxAltitudeMax NOTIFY maxAltitudeMaxChanged) Q_PROPERTY(float maxDistance READ maxDistance NOTIFY maxDistanceChanged) Q_PROPERTY(float maxDistanceMin READ maxDistanceMin NOTIFY maxDistanceMinChanged) Q_PROPERTY(float maxDistanceMax READ maxDistanceMax NOTIFY maxDistanceMaxChanged) Q_PROPERTY(QGeoCoordinate gpsPosition READ gpsPosition NOTIFY gpsPositionChanged) Q_PROPERTY(float distance READ distance NOTIFY distanceChanged) Q_PROPERTY(float altitude READ altitude NOTIFY altitudeChanged) Q_PROPERTY(int speed READ speed NOTIFY speedChanged) Q_PROPERTY(float roll READ roll NOTIFY attitudeChanged) Q_PROPERTY(float pitch READ pitch NOTIFY attitudeChanged) Q_PROPERTY(float yaw READ yaw NOTIFY attitudeChanged) Q_PROPERTY(int signalStrength READ signalStrength NOTIFY signalStrengthChanged) Q_PROPERTY(int batteryLevel READ batteryLevel NOTIFY batteryLevelChanged) Q_PROPERTY(bool gpsSupported READ gpsSupported NOTIFY gpsSupportedChanged) Q_PROPERTY(bool gpsFix READ gpsFix NOTIFY gpsFixChanged) Q_PROPERTY(QString videoSource READ videoSource NOTIFY videoSourceChanged) Q_PROPERTY(bool videoStreamEnabled READ videoStreamEnabled NOTIFY videoStreamEnabledChanged) Q_PROPERTY(bool videoStabilization READ videoStabilization NOTIFY videoStabilizationChanged) Q_PROPERTY(bool canTakePicture READ canTakePicture NOTIFY canTakePictureChanged) Q_PROPERTY(bool isRecordingVideo READ isRecordingVideo NOTIFY isRecordingVideoChanged) Q_PROPERTY(quint16 numberOfFlights READ numberOfFlights NOTIFY numberOfFlightsChanged) Q_PROPERTY(quint16 lastFlightDuration READ lastFlightDuration NOTIFY lastFlightDurationChanged) + Q_PROPERTY(ParameterModel *parameters READ parameters NOTIFY parametersChanged) + public: enum VehicleType { UnknownVehicleType = 0, QuadCopter = 1 }; Q_ENUM(VehicleType) enum ConnectionState { Disconnected = 0, Connecting = 1, Connected = 2, Ready = 3 }; Q_ENUM(ConnectionState) enum FlyingState { Unknown = 0, Landed = 1, TakingOff = 2, Hovering = 3, Flying = 4, Landing = 5, // FIXME: (Parrot) Not handled yet. // Emergency = 5, // UserTakeoff = 6, // MotorRamping = 7, // EmergencyLanding = 8 }; Q_ENUM(FlyingState) enum VehicleAction { TakeOff = 1, Land = 2, MoveTo = 3, FlatTrim = 4, FlipForward = 5, FlipBackward = 6, FlipLeft = 7, FlipRight = 8, SwitchPerformanceMode = 9, SetMaxRollSpeed = 10, SetMaxPitchSpeed = 11, SetMaxYawSpeed = 12, SetMaxGazSpeed = 13, SetMaxTilt = 14, ToggleBankedTurns = 15, ToggleGeofence = 16, SetMaxAltitude = 17, SetMaxDistance = 18, ToggleVideoStream = 19, ToggleVideoStabilization = 20, TakePicture = 21, RecordVideo = 22 }; Q_ENUM(VehicleAction) enum PerformanceMode { CustomPerformance = 0, FilmPerformance = 1, SportPerformance = 2 }; Q_ENUM(PerformanceMode) explicit AbstractVehicle(QObject *parent = nullptr); virtual ~AbstractVehicle() override; int id() const; virtual QString name() const = 0; virtual QString iconName() const; virtual VehicleType vehicleType() const; virtual ConnectionState connectionState() const; virtual FlyingState flyingState() const; bool connected() const; bool ready() const; bool flying() const; virtual QList supportedActions() const; Q_INVOKABLE virtual bool isActionSupported(VehicleAction action) const; virtual bool piloting() const; Q_INVOKABLE virtual void setPiloting(bool piloting); Q_INVOKABLE virtual void requestAction(VehicleAction action); Q_INVOKABLE virtual void requestTakeOff(); Q_INVOKABLE virtual void requestLand(); Q_INVOKABLE virtual void pilot(qint8 roll, qint8 pitch, qint8 yaw, qint8 gaz); Q_INVOKABLE virtual void requestMoveTo(QGeoCoordinate destination); virtual int flightTime() const; virtual PerformanceMode performanceMode() const; Q_INVOKABLE virtual void requestPerformanceMode(PerformanceMode mode); virtual float maxRollSpeed() const; Q_INVOKABLE virtual void requestMaxRollSpeed(float speed); virtual float maxRollSpeedMin() const; virtual float maxRollSpeedMax() const; virtual float maxPitchSpeed() const; Q_INVOKABLE virtual void requestMaxPitchSpeed(float speed); virtual float maxPitchSpeedMin() const; virtual float maxPitchSpeedMax() const; virtual float maxYawSpeed() const; Q_INVOKABLE virtual void requestMaxYawSpeed(float speed); virtual float maxYawSpeedMin() const; virtual float maxYawSpeedMax() const; virtual float maxGazSpeed() const; Q_INVOKABLE virtual void requestMaxGazSpeed(float speed); virtual float maxGazSpeedMin() const; virtual float maxGazSpeedMax() const; virtual float maxTilt() const; Q_INVOKABLE virtual void requestMaxTilt(float tilt); virtual float maxTiltMin() const; virtual float maxTiltMax() const; virtual bool bankedTurns() const; Q_INVOKABLE virtual void requestEnableBankedTurns(bool enable); virtual bool geofence() const; Q_INVOKABLE virtual void requestEnableGeofence(bool enable); virtual float maxAltitude() const; Q_INVOKABLE virtual void requestMaxAltitude(float altitude); virtual float maxAltitudeMin() const; virtual float maxAltitudeMax() const; virtual float maxDistance() const; Q_INVOKABLE virtual void requestMaxDistance(float distance); virtual float maxDistanceMin() const; virtual float maxDistanceMax() const; virtual float roll() const; virtual float pitch() const; virtual float yaw() const; virtual int signalStrength() const; virtual int batteryLevel() const; virtual bool gpsSupported() const; virtual bool gpsFix() const; virtual QGeoCoordinate gpsPosition() const; virtual float distance() const; virtual float altitude() const; virtual void setControllerGpsPosition(const QGeoCoordinate &position); Q_INVOKABLE virtual void requestReturnHome(); virtual float speed() const; virtual QString videoSource() const; virtual bool videoStreamEnabled() const; Q_INVOKABLE virtual void requestEnableVideoStream(bool enable); virtual bool videoStabilization() const; Q_INVOKABLE virtual void requestEnableVideoStabilization(bool enable); virtual bool canTakePicture() const; virtual bool isRecordingVideo() const; virtual quint16 numberOfFlights() const; virtual quint16 lastFlightDuration() const; + ParameterModel *parameters(); + Q_SIGNALS: void nameChanged() const; void iconNameChanged() const; void connectionStateChanged() const; void flyingStateChanged() const; void pilotingChanged() const; void flightTimeChanged() const; void performanceModeChanged() const; void maxRollSpeedChanged() const; void maxRollSpeedMinChanged() const; void maxRollSpeedMaxChanged() const; void maxPitchSpeedChanged() const; void maxPitchSpeedMinChanged() const; void maxPitchSpeedMaxChanged() const; void maxYawSpeedChanged() const; void maxYawSpeedMinChanged() const; void maxYawSpeedMaxChanged() const; void maxGazSpeedChanged() const; void maxGazSpeedMinChanged() const; void maxGazSpeedMaxChanged() const; void maxTiltChanged() const; void maxTiltMinChanged() const; void maxTiltMaxChanged() const; void bankedTurnsChanged() const; void geofenceChanged() const; void maxAltitudeChanged() const; void maxAltitudeMinChanged() const; void maxAltitudeMaxChanged() const; void maxDistanceChanged() const; void maxDistanceMinChanged() const; void maxDistanceMaxChanged() const; void attitudeChanged() const; void rollChanged() const; void pitchChanged() const; void yawChanged() const; void signalStrengthChanged() const; void batteryLevelChanged() const; void gpsSupportedChanged() const; void gpsFixChanged() const; void gpsPositionChanged() const; void distanceChanged() const; void altitudeChanged() const; void speedChanged() const; void videoSourceChanged() const; void videoStreamEnabledChanged() const; void videoStabilizationChanged() const; void canTakePictureChanged() const; void isRecordingVideoChanged() const; void numberOfFlightsChanged() const; void lastFlightDurationChanged() const; + void parametersChanged() const; + protected Q_SLOTS: virtual void setConnectionState(ConnectionState state); virtual void setFlyingState(FlyingState state); private: class Private; QScopedPointer d; }; } diff --git a/src/lib/qtquickplugin.cpp b/src/lib/qtquickplugin.cpp index de5eedd..4de49ef 100644 --- a/src/lib/qtquickplugin.cpp +++ b/src/lib/qtquickplugin.cpp @@ -1,43 +1,45 @@ /* * Copyright 2019 Eike Hein * * This library is free software; you can redistribute it and/or * modify it under the terms of the GNU Lesser General Public * License as published by the Free Software Foundation; either * version 2.1 of the License, or (at your option) version 3, or any * later version accepted by the membership of KDE e.V. (or its * successor approved by the membership of KDE e.V.), which shall * act as a proxy defined in Section 6 of version 3 of the license. * * This library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU * Lesser General Public License for more details. * * You should have received a copy of the GNU Lesser General Public * License along with this library. If not, see . */ #include "qtquickplugin.h" #include "abstractvehicle.h" +#include "parametermodel.h" #include "vehiclesupportplugin.h" #include "vehiclesupportpluginmodel.h" #include "positionsource/positionsource.h" #include namespace Kirogi { void QtQuickPlugin::registerTypes(const char *uri) { Q_ASSERT(uri == QLatin1String("org.kde.kirogi")); qmlRegisterUncreatableType(uri, 0, 1, "AbstractVehicle", "AbstractVehicle cannot be created from QML."); qmlRegisterType(uri, 0, 1, "VehicleSupportPluginModel"); + qRegisterMetaType("ParameterModel*"); qmlRegisterSingletonType(uri, 0, 1, "PositionSource", PositionSource::qmlSingletonRegister); } } diff --git a/src/lib/vehicleparameters/CMakeLists.txt b/src/lib/vehicleparameters/CMakeLists.txt new file mode 100644 index 0000000..ec602e2 --- /dev/null +++ b/src/lib/vehicleparameters/CMakeLists.txt @@ -0,0 +1,24 @@ +set(vehicleparameters_SRCS + parametermodel.cpp +) + +ecm_qt_declare_logging_category(vehicleparameters_SRCS + HEADER debug.h + IDENTIFIER VEHICLEPARAMETERS + CATEGORY_NAME "kirogi.vehicleparameters" +) + +add_library( + vehicleparameters +STATIC + ${vehicleparameters_SRCS} +) + +target_link_libraries(vehicleparameters + PRIVATE + Qt5::Core +) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + target_compile_options(vehicleparameters PRIVATE -pedantic) +endif() diff --git a/src/lib/vehicleparameters/parametermodel.cpp b/src/lib/vehicleparameters/parametermodel.cpp new file mode 100644 index 0000000..d023e9d --- /dev/null +++ b/src/lib/vehicleparameters/parametermodel.cpp @@ -0,0 +1,112 @@ +/* + * Copyright 2019 Patrick José Pereira + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) version 3, or any + * later version accepted by the membership of KDE e.V. (or its + * successor approved by the membership of KDE e.V.), which shall + * act as a proxy defined in Section 6 of version 3 of the license. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library. If not, see . + */ + +#include "parametermodel.h" + +#include +#include + +ParameterModel::ParameterModel(QObject *parent) + : QAbstractListModel(parent) +{ + initializeRoleNames(); + + // Initialize vector. + for (const auto &key : m_roleNames.keys()) { + m_vectors.insert(key, {}); + } + + // Allow the usage of this class in different threads. + connect(this, &ParameterModel::update, this, &ParameterModel::doUpdate); +} + +void ParameterModel::initializeRoleNames() +{ + Q_ASSERT(m_roleNames.empty()); + + auto desCapitalize = [](const char *input) -> QByteArray { + QByteArray array(input); + return array.left(1).toLower() + array.mid(1); + }; + + QMetaEnum e = metaObject()->enumerator(metaObject()->indexOfEnumerator("Roles")); + for (int i {0}; i < e.keyCount(); i++) { + m_roleNames.insert(e.value(i), desCapitalize(e.key(i))); + } +} + +void ParameterModel::loadDescriptionFile(const QString &path) +{ + // TODO: Deal with description files. +} + +void ParameterModel::doUpdate(const QMap ¶meter) +{ + // Check if parameter argument contains name. + if (!parameter.contains(ParameterModel::Roles::Name)) { + qDebug() << "No name identification in parameter"; + return; + }; + + // If name already exists in the model, get the index and update the other keys. + int nameIndex = -1; + if (m_vectors[ParameterModel::Roles::Name].contains(parameter[ParameterModel::Roles::Name])) { + nameIndex = m_vectors[ParameterModel::Roles::Name].indexOf(parameter[ParameterModel::Roles::Name]); + } + + const int line = rowCount(); + + beginInsertRows(QModelIndex(), line, line); + // Run over all keys in the parameter argument and update the model. + QMapIterator parameterIterator {parameter}; + while (parameterIterator.hasNext()) { + parameterIterator.next(); + // Ignore name if already exist in the model. + if (nameIndex >= 0 && parameterIterator.key() == ParameterModel::Roles::Name) { + continue; + } + + // Update the key if name already exist otherwise append it in the model. + if (nameIndex >= 0) { + m_vectors[parameterIterator.key()][nameIndex] = parameterIterator.value(); + } else { + m_vectors[parameterIterator.key()].append(parameterIterator.value()); + } + } + const auto &indexRow = index(line); + endInsertRows(); + + emit dataChanged(indexRow, indexRow, QVector::fromList(m_vectors.keys())); + emit countChanged(); +} + +QVariant ParameterModel::data(const QModelIndex &index, int role) const +{ + if (!m_roleNames.contains(role)) { + return {"No valid data"}; + } + + return m_vectors[role][index.row()]; +} + +QHash ParameterModel::roleNames() const +{ + return m_roleNames; +} diff --git a/src/lib/vehicleparameters/parametermodel.h b/src/lib/vehicleparameters/parametermodel.h new file mode 100644 index 0000000..045a61b --- /dev/null +++ b/src/lib/vehicleparameters/parametermodel.h @@ -0,0 +1,121 @@ +/* + * Copyright 2019 Patrick José Pereira + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) version 3, or any + * later version accepted by the membership of KDE e.V. (or its + * successor approved by the membership of KDE e.V.), which shall + * act as a proxy defined in Section 6 of version 3 of the license. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library. If not, see . + */ + +#pragma once + +#include + +/** + * @brief ParameterModel for qml interface. + * + */ +class ParameterModel : public QAbstractListModel +{ + Q_OBJECT + + Q_PROPERTY(int count READ rowCount NOTIFY countChanged) + +public: + /** + * @brief Construct a new ParameterModel. + * + * @param parent + */ + ParameterModel(QObject *parent = nullptr); + + /** + * @brief Load description file + * + * @param path + */ + void loadDescriptionFile(const QString &path); + + /** + * @brief Roles + * + */ + enum Roles { + Name = Qt::UserRole, // ACRO_BAL_PITCH + HumanName, // Acro Balance Pitch + Description, // rate at which pitch angle returns... + Index, // 0 + Value, // X + ValidValues, // { 0: "Disabled", "0.1": "Very Low", ... } + Bitmask, // True/False + Units, // deg + Increment, // 0.1 + Range, // [0, 3] + UserType, // Advanced/Standard + }; + Q_ENUM(Roles) + + /** + * @brief Return data. + * + * @param index + * @param role + * @return QVariant + */ + QVariant data(const QModelIndex &index, int role) const override; + + /** + * @brief Get role names. + * + * @return QHash + */ + QHash roleNames() const override; + + /** + * @brief Return ParameterModel size + * + * @param parent + * @return int + */ + int rowCount(const QModelIndex &parent = QModelIndex()) const override + { + Q_UNUSED(parent); + return m_vectors[ParameterModel::Roles::Name].size(); + }; + +Q_SIGNALS: + void countChanged(); + + /** + * @brief Update parameter + * + * @param parameter + */ + void update(const QMap ¶meter); + +private: + Q_DISABLE_COPY(ParameterModel) + + /** + * @brief Do update inside ParameterModel thread. + * + * @param parameter + */ + void doUpdate(const QMap ¶meter); + + void initializeRoleNames(); + + QHash m_roleNames; + QHash> m_vectors; +}; diff --git a/src/lib/vehiclesupportpluginmodel.cpp b/src/lib/vehiclesupportpluginmodel.cpp index 39ed2b3..e6c6a83 100644 --- a/src/lib/vehiclesupportpluginmodel.cpp +++ b/src/lib/vehiclesupportpluginmodel.cpp @@ -1,237 +1,242 @@ /* * Copyright 2019 Eike Hein * * This library is free software; you can redistribute it and/or * modify it under the terms of the GNU Lesser General Public * License as published by the Free Software Foundation; either * version 2.1 of the License, or (at your option) version 3, or any * later version accepted by the membership of KDE e.V. (or its * successor approved by the membership of KDE e.V.), which shall * act as a proxy defined in Section 6 of version 3 of the license. * * This library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU * Lesser General Public License for more details. * * You should have received a copy of the GNU Lesser General Public * License along with this library. If not, see . */ #include "vehiclesupportpluginmodel.h" #include "debug.h" #include "vehiclesupportplugin.h" #include #include #include #include #include namespace Kirogi { class Q_DECL_HIDDEN VehicleSupportPluginModel::Private { public: Private(VehicleSupportPluginModel *q); ~Private(); QVector plugins; // This is QMap so `VehicleSupportPluginModel::loadedPlugins` returns a stable sort. QMap loadedPlugins; void findPlugins(); private: VehicleSupportPluginModel *q; }; VehicleSupportPluginModel::Private::Private(VehicleSupportPluginModel *q) : q(q) { } VehicleSupportPluginModel::Private::~Private() { } void VehicleSupportPluginModel::Private::findPlugins() { auto filter = [](const KPluginMetaData &metaData) { return metaData.serviceTypes().contains(QStringLiteral("Kirogi/VehicleSupport")); }; // Look for plugins in a relative path, covers the case when the application is // not installed in the system. plugins = KPluginLoader::findPlugins(QCoreApplication::applicationDirPath() + QStringLiteral("/../lib/plugins/kirogi/vehiclesupport"), filter); plugins += KPluginLoader::findPlugins(QStringLiteral("kirogi/vehiclesupport"), filter); // Unload plugins that apparently got uninstalled at runtime. for (const QString &id : loadedPlugins.keys()) { bool found = false; for (const KPluginMetaData &md : plugins) { if (md.pluginId() == id) { found = true; break; } } if (!found) { delete loadedPlugins.take(id); } } } VehicleSupportPluginModel::VehicleSupportPluginModel(QObject *parent) : QAbstractListModel(parent) , d(new Private(this)) { // FIXME TODO: Watch KSycoca and reload when new plugins are installed at runtime. d->findPlugins(); } VehicleSupportPluginModel::~VehicleSupportPluginModel() { } QHash VehicleSupportPluginModel::roleNames() const { QHash roles = QAbstractItemModel::roleNames(); QMetaEnum e = metaObject()->enumerator(metaObject()->indexOfEnumerator("AdditionalRoles")); + auto desCapitalize = [](const char *input) -> QByteArray { + QByteArray array(input); + return array.left(1).toLower() + array.mid(1); + }; + for (int i = 0; i < e.keyCount(); ++i) { - roles.insert(e.value(i), e.key(i)); + roles.insert(e.value(i), desCapitalize(e.key(i))); } return roles; } int VehicleSupportPluginModel::rowCount(const QModelIndex &parent) const { if (!checkIndex(parent, CheckIndexOption::ParentIsInvalid)) { return 0; } return d->plugins.count(); } QVariant VehicleSupportPluginModel::data(const QModelIndex &index, int role) const { if (!checkIndex(index, CheckIndexOption::IndexIsValid | CheckIndexOption::ParentIsInvalid)) { return QVariant(); } switch (role) { case Qt::DisplayRole: { return d->plugins.at(index.row()).name(); } case Id: { return d->plugins.at(index.row()).pluginId(); } case Status: { const QString &id = d->plugins.at(index.row()).pluginId(); if (d->loadedPlugins.contains(id)) { return PluginLoaded; } else { return PluginNotLoaded; } } case Plugin: { const QString &id = d->plugins.at(index.row()).pluginId(); return QVariant::fromValue(d->loadedPlugins.value(id)); } } return QVariant(); } bool VehicleSupportPluginModel::loadPlugin(int row) { const KPluginMetaData &md = d->plugins.at(row); if (d->loadedPlugins.contains(md.pluginId())) { return false; } KPluginLoader loader(md.fileName(), this); KPluginFactory *factory = loader.factory(); if (!factory) { qCWarning(KIROGI_CORE) << "Error loading plugin:" << md.pluginId() << "-" << loader.errorString(); } else { VehicleSupportPlugin *vehicleSupportPlugin = factory->create(this); if (!vehicleSupportPlugin) { qCWarning(KIROGI_CORE) << "Scheduling invalid plugin to be deleted:" << md.pluginId() << "/" << factory; factory->deleteLater(); } else { qCWarning(KIROGI_CORE) << "Loaded plugin with id:" << md.pluginId(); d->loadedPlugins[md.pluginId()] = vehicleSupportPlugin; emit pluginLoaded(md.pluginId(), md.name(), vehicleSupportPlugin); const QModelIndex &idx = index(row, 0); emit dataChanged(idx, idx, QVector {Status, Plugin}); } } return false; } bool VehicleSupportPluginModel::loadPluginById(const QString &id) { for (int i = 0; i < d->plugins.count(); ++i) { const KPluginMetaData &md = d->plugins.at(i); if (md.pluginId() == id) { return loadPlugin(i); } } return false; } bool VehicleSupportPluginModel::unloadPlugin(int row) { const QString &id = d->plugins.at(row).pluginId(); if (!d->loadedPlugins.contains(id)) { return false; } delete d->loadedPlugins.take(id); const QModelIndex &idx = index(row, 0); emit dataChanged(idx, idx, QVector {Status, Plugin}); return true; } bool VehicleSupportPluginModel::unloadAllPlugins() { if (!d->loadedPlugins.count()) { return false; } for (int i = 0; i < d->plugins.count(); ++i) { const KPluginMetaData &md = d->plugins.at(i); VehicleSupportPlugin *plugin = d->loadedPlugins.take(md.pluginId()); if (plugin) { delete plugin; const QModelIndex &idx = index(i, 0); emit dataChanged(idx, idx, QVector {Status, Plugin}); } } return true; } } diff --git a/src/plugins/mavlink/CMakeLists.txt b/src/plugins/mavlink/CMakeLists.txt index 53ec127..ea5afef 100644 --- a/src/plugins/mavlink/CMakeLists.txt +++ b/src/plugins/mavlink/CMakeLists.txt @@ -1,54 +1,55 @@ add_definitions(-DTRANSLATION_DOMAIN=\"kirogimavlinkplugin\") find_package(MAVLink) if(MAVLink_FOUND) message(STATUS "MAVLink found: Kirogi will build with MAVLink integration.") else() message(WARNING "MAVLink not found.") return() endif() set(kirogimavlinkplugin_SRCS mavlinkconnection.cpp mavlinkplugin.cpp mavlinkvehicle.cpp ) ecm_qt_declare_logging_category(kirogimavlinkplugin_SRCS HEADER debug.h IDENTIFIER KIROGI_VEHICLESUPPORT_MAVLINK CATEGORY_NAME "kirogi.vehiclesupport.mavlink" ) kcoreaddons_add_plugin(kirogimavlinkplugin SOURCES ${kirogimavlinkplugin_SRCS} JSON "${CMAKE_CURRENT_SOURCE_DIR}/kirogimavlinkplugin.json" INSTALL_NAMESPACE "kirogi/vehiclesupport" ) include_directories( ${MAVLINK_INCLUDE_DIR} ${MAVLINK_INCLUDE_DIR}/ardupilotmega ) set_target_properties(kirogimavlinkplugin PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${CMAKE_LIBRARY_OUTPUT_DIRECTORY}" ) target_link_libraries(kirogimavlinkplugin PRIVATE Qt5::Core Qt5::Network Qt5::Positioning KF5::CoreAddons KF5::I18n KirogiCore + vehicleparameters ) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") target_compile_options(kirogimavlinkplugin PRIVATE -pedantic) endif() install(FILES kirogimavlinkplugin.categories DESTINATION ${KDE_INSTALL_CONFDIR}) diff --git a/src/plugins/mavlink/mavlinkvehicle.cpp b/src/plugins/mavlink/mavlinkvehicle.cpp index a3145c6..38d5c67 100644 --- a/src/plugins/mavlink/mavlinkvehicle.cpp +++ b/src/plugins/mavlink/mavlinkvehicle.cpp @@ -1,416 +1,448 @@ /* * Copyright 2019 Patrick José Pereira * * This library is free software; you can redistribute it and/or * modify it under the terms of the GNU Lesser General Public * License as published by the Free Software Foundation; either * version 2.1 of the License, or (at your option) version 3, or any * later version accepted by the membership of KDE e.V. (or its * successor approved by the membership of KDE e.V.), which shall * act as a proxy defined in Section 6 of version 3 of the license. * * This library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU * Lesser General Public License for more details. * * You should have received a copy of the GNU Lesser General Public * License along with this library. If not, see . */ #include "mavlinkvehicle.h" #include "debug.h" +#include "parametermodel.h" #include #include #include MAVLinkVehicle::MAVLinkVehicle(QObject *parent) : Kirogi::AbstractVehicle(parent) , m_roll(0.0) , m_pitch(0.0) , m_yaw(0.0) , m_signalStrength(-1) , m_batteryLevel(-1) , m_gpsFix(false) , m_connection(nullptr) { m_connection = new MAVLinkConnection(name()); // Queued connections across thread boundaries. QObject::connect(m_connection, &MAVLinkConnection::stateChanged, this, &MAVLinkVehicle::setConnectionState, Qt::QueuedConnection); + // Request vehicle parameters if we are in connected state. + QObject::connect(this, &MAVLinkVehicle::connectionStateChanged, this, &MAVLinkVehicle::fetchParameters, Qt::QueuedConnection); + QObject::connect(m_connection, &MAVLinkConnection::mavlinkMessage, this, &MAVLinkVehicle::processMavlinkMessage); - // Do the networking on a seperate thread, so our fixed-tick work never gets + // Do the networking on a separate thread, so our fixed-tick work never gets // blocked by activity on the main thread. m_connection->moveToThread(&m_connectionThread); QObject::connect(&m_connectionThread, &QThread::finished, m_connection, &QObject::deleteLater); m_connectionThread.setObjectName(QLatin1String("MAVLinkConnectionThread")); m_connectionThread.start(); } MAVLinkVehicle::~MAVLinkVehicle() { m_connectionThread.quit(); m_connectionThread.wait(); } void MAVLinkVehicle::processMavlinkMessage(const mavlink_message_t &message) { if (message.sysid == 255) { // GSC sysid return; } switch (message.msgid) { case MAVLINK_MSG_ID_HEARTBEAT: { mavlink_heartbeat_t heartbeat; mavlink_msg_heartbeat_decode(&message, &heartbeat); switch (heartbeat.system_status) { case MAV_STATE::MAV_STATE_UNINIT: case MAV_STATE::MAV_STATE_BOOT: case MAV_STATE::MAV_STATE_CALIBRATING: case MAV_STATE::MAV_STATE_CRITICAL: case MAV_STATE::MAV_STATE_EMERGENCY: setConnectionState(Kirogi::AbstractVehicle::ConnectionState::Connected); break; case MAV_STATE::MAV_STATE_STANDBY: case MAV_STATE::MAV_STATE_ACTIVE: setConnectionState(Kirogi::AbstractVehicle::ConnectionState::Ready); break; case MAV_STATE::MAV_STATE_FLIGHT_TERMINATION: case MAV_STATE::MAV_STATE_POWEROFF: setConnectionState(Kirogi::AbstractVehicle::ConnectionState::Disconnected); break; // We did receive a message so it's connected.. default: setConnectionState(Kirogi::AbstractVehicle::ConnectionState::Connected); break; } break; } case MAVLINK_MSG_ID_COMMAND_ACK: { mavlink_command_ack_t command_ack; mavlink_msg_command_ack_decode(&message, &command_ack); // TODO: Do something related to nack break; } case MAVLINK_MSG_ID_RC_CHANNELS_SCALED: { mavlink_rc_channels_scaled_t rc_channels_scaled; mavlink_msg_rc_channels_scaled_decode(&message, &rc_channels_scaled); m_signalStrength = rc_channels_scaled.rssi >= 255 ? -1 : static_cast(rc_channels_scaled.rssi) / 2.54f; emit signalStrengthChanged(); break; } case MAVLINK_MSG_ID_RC_CHANNELS_RAW: { mavlink_rc_channels_raw_t rc_channels_raw; mavlink_msg_rc_channels_raw_decode(&message, &rc_channels_raw); m_signalStrength = rc_channels_raw.rssi >= 255 ? -1 : static_cast(rc_channels_raw.rssi) / 2.54f; emit signalStrengthChanged(); break; } case MAVLINK_MSG_ID_RC_CHANNELS: { mavlink_rc_channels_t rc_channels; mavlink_msg_rc_channels_decode(&message, &rc_channels); m_signalStrength = rc_channels.rssi >= 255 ? -1 : static_cast(rc_channels.rssi) / 2.54f; emit signalStrengthChanged(); break; } case MAVLINK_MSG_ID_ALTITUDE: { mavlink_altitude_t altitude; mavlink_msg_altitude_decode(&message, &altitude); m_altitudeSource.altitudeMessage = true; m_altitudeSource.altitude = altitude.altitude_terrain; emit altitudeChanged(); break; } case MAVLINK_MSG_ID_ATTITUDE: { mavlink_attitude_t attitude; mavlink_msg_attitude_decode(&message, &attitude); m_yaw = attitude.yaw; m_roll = attitude.roll; m_pitch = attitude.pitch; emit rollChanged(); emit pitchChanged(); emit yawChanged(); emit attitudeChanged(); break; } case MAVLINK_MSG_ID_BATTERY_STATUS: { mavlink_battery_status_t battery_status; mavlink_msg_battery_status_decode(&message, &battery_status); m_batteryLevel = battery_status.battery_remaining; emit batteryLevelChanged(); break; } case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: { // Both latitude and longitude are provided in degE7 // Altitude is provided in mm mavlink_global_position_int_t global_position_int; mavlink_msg_global_position_int_decode(&message, &global_position_int); m_gpsFix = !(qFuzzyCompare(global_position_int.lat, 0.0) && qFuzzyCompare(global_position_int.lon, 0.0)); emit gpsFixChanged(); if (m_gpsFix) { m_gpsPosition.setLatitude(global_position_int.lat / 1e7); m_gpsPosition.setLongitude(global_position_int.lon / 1e7); } else { // Invalidate position if there is no fix m_gpsPosition.setLatitude(qQNaN()); m_gpsPosition.setLongitude(qQNaN()); } m_gpsPosition.setAltitude(global_position_int.alt / 1e3); emit gpsPositionChanged(); // Check if altitude message was received if (!m_altitudeSource.altitudeMessage) { m_altitudeSource.altitude = m_gpsPosition.altitude(); emit altitudeChanged(); } break; } + case MAVLINK_MSG_ID_PARAM_VALUE: { + mavlink_param_value_t param_value; + mavlink_msg_param_value_decode(&message, ¶m_value); + + parameters()->update({ + {ParameterModel::Roles::Name, QString(param_value.param_id)}, + {ParameterModel::Roles::Value, static_cast(param_value.param_value)}, + {ParameterModel::Roles::Index, static_cast(param_value.param_index)}, + }); + } + default: { break; } } } QString MAVLinkVehicle::name() const { return QStringLiteral("MAVLink"); } QString MAVLinkVehicle::iconName() const { return QStringLiteral("uav-quadcopter"); } Kirogi::AbstractVehicle::VehicleType MAVLinkVehicle::vehicleType() const { // TODO: Get this from mavlink messages return Kirogi::AbstractVehicle::QuadCopter; } QList MAVLinkVehicle::supportedActions() const { // TODO: Improve this to work with mavlink infraestructure QList actions; actions << Kirogi::AbstractVehicle::TakeOff; actions << Kirogi::AbstractVehicle::Land; actions << Kirogi::AbstractVehicle::FlipForward; actions << Kirogi::AbstractVehicle::FlipBackward; actions << Kirogi::AbstractVehicle::FlipLeft; actions << Kirogi::AbstractVehicle::FlipRight; actions << Kirogi::AbstractVehicle::SwitchPerformanceMode; return actions; } void MAVLinkVehicle::requestAction(Kirogi::AbstractVehicle::VehicleAction action) { if (!ready()) { qWarning() << name() << "Requested an action while not ready, aborting. Current " "connection state:" << connectionState(); return; } switch (action) { case TakeOff: { if (flying()) { return; } // Set the vehicle in stabilize mode and after that arm mavlink_message_t message; mavlink_command_long_t command_long; command_long.target_system = 1; // TODO: get from system heartbeat command_long.target_component = 1; // TODO: get from system heartbeat command_long.command = MAV_CMD_DO_SET_MODE; command_long.confirmation = 0; command_long.param1 = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; command_long.param2 = 0; // 0 for stabilize command_long.param3 = 0; command_long.param4 = 0; command_long.param5 = 0; command_long.param6 = 0; command_long.param7 = 0; mavlink_msg_command_long_encode(255, MAV_COMP_ID_MISSIONPLANNER, &message, &command_long); m_connection->sendMessage(message); command_long.target_system = 1; // TODO: get from system heartbeat command_long.target_component = 1; // TODO: get from system heartbeat command_long.command = MAV_CMD_COMPONENT_ARM_DISARM; command_long.confirmation = 0; command_long.param1 = 1; command_long.param2 = 0; command_long.param3 = 0; command_long.param4 = 0; command_long.param5 = 0; command_long.param6 = 0; command_long.param7 = 0; mavlink_msg_command_long_encode(255, MAV_COMP_ID_MISSIONPLANNER, &message, &command_long); m_connection->sendMessage(message); setFlyingState(TakingOff); // FIXME: We don't /really/ know that without // looking at the response. break; } case Land: { if (!flying()) { return; } // Disarm vehicle mavlink_message_t message; mavlink_command_long_t command_long; command_long.target_system = 1; // TODO: get from system heartbeat command_long.target_component = 1; // TODO: get from system heartbeat command_long.command = MAV_CMD_COMPONENT_ARM_DISARM; command_long.confirmation = 0; command_long.param1 = 0; command_long.param2 = 0; command_long.param3 = 0; command_long.param4 = 0; command_long.param5 = 0; command_long.param6 = 0; command_long.param7 = 0; mavlink_msg_command_long_encode(255, MAV_COMP_ID_MISSIONPLANNER, &message, &command_long); m_connection->sendMessage(message); setFlyingState(Landed); // FIXME: We don't /really/ know that without // looking at the response. break; } default: { } } } void MAVLinkVehicle::pilot(qint8 roll, qint8 pitch, qint8 yaw, qint8 gaz) { mavlink_message_t message; mavlink_manual_control_t manual_control; manual_control.target = 1; manual_control.x = pitch * 10; // [-1000,1000] range manual_control.y = roll * 10; // [-1000,1000] range manual_control.z = gaz * 10; // [-1000,1000] range manual_control.r = yaw * 10; // [-1000,1000] range manual_control.buttons = 0; mavlink_msg_manual_control_encode(255, MAV_COMP_ID_MISSIONPLANNER, &message, &manual_control); m_connection->sendMessage(message); } float MAVLinkVehicle::roll() const { return m_roll; } float MAVLinkVehicle::pitch() const { return m_pitch; } float MAVLinkVehicle::yaw() const { return m_yaw; } int MAVLinkVehicle::signalStrength() const { return m_signalStrength; } int MAVLinkVehicle::batteryLevel() const { return m_batteryLevel; } QGeoCoordinate MAVLinkVehicle::gpsPosition() const { return m_gpsPosition; } bool MAVLinkVehicle::gpsFix() const { return m_gpsFix; } bool MAVLinkVehicle::gpsSupported() const { return true; } float MAVLinkVehicle::altitude() const { return m_altitudeSource.altitude; } void MAVLinkVehicle::connectToVehicle() { if (connectionState() > Disconnected) { if (connectionState() > Connecting) { qCDebug(KIROGI_VEHICLESUPPORT_MAVLINK) << name() << "Asked to connect when not disconnected."; } QMetaObject::invokeMethod(m_connection, "reset", Qt::BlockingQueuedConnection); } QMetaObject::invokeMethod(m_connection, "handshake", Qt::QueuedConnection); // Keep re-trying every 3 seconds until we're successfully connected. QTimer::singleShot(3000, this, [this]() { if (connectionState() != Ready) { qCWarning(KIROGI_VEHICLESUPPORT_MAVLINK) << name() << "Unable to establish connection within 3 seconds. Starting " "over."; connectToVehicle(); } }); } +void MAVLinkVehicle::fetchParameters() const +{ + // We need to handle this in a different way to ensure that we are going to receive all parameters. + static bool requested = false; + if (connectionState() < Kirogi::AbstractVehicle::ConnectionState::Connected || requested) { + return; + } + requested = true; + + mavlink_message_t message; + mavlink_param_request_list_t param_request_list; + param_request_list.target_system = 1; + param_request_list.target_component = 1; + mavlink_msg_param_request_list_encode(255, MAV_COMP_ID_MISSIONPLANNER, &message, ¶m_request_list); + m_connection->sendMessage(message); +} + QString MAVLinkVehicle::videoSource() const { return QLatin1String( "rtspsrc location=rtsp://192.168.99.1/media/stream2 latency=5 ! " "rtph264depay ! " "video/x-h264 ! " "queue ! " "h264parse ! " "decodebin ! " "glupload ! " "glcolorconvert ! " "qmlglsink name=sink"); } diff --git a/src/plugins/mavlink/mavlinkvehicle.h b/src/plugins/mavlink/mavlinkvehicle.h index 42744ea..1e9b906 100644 --- a/src/plugins/mavlink/mavlinkvehicle.h +++ b/src/plugins/mavlink/mavlinkvehicle.h @@ -1,87 +1,88 @@ /* * Copyright 2019 Patrick José Pereira * * This library is free software; you can redistribute it and/or * modify it under the terms of the GNU Lesser General Public * License as published by the Free Software Foundation; either * version 2.1 of the License, or (at your option) version 3, or any * later version accepted by the membership of KDE e.V. (or its * successor approved by the membership of KDE e.V.), which shall * act as a proxy defined in Section 6 of version 3 of the license. * * This library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU * Lesser General Public License for more details. * * You should have received a copy of the GNU Lesser General Public * License along with this library. If not, see . */ #pragma once #include "abstractvehicle.h" #include "mavlinkconnection.h" #include class MAVLinkConnection; class QTimer; class MAVLinkVehicle : public Kirogi::AbstractVehicle { Q_OBJECT public: explicit MAVLinkVehicle(QObject *parent = nullptr); ~MAVLinkVehicle() override; QString name() const override; QString iconName() const override; Kirogi::AbstractVehicle::VehicleType vehicleType() const override; QList supportedActions() const override; Q_INVOKABLE void requestAction(Kirogi::AbstractVehicle::VehicleAction action) override; Q_INVOKABLE void pilot(qint8 roll, qint8 pitch, qint8 yaw, qint8 gaz) override; float roll() const override; float pitch() const override; float yaw() const override; int signalStrength() const override; int batteryLevel() const override; bool gpsSupported() const override; bool gpsFix() const override; QGeoCoordinate gpsPosition() const override; float altitude() const override; QString videoSource() const override; public Q_SLOTS: void connectToVehicle(); private Q_SLOTS: + void fetchParameters() const; void processMavlinkMessage(const mavlink_message_t &message); private: float m_roll; float m_pitch; float m_yaw; int m_signalStrength; int m_batteryLevel; bool m_gpsFix; QGeoCoordinate m_gpsPosition; struct { bool altitudeMessage {false}; float altitude {0.0f}; } m_altitudeSource; QThread m_connectionThread; MAVLinkConnection *m_connection; }; diff --git a/src/ui/Vehicle.qml b/src/ui/Vehicle.qml index 2f3023e..74f7355 100644 --- a/src/ui/Vehicle.qml +++ b/src/ui/Vehicle.qml @@ -1,494 +1,494 @@ /* * Copyright 2019 Eike Hein * * This program is free software; you can redistribute it and/or * modify it under the terms of the GNU General Public License as * published by the Free Software Foundation; either version 2 of * the License or (at your option) version 3 or any later version * accepted by the membership of KDE e.V. (or its successor approved * by the membership of KDE e.V.), which shall act as a proxy * defined in Section 14 of version 3 of the license. * * This program is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with this program. If not, see . */ import QtQuick 2.12 import QtQuick.Layouts 1.12 import QtQuick.Controls 2.12 as QQC2 import org.kde.kirigami 2.6 as Kirigami import org.kde.kirogi 0.1 as Kirogi Kirigami.Page { id: page leftPadding: 0 rightPadding: 0 topPadding: 0 bottomPadding: 0 Image { anchors.left: parent.left anchors.leftMargin: (((LayoutMirroring.enabled ? (parent.width - flightChecklist.x - flightChecklist.width) : flightChecklist.x) / 2) - (width / 2)) anchors.verticalCenter: parent.verticalCenter width: height height: Math.min(parent.height, LayoutMirroring.enabled ? (parent.width - flightChecklist.x - flightChecklist.width) : flightChecklist.x) * 0.94 fillMode: Image.PreserveAspectFit smooth: true source: "goose.webp" asynchronous: true } Component { id: pluginItemComponent Kirigami.BasicListItem { id: pluginItem height: Math.max(implicitHeight, Kirigami.Units.iconSizes.medium) - supportsMouseEvents: model.Status == Kirogi.VehicleSupportPluginModel.PluginNotLoaded + supportsMouseEvents: model.status == Kirogi.VehicleSupportPluginModel.PluginNotLoaded reserveSpaceForIcon: kirogi.currentPlugin - icon: model.Status == Kirogi.VehicleSupportPluginModel.PluginLoaded ? "emblem-default-symbolic" : "" + icon: model.status == Kirogi.VehicleSupportPluginModel.PluginLoaded ? "emblem-default-symbolic" : "" label: model.display onClicked: { pluginSheet.sheetOpen = false; pluginModel.unloadAllPlugins(); pluginModel.loadPlugin(index); } } } Kirigami.OverlaySheet { id: pluginSheet parent: kirogi topPadding: 0 leftPadding: 0 rightPadding: 0 bottomPadding: 0 header: Kirigami.Heading { text: i18nc("@title:window", "Select Model") } ListView { id: pluginList implicitWidth: 18 * Kirigami.Units.gridUnit model: pluginSheet.sheetOpen ? pluginModel : null delegate: Kirigami.DelegateRecycler { width: parent.width sourceComponent: pluginItemComponent } } } Kirigami.AbstractCard { id: flightChecklist width: (page.width / 3) + (Kirigami.Units.gridUnit * 2) implicitHeight: height // FIXME TODO Silence Kirigami warning. anchors.right: parent.right anchors.rightMargin: Kirigami.Units.gridUnit anchors.top: parent.top anchors.topMargin: Kirigami.Units.gridUnit anchors.bottom: parent.bottom anchors.bottomMargin: Kirigami.Units.gridUnit topPadding: Kirigami.Settings.isMobile ? header.height * 0.5 : header.height header: Kirigami.Heading { text: i18n("Flight Checklist") level: 1 horizontalAlignment: Text.AlignHCenter elide: Text.ElideRight } contentItem: QQC2.ScrollView { id: checksList clip: true Column { id: col width: checksList.width height: implicitHeight Kirigami.BasicListItem { implicitHeight: Kirigami.Units.iconSizes.medium + (Kirigami.Units.smallSpacing * 2) supportsMouseEvents: false separatorVisible: !Kirigami.Settings.isMobile contentItem: RowLayout { Kirigami.Icon { Layout.alignment: Qt.AlignVCenter width: Kirigami.Units.iconSizes.medium height: width source: kirogi.currentPlugin ? "emblem-default-symbolic" : "emblem-important-symbolic" color: kirogi.currentPlugin ? Kirigami.Theme.positiveTextColor : Kirigami.Theme.negativeTextColor } QQC2.Label { Layout.fillWidth: true Layout.alignment: Qt.AlignVCenter text: i18n("Model: %1", kirogi.currentPlugin ? kirogi.currentPluginName : i18n("Select now")) color: kirogi.currentPlugin ? Kirigami.Theme.textColor : Kirigami.Theme.negativeTextColor elide: Text.ElideRight } QQC2.ToolButton { Layout.alignment: Qt.AlignVCenter implicitWidth: Kirigami.Units.iconSizes.medium implicitHeight: implicitWidth icon.name: "configure" onClicked: pluginSheet.sheetOpen = !pluginSheet.sheetOpen QQC2.ToolTip.visible: modelButtonHoverHandler.hovered QQC2.ToolTip.delay: Kirigami.Units.toolTipDelay QQC2.ToolTip.text: i18n("Select Model") HoverHandler { id: modelButtonHoverHandler } } } } Kirigami.BasicListItem { implicitHeight: Kirigami.Units.iconSizes.medium + (Kirigami.Units.smallSpacing * 2) supportsMouseEvents: false separatorVisible: !Kirigami.Settings.isMobile contentItem: RowLayout { Kirigami.Icon { visible: !kirogi.currentPlugin || kirogi.currentPlugin && kirogi.currentVehicle Layout.alignment: Qt.AlignVCenter width: Kirigami.Units.iconSizes.medium height: width source: kirogi.currentVehicle ? "emblem-default-symbolic" : "question" color: kirogi.currentVehicle ? Kirigami.Theme.positiveTextColor : Kirigami.Theme.disabledTextColor } QQC2.BusyIndicator { visible: kirogi.currentPlugin && !kirogi.currentVehicle Layout.alignment: Qt.AlignVCenter implicitWidth: Kirigami.Units.iconSizes.medium implicitHeight: implicitWidth topPadding: 0 bottomPadding: 0 leftPadding: 0 rightPadding: 0 running: visible } QQC2.Label { Layout.fillWidth: true Layout.alignment: Qt.AlignVCenter text: { var state = i18n("N/A"); if (kirogi.currentPlugin) { state = i18n("Searching ..."); } return i18n("Drone: %1", kirogi.currentVehicle ? kirogi.currentVehicle.name : state); } color: kirogi.currentPlugin ? Kirigami.Theme.textColor : Kirigami.Theme.disabledTextColor elide: Text.ElideRight } } } Kirigami.BasicListItem { implicitHeight: Kirigami.Units.iconSizes.medium + (Kirigami.Units.smallSpacing * 2) supportsMouseEvents: false separatorVisible: !Kirigami.Settings.isMobile contentItem: RowLayout { Kirigami.Icon { visible: !kirogi.currentVehicle || kirogi.ready Layout.alignment: Qt.AlignVCenter width: Kirigami.Units.iconSizes.medium height: width source: kirogi.currentVehicle ? "emblem-default-symbolic" : "question" color: kirogi.currentVehicle ? Kirigami.Theme.positiveTextColor : Kirigami.Theme.disabledTextColor } QQC2.BusyIndicator { visible: kirogi.currentVehicle && !kirogi.ready Layout.alignment: Qt.AlignVCenter implicitWidth: Kirigami.Units.iconSizes.medium implicitHeight: implicitWidth topPadding: 0 bottomPadding: 0 leftPadding: 0 rightPadding: 0 running: visible } QQC2.Label { Layout.fillWidth: true Layout.alignment: Qt.AlignVCenter text: { var state = "N/A"; if (kirogi.flying) { state = i18n("Flying"); } else if (kirogi.ready) { state = i18n("Ready"); } else if (kirogi.connected) { state = i18n("Preparing ..."); } else if (kirogi.currentVehicle && (kirogi.currentVehicle.connectionState == Kirogi.AbstractVehicle.Connecting || kirogi.currentVehicle.connectionState == Kirogi.AbstractVehicle.Disconnected)) { state = i18n("Connecting ..."); } i18n("Status: %1", state); } color: kirogi.currentVehicle ? Kirigami.Theme.textColor : Kirigami.Theme.disabledTextColor elide: Text.ElideRight } } } Kirigami.BasicListItem { implicitHeight: Kirigami.Units.iconSizes.medium + (Kirigami.Units.smallSpacing * 2) supportsMouseEvents: false separatorVisible: !Kirigami.Settings.isMobile contentItem: RowLayout { Kirigami.Icon { Layout.alignment: Qt.AlignVCenter width: Kirigami.Units.iconSizes.medium height: width source: { if (kirogi.currentVehicle) { if (kirogi.currentVehicle.signalStrength === 0) { return "network-wireless-connected-00"; } else if (kirogi.currentVehicle.signalStrength < 25) { return "network-wireless-connected-25"; } else if (kirogi.currentVehicle.signalStrength < 50) { return "network-wireless-connected-50"; } else if (kirogi.currentVehicle.signalStrength < 75) { return "network-wireless-connected-75"; } else if (kirogi.currentVehicle.signalStrength <= 100) { return "network-wireless-connected-100"; } } if (kirogi.connected) { return "network-wireless-acquiring"; } return "network-wireless-disconnected"; } color: kirogi.currentVehicle ? Kirigami.Theme.textColor : Kirigami.Theme.disabledTextColor } QQC2.Label { Layout.fillWidth: true Layout.alignment: Qt.AlignVCenter text: { var state = kirogi.currentVehicle ? i18n("%1%", kirogi.currentVehicle.signalStrength) : i18n("N/A"); return i18n("Signal: %1", state); } color: kirogi.connected ? Kirigami.Theme.textColor : Kirigami.Theme.disabledTextColor elide: Text.ElideRight } } } Kirigami.BasicListItem { implicitHeight: Kirigami.Units.iconSizes.medium + (Kirigami.Units.smallSpacing * 2) supportsMouseEvents: false separatorVisible: !Kirigami.Settings.isMobile contentItem: RowLayout { Kirigami.Icon { Layout.alignment: Qt.AlignVCenter width: Kirigami.Units.iconSizes.medium height: width source: { if (kirogi.currentVehicle) { var roundedBatteryLevel = Math.round(kirogi.currentVehicle.batteryLevel / 10); return "battery-" + roundedBatteryLevel.toString().padStart(2, "0") + "0"; } return "battery-missing"; } color: kirogi.currentVehicle ? Kirigami.Theme.textColor : Kirigami.Theme.disabledTextColor } QQC2.Label { Layout.fillWidth: true Layout.alignment: Qt.AlignVCenter text: { var state = kirogi.currentVehicle ? i18n("%1%", kirogi.currentVehicle.batteryLevel) : i18n("N/A"); return i18n("Battery: %1", state); } color: kirogi.connected ? Kirigami.Theme.textColor : Kirigami.Theme.disabledTextColor elide: Text.ElideRight } } } Kirigami.BasicListItem { implicitHeight: Kirigami.Units.iconSizes.medium + (Kirigami.Units.smallSpacing * 2) supportsMouseEvents: false separatorVisible: !Kirigami.Settings.isMobile contentItem: RowLayout { Kirigami.Icon { Layout.alignment: Qt.AlignVCenter width: Kirigami.Units.iconSizes.medium height: width source: "gps" color: { if (kirogi.connected) { if (kirogi.currentVehicle.gpsFix) { return Kirigami.Theme.positiveTextColor; } else if (kirogi.currentVehicle.gpsSupported) { return Kirigami.Theme.negativeTextColor; } } return Kirigami.Theme.disabledTextColor; } } QQC2.Label { Layout.fillWidth: true Layout.alignment: Qt.AlignVCenter text: { var state = i18n("N/A"); if (kirogi.currentVehicle) { if (kirogi.currentVehicle.gpsFix) { state = i18n("Got fix"); } else if (kirogi.currentVehicle.gpsSupported) { state = i18n("No fix"); } else { state = i18n("Not supported"); } } return i18n("GPS: %1", state) } color: { if (kirogi.connected) { if (kirogi.currentVehicle.gpsFix) { return Kirigami.Theme.positiveTextColor; } else if (kirogi.currentVehicle.gpsSupported) { return Kirigami.Theme.textColor; } } return Kirigami.Theme.disabledTextColor; } elide: Text.ElideRight } } } } } footer: QQC2.Button { text: { if (!kirogi.currentPlugin) { return i18n("Select Model"); } else if (kirogi.ready) { return i18n("Go to Flight Controls"); } return i18n("Try Flight Controls"); } onClicked: { if (!kirogi.currentPlugin) { pluginSheet.sheetOpen = !pluginSheet.sheetOpen; return; } switchApplicationPage(flightControlsPage); } } } }