mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: use EKFType enum class in set_ekf_type()
This commit is contained in:
parent
757607e4f8
commit
6f79c1cee2
@ -220,12 +220,12 @@ void AP_AHRS::init()
|
|||||||
}
|
}
|
||||||
#if !HAL_NAVEKF2_AVAILABLE && HAL_NAVEKF3_AVAILABLE
|
#if !HAL_NAVEKF2_AVAILABLE && HAL_NAVEKF3_AVAILABLE
|
||||||
if (_ekf_type.get() == 2) {
|
if (_ekf_type.get() == 2) {
|
||||||
_ekf_type.set(3);
|
_ekf_type.set(EKFType::THREE);
|
||||||
EKF3.set_enable(true);
|
EKF3.set_enable(true);
|
||||||
}
|
}
|
||||||
#elif !HAL_NAVEKF3_AVAILABLE && HAL_NAVEKF2_AVAILABLE
|
#elif !HAL_NAVEKF3_AVAILABLE && HAL_NAVEKF2_AVAILABLE
|
||||||
if (_ekf_type.get() == 3) {
|
if (_ekf_type.get() == 3) {
|
||||||
_ekf_type.set(2);
|
_ekf_type.set(EKFType::TWO);
|
||||||
EKF2.set_enable(true);
|
EKF2.set_enable(true);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -234,7 +234,7 @@ void AP_AHRS::init()
|
|||||||
// a special case to catch users who had AHRS_EKF_TYPE=2 saved and
|
// a special case to catch users who had AHRS_EKF_TYPE=2 saved and
|
||||||
// updated to a version where EK2_ENABLE=0
|
// updated to a version where EK2_ENABLE=0
|
||||||
if (_ekf_type.get() == 2 && !EKF2.get_enable() && EKF3.get_enable()) {
|
if (_ekf_type.get() == 2 && !EKF2.get_enable() && EKF3.get_enable()) {
|
||||||
_ekf_type.set(3);
|
_ekf_type.set(EKFType::THREE);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -421,8 +421,26 @@ public:
|
|||||||
return _ekf_type;
|
return _ekf_type;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
enum class EKFType : uint8_t {
|
||||||
|
#if AP_AHRS_DCM_ENABLED
|
||||||
|
DCM = 0,
|
||||||
|
#endif
|
||||||
|
#if HAL_NAVEKF3_AVAILABLE
|
||||||
|
THREE = 3,
|
||||||
|
#endif
|
||||||
|
#if HAL_NAVEKF2_AVAILABLE
|
||||||
|
TWO = 2,
|
||||||
|
#endif
|
||||||
|
#if AP_AHRS_SIM_ENABLED
|
||||||
|
SIM = 10,
|
||||||
|
#endif
|
||||||
|
#if HAL_EXTERNAL_AHRS_ENABLED
|
||||||
|
EXTERNAL = 11,
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
// set the selected ekf type, for RC aux control
|
// set the selected ekf type, for RC aux control
|
||||||
void set_ekf_type(uint8_t ahrs_type) {
|
void set_ekf_type(EKFType ahrs_type) {
|
||||||
_ekf_type.set(ahrs_type);
|
_ekf_type.set(ahrs_type);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -673,7 +691,7 @@ private:
|
|||||||
*/
|
*/
|
||||||
AP_Int8 _wind_max;
|
AP_Int8 _wind_max;
|
||||||
AP_Int8 _board_orientation;
|
AP_Int8 _board_orientation;
|
||||||
AP_Int8 _ekf_type;
|
AP_Enum<EKFType> _ekf_type;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* DCM-backend parameters; it takes references to these
|
* DCM-backend parameters; it takes references to these
|
||||||
@ -688,24 +706,6 @@ private:
|
|||||||
AP_Enum<GPSUse> _gps_use;
|
AP_Enum<GPSUse> _gps_use;
|
||||||
AP_Int8 _gps_minsats;
|
AP_Int8 _gps_minsats;
|
||||||
|
|
||||||
enum class EKFType {
|
|
||||||
#if AP_AHRS_DCM_ENABLED
|
|
||||||
DCM = 0,
|
|
||||||
#endif
|
|
||||||
#if HAL_NAVEKF3_AVAILABLE
|
|
||||||
THREE = 3,
|
|
||||||
#endif
|
|
||||||
#if HAL_NAVEKF2_AVAILABLE
|
|
||||||
TWO = 2,
|
|
||||||
#endif
|
|
||||||
#if AP_AHRS_SIM_ENABLED
|
|
||||||
SIM = 10,
|
|
||||||
#endif
|
|
||||||
#if HAL_EXTERNAL_AHRS_ENABLED
|
|
||||||
EXTERNAL = 11,
|
|
||||||
#endif
|
|
||||||
};
|
|
||||||
|
|
||||||
EKFType active_EKF_type(void) const { return state.active_EKF; }
|
EKFType active_EKF_type(void) const { return state.active_EKF; }
|
||||||
|
|
||||||
bool always_use_EKF() const {
|
bool always_use_EKF() const {
|
||||||
|
Loading…
Reference in New Issue
Block a user