QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
GimbalController.cc
Go to the documentation of this file.
1#include "GimbalController.h"
3#include "MAVLinkProtocol.h"
4#include "ParameterManager.h"
7#include "SettingsManager.h"
8#include "Vehicle.h"
9#include <cmath>
10#include "Gimbal.h"
11#include "QGCCameraManager.h"
12
13QGC_LOGGING_CATEGORY(GimbalControllerLog, "Gimbal.GimbalController")
14
16 : QObject(vehicle)
17 , _vehicle(vehicle)
18 , _gimbals(new QmlObjectListModel(this))
19{
20 qCDebug(GimbalControllerLog) << this;
21
22 (void) connect(_vehicle, &Vehicle::initialConnectComplete, this, &GimbalController::_initialConnectCompleted, Qt::UniqueConnection);
23 (void) connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &GimbalController::_mavlinkMessageReceived);
24
25 _rateSenderTimer.setInterval(500);
26 (void) connect(&_rateSenderTimer, &QTimer::timeout, this, &GimbalController::_rateSenderTimeout);
27}
28
29GimbalController::~GimbalController()
30{
31 qCDebug(GimbalControllerLog) << this;
32}
33
34void GimbalController::_initialConnectCompleted()
35{
36 _initialConnectComplete = true;
37}
38
39void GimbalController::setActiveGimbal(Gimbal *gimbal)
40{
41 if (!gimbal) {
42 qCDebug(GimbalControllerLog) << "Set active gimbal: attempted to set a nullptr, returning";
43 return;
44 }
45
46 if (gimbal != _activeGimbal) {
47 qCDebug(GimbalControllerLog) << "Set active gimbal:" << gimbal;
48 _activeGimbal = gimbal;
50 }
51}
52
53void GimbalController::_mavlinkMessageReceived(const mavlink_message_t &message)
54{
55 if (!_initialConnectComplete) {
56 return;
57 }
58
59 switch (message.msgid) {
60 case MAVLINK_MSG_ID_HEARTBEAT:
61 _handleHeartbeat(message);
62 break;
63 case MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION:
64 _handleGimbalManagerInformation(message);
65 break;
66 case MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS:
67 _handleGimbalManagerStatus(message);
68 break;
69 case MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS:
70 _handleGimbalDeviceAttitudeStatus(message);
71 break;
72 default:
73 break;
74 }
75}
76
77void GimbalController::_handleHeartbeat(const mavlink_message_t &message)
78{
79 if (!_potentialGimbalManagers.contains(message.compid)) {
80 qCDebug(GimbalControllerLog) << "new potential gimbal manager component:" << message.compid;
81 }
82
83 PotentialGimbalManager &gimbalManager = _potentialGimbalManagers[message.compid];
84
85 // Note that we are working over potential gimbal managers here, instead of potential gimbals.
86 // This is because we address the gimbal manager by compid, but a gimbal device might have an
87 // id different than the message compid it comes from. For more information see https://mavlink.io/en/services/gimbal_v2.html
88 if (!gimbalManager.receivedGimbalManagerInformation && (gimbalManager.requestGimbalManagerInformationRetries > 0)) {
89 _requestGimbalInformation(message.compid);
90 --gimbalManager.requestGimbalManagerInformationRetries;
91 }
92}
93
94void GimbalController::_handleGimbalManagerInformation(const mavlink_message_t &message)
95{
96 mavlink_gimbal_manager_information_t information{};
97 mavlink_msg_gimbal_manager_information_decode(&message, &information);
98
99 if (information.gimbal_device_id == 0) {
100 qCWarning(GimbalControllerLog) << "_handleGimbalManagerInformation for invalid gimbal device:"
101 << information.gimbal_device_id << ", from component id:" << message.compid;
102 return;
103 }
104
105 qCDebug(GimbalControllerLog) << "_handleGimbalManagerInformation for gimbal device:" << information.gimbal_device_id << ", component id:" << message.compid;
106
107 const GimbalPairId pairId{message.compid, information.gimbal_device_id};
108
109 auto gimbalIt = _potentialGimbals.find(pairId);
110 if (gimbalIt == _potentialGimbals.constEnd()) {
111 gimbalIt = _potentialGimbals.insert(pairId, new Gimbal(this));
112 }
113
114 Gimbal *const gimbal = gimbalIt.value();
115 gimbal->setManagerCompid(message.compid);
116 gimbal->setDeviceId(information.gimbal_device_id);
117 gimbal->setCapabilityFlags(information.cap_flags);
118
119 if (!gimbal->_receivedGimbalManagerInformation) {
120 qCDebug(GimbalControllerLog) << "gimbal manager with compId:" << message.compid
121 << " is responsible for gimbal device:" << information.gimbal_device_id;
122 }
123
124 gimbal->_receivedGimbalManagerInformation = true;
125 // It is important to flag our potential gimbal manager as well, so we stop requesting gimbal_manger_information message
126 PotentialGimbalManager &gimbalManager = _potentialGimbalManagers[message.compid];
127 gimbalManager.receivedGimbalManagerInformation = true;
128
129 _checkComplete(*gimbal, pairId);
130}
131
132void GimbalController::_handleGimbalManagerStatus(const mavlink_message_t &message)
133{
134 mavlink_gimbal_manager_status_t status{};
135 mavlink_msg_gimbal_manager_status_decode(&message, &status);
136
137 // qCDebug(GimbalControllerLog) << "_handleGimbalManagerStatus for gimbal device:" << status.gimbal_device_id << ", component id:" << message.compid;
138
139 if (status.gimbal_device_id == 0) {
140 qCDebug(GimbalControllerLog) << "gimbal manager with compId:" << message.compid
141 << "reported status of gimbal device id:" << status.gimbal_device_id << "which is not a valid gimbal device id";
142 return;
143 }
144
145 const GimbalPairId pairId{message.compid, status.gimbal_device_id};
146
147 auto gimbalIt = _potentialGimbals.find(pairId);
148 if (gimbalIt == _potentialGimbals.constEnd()) {
149 gimbalIt = _potentialGimbals.insert(pairId, new Gimbal(this));
150 }
151
152 Gimbal *const gimbal = gimbalIt.value();
153 if (gimbal->deviceId()->rawValue().toUInt() == 0) {
154 gimbal->setDeviceId(status.gimbal_device_id);
155 } else if (gimbal->deviceId()->rawValue().toUInt() != status.gimbal_device_id) {
156 qCWarning(GimbalControllerLog) << "conflicting GIMBAL_MANAGER_STATUS.gimbal_device_id:" << status.gimbal_device_id;
157 }
158
159 if (gimbal->managerCompid()->rawValue().toUInt() == 0) {
160 gimbal->setManagerCompid(message.compid);
161 } else if (gimbal->managerCompid()->rawValue().toUInt() != message.compid) {
162 qCWarning(GimbalControllerLog) << "conflicting GIMBAL_MANAGER_STATUS compid:" << message.compid;
163 }
164
165 // Only log this message once
166 if (!gimbal->_receivedGimbalManagerStatus) {
167 qCDebug(GimbalControllerLog) << "_handleGimbalManagerStatus: gimbal manager with compId" << message.compid
168 << "is responsible for gimbal device" << status.gimbal_device_id;
169 }
170
171 gimbal->_receivedGimbalManagerStatus = true;
172
173 const bool haveControl =
174 (status.primary_control_sysid == MAVLinkProtocol::instance()->getSystemId()) &&
175 (status.primary_control_compid == MAVLinkProtocol::getComponentId());
176
177 const bool othersHaveControl = !haveControl &&
178 (status.primary_control_sysid != 0 && status.primary_control_compid != 0);
179
180 if (gimbal->gimbalHaveControl() != haveControl) {
181 gimbal->setGimbalHaveControl(haveControl);
182 }
183
184 if (gimbal->gimbalOthersHaveControl() != othersHaveControl) {
185 gimbal->setGimbalOthersHaveControl(othersHaveControl);
186 }
187
188 _checkComplete(*gimbal, pairId);
189}
190
191void GimbalController::_handleGimbalDeviceAttitudeStatus(const mavlink_message_t &message)
192{
193 mavlink_gimbal_device_attitude_status_t attitude_status{};
194 mavlink_msg_gimbal_device_attitude_status_decode(&message, &attitude_status);
195
196 GimbalPairId pairId{};
197
198 if (attitude_status.gimbal_device_id == 0) {
199 // If gimbal_device_id is 0, we must take the compid of the message
200 pairId.deviceId = message.compid;
201
202 // We do a reverse lookup here
203 const auto foundGimbal = std::find_if(_potentialGimbals.begin(), _potentialGimbals.end(),
204 [pairId](Gimbal *gimbal) { return (gimbal->deviceId()->rawValue().toUInt() == pairId.deviceId); });
205
206 if (foundGimbal == _potentialGimbals.constEnd()) {
207 qCDebug(GimbalControllerLog) << "_handleGimbalDeviceAttitudeStatus for unknown device id:"
208 << pairId.deviceId << "from component id:" << message.compid;
209 return;
210 }
211
212 pairId.managerCompid = foundGimbal.key().managerCompid;
213 } else if (attitude_status.gimbal_device_id <= 6) {
214 // If the gimbal_device_id field is set to 1-6, we must use this device id instead
215 pairId.deviceId = attitude_status.gimbal_device_id;
216 pairId.managerCompid = message.compid;
217 } else {
218 // Otherwise, this is invalid and we don't know how to deal with it.
219 qCDebug(GimbalControllerLog) << "_handleGimbalDeviceAttitudeStatus for invalid device id: "
220 << attitude_status.gimbal_device_id << " from component id: " << message.compid;
221 return;
222 }
223
224 auto gimbalIt = _potentialGimbals.find(pairId);
225 if (gimbalIt == _potentialGimbals.end()) {
226 gimbalIt = _potentialGimbals.insert(pairId, new Gimbal(this));
227 }
228
229 Gimbal *const gimbal = gimbalIt.value();
230
231 gimbal->setRetracted((attitude_status.flags & GIMBAL_DEVICE_FLAGS_RETRACT) > 0);
232 gimbal->setYawLock((attitude_status.flags & GIMBAL_DEVICE_FLAGS_YAW_LOCK) > 0);
233 gimbal->_neutral = (attitude_status.flags & GIMBAL_DEVICE_FLAGS_NEUTRAL) > 0;
234
235 float roll, pitch, yaw;
236 mavlink_quaternion_to_euler(attitude_status.q, &roll, &pitch, &yaw);
237
238 gimbal->setAbsoluteRoll(qRadiansToDegrees(roll));
239 gimbal->setAbsolutePitch(qRadiansToDegrees(pitch));
240
241 const bool yaw_in_vehicle_frame = _yawInVehicleFrame(attitude_status.flags);
242 if (yaw_in_vehicle_frame) {
243 const float bodyYaw = qRadiansToDegrees(yaw);
244 float absoluteYaw = bodyYaw + _vehicle->heading()->rawValue().toFloat();
245 if (absoluteYaw > 180.0f) {
246 absoluteYaw -= 360.0f;
247 }
248
249 gimbal->setBodyYaw(bodyYaw);
250 gimbal->setAbsoluteYaw(absoluteYaw);
251
252 } else {
253 const float absoluteYaw = qRadiansToDegrees(yaw);
254 float bodyYaw = absoluteYaw - _vehicle->heading()->rawValue().toFloat();
255 if (bodyYaw < -180.0f) {
256 bodyYaw += 360.0f;
257 }
258
259 gimbal->setBodyYaw(bodyYaw);
260 gimbal->setAbsoluteYaw(absoluteYaw);
261 }
262
263 gimbal->_receivedGimbalDeviceAttitudeStatus = true;
264
265 _checkComplete(*gimbal, pairId);
266}
267
268void GimbalController::_requestGimbalInformation(uint8_t compid)
269{
270 qCDebug(GimbalControllerLog) << "_requestGimbalInformation(" << compid << ")";
271
272 if (_vehicle) {
273 _vehicle->sendMavCommand(compid,
274 MAV_CMD_REQUEST_MESSAGE,
275 false /* no error */,
276 MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION);
277 }
278}
279
280void GimbalController::_checkComplete(Gimbal &gimbal, GimbalPairId pairId)
281{
282 if (gimbal._isComplete) {
283 // Already complete, nothing to do.
284 return;
285 }
286
287 if (!gimbal._receivedGimbalManagerInformation && gimbal._requestInformationRetries > 0) {
288 _requestGimbalInformation(pairId.managerCompid);
289 --gimbal._requestInformationRetries;
290 }
291 // Limit to 1 second between set message interface requests
292 static qint64 lastRequestStatusMessage = 0;
293 qint64 now = QDateTime::currentMSecsSinceEpoch();
294 if (!gimbal._receivedGimbalManagerStatus && (gimbal._requestStatusRetries > 0) && (now - lastRequestStatusMessage > 1000)) {
295 lastRequestStatusMessage = now;
296 _vehicle->sendMavCommand(pairId.managerCompid,
297 MAV_CMD_SET_MESSAGE_INTERVAL,
298 false /* no error */,
299 MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS,
300 (gimbal._requestStatusRetries > 2) ? 0 : 5000000); // request default rate, if we don't succeed, last attempt is fixed 0.2 Hz instead
301 --gimbal._requestStatusRetries;
302 qCDebug(GimbalControllerLog) << "attempt to set GIMBAL_MANAGER_STATUS message at"
303 << (gimbal._requestStatusRetries > 2 ? "default rate" : "0.2 Hz") << "interval for device:"
304 << gimbal.deviceId()->rawValue().toUInt() << "manager compID:" << pairId.managerCompid
305 << ", retries remaining:" << gimbal._requestStatusRetries;
306 }
307
308 if (!gimbal._receivedGimbalDeviceAttitudeStatus && (gimbal._requestAttitudeRetries > 0) &&
309 gimbal._receivedGimbalManagerInformation && (pairId.deviceId != 0)) {
310 // We request the attitude directly from the gimbal device component.
311 // We can only do that once we have received the gimbal manager information
312 // telling us which gimbal device it is responsible for.
313 uint8_t gimbalDeviceCompid = pairId.deviceId;
314 // If the device ID is 1-6, we need to request the message from the manager itself.
315 if (gimbalDeviceCompid <= 6) {
316 gimbalDeviceCompid = pairId.managerCompid;
317 }
318 _vehicle->sendMavCommand(gimbalDeviceCompid,
319 MAV_CMD_SET_MESSAGE_INTERVAL,
320 false /* no error */,
321 MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS,
322 0 /* request default rate */);
323
324 --gimbal._requestAttitudeRetries;
325 }
326
327 if (!gimbal._receivedGimbalManagerInformation || !gimbal._receivedGimbalManagerStatus || !gimbal._receivedGimbalDeviceAttitudeStatus) {
328 // Not complete yet.
329 return;
330 }
331
332 gimbal._isComplete = true;
333
334 // If there is no current active gimbal, set this one as active
335 if (!_activeGimbal) {
336 setActiveGimbal(&gimbal);
337 }
338
339 _gimbals->append(&gimbal);
340 // This is needed for new Gimbals telemetry to be available for the user to show in flyview telemetry panel
341 _vehicle->_addFactGroup(&gimbal, QStringLiteral("%1%2%3").arg(_gimbalFactGroupNamePrefix).arg(pairId.managerCompid).arg(pairId.deviceId));
342}
343
344bool GimbalController::_tryGetGimbalControl()
345{
346 if (!_activeGimbal) {
347 qCDebug(GimbalControllerLog) << "_tryGetGimbalControl: active gimbal is nullptr, returning";
348 return false;
349 }
350
351 if (_activeGimbal->gimbalOthersHaveControl()) {
352 qCDebug(GimbalControllerLog) << "Others in control, showing popup for user to confirm control..";
354 return false;
355 } else if (!_activeGimbal->gimbalHaveControl()) {
356 qCDebug(GimbalControllerLog) << "Nobody in control, acquiring control ourselves..";
357 acquireGimbalControl();
358 }
359
360 return true;
361}
362
363bool GimbalController::_yawInVehicleFrame(uint32_t flags)
364{
365 if ((flags & GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME) > 0) {
366 return true;
367 } else if ((flags & GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME) > 0) {
368 return false;
369 } else {
370 // For backwards compatibility: if both new flags are 0, yaw lock defines the frame.
371 return ((flags & GIMBAL_DEVICE_FLAGS_YAW_LOCK) == 0);
372 }
373}
374
376{
377 if (!_activeGimbal) {
378 qCDebug(GimbalControllerLog) << "gimbalPitchStart: active gimbal is nullptr, returning";
379 return;
380 }
381
382 const float speed = SettingsManager::instance()->gimbalControllerSettings()->joystickButtonsSpeed()->rawValue().toInt();
383 activeGimbal()->setPitchRate(direction * speed);
384
385 sendRate();
386}
387
389{
390 if (!_activeGimbal) {
391 qCDebug(GimbalControllerLog) << "gimbalYawStart: active gimbal is nullptr, returning";
392 return;
393 }
394
395 const float speed = SettingsManager::instance()->gimbalControllerSettings()->joystickButtonsSpeed()->rawValue().toInt();
396 activeGimbal()->setYawRate(direction * speed);
397 sendRate();
398}
399
401{
402 if (!_activeGimbal) {
403 qCDebug(GimbalControllerLog) << "gimbalPitchStop: active gimbal is nullptr, returning";
404 return;
405 }
406
407 activeGimbal()->setPitchRate(0.0f);
408 sendRate();
409}
410
412{
413 if (!_activeGimbal) {
414 qCDebug(GimbalControllerLog) << "gimbalYawStop: active gimbal is nullptr, returning";
415 return;
416 }
417
418 activeGimbal()->setYawRate(0.0f);
419 sendRate();
420}
421
423{
424 if (!_activeGimbal) {
425 qCDebug(GimbalControllerLog) << "gimbalYawStep: active gimbal is nullptr, returning";
426 return;
427 }
428 sendPitchBodyYaw(0.0, 0.0, true);
429}
430
431void GimbalController::gimbalOnScreenControl(float panPct, float tiltPct, bool clickAndPoint, bool clickAndDrag, bool /*rateControl*/, bool /*retract*/, bool /*neutral*/, bool /*yawlock*/)
432{
433 // Pan and tilt comes as +-(0-1)
434
435 if (!_activeGimbal) {
436 qCDebug(GimbalControllerLog) << "gimbalOnScreenControl: active gimbal is nullptr, returning";
437 return;
438 }
439
440 if (clickAndPoint) { // based on FOV
441 const float hFov = SettingsManager::instance()->gimbalControllerSettings()->CameraHFov()->rawValue().toFloat();
442 const float vFov = SettingsManager::instance()->gimbalControllerSettings()->CameraVFov()->rawValue().toFloat();
443
444 const float panIncDesired = panPct * hFov * 0.5f;
445 const float tiltIncDesired = tiltPct * vFov * 0.5f;
446
447 const float panDesired = panIncDesired + _activeGimbal->bodyYaw()->rawValue().toFloat();
448 const float tiltDesired = tiltIncDesired + _activeGimbal->absolutePitch()->rawValue().toFloat();
449
450 if (_activeGimbal->yawLock()) {
451 sendPitchAbsoluteYaw(tiltDesired, panDesired + _vehicle->heading()->rawValue().toFloat(), false);
452 } else {
453 sendPitchBodyYaw(tiltDesired, panDesired, false);
454 }
455 } else if (clickAndDrag) { // based on maximum speed
456 // Should send rate commands, but it seems for some reason it is not working on AP side.
457 // Pitch works ok but yaw doesn't stop, it keeps like inertia, like if it was buffering the messages.
458 // So we do a workaround with angle targets
459 const float maxSpeed = SettingsManager::instance()->gimbalControllerSettings()->CameraSlideSpeed()->rawValue().toFloat();
460
461 const float panIncDesired = panPct * maxSpeed * 0.1f;
462 const float tiltIncDesired = tiltPct * maxSpeed * 0.1f;
463
464 const float panDesired = panIncDesired + _activeGimbal->bodyYaw()->rawValue().toFloat();
465 const float tiltDesired = tiltIncDesired + _activeGimbal->absolutePitch()->rawValue().toFloat();
466
467 if (_activeGimbal->yawLock()) {
468 sendPitchAbsoluteYaw(tiltDesired, panDesired + _vehicle->heading()->rawValue().toFloat(), false);
469 } else {
470 sendPitchBodyYaw(tiltDesired, panDesired, false);
471 }
472 }
473}
474
475void GimbalController::sendPitchBodyYaw(float pitch, float yaw, bool showError)
476{
477 if (!_tryGetGimbalControl()) {
478 return;
479 }
480
481 _rateSenderTimer.stop();
482 _activeGimbal->setAbsolutePitch(0.0f);
483 _activeGimbal->setYawRate(0.0f);
484
485 // qCDebug(GimbalControllerLog) << "sendPitch: " << pitch << " BodyYaw: " << yaw;
486
487 const unsigned flags = GIMBAL_MANAGER_FLAGS_ROLL_LOCK
488 | GIMBAL_MANAGER_FLAGS_PITCH_LOCK
489 | GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME;
490
491 _vehicle->sendMavCommand(
492 _activeGimbal->managerCompid()->rawValue().toUInt(),
493 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
494 showError,
495 pitch,
496 yaw,
497 NAN,
498 NAN,
499 flags,
500 0,
501 _activeGimbal->deviceId()->rawValue().toUInt());
502}
503
504void GimbalController::sendPitchAbsoluteYaw(float pitch, float yaw, bool showError)
505{
506 if (!_tryGetGimbalControl()) {
507 return;
508 }
509
510 _rateSenderTimer.stop();
511 _activeGimbal->setAbsolutePitch(0.0f);
512 _activeGimbal->setYawRate(0.0f);
513
514 if (yaw > 180.0f) {
515 yaw -= 360.0f;
516 }
517
518 if (yaw < -180.0f) {
519 yaw += 360.0f;
520 }
521
522 // qCDebug() << "sendPitch: " << pitch << " absoluteYaw: " << yaw;
523
524 const unsigned flags = GIMBAL_MANAGER_FLAGS_ROLL_LOCK
525 | GIMBAL_MANAGER_FLAGS_PITCH_LOCK
526 | GIMBAL_MANAGER_FLAGS_YAW_LOCK
527 | GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME;
528
529 _vehicle->sendMavCommand(
530 _activeGimbal->managerCompid()->rawValue().toUInt(),
531 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
532 showError,
533 pitch,
534 yaw,
535 NAN,
536 NAN,
537 flags,
538 0,
539 _activeGimbal->deviceId()->rawValue().toUInt());
540}
541
542void GimbalController::setGimbalRetract(bool set)
543{
544 if (!_tryGetGimbalControl()) {
545 return;
546 }
547
548 uint32_t flags = 0;
549 if (set) {
550 flags |= GIMBAL_DEVICE_FLAGS_RETRACT;
551 } else {
552 flags &= ~GIMBAL_DEVICE_FLAGS_RETRACT;
553 }
554
555 sendPitchYawFlags(flags);
556}
557
558void GimbalController::sendRate()
559{
560 if (!_tryGetGimbalControl()) {
561 return;
562 }
563
564 unsigned flags = GIMBAL_MANAGER_FLAGS_ROLL_LOCK | GIMBAL_MANAGER_FLAGS_PITCH_LOCK;
565
566 if (_activeGimbal->yawLock()) {
567 flags |= GIMBAL_MANAGER_FLAGS_YAW_LOCK;
568 }
569
570 _vehicle->sendMavCommand(
571 _activeGimbal->managerCompid()->rawValue().toUInt(),
572 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
573 false,
574 NAN,
575 NAN,
576 _activeGimbal->pitchRate(),
577 _activeGimbal->yawRate(),
578 flags,
579 0,
580 _activeGimbal->deviceId()->rawValue().toUInt());
581
582 qCDebug(GimbalControllerLog) << "Gimbal rate sent!";
583
584 // Stop timeout if both unset.
585 if ((_activeGimbal->pitchRate() == 0.f) && (_activeGimbal->yawRate() == 0.f)) {
586 _rateSenderTimer.stop();
587 } else {
588 _rateSenderTimer.start();
589 }
590}
591
592void GimbalController::sendGimbalRate(float pitch_rate_deg_s, float yaw_rate_deg_s)
593{
594 if (!_tryGetGimbalControl()) {
595 return;
596 }
597
598 _sendGimbalAttitudeRates(pitch_rate_deg_s, yaw_rate_deg_s);
599
600 if (pitch_rate_deg_s == 0.f && yaw_rate_deg_s == 0.f) {
601 _rateSenderTimer.stop();
602 } else {
603 _rateSenderTimer.start();
604 }
605}
606
607void GimbalController::_sendGimbalAttitudeRates(float pitch_rate_deg_s,
608 float yaw_rate_deg_s)
609{
610
611 auto sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
612 if (!sharedLink) {
613 qCDebug(GimbalControllerLog) << "_sendGimbalAttitudeRates: primary link gone!";
614 return;
615 }
616
617 uint32_t flags =
618 GIMBAL_MANAGER_FLAGS_ROLL_LOCK |
619 GIMBAL_MANAGER_FLAGS_PITCH_LOCK |
620 GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME; // use vehicle/body frame
621
622 // Preserve current yaw-lock state instead of changing it:
623 if (_activeGimbal->yawLock()) {
624 flags |= GIMBAL_MANAGER_FLAGS_YAW_LOCK;
625 }
626
627 const float qnan[4] = {NAN, NAN, NAN, NAN};
629
630 mavlink_msg_gimbal_manager_set_attitude_pack_chan(
631 MAVLinkProtocol::instance()->getSystemId(),
633 sharedLink->mavlinkChannel(),
634 &msg,
635 _vehicle->id(),
636 static_cast<uint8_t>(_activeGimbal->managerCompid()->rawValue().toUInt()),
637 flags,
638 static_cast<uint8_t>(_activeGimbal->deviceId()->rawValue().toUInt()),
639 qnan,
640 NAN,
641 qDegreesToRadians(pitch_rate_deg_s),
642 qDegreesToRadians(yaw_rate_deg_s)
643 );
644
645 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
646}
647
648void GimbalController::_rateSenderTimeout()
649{
650 // Send rate again to avoid timeout on autopilot side.
651 sendRate();
652}
653
654void GimbalController::setGimbalYawLock(bool set)
655{
656 if (!_tryGetGimbalControl()) {
657 return;
658 }
659
660 // Roll and pitch are usually "locked", so with horizon and not with aircraft.
661 uint32_t flags = GIMBAL_DEVICE_FLAGS_ROLL_LOCK | GIMBAL_DEVICE_FLAGS_PITCH_LOCK;
662 if (set) {
663 flags |= GIMBAL_DEVICE_FLAGS_YAW_LOCK;
664 }
665
666 sendPitchYawFlags(flags);
667}
668
669void GimbalController::sendPitchYawFlags(uint32_t flags)
670{
671 const bool yaw_in_vehicle_frame = _yawInVehicleFrame(flags);
672
673 _vehicle->sendMavCommand(
674 _activeGimbal->managerCompid()->rawValue().toUInt(),
675 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
676 true,
677 _activeGimbal->absolutePitch()->rawValue().toFloat(),
678 yaw_in_vehicle_frame ? _activeGimbal->bodyYaw()->rawValue().toFloat() : _activeGimbal->absoluteYaw()->rawValue().toFloat(),
679 NAN,
680 NAN,
681 flags,
682 0,
683 _activeGimbal->deviceId()->rawValue().toUInt());
684}
685
686void GimbalController::acquireGimbalControl()
687{
688 if (!_activeGimbal) {
689 qCDebug(GimbalControllerLog) << "acquireGimbalControl: active gimbal is nullptr, returning";
690 return;
691 }
692
693 _vehicle->sendMavCommand(
694 _activeGimbal->managerCompid()->rawValue().toUInt(),
695 MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE,
696 true,
697 MAVLinkProtocol::instance()->getSystemId(), // Set us in primary control.
698 MAVLinkProtocol::getComponentId(), // Set us in primary control
699 -1.f, // Leave secondary unchanged
700 -1.f, // Leave secondary unchanged
701 NAN, // Reserved
702 NAN, // Reserved
703 _activeGimbal->deviceId()->rawValue().toUInt());
704}
705
706void GimbalController::releaseGimbalControl()
707{
708 if (!_activeGimbal) {
709 qCDebug(GimbalControllerLog) << "releaseGimbalControl: active gimbal is nullptr, returning";
710 return;
711 }
712
713 _vehicle->sendMavCommand(
714 _activeGimbal->managerCompid()->rawValue().toUInt(),
715 MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE,
716 true,
717 -3.f, // Release primary control if we have control
718 -3.f, // Release primary control if we have control
719 -1.f, // Leave secondary control unchanged
720 -1.f, // Leave secondary control unchanged
721 NAN, // Reserved
722 NAN, // Reserved
723 _activeGimbal->deviceId()->rawValue().toUInt());
724}
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void _addFactGroup(FactGroup *factGroup, const QString &name)
Definition FactGroup.cc:130
Fact *joystickButtonsSpeed READ joystickButtonsSpeed CONSTANT Fact * joystickButtonsSpeed()
Fact *CameraVFov READ CameraVFov CONSTANT Fact * CameraVFov()
Fact *CameraHFov READ CameraHFov CONSTANT Fact * CameraHFov()
Fact *CameraSlideSpeed READ CameraSlideSpeed CONSTANT Fact * CameraSlideSpeed()
void activeGimbalChanged()
void gimbalYawStart(int direction)
void showAcquireGimbalControlPopup()
void gimbalPitchStart(int direction)
void setAbsolutePitch(float absPitch)
Definition Gimbal.h:53
float pitchRate() const
Definition Gimbal.h:45
void setYawLock(bool yawLock)
Definition Gimbal.h:61
void setPitchRate(float pitchRate)
Definition Gimbal.h:59
Fact * absolutePitch()
Definition Gimbal.h:39
bool yawLock() const
Definition Gimbal.h:47
void setManagerCompid(uint id)
Definition Gimbal.h:57
Fact * managerCompid()
Definition Gimbal.h:43
Fact * deviceId()
Definition Gimbal.h:42
void setAbsoluteYaw(float absYaw)
Definition Gimbal.h:55
void setYawRate(float yawRate)
Definition Gimbal.h:60
bool gimbalOthersHaveControl() const
Definition Gimbal.h:50
void setGimbalHaveControl(bool set)
Definition Gimbal.h:63
void setBodyYaw(float yaw)
Definition Gimbal.h:54
void setDeviceId(uint id)
Definition Gimbal.h:56
void setRetracted(bool retracted)
Definition Gimbal.h:62
bool gimbalHaveControl() const
Definition Gimbal.h:49
void setAbsoluteRoll(float absRoll)
Definition Gimbal.h:52
void setGimbalOthersHaveControl(bool set)
Definition Gimbal.h:64
float yawRate() const
Definition Gimbal.h:46
void setCapabilityFlags(uint32_t flags)
Definition Gimbal.cc:69
Fact * bodyYaw()
Definition Gimbal.h:40
static int getComponentId()
Get the component id of this application.
static MAVLinkProtocol * instance()
int getSystemId() const
Get the system id of this application.
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
WeakLinkInterfacePtr primaryLink() const
void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Definition Vehicle.cc:2309
void initialConnectComplete()
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:580
int id() const
Definition Vehicle.h:425
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1470
void mavlinkMessageReceived(const mavlink_message_t &message)