QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
GimbalController.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QTimer>
4#include <QtQmlIntegration/QtQmlIntegration>
5
6#include "Gimbal.h"
8
10class Vehicle;
11
12class GimbalController : public QObject
13{
14 Q_OBJECT
15 QML_ELEMENT
16 QML_UNCREATABLE("")
17 Q_MOC_INCLUDE("QmlObjectListModel.h")
18
20 Q_PROPERTY(QmlObjectListModel* gimbals READ gimbals CONSTANT)
21
22public:
23 GimbalController(Vehicle *vehicle);
25
26 Gimbal *activeGimbal() const { return _activeGimbal; }
27 QmlObjectListModel *gimbals() const { return _gimbals; }
28
29 void setActiveGimbal(Gimbal *gimbal);
30
31 void sendPitchYawFlags(uint32_t flags);
32 Q_INVOKABLE void gimbalOnScreenControl(float panpct, float tiltpct, bool clickAndPoint, bool clickAndDrag, bool rateControl, bool retract = false, bool neutral = false, bool yawlock = false);
33 Q_INVOKABLE void sendPitchBodyYaw(float pitch, float yaw, bool showError = true);
34 Q_INVOKABLE void sendPitchAbsoluteYaw(float pitch, float yaw, bool showError = true);
35 Q_INVOKABLE void setGimbalRetract(bool set);
36 Q_INVOKABLE void setGimbalYawLock(bool set);
37 Q_INVOKABLE void acquireGimbalControl();
38 Q_INVOKABLE void releaseGimbalControl();
39 Q_INVOKABLE void sendRate();
40
44 Q_INVOKABLE void sendGimbalRate(float pitch_rate_deg_s, float yaw_rate_deg_s);
45
46signals:
48 void showAcquireGimbalControlPopup(); // This triggers a popup in QML asking the user for aproval to take control
49
50public slots:
51 // These slots are conected with joysticks for button control
52 void gimbalYawLock(bool yawLock) { setGimbalYawLock(yawLock); }
53 Q_INVOKABLE void centerGimbal();
54 void gimbalPitchStart(int direction);
55 void gimbalYawStart(int direction);
56 void gimbalPitchStop();
57 void gimbalYawStop();
58
59private slots:
60 void _initialConnectCompleted();
61 void _mavlinkMessageReceived(const mavlink_message_t& message);
62 void _rateSenderTimeout();
63
64private:
65 struct GimbalPairId {
66 GimbalPairId() = default;
67 GimbalPairId(uint8_t _managerCompid, uint8_t _deviceId)
68 : managerCompid(_managerCompid)
69 , deviceId(_deviceId) {}
70
71 // In order to use this as a key, we need to implement <,
72 bool operator<(const GimbalPairId &other) const {
73 // We compare managerCompid primarily, if they are equal, we compare the deviceId
74 if (managerCompid < other.managerCompid) {
75 return true;
76 } else if (managerCompid > other.managerCompid) {
77 return false;
78 } else if (deviceId < other.deviceId) {
79 return true;
80 } else {
81 return false;
82 }
83 }
84
85 bool operator==(const GimbalPairId &other) const {
86 return (managerCompid == other.managerCompid) && (deviceId == other.deviceId);
87 }
88
89 uint8_t managerCompid = 0;
90 uint8_t deviceId = 0;
91 };
92
93 void _requestGimbalInformation(uint8_t compid);
94 void _handleHeartbeat(const mavlink_message_t &message);
95 void _handleGimbalManagerInformation(const mavlink_message_t &message);
96 void _handleGimbalManagerStatus(const mavlink_message_t &message);
97 void _handleGimbalDeviceAttitudeStatus(const mavlink_message_t &message);
98 void _checkComplete(Gimbal &gimbal, GimbalPairId pairId);
99 bool _tryGetGimbalControl();
100 bool _yawInVehicleFrame(uint32_t flags);
101
102 void _sendGimbalAttitudeRates(float pitch_rate_deg_s, float yaw_rate_deg_s);
103
104 QTimer _rateSenderTimer;
105 Vehicle *_vehicle = nullptr;
106 Gimbal *_activeGimbal = nullptr;
107
108 struct PotentialGimbalManager {
109 unsigned requestGimbalManagerInformationRetries = 6;
110 bool receivedGimbalManagerInformation = false;
111 };
112 QMap<uint8_t, PotentialGimbalManager> _potentialGimbalManagers; // key is compid
113
114 QMap<GimbalPairId, Gimbal*> _potentialGimbals;
115 QmlObjectListModel *_gimbals = nullptr;
116 bool _initialConnectComplete = false;
117
118 static constexpr const char *_gimbalFactGroupNamePrefix = "gimbal";
119};
struct __mavlink_message mavlink_message_t
void sendPitchYawFlags(uint32_t flags)
Q_INVOKABLE void sendGimbalRate(float pitch_rate_deg_s, float yaw_rate_deg_s)
Q_INVOKABLE void setGimbalYawLock(bool set)
QmlObjectListModel * gimbals() const
Q_INVOKABLE void centerGimbal()
Gimbal * activeGimbal() const
void activeGimbalChanged()
Q_INVOKABLE void sendRate()
Q_INVOKABLE void sendPitchAbsoluteYaw(float pitch, float yaw, bool showError=true)
void gimbalYawLock(bool yawLock)
Q_INVOKABLE void gimbalOnScreenControl(float panpct, float tiltpct, bool clickAndPoint, bool clickAndDrag, bool rateControl, bool retract=false, bool neutral=false, bool yawlock=false)
Q_INVOKABLE void acquireGimbalControl()
void setActiveGimbal(Gimbal *gimbal)
void gimbalYawStart(int direction)
Q_INVOKABLE void setGimbalRetract(bool set)
void showAcquireGimbalControlPopup()
void gimbalPitchStart(int direction)
Q_INVOKABLE void releaseGimbalControl()
Q_INVOKABLE void sendPitchBodyYaw(float pitch, float yaw, bool showError=true)
Definition Gimbal.h:9