Skip to content

Commit

Permalink
prearm, tidy
Browse files Browse the repository at this point in the history
  • Loading branch information
olliw42 committed Dec 30, 2023
1 parent 672fbe8 commit 1b4a4cb
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 2 deletions.
11 changes: 11 additions & 0 deletions libraries/AP_Mount/AP_Mount_STorM32_MAVLink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1222,6 +1222,17 @@ void AP_Mount_STorM32_MAVLink::update_checks()
{
char txt[255];

if (!(AP::arming().get_enabled_checks() & AP_Arming::ArmingChecks::ARMING_CHECK_ALL ||
AP::arming().get_enabled_checks() & AP_Arming::ArmingChecks::ARMING_CHECK_CAMERA)) {
if (_initialised && _gimbal_prearmchecks_ok) {
if (!_prearmchecks_passed && !_request_send_banner_ms) { // state changed and not going to send soon anyways
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MNT%u: prearm checks passed", _instance+1);
}
_prearmchecks_passed = true;
}
return;
}

if (_armingchecks_running) _armingchecks_running--; // count down

if (_prearmchecks_passed && AP::notify().flags.armed &&
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Mount/AP_Mount_STorM32_MAVLink.h
Original file line number Diff line number Diff line change
Expand Up @@ -235,7 +235,7 @@ class AP_Mount_STorM32_MAVLink : public AP_Mount_Backend
uint32_t _gimbal_error_flags; // error flags in custom_mode field of the HEARTBEAT message (restricted to 16 bits)
bool _gimbal_prearmchecks_ok; // true when the gimbal stops reporting prearm fail in the HEARTBEAT message

mutable uint8_t _armingchecks_running; // true when ARMING_CHECK_ALL or ARMING_CHECK_CAMERA set, we know from healty()
mutable uint8_t _armingchecks_running; // true when ARMING_CHECK_ALL,ARMING_CHECK_CAMERA set and running, we know from healthy()
bool _healthy;

bool _prearmchecks_passed; // becomes true when all checks were passed once at startup
Expand Down Expand Up @@ -267,7 +267,7 @@ class AP_Mount_STorM32_MAVLink : public AP_Mount_Backend

struct {
uint16_t received_flags; // obtained from GIMBAL_DEVICE_ATTITUDE_STATUS
uint32_t received_failure_flags; // obtained from GIMBAL_DEVICE_ATTITUDE_STATUS
uint32_t received_failure_flags; // obtained from GIMBAL_DEVICE_ATTITUDE_STATUS
uint32_t received_tlast_ms; // time last GIMBAL_DEVICE_ATTITUDE_STATUS was received (used for health reporting)
} _device_status;

Expand Down

0 comments on commit 1b4a4cb

Please sign in to comment.