Skip to content

Commit

Permalink
AP_Mount: Gremsy fix for attitude reporting
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Jul 20, 2023
1 parent 66a6f67 commit e80be4a
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 7 deletions.
6 changes: 0 additions & 6 deletions libraries/AP_Mount/AP_Mount_Gremsy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,12 +126,6 @@ bool AP_Mount_Gremsy::healthy() const
// get attitude as a quaternion. returns true on success
bool AP_Mount_Gremsy::get_attitude_quaternion(Quaternion& att_quat)
{
// check we have received an updated message
if (_gimbal_device_attitude_status.time_boot_ms == _sent_gimbal_device_attitude_status_ms) {
return false;
}
_sent_gimbal_device_attitude_status_ms = _gimbal_device_attitude_status.time_boot_ms;

att_quat = _gimbal_device_attitude_status.q;
return true;
}
Expand Down
1 change: 0 additions & 1 deletion libraries/AP_Mount/AP_Mount_Gremsy.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,5 @@ class AP_Mount_Gremsy : public AP_Mount_Backend
uint8_t _compid; // component id of gimbal
mavlink_gimbal_device_attitude_status_t _gimbal_device_attitude_status; // copy of most recently received gimbal status
uint32_t _last_attitude_status_ms; // system time last attitude status was received (used for health reporting)
uint32_t _sent_gimbal_device_attitude_status_ms; // time_boot_ms field of gimbal_device_status message last forwarded to the GCS (used to prevent sending duplicates)
};
#endif // HAL_MOUNT_GREMSY_ENABLED

0 comments on commit e80be4a

Please sign in to comment.