30 bool hasRollAxis =
true,
31 bool hasPitchAxis =
true,
32 bool hasYawAxis =
true,
33 bool hasYawFollow =
true,
34 bool hasYawLock =
true,
35 bool hasRetract =
true,
36 bool hasNeutral =
true);
49 bool _handleSetMessageInterval(
const mavlink_command_long_t &request);
53 bool _handleRequestMessage(
const mavlink_command_long_t &request);
57 bool _handleGimbalManagerPitchYaw(
const mavlink_command_long_t &request);
61 bool _handleGimbalManagerConfigure(
const mavlink_command_long_t &request);
63 void _sendGimbalManagerStatus();
64 void _sendGimbalDeviceAttitudeStatus();
65 void _sendGimbalManagerInformation();
66 void _sendCommandAck(uint16_t command, uint8_t result);
68 static constexpr uint8_t kGimbalCompId = MAV_COMP_ID_GIMBAL;
69 static constexpr int kDefaultIntervalUs = 1000000;
72 int _managerStatusIntervalUs = 0;
73 int _deviceAttitudeStatusIntervalUs = 0;
74 qint64 _managerStatusLastSentMs = 0;
75 qint64 _deviceAttitudeStatusLastSentMs = 0;
81 bool _manualControl =
false;
89 uint8_t _gimbalManagerSysidPrimary = 0;
90 uint8_t _gimbalManagerCompidPrimary = 0;
91 uint8_t _gimbalManagerSysidSecondary = 0;
92 uint8_t _gimbalManagerCompidSecondary = 0;
95 bool _hasRollAxis =
true;
96 bool _hasPitchAxis =
true;
97 bool _hasYawAxis =
true;
98 bool _hasYawFollow =
true;
99 bool _hasYawLock =
true;
100 bool _hasRetract =
true;
101 bool _hasNeutral =
true;