File indexing completed on 2024-06-09 05:46:37
0001 /* 0002 * Copyright 2019 Eike Hein <hein@kde.org> 0003 * 0004 * This library is free software; you can redistribute it and/or 0005 * modify it under the terms of the GNU Lesser General Public 0006 * License as published by the Free Software Foundation; either 0007 * version 2.1 of the License, or (at your option) version 3, or any 0008 * later version accepted by the membership of KDE e.V. (or its 0009 * successor approved by the membership of KDE e.V.), which shall 0010 * act as a proxy defined in Section 6 of version 3 of the license. 0011 * 0012 * This library is distributed in the hope that it will be useful, 0013 * but WITHOUT ANY WARRANTY; without even the implied warranty of 0014 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 0015 * Lesser General Public License for more details. 0016 * 0017 * You should have received a copy of the GNU Lesser General Public 0018 * License along with this library. If not, see <http://www.gnu.org/licenses/>. 0019 */ 0020 0021 #pragma once 0022 0023 #include "abstractvehicle.h" 0024 0025 #include "parrotprotocol.h" 0026 0027 #include <QThread> 0028 0029 class ParrotConnection; 0030 0031 class ParrotVehicle : public Kirogi::AbstractVehicle 0032 { 0033 Q_OBJECT 0034 0035 public: 0036 enum Type { Bebop2 = 0, Anafi }; 0037 Q_ENUM(Type) 0038 0039 explicit ParrotVehicle(Type type, const QString &hostName, int port, const QString &productSerial, QObject *parent = nullptr); 0040 ~ParrotVehicle() override; 0041 0042 QString name() const override; 0043 QString iconName() const override; 0044 0045 Kirogi::AbstractVehicle::VehicleType vehicleType() const override; 0046 0047 QList<Kirogi::AbstractVehicle::VehicleAction> supportedActions() const override; 0048 0049 bool piloting() const override; 0050 Q_INVOKABLE void setPiloting(bool piloting) override; 0051 0052 Q_INVOKABLE void requestAction(Kirogi::AbstractVehicle::VehicleAction action) override; 0053 0054 Q_INVOKABLE void pilot(qint8 roll, qint8 pitch, qint8 yaw, qint8 gaz) override; 0055 Q_INVOKABLE void requestMoveTo(QGeoCoordinate destination) override; 0056 0057 Kirogi::AbstractVehicle::PerformanceMode performanceMode() const override; 0058 void requestPerformanceMode(Kirogi::AbstractVehicle::PerformanceMode mode) override; 0059 0060 float maxRollSpeed() const override; 0061 void requestMaxRollSpeed(float speed) override; 0062 float maxRollSpeedMin() const override; 0063 float maxRollSpeedMax() const override; 0064 0065 float maxPitchSpeed() const override; 0066 void requestMaxPitchSpeed(float speed) override; 0067 float maxPitchSpeedMin() const override; 0068 float maxPitchSpeedMax() const override; 0069 0070 float maxYawSpeed() const override; 0071 void requestMaxYawSpeed(float speed) override; 0072 float maxYawSpeedMin() const override; 0073 float maxYawSpeedMax() const override; 0074 0075 float maxGazSpeed() const override; 0076 void requestMaxGazSpeed(float speed) override; 0077 float maxGazSpeedMin() const override; 0078 float maxGazSpeedMax() const override; 0079 0080 float maxTilt() const override; 0081 void requestMaxTilt(float tilt) override; 0082 float maxTiltMin() const override; 0083 float maxTiltMax() const override; 0084 0085 bool bankedTurns() const override; 0086 void requestEnableBankedTurns(bool bankedTurns) override; 0087 0088 bool geofence() const override; 0089 void requestEnableGeofence(bool enable) override; 0090 0091 float maxAltitude() const override; 0092 void requestMaxAltitude(float altitude) override; 0093 float maxAltitudeMin() const override; 0094 float maxAltitudeMax() const override; 0095 0096 float maxDistance() const override; 0097 void requestMaxDistance(float distance) override; 0098 float maxDistanceMin() const override; 0099 float maxDistanceMax() const override; 0100 0101 float roll() const override; 0102 float pitch() const override; 0103 float yaw() const override; 0104 0105 int signalStrength() const override; 0106 int batteryLevel() const override; 0107 0108 bool gpsSupported() const override; 0109 bool gpsFix() const override; 0110 QGeoCoordinate gpsPosition() const override; 0111 float altitude() const override; 0112 void setControllerGpsPosition(const QGeoCoordinate &position) override; 0113 void requestReturnHome() override; 0114 0115 float speed() const override; 0116 0117 quint16 numberOfFlights() const override; 0118 quint16 lastFlightDuration() const override; 0119 0120 QString videoSource() const override; 0121 bool videoStreamEnabled() const override; 0122 Q_INVOKABLE void requestEnableVideoStream(bool enable) override; 0123 bool videoStabilization() const override; 0124 void requestEnableVideoStabilization(bool enable) override; 0125 bool canTakePicture() const override; 0126 bool isRecordingVideo() const override; 0127 0128 public Q_SLOTS: 0129 void connectToVehicle(); 0130 0131 private Q_SLOTS: 0132 void processIncomingCommand(const ParrotCommand &command); 0133 0134 private: 0135 void initVehicle(); 0136 void sendCommand(Parrot::Command command, const QVariantList &arguments = QVariantList(), bool retryForever = false); 0137 0138 Type m_type; 0139 0140 QString m_hostName; 0141 QString m_productSerial; 0142 0143 int m_initialized; 0144 0145 bool m_piloting; 0146 0147 float m_maxRollPitchSpeed; 0148 float m_maxRollPitchSpeedMin; 0149 float m_maxRollPitchSpeedMax; 0150 0151 float m_maxYawSpeed; 0152 float m_maxYawSpeedMin; 0153 float m_maxYawSpeedMax; 0154 0155 float m_maxGazSpeed; 0156 float m_maxGazSpeedMin; 0157 float m_maxGazSpeedMax; 0158 0159 float m_maxTilt; 0160 float m_maxTiltMin; 0161 float m_maxTiltMax; 0162 0163 bool m_bankedTurns; 0164 0165 bool m_geofence; 0166 0167 float m_maxAltitude; 0168 float m_maxAltitudeMin; 0169 float m_maxAltitudeMax; 0170 0171 float m_maxDistance; 0172 float m_maxDistanceMin; 0173 float m_maxDistanceMax; 0174 0175 float m_roll; 0176 float m_pitch; 0177 float m_yaw; 0178 0179 float m_defaultCameraOrientationTilt; 0180 float m_defaultCameraOrientationPan; 0181 0182 qint16 m_signalStrength; 0183 int m_batteryLevel; 0184 0185 bool m_gpsFix; 0186 QGeoCoordinate m_gpsPosition; 0187 float m_altitude; 0188 0189 float m_speed; 0190 0191 bool m_videoStreamEnabled; 0192 qint32 m_videoStreamMode; 0193 qint32 m_videoStabilizationMode; 0194 bool m_canTakePicture; 0195 bool m_isRecordingVideo; 0196 0197 quint16 m_numberOfFlights; 0198 quint16 m_lastFlightDuration; 0199 0200 QThread m_connectionThread; 0201 ParrotConnection *m_connection; 0202 };