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/QLoggingCategory>
6#include <QtCore/QMutex>
7
8Q_DECLARE_LOGGING_CATEGORY(MockLinkGimbalLog)
9
10class MockLink;
11
26{
27public:
28 explicit MockLinkGimbal(
29 MockLink *mockLink,
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);
37 ~MockLinkGimbal() = default;
38
40 void run1HzTasks();
41
45
46private:
49 bool _handleSetMessageInterval(const mavlink_command_long_t &request);
50
53 bool _handleRequestMessage(const mavlink_command_long_t &request);
54
57 bool _handleGimbalManagerPitchYaw(const mavlink_command_long_t &request);
58
61 bool _handleGimbalManagerConfigure(const mavlink_command_long_t &request);
62
63 void _sendGimbalManagerStatus();
64 void _sendGimbalDeviceAttitudeStatus();
65 void _sendGimbalManagerInformation();
66 void _sendCommandAck(uint16_t command, uint8_t result);
67
68 static constexpr uint8_t kGimbalCompId = MAV_COMP_ID_GIMBAL;
69 static constexpr int kDefaultIntervalUs = 1000000; // 1 Hz default
70
71 MockLink *_mockLink = nullptr;
72 int _managerStatusIntervalUs = 0; // 0 = disabled
73 int _deviceAttitudeStatusIntervalUs = 0; // 0 = disabled by default
74 qint64 _managerStatusLastSentMs = 0;
75 qint64 _deviceAttitudeStatusLastSentMs = 0;
76
77 // Simulated gimbal attitude (degrees)
78 float _roll = 0.0f;
79 float _pitch = 0.0f;
80 float _yaw = 0.0f;
81 bool _manualControl = false; // true when under external control command
86 QMutex _stateMutex;
87
88 // Gimbal manager configuration
89 uint8_t _gimbalManagerSysidPrimary = 0; // System ID for primary control
90 uint8_t _gimbalManagerCompidPrimary = 0; // Component ID for primary control
91 uint8_t _gimbalManagerSysidSecondary = 0; // System ID for secondary control
92 uint8_t _gimbalManagerCompidSecondary = 0; // Component ID for secondary control
93
94 // Gimbal capability flags
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;
102};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
struct __mavlink_message mavlink_message_t
~MockLinkGimbal()=default
void run1HzTasks()
Send periodic gimbal status messages (call from 1Hz tasks)
bool handleMavlinkMessage(const mavlink_message_t &msg)