20 qCDebug(GimbalControllerLog) <<
this;
25 _rateSenderTimer.setInterval(500);
26 (void) connect(&_rateSenderTimer, &QTimer::timeout,
this, &GimbalController::_rateSenderTimeout);
29GimbalController::~GimbalController()
31 qCDebug(GimbalControllerLog) <<
this;
34void GimbalController::_initialConnectCompleted()
36 _initialConnectComplete =
true;
39void GimbalController::setActiveGimbal(
Gimbal *gimbal)
42 qCDebug(GimbalControllerLog) <<
"Set active gimbal: attempted to set a nullptr, returning";
46 if (gimbal != _activeGimbal) {
47 qCDebug(GimbalControllerLog) <<
"Set active gimbal:" << gimbal;
48 _activeGimbal = gimbal;
55 if (!_initialConnectComplete) {
59 switch (message.msgid) {
60 case MAVLINK_MSG_ID_HEARTBEAT:
61 _handleHeartbeat(message);
63 case MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION:
64 _handleGimbalManagerInformation(message);
66 case MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS:
67 _handleGimbalManagerStatus(message);
69 case MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS:
70 _handleGimbalDeviceAttitudeStatus(message);
79 if (!_potentialGimbalManagers.contains(message.compid)) {
80 qCDebug(GimbalControllerLog) <<
"new potential gimbal manager component:" << message.compid;
83 PotentialGimbalManager &gimbalManager = _potentialGimbalManagers[message.compid];
88 if (!gimbalManager.receivedGimbalManagerInformation && (gimbalManager.requestGimbalManagerInformationRetries > 0)) {
89 _requestGimbalInformation(message.compid);
90 --gimbalManager.requestGimbalManagerInformationRetries;
94void GimbalController::_handleGimbalManagerInformation(
const mavlink_message_t &message)
96 mavlink_gimbal_manager_information_t information{};
97 mavlink_msg_gimbal_manager_information_decode(&message, &information);
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;
105 qCDebug(GimbalControllerLog) <<
"_handleGimbalManagerInformation for gimbal device:" << information.gimbal_device_id <<
", component id:" << message.compid;
107 const GimbalPairId pairId{message.compid, information.gimbal_device_id};
109 auto gimbalIt = _potentialGimbals.find(pairId);
110 if (gimbalIt == _potentialGimbals.constEnd()) {
111 gimbalIt = _potentialGimbals.insert(pairId,
new Gimbal(
this));
114 Gimbal *
const gimbal = gimbalIt.value();
119 if (!gimbal->_receivedGimbalManagerInformation) {
120 qCDebug(GimbalControllerLog) <<
"gimbal manager with compId:" << message.compid
121 <<
" is responsible for gimbal device:" << information.gimbal_device_id;
124 gimbal->_receivedGimbalManagerInformation =
true;
126 PotentialGimbalManager &gimbalManager = _potentialGimbalManagers[message.compid];
127 gimbalManager.receivedGimbalManagerInformation =
true;
129 _checkComplete(*gimbal, pairId);
132void GimbalController::_handleGimbalManagerStatus(
const mavlink_message_t &message)
134 mavlink_gimbal_manager_status_t status{};
135 mavlink_msg_gimbal_manager_status_decode(&message, &status);
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";
145 const GimbalPairId pairId{message.compid, status.gimbal_device_id};
147 auto gimbalIt = _potentialGimbals.find(pairId);
148 if (gimbalIt == _potentialGimbals.constEnd()) {
149 gimbalIt = _potentialGimbals.insert(pairId,
new Gimbal(
this));
152 Gimbal *
const gimbal = gimbalIt.value();
153 if (gimbal->
deviceId()->rawValue().toUInt() == 0) {
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;
161 }
else if (gimbal->
managerCompid()->rawValue().toUInt() != message.compid) {
162 qCWarning(GimbalControllerLog) <<
"conflicting GIMBAL_MANAGER_STATUS compid:" << message.compid;
166 if (!gimbal->_receivedGimbalManagerStatus) {
167 qCDebug(GimbalControllerLog) <<
"_handleGimbalManagerStatus: gimbal manager with compId" << message.compid
168 <<
"is responsible for gimbal device" << status.gimbal_device_id;
171 gimbal->_receivedGimbalManagerStatus =
true;
173 const bool haveControl =
177 const bool othersHaveControl = !haveControl &&
178 (status.primary_control_sysid != 0 && status.primary_control_compid != 0);
188 _checkComplete(*gimbal, pairId);
191void GimbalController::_handleGimbalDeviceAttitudeStatus(
const mavlink_message_t &message)
193 mavlink_gimbal_device_attitude_status_t attitude_status{};
194 mavlink_msg_gimbal_device_attitude_status_decode(&message, &attitude_status);
196 GimbalPairId pairId{};
198 if (attitude_status.gimbal_device_id == 0) {
200 pairId.deviceId = message.compid;
203 const auto foundGimbal = std::find_if(_potentialGimbals.begin(), _potentialGimbals.end(),
204 [pairId](
Gimbal *gimbal) { return (gimbal->deviceId()->rawValue().toUInt() == pairId.deviceId); });
206 if (foundGimbal == _potentialGimbals.constEnd()) {
207 qCDebug(GimbalControllerLog) <<
"_handleGimbalDeviceAttitudeStatus for unknown device id:"
208 << pairId.deviceId <<
"from component id:" << message.compid;
212 pairId.managerCompid = foundGimbal.key().managerCompid;
213 }
else if (attitude_status.gimbal_device_id <= 6) {
215 pairId.deviceId = attitude_status.gimbal_device_id;
216 pairId.managerCompid = message.compid;
219 qCDebug(GimbalControllerLog) <<
"_handleGimbalDeviceAttitudeStatus for invalid device id: "
220 << attitude_status.gimbal_device_id <<
" from component id: " << message.compid;
224 auto gimbalIt = _potentialGimbals.find(pairId);
225 if (gimbalIt == _potentialGimbals.end()) {
226 gimbalIt = _potentialGimbals.insert(pairId,
new Gimbal(
this));
229 Gimbal *
const gimbal = gimbalIt.value();
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;
235 float roll, pitch, yaw;
236 mavlink_quaternion_to_euler(attitude_status.q, &roll, &pitch, &yaw);
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;
253 const float absoluteYaw = qRadiansToDegrees(yaw);
254 float bodyYaw = absoluteYaw - _vehicle->heading()->rawValue().toFloat();
255 if (bodyYaw < -180.0f) {
263 gimbal->_receivedGimbalDeviceAttitudeStatus =
true;
265 _checkComplete(*gimbal, pairId);
268void GimbalController::_requestGimbalInformation(uint8_t compid)
270 qCDebug(GimbalControllerLog) <<
"_requestGimbalInformation(" << compid <<
")";
274 MAV_CMD_REQUEST_MESSAGE,
276 MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION);
280void GimbalController::_checkComplete(
Gimbal &gimbal, GimbalPairId pairId)
282 if (gimbal._isComplete) {
287 if (!gimbal._receivedGimbalManagerInformation && gimbal._requestInformationRetries > 0) {
288 _requestGimbalInformation(pairId.managerCompid);
289 --gimbal._requestInformationRetries;
292 static qint64 lastRequestStatusMessage = 0;
293 qint64 now = QDateTime::currentMSecsSinceEpoch();
294 if (!gimbal._receivedGimbalManagerStatus && (gimbal._requestStatusRetries > 0) && (now - lastRequestStatusMessage > 1000)) {
295 lastRequestStatusMessage = now;
297 MAV_CMD_SET_MESSAGE_INTERVAL,
299 MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS,
300 (gimbal._requestStatusRetries > 2) ? 0 : 5000000);
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;
308 if (!gimbal._receivedGimbalDeviceAttitudeStatus && (gimbal._requestAttitudeRetries > 0) &&
309 gimbal._receivedGimbalManagerInformation && (pairId.deviceId != 0)) {
313 uint8_t gimbalDeviceCompid = pairId.deviceId;
315 if (gimbalDeviceCompid <= 6) {
316 gimbalDeviceCompid = pairId.managerCompid;
319 MAV_CMD_SET_MESSAGE_INTERVAL,
321 MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS,
324 --gimbal._requestAttitudeRetries;
327 if (!gimbal._receivedGimbalManagerInformation || !gimbal._receivedGimbalManagerStatus || !gimbal._receivedGimbalDeviceAttitudeStatus) {
332 gimbal._isComplete =
true;
335 if (!_activeGimbal) {
336 setActiveGimbal(&gimbal);
339 _gimbals->
append(&gimbal);
341 _vehicle->
_addFactGroup(&gimbal, QStringLiteral(
"%1%2%3").arg(_gimbalFactGroupNamePrefix).arg(pairId.managerCompid).arg(pairId.deviceId));
344bool GimbalController::_tryGetGimbalControl()
346 if (!_activeGimbal) {
347 qCDebug(GimbalControllerLog) <<
"_tryGetGimbalControl: active gimbal is nullptr, returning";
352 qCDebug(GimbalControllerLog) <<
"Others in control, showing popup for user to confirm control..";
356 qCDebug(GimbalControllerLog) <<
"Nobody in control, acquiring control ourselves..";
357 acquireGimbalControl();
363bool GimbalController::_yawInVehicleFrame(uint32_t flags)
365 if ((flags & GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME) > 0) {
367 }
else if ((flags & GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME) > 0) {
371 return ((flags & GIMBAL_DEVICE_FLAGS_YAW_LOCK) == 0);
377 if (!_activeGimbal) {
378 qCDebug(GimbalControllerLog) <<
"gimbalPitchStart: active gimbal is nullptr, returning";
382 const float speed = SettingsManager::instance()->gimbalControllerSettings()->
joystickButtonsSpeed()->rawValue().toInt();
390 if (!_activeGimbal) {
391 qCDebug(GimbalControllerLog) <<
"gimbalYawStart: active gimbal is nullptr, returning";
395 const float speed = SettingsManager::instance()->gimbalControllerSettings()->
joystickButtonsSpeed()->rawValue().toInt();
396 activeGimbal()->
setYawRate(direction * speed);
402 if (!_activeGimbal) {
403 qCDebug(GimbalControllerLog) <<
"gimbalPitchStop: active gimbal is nullptr, returning";
413 if (!_activeGimbal) {
414 qCDebug(GimbalControllerLog) <<
"gimbalYawStop: active gimbal is nullptr, returning";
424 if (!_activeGimbal) {
425 qCDebug(GimbalControllerLog) <<
"gimbalYawStep: active gimbal is nullptr, returning";
428 sendPitchBodyYaw(0.0, 0.0,
true);
431void GimbalController::gimbalOnScreenControl(
float panPct,
float tiltPct,
bool clickAndPoint,
bool clickAndDrag,
bool ,
bool ,
bool ,
bool )
435 if (!_activeGimbal) {
436 qCDebug(GimbalControllerLog) <<
"gimbalOnScreenControl: active gimbal is nullptr, returning";
441 const float hFov = SettingsManager::instance()->gimbalControllerSettings()->
CameraHFov()->rawValue().toFloat();
442 const float vFov = SettingsManager::instance()->gimbalControllerSettings()->
CameraVFov()->rawValue().toFloat();
444 const float panIncDesired = panPct * hFov * 0.5f;
445 const float tiltIncDesired = tiltPct * vFov * 0.5f;
447 const float panDesired = panIncDesired + _activeGimbal->
bodyYaw()->rawValue().toFloat();
448 const float tiltDesired = tiltIncDesired + _activeGimbal->
absolutePitch()->rawValue().toFloat();
450 if (_activeGimbal->
yawLock()) {
451 sendPitchAbsoluteYaw(tiltDesired, panDesired + _vehicle->heading()->rawValue().toFloat(),
false);
453 sendPitchBodyYaw(tiltDesired, panDesired,
false);
455 }
else if (clickAndDrag) {
459 const float maxSpeed = SettingsManager::instance()->gimbalControllerSettings()->
CameraSlideSpeed()->rawValue().toFloat();
461 const float panIncDesired = panPct * maxSpeed * 0.1f;
462 const float tiltIncDesired = tiltPct * maxSpeed * 0.1f;
464 const float panDesired = panIncDesired + _activeGimbal->
bodyYaw()->rawValue().toFloat();
465 const float tiltDesired = tiltIncDesired + _activeGimbal->
absolutePitch()->rawValue().toFloat();
467 if (_activeGimbal->
yawLock()) {
468 sendPitchAbsoluteYaw(tiltDesired, panDesired + _vehicle->heading()->rawValue().toFloat(),
false);
470 sendPitchBodyYaw(tiltDesired, panDesired,
false);
475void GimbalController::sendPitchBodyYaw(
float pitch,
float yaw,
bool showError)
477 if (!_tryGetGimbalControl()) {
481 _rateSenderTimer.stop();
487 const unsigned flags = GIMBAL_MANAGER_FLAGS_ROLL_LOCK
488 | GIMBAL_MANAGER_FLAGS_PITCH_LOCK
489 | GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME;
493 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
501 _activeGimbal->
deviceId()->rawValue().toUInt());
504void GimbalController::sendPitchAbsoluteYaw(
float pitch,
float yaw,
bool showError)
506 if (!_tryGetGimbalControl()) {
510 _rateSenderTimer.stop();
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;
531 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
539 _activeGimbal->
deviceId()->rawValue().toUInt());
542void GimbalController::setGimbalRetract(
bool set)
544 if (!_tryGetGimbalControl()) {
550 flags |= GIMBAL_DEVICE_FLAGS_RETRACT;
552 flags &= ~GIMBAL_DEVICE_FLAGS_RETRACT;
555 sendPitchYawFlags(flags);
558void GimbalController::sendRate()
560 if (!_tryGetGimbalControl()) {
564 unsigned flags = GIMBAL_MANAGER_FLAGS_ROLL_LOCK | GIMBAL_MANAGER_FLAGS_PITCH_LOCK;
566 if (_activeGimbal->
yawLock()) {
567 flags |= GIMBAL_MANAGER_FLAGS_YAW_LOCK;
572 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
580 _activeGimbal->
deviceId()->rawValue().toUInt());
582 qCDebug(GimbalControllerLog) <<
"Gimbal rate sent!";
585 if ((_activeGimbal->
pitchRate() == 0.f) && (_activeGimbal->
yawRate() == 0.f)) {
586 _rateSenderTimer.stop();
588 _rateSenderTimer.start();
592void GimbalController::sendGimbalRate(
float pitch_rate_deg_s,
float yaw_rate_deg_s)
594 if (!_tryGetGimbalControl()) {
598 _sendGimbalAttitudeRates(pitch_rate_deg_s, yaw_rate_deg_s);
600 if (pitch_rate_deg_s == 0.f && yaw_rate_deg_s == 0.f) {
601 _rateSenderTimer.stop();
603 _rateSenderTimer.start();
607void GimbalController::_sendGimbalAttitudeRates(
float pitch_rate_deg_s,
608 float yaw_rate_deg_s)
613 qCDebug(GimbalControllerLog) <<
"_sendGimbalAttitudeRates: primary link gone!";
618 GIMBAL_MANAGER_FLAGS_ROLL_LOCK |
619 GIMBAL_MANAGER_FLAGS_PITCH_LOCK |
620 GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME;
623 if (_activeGimbal->
yawLock()) {
624 flags |= GIMBAL_MANAGER_FLAGS_YAW_LOCK;
627 const float qnan[4] = {NAN, NAN, NAN, NAN};
630 mavlink_msg_gimbal_manager_set_attitude_pack_chan(
633 sharedLink->mavlinkChannel(),
636 static_cast<uint8_t
>(_activeGimbal->
managerCompid()->rawValue().toUInt()),
638 static_cast<uint8_t
>(_activeGimbal->
deviceId()->rawValue().toUInt()),
641 qDegreesToRadians(pitch_rate_deg_s),
642 qDegreesToRadians(yaw_rate_deg_s)
648void GimbalController::_rateSenderTimeout()
654void GimbalController::setGimbalYawLock(
bool set)
656 if (!_tryGetGimbalControl()) {
661 uint32_t flags = GIMBAL_DEVICE_FLAGS_ROLL_LOCK | GIMBAL_DEVICE_FLAGS_PITCH_LOCK;
663 flags |= GIMBAL_DEVICE_FLAGS_YAW_LOCK;
666 sendPitchYawFlags(flags);
669void GimbalController::sendPitchYawFlags(uint32_t flags)
671 const bool yaw_in_vehicle_frame = _yawInVehicleFrame(flags);
675 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
678 yaw_in_vehicle_frame ? _activeGimbal->
bodyYaw()->rawValue().toFloat() : _activeGimbal->absoluteYaw()->rawValue().toFloat(),
683 _activeGimbal->deviceId()->rawValue().toUInt());
686void GimbalController::acquireGimbalControl()
688 if (!_activeGimbal) {
689 qCDebug(GimbalControllerLog) <<
"acquireGimbalControl: active gimbal is nullptr, returning";
695 MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE,
703 _activeGimbal->
deviceId()->rawValue().toUInt());
706void GimbalController::releaseGimbalControl()
708 if (!_activeGimbal) {
709 qCDebug(GimbalControllerLog) <<
"releaseGimbalControl: active gimbal is nullptr, returning";
715 MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE,
723 _activeGimbal->
deviceId()->rawValue().toUInt());
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void _addFactGroup(FactGroup *factGroup, const QString &name)
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)
void setYawLock(bool yawLock)
void setPitchRate(float pitchRate)
void setManagerCompid(uint id)
void setAbsoluteYaw(float absYaw)
void setYawRate(float yawRate)
bool gimbalOthersHaveControl() const
void setGimbalHaveControl(bool set)
void setBodyYaw(float yaw)
void setDeviceId(uint id)
void setRetracted(bool retracted)
bool gimbalHaveControl() const
void setAbsoluteRoll(float absRoll)
void setGimbalOthersHaveControl(bool set)
void setCapabilityFlags(uint32_t flags)
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)
void initialConnectComplete()
VehicleLinkManager * vehicleLinkManager()
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
void mavlinkMessageReceived(const mavlink_message_t &message)