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