mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_AHRS: allow NavEKFs to be compiled out
This commit is contained in:
parent
73c32f403b
commit
583b25e6aa
File diff suppressed because it is too large
Load Diff
@ -23,6 +23,14 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
|
#ifndef HAL_NAVEKF2_AVAILABLE
|
||||||
|
#define HAL_NAVEKF2_AVAILABLE 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef HAL_NAVEKF3_AVAILABLE
|
||||||
|
#define HAL_NAVEKF3_AVAILABLE 1
|
||||||
|
#endif
|
||||||
|
|
||||||
#define AP_AHRS_NAVEKF_AVAILABLE 1
|
#define AP_AHRS_NAVEKF_AVAILABLE 1
|
||||||
#include "AP_AHRS.h"
|
#include "AP_AHRS.h"
|
||||||
|
|
||||||
@ -89,19 +97,23 @@ public:
|
|||||||
bool use_compass() override;
|
bool use_compass() override;
|
||||||
|
|
||||||
// we will need to remove these to fully hide which EKF we are using
|
// we will need to remove these to fully hide which EKF we are using
|
||||||
|
#if HAL_NAVEKF2_AVAILABLE
|
||||||
NavEKF2 &get_NavEKF2(void) {
|
NavEKF2 &get_NavEKF2(void) {
|
||||||
return EKF2;
|
return EKF2;
|
||||||
}
|
}
|
||||||
const NavEKF2 &get_NavEKF2_const(void) const {
|
const NavEKF2 &get_NavEKF2_const(void) const {
|
||||||
return EKF2;
|
return EKF2;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAL_NAVEKF3_AVAILABLE
|
||||||
NavEKF3 &get_NavEKF3(void) {
|
NavEKF3 &get_NavEKF3(void) {
|
||||||
return EKF3;
|
return EKF3;
|
||||||
}
|
}
|
||||||
const NavEKF3 &get_NavEKF3_const(void) const {
|
const NavEKF3 &get_NavEKF3_const(void) const {
|
||||||
return EKF3;
|
return EKF3;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// return secondary attitude solution if available, as eulers in radians
|
// return secondary attitude solution if available, as eulers in radians
|
||||||
bool get_secondary_attitude(Vector3f &eulers) const override;
|
bool get_secondary_attitude(Vector3f &eulers) const override;
|
||||||
@ -272,14 +284,22 @@ public:
|
|||||||
bool is_ext_nav_used_for_yaw(void) const;
|
bool is_ext_nav_used_for_yaw(void) const;
|
||||||
|
|
||||||
// these are only out here so vehicles can reference them for parameters
|
// these are only out here so vehicles can reference them for parameters
|
||||||
|
#if HAL_NAVEKF2_AVAILABLE
|
||||||
NavEKF2 EKF2;
|
NavEKF2 EKF2;
|
||||||
|
#endif
|
||||||
|
#if HAL_NAVEKF3_AVAILABLE
|
||||||
NavEKF3 EKF3;
|
NavEKF3 EKF3;
|
||||||
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
enum class EKFType {
|
enum class EKFType {
|
||||||
NONE = 0,
|
NONE = 0,
|
||||||
|
#if HAL_NAVEKF3_AVAILABLE
|
||||||
THREE = 3,
|
THREE = 3,
|
||||||
|
#endif
|
||||||
|
#if HAL_NAVEKF2_AVAILABLE
|
||||||
TWO = 2
|
TWO = 2
|
||||||
|
#endif
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
,SITL = 10
|
,SITL = 10
|
||||||
#endif
|
#endif
|
||||||
@ -290,8 +310,14 @@ private:
|
|||||||
return _ekf_flags & FLAG_ALWAYS_USE_EKF;
|
return _ekf_flags & FLAG_ALWAYS_USE_EKF;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_NAVEKF2_AVAILABLE
|
||||||
|
void update_EKF2(void);
|
||||||
bool _ekf2_started;
|
bool _ekf2_started;
|
||||||
|
#endif
|
||||||
|
#if HAL_NAVEKF3_AVAILABLE
|
||||||
bool _ekf3_started;
|
bool _ekf3_started;
|
||||||
|
void update_EKF3(void);
|
||||||
|
#endif
|
||||||
bool _force_ekf;
|
bool _force_ekf;
|
||||||
|
|
||||||
// rotation from vehicle body to NED frame
|
// rotation from vehicle body to NED frame
|
||||||
@ -308,8 +334,6 @@ private:
|
|||||||
|
|
||||||
EKFType ekf_type(void) const;
|
EKFType ekf_type(void) const;
|
||||||
void update_DCM(bool skip_ins_update);
|
void update_DCM(bool skip_ins_update);
|
||||||
void update_EKF2(void);
|
|
||||||
void update_EKF3(void);
|
|
||||||
|
|
||||||
// get the index of the current primary IMU
|
// get the index of the current primary IMU
|
||||||
uint8_t get_primary_IMU_index(void) const;
|
uint8_t get_primary_IMU_index(void) const;
|
||||||
|
Loading…
Reference in New Issue
Block a user