|
| 1 | +/**************************************************************************** |
| 2 | + * |
| 3 | + * (c) 2009-2024 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> |
| 4 | + * |
| 5 | + * QGroundControl is licensed according to the terms in the file |
| 6 | + * COPYING.md in the root of the source code directory. |
| 7 | + * |
| 8 | + ****************************************************************************/ |
| 9 | + |
| 10 | +#pragma once |
| 11 | + |
| 12 | +#include <QtCore/QLoggingCategory> |
| 13 | + |
| 14 | +#include "FactGroup.h" |
| 15 | + |
| 16 | +Q_DECLARE_LOGGING_CATEGORY(GimbalLog) |
| 17 | + |
| 18 | +class GimbalController; |
| 19 | + |
| 20 | +class Gimbal : public FactGroup |
| 21 | +{ |
| 22 | + Q_OBJECT |
| 23 | + Q_PROPERTY(Fact *absoluteRoll READ absoluteRoll CONSTANT) |
| 24 | + Q_PROPERTY(Fact *absolutePitch READ absolutePitch CONSTANT) |
| 25 | + Q_PROPERTY(Fact *bodyYaw READ bodyYaw CONSTANT) |
| 26 | + Q_PROPERTY(Fact *absoluteYaw READ absoluteYaw CONSTANT) |
| 27 | + Q_PROPERTY(Fact *deviceId READ deviceId CONSTANT) |
| 28 | + Q_PROPERTY(Fact *managerCompid READ managerCompid CONSTANT) |
| 29 | + Q_PROPERTY(float pitchRate READ pitchRate CONSTANT) |
| 30 | + Q_PROPERTY(float yawRate READ yawRate CONSTANT) |
| 31 | + Q_PROPERTY(bool yawLock READ yawLock NOTIFY yawLockChanged) |
| 32 | + Q_PROPERTY(bool retracted READ retracted NOTIFY retractedChanged) |
| 33 | + Q_PROPERTY(bool gimbalHaveControl READ gimbalHaveControl NOTIFY gimbalHaveControlChanged) |
| 34 | + Q_PROPERTY(bool gimbalOthersHaveControl READ gimbalOthersHaveControl NOTIFY gimbalOthersHaveControlChanged) |
| 35 | + |
| 36 | + friend class GimbalController; ///< so it can set private members of gimbal, it is the only class that will need to modify them |
| 37 | + |
| 38 | +public: |
| 39 | + explicit Gimbal(GimbalController *parent = nullptr); |
| 40 | + Gimbal(const Gimbal &other); |
| 41 | + ~Gimbal(); |
| 42 | + const Gimbal &operator=(const Gimbal &other); |
| 43 | + |
| 44 | + Fact *absoluteRoll() { return &_absoluteRollFact; } |
| 45 | + Fact *absolutePitch() { return &_absolutePitchFact; } |
| 46 | + Fact *bodyYaw() { return &_bodyYawFact; } |
| 47 | + Fact *absoluteYaw() { return &_absoluteYawFact; } |
| 48 | + Fact *deviceId() { return &_deviceIdFact; } |
| 49 | + Fact *managerCompid() { return &_managerCompidFact; } |
| 50 | + float pitchRate() const { return _pitchRate; } |
| 51 | + float yawRate() const { return _yawRate; } |
| 52 | + bool yawLock() const { return _yawLock; } |
| 53 | + bool retracted() const { return _retracted; } |
| 54 | + bool gimbalHaveControl() const { return _haveControl; } |
| 55 | + bool gimbalOthersHaveControl() const { return _othersHaveControl; } |
| 56 | + |
| 57 | + void setAbsoluteRoll(float absoluteRoll) { _absoluteRollFact.setRawValue(absoluteRoll); } |
| 58 | + void setAbsolutePitch(float absolutePitch) { _absolutePitchFact.setRawValue(absolutePitch); } |
| 59 | + void setBodyYaw(float bodyYaw) { _bodyYawFact.setRawValue(bodyYaw); } |
| 60 | + void setAbsoluteYaw(float absoluteYaw) { _absoluteYawFact.setRawValue(absoluteYaw); } |
| 61 | + void setDeviceId(uint id) { _deviceIdFact.setRawValue(id); } |
| 62 | + void setManagerCompid(uint id) { _managerCompidFact.setRawValue(id); } |
| 63 | + void setPitchRate(float pitchRate) { _pitchRate = pitchRate; } |
| 64 | + void setYawRate(float yawRate) { _yawRate = yawRate; } |
| 65 | + void setYawLock(bool yawLock) { _yawLock = yawLock; emit yawLockChanged(); } |
| 66 | + void setRetracted(bool retracted) { _retracted = retracted; emit retractedChanged(); } |
| 67 | + void setGimbalHaveControl(bool set) { _haveControl = set; emit gimbalHaveControlChanged(); } |
| 68 | + void setGimbalOthersHaveControl(bool set) { _othersHaveControl = set; emit gimbalOthersHaveControlChanged(); } |
| 69 | + |
| 70 | +signals: |
| 71 | + void yawLockChanged(); |
| 72 | + void retractedChanged(); |
| 73 | + void gimbalHaveControlChanged(); |
| 74 | + void gimbalOthersHaveControlChanged(); |
| 75 | + |
| 76 | +private: |
| 77 | + void _initFacts(); ///< To be called EXCLUSIVELY in Gimbal constructors |
| 78 | + |
| 79 | + /// Private members only accesed by friend class GimbalController |
| 80 | + unsigned _requestInformationRetries = 3; |
| 81 | + unsigned _requestStatusRetries = 6; |
| 82 | + unsigned _requestAttitudeRetries = 3; |
| 83 | + bool _receivedInformation = false; |
| 84 | + bool _receivedStatus = false; |
| 85 | + bool _receivedAttitude = false; |
| 86 | + bool _isComplete = false; |
| 87 | + bool _neutral = false; |
| 88 | + |
| 89 | + /// Q_PROPERTIES |
| 90 | + Fact _absoluteRollFact; |
| 91 | + Fact _absolutePitchFact; |
| 92 | + Fact _bodyYawFact; |
| 93 | + Fact _absoluteYawFact; |
| 94 | + Fact _deviceIdFact; ///< Component ID of gimbal device (or 1-6 for non-MAVLink gimbal) |
| 95 | + Fact _managerCompidFact; |
| 96 | + float _pitchRate = 0.f; |
| 97 | + float _yawRate = 0.f; |
| 98 | + bool _yawLock = false; |
| 99 | + bool _retracted = false; |
| 100 | + bool _haveControl = false; |
| 101 | + bool _othersHaveControl = false; |
| 102 | + |
| 103 | + /// Fact names |
| 104 | + static constexpr const char *_absoluteRollFactName = "gimbalRoll"; |
| 105 | + static constexpr const char *_absolutePitchFactName = "gimbalPitch"; |
| 106 | + static constexpr const char *_bodyYawFactName = "gimbalYaw"; |
| 107 | + static constexpr const char *_absoluteYawFactName = "gimbalAzimuth"; |
| 108 | + static constexpr const char *_deviceIdFactName = "deviceId"; |
| 109 | + static constexpr const char *_managerCompidFactName = "managerCompid"; |
| 110 | +}; |
0 commit comments