File indexing completed on 2024-05-12 05:53:14
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 #include <memory> 0022 0023 #include "abstractvehicle.h" 0024 #include "debug.h" 0025 #include "parametermodel.h" 0026 0027 #include <QElapsedTimer> 0028 #include <QTimer> 0029 0030 namespace Kirogi 0031 { 0032 class Q_DECL_HIDDEN AbstractVehicle::Private 0033 { 0034 public: 0035 explicit Private(AbstractVehicle *q); 0036 ~Private(); 0037 0038 static int s_availableId; 0039 int id; 0040 AbstractVehicle::ConnectionState connectionState = AbstractVehicle::Disconnected; 0041 AbstractVehicle::FlyingState flyingState = AbstractVehicle::Unknown; 0042 0043 QElapsedTimer *flightTime = nullptr; 0044 std::unique_ptr<QTimer> flightTimeTimer; 0045 0046 ParameterModel parameters; 0047 0048 private: 0049 AbstractVehicle *m_q; 0050 }; 0051 0052 int AbstractVehicle::Private::s_availableId = 0; 0053 0054 AbstractVehicle::Private::Private(AbstractVehicle *q) 0055 : m_q(q) 0056 { 0057 id = s_availableId; 0058 ++s_availableId; 0059 } 0060 0061 AbstractVehicle::Private::~Private() 0062 { 0063 delete flightTime; 0064 } 0065 0066 AbstractVehicle::AbstractVehicle(QObject *parent) 0067 : QObject(parent) 0068 , d(new Private(this)) 0069 { 0070 } 0071 0072 AbstractVehicle::~AbstractVehicle() 0073 { 0074 } 0075 0076 int AbstractVehicle::id() const 0077 { 0078 return d->id; 0079 } 0080 0081 QString AbstractVehicle::iconName() const 0082 { 0083 return QStringLiteral("uav"); 0084 } 0085 0086 Kirogi::AbstractVehicle::VehicleType AbstractVehicle::vehicleType() const 0087 { 0088 return UnknownVehicleType; 0089 } 0090 0091 AbstractVehicle::ConnectionState AbstractVehicle::connectionState() const 0092 { 0093 return d->connectionState; 0094 } 0095 0096 void Kirogi::AbstractVehicle::setConnectionState(Kirogi::AbstractVehicle::ConnectionState state) 0097 { 0098 if (connectionState() != state) { 0099 qCDebug(KIROGI_CORE) << name() << "changed connection state to:" << state; 0100 d->connectionState = state; 0101 emit connectionStateChanged(); 0102 } 0103 } 0104 0105 Kirogi::AbstractVehicle::FlyingState AbstractVehicle::flyingState() const 0106 { 0107 return d->flyingState; 0108 } 0109 0110 void Kirogi::AbstractVehicle::setFlyingState(Kirogi::AbstractVehicle::FlyingState state) 0111 { 0112 if (flyingState() != state) { 0113 qCDebug(KIROGI_CORE) << name() << "changed flying state to:" << state; 0114 d->flyingState = state; 0115 emit flyingStateChanged(); 0116 0117 if (state > Landed) { 0118 if (!d->flightTime) { 0119 d->flightTime = new QElapsedTimer(); 0120 } 0121 0122 if (!d->flightTimeTimer) { 0123 d->flightTimeTimer = std::make_unique<QTimer>(this); 0124 QObject::connect(d->flightTimeTimer.get(), &QTimer::timeout, this, &AbstractVehicle::flightTimeChanged); 0125 d->flightTimeTimer->setTimerType(Qt::PreciseTimer); 0126 d->flightTimeTimer->setInterval(1000); 0127 } 0128 0129 d->flightTime->start(); 0130 d->flightTimeTimer->start(); 0131 } else { 0132 if (d->flightTime) { 0133 d->flightTime->invalidate(); 0134 } 0135 0136 if (d->flightTimeTimer) { 0137 d->flightTimeTimer->stop(); 0138 } 0139 } 0140 } 0141 } 0142 0143 bool AbstractVehicle::connected() const 0144 { 0145 return connectionState() >= Connected; 0146 } 0147 0148 bool AbstractVehicle::ready() const 0149 { 0150 return connectionState() >= Ready; 0151 } 0152 0153 bool AbstractVehicle::flying() const 0154 { 0155 return flyingState() >= TakingOff; 0156 } 0157 0158 QList<Kirogi::AbstractVehicle::VehicleAction> AbstractVehicle::supportedActions() const 0159 { 0160 return QList<VehicleAction>(); 0161 } 0162 0163 bool AbstractVehicle::isActionSupported(Kirogi::AbstractVehicle::VehicleAction action) const 0164 { 0165 return supportedActions().contains(action); 0166 } 0167 0168 bool AbstractVehicle::piloting() const 0169 { 0170 return false; 0171 } 0172 0173 void AbstractVehicle::setPiloting(bool piloting) 0174 { 0175 Q_UNUSED(piloting) 0176 } 0177 0178 int AbstractVehicle::flightTime() const 0179 { 0180 if (d->flightTime && d->flightTime->isValid()) { 0181 return d->flightTime->elapsed() / 1000; 0182 } 0183 0184 return 0; 0185 } 0186 0187 Kirogi::AbstractVehicle::PerformanceMode AbstractVehicle::performanceMode() const 0188 { 0189 return CustomPerformance; 0190 } 0191 0192 void AbstractVehicle::requestPerformanceMode(Kirogi::AbstractVehicle::PerformanceMode mode) 0193 { 0194 Q_UNUSED(mode) 0195 } 0196 0197 float AbstractVehicle::maxRollSpeed() const 0198 { 0199 return 0.0; 0200 } 0201 0202 void AbstractVehicle::requestMaxRollSpeed(float speed) 0203 { 0204 Q_UNUSED(speed) 0205 } 0206 0207 float AbstractVehicle::maxRollSpeedMin() const 0208 { 0209 return 0.0; 0210 } 0211 0212 float AbstractVehicle::maxRollSpeedMax() const 0213 { 0214 return 0.0; 0215 } 0216 0217 float AbstractVehicle::maxPitchSpeed() const 0218 { 0219 return 0.0; 0220 } 0221 0222 void AbstractVehicle::requestMaxPitchSpeed(float speed) 0223 { 0224 Q_UNUSED(speed) 0225 } 0226 0227 float AbstractVehicle::maxPitchSpeedMin() const 0228 { 0229 return 0.0; 0230 } 0231 0232 float AbstractVehicle::maxPitchSpeedMax() const 0233 { 0234 return 0.0; 0235 } 0236 0237 float AbstractVehicle::maxYawSpeed() const 0238 { 0239 return 0.0; 0240 } 0241 0242 void AbstractVehicle::requestMaxYawSpeed(float speed) 0243 { 0244 Q_UNUSED(speed) 0245 } 0246 0247 float AbstractVehicle::maxYawSpeedMin() const 0248 { 0249 return 0.0; 0250 } 0251 0252 float AbstractVehicle::maxYawSpeedMax() const 0253 { 0254 return 0.0; 0255 } 0256 0257 float AbstractVehicle::maxGazSpeed() const 0258 { 0259 return 0.0; 0260 } 0261 0262 void AbstractVehicle::requestMaxGazSpeed(float speed) 0263 { 0264 Q_UNUSED(speed) 0265 } 0266 0267 float AbstractVehicle::maxGazSpeedMin() const 0268 { 0269 return 0.0; 0270 } 0271 0272 float AbstractVehicle::maxGazSpeedMax() const 0273 { 0274 return 0.0; 0275 } 0276 0277 float AbstractVehicle::maxTilt() const 0278 { 0279 return 0.0; 0280 } 0281 0282 void AbstractVehicle::requestMaxTilt(float tilt) 0283 { 0284 Q_UNUSED(tilt) 0285 } 0286 0287 float AbstractVehicle::maxTiltMin() const 0288 { 0289 return 0.0; 0290 } 0291 0292 float AbstractVehicle::maxTiltMax() const 0293 { 0294 return 0.0; 0295 } 0296 0297 bool AbstractVehicle::bankedTurns() const 0298 { 0299 return false; 0300 } 0301 0302 void AbstractVehicle::requestEnableBankedTurns(bool enable) 0303 { 0304 Q_UNUSED(enable) 0305 } 0306 0307 bool AbstractVehicle::geofence() const 0308 { 0309 return false; 0310 } 0311 0312 void AbstractVehicle::requestEnableGeofence(bool enable) 0313 { 0314 Q_UNUSED(enable) 0315 } 0316 0317 float AbstractVehicle::maxAltitude() const 0318 { 0319 return 0.0; 0320 } 0321 0322 void AbstractVehicle::requestMaxAltitude(float altitude) 0323 { 0324 Q_UNUSED(altitude) 0325 } 0326 0327 float AbstractVehicle::maxAltitudeMin() const 0328 { 0329 return 0.0; 0330 } 0331 0332 float AbstractVehicle::maxAltitudeMax() const 0333 { 0334 return 0.0; 0335 } 0336 0337 float AbstractVehicle::maxDistance() const 0338 { 0339 return 0.0; 0340 } 0341 0342 void AbstractVehicle::requestMaxDistance(float distance) 0343 { 0344 Q_UNUSED(distance) 0345 } 0346 0347 float AbstractVehicle::maxDistanceMin() const 0348 { 0349 return 0.0; 0350 } 0351 0352 float AbstractVehicle::maxDistanceMax() const 0353 { 0354 return 0.0; 0355 } 0356 0357 void AbstractVehicle::requestAction(Kirogi::AbstractVehicle::VehicleAction action) 0358 { 0359 if (!ready()) { 0360 qCWarning(KIROGI_CORE) << name() << "Requested an action while not ready, aborting. Current connection state:" << connectionState(); 0361 return; 0362 } 0363 0364 qCDebug(KIROGI_CORE) << name() << "No implementation for action:" << action; 0365 } 0366 0367 void AbstractVehicle::requestTakeOff() 0368 { 0369 if (flying()) { 0370 qCWarning(KIROGI_CORE) << name() << "Requested to take off while flying, aborting. Current flying state:" << flyingState(); 0371 return; 0372 } 0373 0374 requestAction(TakeOff); 0375 } 0376 0377 void AbstractVehicle::requestLand() 0378 { 0379 if (!flying()) { 0380 qCWarning(KIROGI_CORE) << name() << "Requested to land while not flying, aborting. Current flying state:" << flyingState(); 0381 return; 0382 } 0383 0384 requestAction(Land); 0385 } 0386 0387 void AbstractVehicle::pilot(qint8 roll, qint8 pitch, qint8 yaw, qint8 gaz) 0388 { 0389 Q_UNUSED(roll) 0390 Q_UNUSED(pitch) 0391 Q_UNUSED(yaw) 0392 Q_UNUSED(gaz) 0393 } 0394 0395 void AbstractVehicle::requestMoveTo(QGeoCoordinate destination) 0396 { 0397 Q_UNUSED(destination) 0398 } 0399 0400 float AbstractVehicle::roll() const 0401 { 0402 return 0.0; 0403 } 0404 0405 float AbstractVehicle::pitch() const 0406 { 0407 return 0.0; 0408 } 0409 0410 float AbstractVehicle::yaw() const 0411 { 0412 return 0.0; 0413 } 0414 0415 int AbstractVehicle::signalStrength() const 0416 { 0417 return -1; 0418 } 0419 0420 int AbstractVehicle::batteryLevel() const 0421 { 0422 return -1; 0423 } 0424 0425 bool AbstractVehicle::gpsSupported() const 0426 { 0427 return false; 0428 } 0429 0430 bool AbstractVehicle::gpsFix() const 0431 { 0432 return false; 0433 } 0434 0435 QGeoCoordinate AbstractVehicle::gpsPosition() const 0436 { 0437 return QGeoCoordinate(); 0438 } 0439 0440 float AbstractVehicle::altitude() const 0441 { 0442 return 0.0; 0443 } 0444 0445 float AbstractVehicle::distance() const 0446 { 0447 return -1.0; 0448 } 0449 0450 void AbstractVehicle::setControllerGpsPosition(const QGeoCoordinate &position) 0451 { 0452 Q_UNUSED(position) 0453 } 0454 0455 void AbstractVehicle::requestReturnHome() 0456 { 0457 } 0458 0459 float AbstractVehicle::speed() const 0460 { 0461 return 0.0; 0462 } 0463 0464 QString AbstractVehicle::videoSource() const 0465 { 0466 return QString(); 0467 } 0468 0469 bool AbstractVehicle::videoStreamEnabled() const 0470 { 0471 return false; 0472 } 0473 0474 void AbstractVehicle::requestEnableVideoStream(bool enable) 0475 { 0476 Q_UNUSED(enable) 0477 0478 qCWarning(KIROGI_CORE) << name() << "Enabling video streaming is not supported."; 0479 } 0480 0481 bool AbstractVehicle::videoStabilization() const 0482 { 0483 return false; 0484 } 0485 0486 void AbstractVehicle::requestEnableVideoStabilization(bool enable) 0487 { 0488 Q_UNUSED(enable) 0489 } 0490 0491 bool AbstractVehicle::canTakePicture() const 0492 { 0493 return false; 0494 } 0495 0496 bool AbstractVehicle::isRecordingVideo() const 0497 { 0498 return false; 0499 } 0500 0501 quint16 AbstractVehicle::numberOfFlights() const 0502 { 0503 return 0; 0504 } 0505 0506 quint16 AbstractVehicle::lastFlightDuration() const 0507 { 0508 return 0; 0509 } 0510 0511 ParameterModel *AbstractVehicle::parameters() 0512 { 0513 return &d->parameters; 0514 } 0515 0516 }