mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_AHRS_NavEKF: reflect changes to getMagOffsets
This commit is contained in:
parent
97112ccd44
commit
6a5f1c0bec
@ -981,16 +981,16 @@ void AP_AHRS_NavEKF::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVel
|
||||
|
||||
// get compass offset estimates
|
||||
// true if offsets are valid
|
||||
bool AP_AHRS_NavEKF::getMagOffsets(Vector3f &magOffsets)
|
||||
bool AP_AHRS_NavEKF::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets)
|
||||
{
|
||||
switch (ekf_type()) {
|
||||
case 0:
|
||||
case 1:
|
||||
return EKF1.getMagOffsets(magOffsets);
|
||||
return EKF1.getMagOffsets(mag_idx, magOffsets);
|
||||
|
||||
case 2:
|
||||
default:
|
||||
return EKF2.getMagOffsets(magOffsets);
|
||||
return EKF2.getMagOffsets(mag_idx, magOffsets);
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
case EKF_TYPE_SITL:
|
||||
|
@ -164,7 +164,7 @@ public:
|
||||
|
||||
// get compass offset estimates
|
||||
// true if offsets are valid
|
||||
bool getMagOffsets(Vector3f &magOffsets);
|
||||
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets);
|
||||
|
||||
// report any reason for why the backend is refusing to initialise
|
||||
const char *prearm_failure_reason(void) const override;
|
||||
|
Loading…
Reference in New Issue
Block a user