26 #define AP_AHRS_NAVEKF_AVAILABLE 1 29 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 33 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 39 #define AP_AHRS_NAVEKF_SETTLE_TIME_MS 20000 // time in milliseconds the ekf needs to settle after being started 66 void update(
bool skip_ins_update=
false)
override;
67 void reset(
bool recover_eulers =
false)
override;
76 bool get_hagl(
float &hagl)
const override;
262 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 295 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
void get_relative_position_D_home(float &posD) const override
bool initialised() const override
bool get_relative_position_D_origin(float &posD) const override
bool use_compass() override
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
uint8_t get_primary_IMU_index(void) const
void send_ekf_status_report(mavlink_channel_t chan) const
const Vector3f & get_accel_ef_blended() const override
bool resetHeightDatum() override
float get_error_yaw() const override
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
bool get_secondary_attitude(Vector3f &eulers) const override
const Vector3f & get_gyro(void) const override
bool have_inertial_nav() const override
bool healthy() const override
const NavEKF3 & get_NavEKF3_const(void) const
bool get_secondary_position(struct Location &loc) const override
float get_error_rp() const override
bool get_filter_status(nav_filter_status &status) const
bool getGpsGlitchStatus() const
uint8_t ekf_type(void) const
AP_AHRS_NavEKF(NavEKF2 &_EKF2, NavEKF3 &_EKF3, Flags flags=FLAG_NONE)
bool get_hagl(float &hagl) const override
bool get_mag_field_correction(Vector3f &ret) const override
bool set_origin(const Location &loc) override
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
void setTakeoffExpected(bool val)
bool get_location(struct Location &loc) const
void reset_attitude(const float &roll, const float &pitch, const float &yaw) override
bool get_origin(Location &ret) const override
Vector3f _accel_ef_ekf_blended
uint32_t getLastYawResetAngle(float &yawAng) const override
NavEKF3 & get_NavEKF3(void)
bool get_relative_position_NED_home(Vector3f &vec) const override
bool airspeed_estimate(float *airspeed_ret) const override
const char * prearm_failure_reason(void) const override
const Vector3f & get_accel_ef() const override
void reset(bool recover_eulers=false) override
void getCorrectedDeltaVelocityNED(Vector3f &ret, float &dt) const override
const NavEKF2 & get_NavEKF2_const(void) const
bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const override
uint8_t get_primary_accel_index(void) const override
void update(bool skip_ins_update=false) override
Vector3f _accel_ef_ekf[INS_MAX_INSTANCES]
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
uint32_t getLastPosDownReset(float &posDelta) const override
bool get_position(struct Location &loc) const override
uint8_t setInhibitGPS(void)
bool get_relative_position_NE_origin(Vector2f &posNE) const override
bool have_ekf_logging(void) const override
uint32_t _last_body_odm_update_ms
bool get_vert_pos_rate(float &velocity) const
AP_AHRS_NavEKF & operator=(const AP_AHRS_NavEKF &)=delete
NavEKF2 & get_NavEKF2(void)
Vector3f wind_estimate() const override
uint8_t get_primary_gyro_index(void) const override
bool always_use_EKF() const
AP_HAL::AnalogSource * chan
const Matrix3f & get_rotation_body_to_ned(void) const override
void reset_gyro_drift() override
EKF_TYPE active_EKF_type(void) const
bool get_mag_field_NED(Vector3f &ret) const
uint32_t getLastVelNorthEastReset(Vector2f &vel) const override
bool get_relative_position_NED_origin(Vector3f &vec) const override
void setTouchdownExpected(bool val)
void force_ekf_start(void)
#define INS_MAX_INSTANCES
bool get_secondary_quaternion(Quaternion &quat) const override
void set_ekf_use(bool setting)
bool get_relative_position_NE_home(Vector2f &posNE) const override
Vector2f groundspeed_vector() override
bool get_velocity_NED(Vector3f &vec) const override
const uint16_t startup_delay_ms
bool get_hgt_ctrl_limit(float &limit) const override
void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms) override
const Vector3f & get_gyro_drift(void) const override
uint32_t getLastPosNorthEastReset(Vector2f &pos) const override
void update_DCM(bool skip_ins_update)