QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MockLinkGimbal.h
Go to the documentation of this file.
1#pragma once
2
3#include "MAVLinkLib.h"
4
5#include <QtCore/QMutex>
6
7class MockLink;
8
24{
25public:
26 explicit MockLinkGimbal(
27 MockLink *mockLink,
28 bool hasRollAxis = true,
29 bool hasPitchAxis = true,
30 bool hasYawAxis = true,
31 bool hasYawFollow = true,
32 bool hasYawLock = true,
33 bool hasRetract = true,
34 bool hasNeutral = true);
35 ~MockLinkGimbal() = default;
36
38 void run1HzTasks();
39
43
44private:
47 bool _handleSetMessageInterval(const mavlink_command_long_t &request);
48
51 bool _handleRequestMessage(const mavlink_command_long_t &request);
52
55 bool _handleGimbalManagerPitchYaw(const mavlink_command_long_t &request);
56
59 bool _handleGimbalManagerConfigure(const mavlink_command_long_t &request);
60
61 void _sendGimbalManagerStatus();
62 void _sendGimbalDeviceAttitudeStatus();
63 void _sendGimbalManagerInformation();
64 void _sendCommandAck(uint16_t command, uint8_t result);
65
66 static constexpr uint8_t kGimbalCompId = MAV_COMP_ID_GIMBAL;
67 static constexpr int kDefaultIntervalUs = 1000000; // 1 Hz default
68
69 MockLink *_mockLink = nullptr;
70 int _managerStatusIntervalUs = 0; // 0 = disabled
71 int _deviceAttitudeStatusIntervalUs = 0; // 0 = disabled by default
72 qint64 _managerStatusLastSentMs = 0;
73 qint64 _deviceAttitudeStatusLastSentMs = 0;
74
75 // Simulated gimbal attitude (degrees)
76 float _roll = 0.0f;
77 float _pitch = 0.0f;
78 float _yaw = 0.0f;
79 bool _manualControl = false; // true when under external control command
84 QMutex _stateMutex;
85
86 // Gimbal manager configuration
87 uint8_t _gimbalManagerSysidPrimary = 0; // System ID for primary control
88 uint8_t _gimbalManagerCompidPrimary = 0; // Component ID for primary control
89 uint8_t _gimbalManagerSysidSecondary = 0; // System ID for secondary control
90 uint8_t _gimbalManagerCompidSecondary = 0; // Component ID for secondary control
91
92 // Gimbal capability flags
93 bool _hasRollAxis = true;
94 bool _hasPitchAxis = true;
95 bool _hasYawAxis = true;
96 bool _hasYawFollow = true;
97 bool _hasYawLock = true;
98 bool _hasRetract = true;
99 bool _hasNeutral = true;
100};
struct __mavlink_message mavlink_message_t
struct __mavlink_command_long_t mavlink_command_long_t
Simulates MAVLink Gimbal Manager Protocol for MockLink.
~MockLinkGimbal()=default
void run1HzTasks()
Send periodic gimbal status messages (call from 1Hz tasks)
bool handleMavlinkMessage(const mavlink_message_t &msg)