diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 8b1f4b3626..634fc8358e 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -3335,10 +3335,10 @@ void AP_AHRS::request_yaw_reset(void) } // set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary -void AP_AHRS::set_posvelyaw_source_set(uint8_t source_set_idx) +void AP_AHRS::set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx) { #if HAL_NAVEKF3_AVAILABLE - EKF3.setPosVelYawSourceSet(source_set_idx); + EKF3.setPosVelYawSourceSet((uint8_t)source_set_idx); #endif } diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index e6d40a6fc5..98cd09fefc 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -417,7 +417,7 @@ public: void request_yaw_reset(void); // set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary - void set_posvelyaw_source_set(uint8_t source_set_idx); + void set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx); //returns index of active source set used, 0=primary, 1=secondary, 2=tertiary uint8_t get_posvelyaw_source_set() const; diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.h b/libraries/AP_AHRS/AP_AHRS_Backend.h index c309084b48..0e70ce9662 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.h +++ b/libraries/AP_AHRS/AP_AHRS_Backend.h @@ -25,6 +25,7 @@ #include #include #include +#include #define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees #define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter @@ -117,7 +118,7 @@ public: virtual void request_yaw_reset(void) {} // set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary - virtual void set_posvelyaw_source_set(uint8_t source_set_idx) {} + virtual void set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx) {} // reset the current gyro drift estimate // should be called if gyro offsets are recalculated