AP_AHRS: use SourceSetSelection enum class

This commit is contained in:
Tatsuya Yamaguchi 2023-06-19 23:19:28 +09:00 committed by Peter Barker
parent 83c544f792
commit f58d88d144
3 changed files with 5 additions and 4 deletions

View File

@ -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
}

View File

@ -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;

View File

@ -25,6 +25,7 @@
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Common/Location.h>
#include <AP_NavEKF/AP_NavEKF_Source.h>
#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