AP_ExternalAHRS: Don't send init message till booted up

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
Ryan Friedman 2024-03-23 17:22:19 -06:00 committed by Andrew Tridgell
parent d383a19c29
commit 9edc0f8ec6
1 changed files with 4 additions and 3 deletions

View File

@ -71,7 +71,7 @@ AP_ExternalAHRS_MicroStrain7::AP_ExternalAHRS_MicroStrain7(AP_ExternalAHRS *_fro
uint16_t(AP_ExternalAHRS::AvailableSensor::COMPASS));
hal.scheduler->delay(5000);
if(!initialised()) {
if (!initialised()) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "MicroStrain7 ExternalAHRS failed to initialise.");
}
}
@ -93,10 +93,11 @@ void AP_ExternalAHRS_MicroStrain7::update_thread(void)
void AP_ExternalAHRS_MicroStrain7::check_initialise_state(void)
{
const auto new_init_state = initialised();
if (!last_init_state && new_init_state) {
// Only send the message after fully booted up, otherwise it gets dropped.
if (!last_init_state && new_init_state && AP_HAL::millis() > 5000) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MicroStrain7 ExternalAHRS initialised.");
last_init_state = new_init_state;
}
last_init_state = new_init_state;
}