mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 15:08:28 -04:00
AP_NavEKF: define SourceSetSelection enum class and use it for clarity
This commit is contained in:
parent
96fe3da083
commit
23ce7cc416
libraries/AP_NavEKF
@ -148,11 +148,11 @@ AP_NavEKF_Source::AP_NavEKF_Source()
|
||||
}
|
||||
|
||||
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
|
||||
void AP_NavEKF_Source::setPosVelYawSourceSet(uint8_t source_set_idx)
|
||||
void AP_NavEKF_Source::setPosVelYawSourceSet(AP_NavEKF_Source::SourceSetSelection source_set_idx)
|
||||
{
|
||||
// sanity check source idx
|
||||
if (source_set_idx < AP_NAKEKF_SOURCE_SET_MAX) {
|
||||
active_source_set = source_set_idx;
|
||||
if ((uint8_t)source_set_idx < AP_NAKEKF_SOURCE_SET_MAX) {
|
||||
active_source_set = (uint8_t)source_set_idx;
|
||||
#if HAL_LOGGING_ENABLED
|
||||
static const LogEvent evt[AP_NAKEKF_SOURCE_SET_MAX] {
|
||||
LogEvent::EK3_SOURCES_SET_TO_PRIMARY,
|
||||
|
@ -51,6 +51,12 @@ public:
|
||||
ALIGN_EXTNAV_POS_WHEN_USING_OPTFLOW = (1 << 1) // align position of inactive sources to ahrs when using optical flow
|
||||
};
|
||||
|
||||
enum class SourceSetSelection : uint8_t {
|
||||
PRIMARY = 0,
|
||||
SECONDARY = 1,
|
||||
TERTIARY = 2,
|
||||
};
|
||||
|
||||
// initialisation
|
||||
void init();
|
||||
|
||||
@ -59,7 +65,7 @@ public:
|
||||
SourceZ getPosZSource() const;
|
||||
|
||||
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
|
||||
void setPosVelYawSourceSet(uint8_t source_set_idx);
|
||||
void setPosVelYawSourceSet(SourceSetSelection source_set_idx);
|
||||
uint8_t getPosVelYawSourceSet() const { return active_source_set; }
|
||||
|
||||
// get/set velocity source
|
||||
|
Loading…
Reference in New Issue
Block a user