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