AP_ExternalAHRS: align origin with AHRS origin

automatically set origin to AHRS origin. This means if on boot
external AHRS is not the primary then it will use the origin from the
active backend, preventing a jump on change of backends
This commit is contained in:
Andrew Tridgell 2023-12-02 08:59:27 +11:00
parent 376426a088
commit cbc14d1fa5
1 changed files with 15 additions and 0 deletions

View File

@ -27,6 +27,7 @@
#include "AP_ExternalAHRS_MicroStrain7.h"
#include <GCS_MAVLink/GCS.h>
#include <AP_AHRS/AP_AHRS.h>
extern const AP_HAL::HAL &hal;
@ -242,6 +243,20 @@ void AP_ExternalAHRS::update(void)
if (backend) {
backend->update();
}
/*
if backend has not supplied an origin and AHRS has an origin
then use that origin so we get a common origin for minimum
disturbance when switching backends
*/
WITH_SEMAPHORE(state.sem);
if (!state.have_origin) {
Location origin;
if (AP::ahrs().get_origin(origin)) {
state.origin = origin;
state.have_origin = true;
}
}
}
// Get model/type name