QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
Gimbal.h
Go to the documentation of this file.
1#pragma once
2
3#include "FactGroup.h"
4#include "MAVLinkEnums.h"
5
7
8class Gimbal : public FactGroup
9{
10 Q_OBJECT
11 Q_PROPERTY(Fact *absoluteRoll READ absoluteRoll CONSTANT)
12 Q_PROPERTY(Fact *absolutePitch READ absolutePitch CONSTANT)
13 Q_PROPERTY(Fact *bodyYaw READ bodyYaw CONSTANT)
14 Q_PROPERTY(Fact *absoluteYaw READ absoluteYaw CONSTANT)
15 Q_PROPERTY(Fact *deviceId READ deviceId CONSTANT)
16 Q_PROPERTY(Fact *managerCompid READ managerCompid CONSTANT)
17 Q_PROPERTY(float pitchRate READ pitchRate NOTIFY pitchRateChanged)
18 Q_PROPERTY(float yawRate READ yawRate NOTIFY yawRateChanged)
19 Q_PROPERTY(bool yawLock READ yawLock NOTIFY yawLockChanged)
20 Q_PROPERTY(bool retracted READ retracted NOTIFY retractedChanged)
23 Q_PROPERTY(bool supportsRetract READ supportsRetract NOTIFY capabilityFlagsChanged)
24 Q_PROPERTY(bool supportsYawLock READ supportsYawLock NOTIFY capabilityFlagsChanged)
25
26 friend class GimbalController;
27
28public:
29 Gimbal(GimbalController *parent);
30 Gimbal(const Gimbal &other);
31 const Gimbal &operator=(const Gimbal &other);
32 ~Gimbal();
33
34 Fact *absoluteRoll() { return &_absoluteRollFact; }
35 Fact *absolutePitch() { return &_absolutePitchFact; }
36 Fact *bodyYaw() { return &_bodyYawFact; }
37 Fact *absoluteYaw() { return &_absoluteYawFact; }
38 Fact *deviceId() { return &_deviceIdFact; }
39 Fact *managerCompid() { return &_managerCompidFact; }
40
41 float pitchRate() const { return _pitchRate; }
42 float yawRate() const { return _yawRate; }
43 bool yawLock() const { return _yawLock; }
44 bool retracted() const { return _retracted; }
45 bool gimbalHaveControl() const { return _haveControl; }
46 bool gimbalOthersHaveControl() const { return _othersHaveControl; }
47
48 void setAbsoluteRoll(float absRoll) { absoluteRoll()->setRawValue(absRoll); }
49 void setAbsolutePitch(float absPitch) { absolutePitch()->setRawValue(absPitch); }
50 void setBodyYaw(float yaw) { bodyYaw()->setRawValue(yaw); }
51 void setAbsoluteYaw(float absYaw) { absoluteYaw()->setRawValue(absYaw); }
52 void setDeviceId(uint id) { deviceId()->setRawValue(id); }
53 void setManagerCompid(uint id) { managerCompid()->setRawValue(id); }
54
55 void setPitchRate(float pitchRate) { if (pitchRate != _pitchRate) { _pitchRate = pitchRate; emit pitchRateChanged(); } }
56 void setYawRate(float yawRate) { if (yawRate != _yawRate) { _yawRate = yawRate; emit yawRateChanged(); } }
57 void setYawLock(bool yawLock) { if (yawLock != _yawLock) { _yawLock = yawLock; emit yawLockChanged(); } }
58 void setRetracted(bool retracted) { if (retracted != _retracted) { _retracted = retracted; emit retractedChanged(); } }
59 void setGimbalHaveControl(bool set) { if (set != _haveControl) { _haveControl = set; emit gimbalHaveControlChanged(); } }
60 void setGimbalOthersHaveControl(bool set) { if (set != _othersHaveControl) { _othersHaveControl = set; emit gimbalOthersHaveControlChanged(); } }
61
62 void setCapabilityFlags(uint32_t flags);
63 bool supportsRetract() const { return (_capabilityFlags & GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT) != 0; }
64 bool supportsYawLock() const { return (_capabilityFlags & GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK) != 0; }
65
66signals:
74
75private:
76 void _initFacts();
77
78 unsigned _requestInformationRetries = 3;
79 unsigned _requestStatusRetries = 6;
80 unsigned _requestAttitudeRetries = 3;
81 bool _receivedGimbalManagerInformation = false;
82 bool _receivedGimbalManagerStatus = false;
83 bool _receivedGimbalDeviceAttitudeStatus = false;
84 bool _isComplete = false;
85 bool _neutral = false;
86 uint32_t _capabilityFlags = 0; // GIMBAL_MANAGER_CAP_FLAGS
87
88 Fact _absoluteRollFact = Fact(0, QStringLiteral("gimbalRoll"), FactMetaData::valueTypeFloat);
89 Fact _absolutePitchFact = Fact(0, QStringLiteral("gimbalPitch"), FactMetaData::valueTypeFloat);
90 Fact _bodyYawFact = Fact(0, QStringLiteral("gimbalYaw"), FactMetaData::valueTypeFloat);
91 Fact _absoluteYawFact = Fact(0, QStringLiteral("gimbalAzimuth"), FactMetaData::valueTypeFloat);
92 Fact _deviceIdFact = Fact(0, QStringLiteral("deviceId"), FactMetaData::valueTypeUint8);
93 Fact _managerCompidFact = Fact(0, QStringLiteral("managerCompid"), FactMetaData::valueTypeUint8);
94
95 float _pitchRate = 0.f;
96 float _yawRate = 0.f;
97 bool _yawLock = false;
98 bool _retracted = false;
99 bool _haveControl = false;
100 bool _othersHaveControl = false;
101};
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:16
A Fact is used to hold a single value within the system.
Definition Fact.h:17
void setRawValue(const QVariant &value)
Definition Fact.cc:128
Definition Gimbal.h:9
void yawRateChanged()
void setAbsolutePitch(float absPitch)
Definition Gimbal.h:49
void gimbalHaveControlChanged()
float pitchRate() const
Definition Gimbal.h:41
void setYawLock(bool yawLock)
Definition Gimbal.h:57
void setPitchRate(float pitchRate)
Definition Gimbal.h:55
Fact * absolutePitch()
Definition Gimbal.h:35
bool yawLock() const
Definition Gimbal.h:43
void setManagerCompid(uint id)
Definition Gimbal.h:53
bool supportsRetract() const
Definition Gimbal.h:63
Fact * managerCompid()
Definition Gimbal.h:39
Fact * deviceId()
Definition Gimbal.h:38
void setAbsoluteYaw(float absYaw)
Definition Gimbal.h:51
void setYawRate(float yawRate)
Definition Gimbal.h:56
bool gimbalOthersHaveControl() const
Definition Gimbal.h:46
void setGimbalHaveControl(bool set)
Definition Gimbal.h:59
void setBodyYaw(float yaw)
Definition Gimbal.h:50
void pitchRateChanged()
void setDeviceId(uint id)
Definition Gimbal.h:52
void setRetracted(bool retracted)
Definition Gimbal.h:58
void retractedChanged()
Fact * absoluteRoll()
Definition Gimbal.h:34
void capabilityFlagsChanged()
Fact * absoluteYaw()
Definition Gimbal.h:37
void yawLockChanged()
bool supportsYawLock() const
Definition Gimbal.h:64
bool gimbalHaveControl() const
Definition Gimbal.h:45
bool retracted() const
Definition Gimbal.h:44
void setAbsoluteRoll(float absRoll)
Definition Gimbal.h:48
void gimbalOthersHaveControlChanged()
void setGimbalOthersHaveControl(bool set)
Definition Gimbal.h:60
float yawRate() const
Definition Gimbal.h:42
void setCapabilityFlags(uint32_t flags)
Definition Gimbal.cc:69
Fact * bodyYaw()
Definition Gimbal.h:36