17 Q_MOC_INCLUDE(
"QmlObjectListModel.h")
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);
44 Q_INVOKABLE
void sendGimbalRate(
float pitch_rate_deg_s,
float yaw_rate_deg_s);
60 void _initialConnectCompleted();
62 void _rateSenderTimeout();
66 GimbalPairId() =
default;
67 GimbalPairId(uint8_t _managerCompid, uint8_t _deviceId)
68 : managerCompid(_managerCompid)
69 , deviceId(_deviceId) {}
72 bool operator<(
const GimbalPairId &other)
const {
74 if (managerCompid < other.managerCompid) {
76 }
else if (managerCompid > other.managerCompid) {
78 }
else if (deviceId < other.deviceId) {
85 bool operator==(
const GimbalPairId &other)
const {
86 return (managerCompid == other.managerCompid) && (deviceId == other.deviceId);
89 uint8_t managerCompid = 0;
93 void _requestGimbalInformation(uint8_t compid);
98 void _checkComplete(
Gimbal &gimbal, GimbalPairId pairId);
99 bool _tryGetGimbalControl();
100 bool _yawInVehicleFrame(uint32_t flags);
102 void _sendGimbalAttitudeRates(
float pitch_rate_deg_s,
float yaw_rate_deg_s);
104 QTimer _rateSenderTimer;
106 Gimbal *_activeGimbal =
nullptr;
108 struct PotentialGimbalManager {
109 unsigned requestGimbalManagerInformationRetries = 6;
110 bool receivedGimbalManagerInformation =
false;
112 QMap<uint8_t, PotentialGimbalManager> _potentialGimbalManagers;
114 QMap<GimbalPairId, Gimbal*> _potentialGimbals;
116 bool _initialConnectComplete =
false;
118 static constexpr const char *_gimbalFactGroupNamePrefix =
"gimbal";
Q_INVOKABLE void gimbalOnScreenControl(float panpct, float tiltpct, bool clickAndPoint, bool clickAndDrag, bool rateControl, bool retract=false, bool neutral=false, bool yawlock=false)