QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MockLinkGimbal.cc
Go to the documentation of this file.
1#include "MockLinkGimbal.h"
2#include "MockLink.h"
5
6#include <QtCore/QDateTime>
7#include <QtMath>
8
9QGC_LOGGING_CATEGORY(MockLinkGimbalLog, "Comms.MockLink.MockLinkGimbal")
10
12 MockLink *mockLink,
13 bool hasRollAxis,
14 bool hasPitchAxis,
15 bool hasYawAxis,
16 bool hasYawFollow,
17 bool hasYawLock,
18 bool hasRetract,
19 bool hasNeutral)
20 : _mockLink(mockLink)
21 , _hasRollAxis(hasRollAxis)
22 , _hasPitchAxis(hasPitchAxis)
23 , _hasYawAxis(hasYawAxis)
24 , _hasYawFollow(hasYawFollow)
25 , _hasYawLock(hasYawLock)
26 , _hasRetract(hasRetract)
27 , _hasNeutral(hasNeutral)
28{
29}
30
32{
33 // Runs every 1s (1Hz on worker thread). Reads intervals and gimbal state main thread modifies.
34 // Must serialize access to prevent:
35 // - Auto-movement overwriting manual control commands
36 // - Reading stale/inconsistent interval values for status transmission
37 QMutexLocker locker(&_stateMutex);
38 const qint64 nowMs = QDateTime::currentMSecsSinceEpoch();
39
40 // Send GIMBAL_MANAGER_STATUS if interval is set
41 if (_managerStatusIntervalUs > 0) {
42 const qint64 intervalMs = _managerStatusIntervalUs / 1000;
43 if ((nowMs - _managerStatusLastSentMs) >= intervalMs) {
44 _sendGimbalManagerStatus();
45 _managerStatusLastSentMs = nowMs;
46 }
47 }
48
49 // Send GIMBAL_DEVICE_ATTITUDE_STATUS if interval is set
50 if (_deviceAttitudeStatusIntervalUs > 0) {
51 const qint64 intervalMs = _deviceAttitudeStatusIntervalUs / 1000;
52 if ((nowMs - _deviceAttitudeStatusLastSentMs) >= intervalMs) {
53 // Only simulate automatic movement if not under manual control
54 if (!_manualControl) {
55 // Simulate simple gimbal movement (slow sine wave)
56 const qint64 secondsSinceEpoch = nowMs / 1000;
57 _pitch = 10.0f * qSin(secondsSinceEpoch * 0.1); // ±10° pitch oscillation
58 _yaw = 15.0f * qCos(secondsSinceEpoch * 0.15); // ±15° yaw oscillation
59 }
60
61 _sendGimbalDeviceAttitudeStatus();
62 _deviceAttitudeStatusLastSentMs = nowMs;
63 }
64 }
65}
66
68{
69 if (msg.msgid != MAVLINK_MSG_ID_COMMAND_LONG) {
70 return false;
71 }
72
73 mavlink_command_long_t request{};
74 mavlink_msg_command_long_decode(&msg, &request);
75
76 // Handle gimbal-specific commands
77 switch (request.command) {
78 case MAV_CMD_SET_MESSAGE_INTERVAL:
79 if (_handleSetMessageInterval(request)) {
80 _sendCommandAck(request.command, MAV_RESULT_ACCEPTED);
81 return true;
82 }
83 return false;
84
85 case MAV_CMD_REQUEST_MESSAGE:
86 if (_handleRequestMessage(request)) {
87 _sendCommandAck(request.command, MAV_RESULT_ACCEPTED);
88 return true;
89 }
90 return false;
91
92 case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW:
93 if (_handleGimbalManagerPitchYaw(request)) {
94 _sendCommandAck(request.command, MAV_RESULT_ACCEPTED);
95 return true;
96 }
97 _sendCommandAck(request.command, MAV_RESULT_DENIED);
98 return true;
99
100 case MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE:
101 if (_handleGimbalManagerConfigure(request)) {
102 _sendCommandAck(request.command, MAV_RESULT_ACCEPTED);
103 return true;
104 }
105 _sendCommandAck(request.command, MAV_RESULT_DENIED);
106 return true;
107
108 default:
109 return false;
110 }
111}
112
113void MockLinkGimbal::_sendCommandAck(uint16_t command, uint8_t result)
114{
115 QString commandName = MissionCommandTree::instance()->rawName(static_cast<MAV_CMD>(command));
116 qCDebug(MockLinkGimbalLog) << "Sending command ACK -" << QString("%1(%2)").arg(commandName).arg(command) << "result:" << (result == MAV_RESULT_ACCEPTED ? "ACCEPTED" : result == MAV_RESULT_DENIED ? "DENIED" : QString::number(result));
117
118 mavlink_message_t msg{};
119 (void) mavlink_msg_command_ack_pack_chan(
120 _mockLink->vehicleId(),
121 MAV_COMP_ID_AUTOPILOT1,
122 _mockLink->mavlinkChannel(),
123 &msg,
124 command,
125 result,
126 0, // progress
127 0, // result_param2
128 0, // target_system
129 0 // target_component
130 );
131 _mockLink->respondWithMavlinkMessage(msg);
132}
133
134bool MockLinkGimbal::_handleSetMessageInterval(const mavlink_command_long_t &request)
135{
136 const int msgId = static_cast<int>(request.param1);
137 const int intervalUs = static_cast<int>(request.param2);
138 const mavlink_message_info_t* info = mavlink_get_message_info_by_id(static_cast<uint32_t>(msgId));
139 QString msgName = info ? info->name : QString::number(msgId);
140
141 qCDebug(MockLinkGimbalLog) << "SET_MESSAGE_INTERVAL -" << QString("%1(%2)").arg(msgName).arg(msgId) << "intervalUs:" << intervalUs;
142
143 // Handle interval values per MAVLink spec:
144 // -1 = disable
145 // 0 = default rate
146 // >0 = interval in microseconds
147 int effectiveInterval = intervalUs;
148 if (intervalUs == 0) {
149 effectiveInterval = kDefaultIntervalUs;
150 } else if (intervalUs < -1) {
151 // Invalid interval
152 return false;
153 }
154
155 // Thread-safe access: Main thread writing interval while worker thread reads every 1s.
156 // Serialize to avoid worker using stale interval for message transmission logic.
157 QMutexLocker locker(&_stateMutex);
158 if (msgId == MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS) {
159 _managerStatusIntervalUs = effectiveInterval;
160 qCDebug(MockLinkGimbalLog) << msgName << "interval set to" << effectiveInterval << "us";
161 return true;
162 } else if (msgId == MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS) {
163 _deviceAttitudeStatusIntervalUs = effectiveInterval;
164 qCDebug(MockLinkGimbalLog) << msgName << "interval set to" << effectiveInterval << "us";
165 return true;
166 }
167 return false;
168}
169
170bool MockLinkGimbal::_handleRequestMessage(const mavlink_command_long_t &request)
171{
172 const int msgId = static_cast<int>(request.param1);
173 const mavlink_message_info_t* info = mavlink_get_message_info_by_id(static_cast<uint32_t>(msgId));
174 QString msgName = info ? info->name : QString::number(msgId);
175
176 if (msgId == MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION) {
177 qCDebug(MockLinkGimbalLog) << "REQUEST_MESSAGE -" << QString("%1(%2)").arg(msgName).arg(msgId);
178 _sendGimbalManagerInformation();
179 return true;
180 }
181
182 return false;
183}
184
185bool MockLinkGimbal::_handleGimbalManagerPitchYaw(const mavlink_command_long_t &request)
186{
187 // param1: pitch angle (degrees, positive: down, negative: up)
188 // param2: yaw angle (degrees, positive: to the right, negative: to the left)
189 // param3: pitch rate (deg/s)
190 // param4: yaw rate (deg/s)
191 // param5: flags (GIMBAL_MANAGER_FLAGS)
192 // param7: gimbal device id
193
194 const float requestedPitch = request.param1;
195 const float requestedYaw = request.param2;
196 const uint32_t flags = static_cast<uint32_t>(request.param5);
197
198 qCDebug(MockLinkGimbalLog) << "DO_GIMBAL_MANAGER_PITCHYAW - pitch:" << requestedPitch << "yaw:" << requestedYaw << "flags:" << flags;
199
200 // Check if this is a valid request (NaN means no change requested)
201 const bool updatePitch = !qIsNaN(requestedPitch);
202 const bool updateYaw = !qIsNaN(requestedYaw);
203
204 if (!updatePitch && !updateYaw) {
205 qCDebug(MockLinkGimbalLog) << "DO_GIMBAL_MANAGER_PITCHYAW - no valid pitch/yaw requested (both NaN)";
206 return false; // Nothing to do
207 }
208
209 // Thread-safe access: Main thread setting manual control state that worker reads every 1s.
210 // Without lock: Worker could read _manualControl=false and auto-update pitch/yaw after main
211 // sets them to manual values, overwriting the manual control with auto-movement.
212 QMutexLocker locker(&_stateMutex);
213 // Apply limits based on gimbal capabilities
214 if (updatePitch && _hasPitchAxis) {
215 _pitch = qBound(-45.0f, requestedPitch, 45.0f);
216 _manualControl = true; // Switch to manual control mode
217 }
218
219 if (updateYaw && _hasYawAxis) {
220 // Handle yaw lock/follow modes
221 if (flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK) {
222 // Yaw lock mode - maintain absolute yaw
223 _yaw = qBound(-180.0f, requestedYaw, 180.0f);
224 } else {
225 // Follow mode - yaw relative to vehicle
226 _yaw = qBound(-180.0f, requestedYaw, 180.0f);
227 }
228 _manualControl = true; // Switch to manual control mode
229 }
230
231 qCDebug(MockLinkGimbalLog) << "Gimbal commanded to pitch:" << _pitch << "yaw:" << _yaw << "- switched to manual control";
232 return true;
233}
234
235bool MockLinkGimbal::_handleGimbalManagerConfigure(const mavlink_command_long_t &request)
236{
237 // param1: sysid primary control (0: no change)
238 // param2: compid primary control (0: no change)
239 // param3: sysid secondary control (0: no change)
240 // param4: compid secondary control (0: no change)
241 // param7: gimbal device id
242
243 const uint8_t sysidPrimary = static_cast<uint8_t>(request.param1);
244 const uint8_t compidPrimary = static_cast<uint8_t>(request.param2);
245 const uint8_t sysidSecondary = static_cast<uint8_t>(request.param3);
246 const uint8_t compidSecondary = static_cast<uint8_t>(request.param4);
247
248 if (sysidPrimary > 0) {
249 _gimbalManagerSysidPrimary = sysidPrimary;
250 }
251 if (compidPrimary > 0) {
252 _gimbalManagerCompidPrimary = compidPrimary;
253 }
254 if (sysidSecondary > 0) {
255 _gimbalManagerSysidSecondary = sysidSecondary;
256 }
257 if (compidSecondary > 0) {
258 _gimbalManagerCompidSecondary = compidSecondary;
259 }
260
261 qCDebug(MockLinkGimbalLog) << "Gimbal manager configured - Primary:" << _gimbalManagerSysidPrimary
262 << "/" << _gimbalManagerCompidPrimary
263 << "Secondary:" << _gimbalManagerSysidSecondary
264 << "/" << _gimbalManagerCompidSecondary;
265 return true;
266}
267
268void MockLinkGimbal::_sendGimbalManagerStatus()
269{
270 qCDebug(MockLinkGimbalLog) << "Sending GIMBAL_MANAGER_STATUS";
271
272 mavlink_message_t msg{};
273 (void) mavlink_msg_gimbal_manager_status_pack_chan(
274 _mockLink->vehicleId(),
275 MAV_COMP_ID_AUTOPILOT1,
276 _mockLink->mavlinkChannel(),
277 &msg,
278 0, // time_boot_ms
279 0, // flags
280 kGimbalCompId, // gimbal_device_id
281 _gimbalManagerSysidPrimary,
282 _gimbalManagerCompidPrimary,
283 _gimbalManagerSysidSecondary,
284 _gimbalManagerCompidSecondary);
285 _mockLink->respondWithMavlinkMessage(msg);
286}
287
288void MockLinkGimbal::_sendGimbalDeviceAttitudeStatus()
289{
290 qCDebug(MockLinkGimbalLog) << "Sending GIMBAL_DEVICE_ATTITUDE_STATUS - pitch:" << _pitch << "yaw:" << _yaw << "manual:" << _manualControl;
291
292 // Convert Euler angles (degrees) to quaternion
293 const float rollRad = qDegreesToRadians(_roll);
294 const float pitchRad = qDegreesToRadians(_pitch);
295 const float yawRad = qDegreesToRadians(_yaw);
296
297 const float cy = qCos(yawRad * 0.5f);
298 const float sy = qSin(yawRad * 0.5f);
299 const float cp = qCos(pitchRad * 0.5f);
300 const float sp = qSin(pitchRad * 0.5f);
301 const float cr = qCos(rollRad * 0.5f);
302 const float sr = qSin(rollRad * 0.5f);
303
304 float q[4];
305 q[0] = cr * cp * cy + sr * sp * sy; // w
306 q[1] = sr * cp * cy - cr * sp * sy; // x
307 q[2] = cr * sp * cy + sr * cp * sy; // y
308 q[3] = cr * cp * sy - sr * sp * cy; // z
309
310 mavlink_message_t msg{};
311 (void) mavlink_msg_gimbal_device_attitude_status_pack_chan(
312 _mockLink->vehicleId(),
313 kGimbalCompId,
314 _mockLink->mavlinkChannel(),
315 &msg,
316 0, 0, // target system, component
317 0, // time_boot_ms
318 GIMBAL_DEVICE_FLAGS_NEUTRAL | GIMBAL_DEVICE_FLAGS_ROLL_LOCK | GIMBAL_DEVICE_FLAGS_PITCH_LOCK,
319 q,
320 0.0f, 0.0f, 0.0f, // angular_velocity_x, y, z
321 0, // failure flags
322 _pitch, _yaw, // delta_pitch, delta_yaw (Euler angles in degrees)
323 0); // gimbal_device_id = 0 means the device id is the same as the message component ID
324 _mockLink->respondWithMavlinkMessage(msg);
325}
326
327void MockLinkGimbal::_sendGimbalManagerInformation()
328{
329 // Build capability flags bitmask based on configuration
330 uint32_t capFlags = 0;
331 if (_hasRollAxis) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS;
332 if (_hasPitchAxis) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS;
333 if (_hasYawAxis) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS;
334 if (_hasYawFollow) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW;
335 if (_hasYawLock) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK;
336 if (_hasRetract) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT;
337 if (_hasNeutral) capFlags |= GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL;
338
339 qCDebug(MockLinkGimbalLog) << "Sending GIMBAL_MANAGER_INFORMATION - capFlags:" << QString::number(capFlags, 16);
340
341 mavlink_message_t msg{};
342 (void) mavlink_msg_gimbal_manager_information_pack_chan(
343 _mockLink->vehicleId(),
344 MAV_COMP_ID_AUTOPILOT1,
345 _mockLink->mavlinkChannel(),
346 &msg,
347 0, // time_boot_ms
348 capFlags,
349 kGimbalCompId,
350 -45, 45,
351 -45, 45,
352 -180, 180);
353 _mockLink->respondWithMavlinkMessage(msg);
354}
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
uint8_t mavlinkChannel() const
static MissionCommandTree * instance()
QString rawName(MAV_CMD command) const
Returns the raw name for the specified command.
void run1HzTasks()
Send periodic gimbal status messages (call from 1Hz tasks)
bool handleMavlinkMessage(const mavlink_message_t &msg)