#include "AP_AHRS_config.h"
#if AP_AHRS_ENABLED
#include <AP_HAL/AP_HAL.h>
#include "AP_AHRS.h"
#include "AP_AHRS_View.h"
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
#include <AP_Module/AP_Module.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_InternalError/AP_InternalError.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_CustomRotations/AP_CustomRotations.h>
#include <AP_Mission/AP_Mission_config.h>
#if AP_MISSION_ENABLED
#include <AP_Mission/AP_Mission.h>
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <SITL/SITL.h>
#endif
#include <AP_NavEKF3/AP_NavEKF3_feature.h>
#define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10)
#define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20)
#ifndef HAL_AHRS_EKF_TYPE_DEFAULT
#define HAL_AHRS_EKF_TYPE_DEFAULT 3
#endif
#ifndef HAL_AHRS_OPTIONS_DEFAULT
#if APM_BUILD_TYPE(APM_BUILD_Rover)
#define HAL_AHRS_OPTIONS_DEFAULT 3
#elif APM_BUILD_TYPE(APM_BUILD_ArduSub)
#define HAL_AHRS_OPTIONS_DEFAULT 16
#else
#define HAL_AHRS_OPTIONS_DEFAULT 0
#endif
#endif
const AP_Param::GroupInfo AP_AHRS::var_info[] = {
AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS, gps_gain, 1.0f),
AP_GROUPINFO("GPS_USE", 3, AP_AHRS, _gps_use, float(GPSUse::Enable)),
AP_GROUPINFO("YAW_P", 4, AP_AHRS, _kp_yaw, 0.2f),
AP_GROUPINFO("RP_P", 5, AP_AHRS, _kp, 0.2f),
AP_GROUPINFO("WIND_MAX", 6, AP_AHRS, _wind_max, 0.0f),
AP_GROUPINFO("TRIM", 8, AP_AHRS, _trim, 0),
AP_GROUPINFO("ORIENTATION", 9, AP_AHRS, _board_orientation, 0),
AP_GROUPINFO("COMP_BETA", 10, AP_AHRS, beta, 0.1f),
AP_GROUPINFO("GPS_MINSATS", 11, AP_AHRS, _gps_minsats, 6),
AP_GROUPINFO("EKF_TYPE", 14, AP_AHRS, _ekf_type, HAL_AHRS_EKF_TYPE_DEFAULT),
AP_GROUPINFO("OPTIONS", 18, AP_AHRS, _options, HAL_AHRS_OPTIONS_DEFAULT),
AP_GROUPINFO("ORIGIN_LAT", 19, AP_AHRS, _origin_lat, 0),
AP_GROUPINFO("ORIGIN_LON", 20, AP_AHRS, _origin_lon, 0),
AP_GROUPINFO("ORIGIN_ALT", 21, AP_AHRS, _origin_alt, 0),
AP_GROUPEND
};
extern const AP_HAL::HAL& hal;
AP_AHRS::AP_AHRS(uint8_t flags) :
_ekf_flags(flags)
{
_singleton = this;
AP_Param::setup_object_defaults(this, var_info);
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduSub)
_ekf_flags |= AP_AHRS::FLAG_ALWAYS_USE_EKF;
#endif
state.dcm_matrix.identity();
_last_trim = _trim.get();
_rotation_autopilot_body_to_vehicle_body.from_euler(_last_trim.x, _last_trim.y, _last_trim.z);
_rotation_vehicle_body_to_autopilot_body = _rotation_autopilot_body_to_vehicle_body.transposed();
}
void AP_AHRS::init()
{
update_orientation();
if (_ekf_type.get() == 1) {
AP_BoardConfig::config_error("EKF1 not available");
}
#if !HAL_NAVEKF2_AVAILABLE && HAL_NAVEKF3_AVAILABLE
if (_ekf_type.get() == 2) {
_ekf_type.set(EKFType::THREE);
EKF3.set_enable(true);
}
#elif !HAL_NAVEKF3_AVAILABLE && HAL_NAVEKF2_AVAILABLE
if (_ekf_type.get() == 3) {
_ekf_type.set(EKFType::TWO);
EKF2.set_enable(true);
}
#endif
#if HAL_NAVEKF2_AVAILABLE && HAL_NAVEKF3_AVAILABLE
if (_ekf_type.get() == 2 && !EKF2.get_enable() && EKF3.get_enable()) {
_ekf_type.set(EKFType::THREE);
}
#endif
last_active_ekf_type = (EKFType)_ekf_type.get();
#if AP_AHRS_DCM_ENABLED
dcm.init();
#endif
#if AP_AHRS_EXTERNAL_ENABLED
external.init();
#endif
#if AP_CUSTOMROTATIONS_ENABLED
if (_board_orientation == ROTATION_CUSTOM_OLD) {
_board_orientation.set_and_save(ROTATION_CUSTOM_1);
AP_Param::ConversionInfo info;
if (AP_Param::find_top_level_key_by_pointer(this, info.old_key)) {
info.type = AP_PARAM_FLOAT;
float rpy[3] = {};
AP_Float rpy_param;
for (info.old_group_element=15; info.old_group_element<=17; info.old_group_element++) {
if (AP_Param::find_old_parameter(&info, &rpy_param)) {
rpy[info.old_group_element-15] = rpy_param.get();
}
}
AP::custom_rotations().convert(ROTATION_CUSTOM_1, rpy[0], rpy[1], rpy[2]);
}
}
#endif
}
bool AP_AHRS::has_status(Status status) const {
nav_filter_status filter_status;
if (!get_filter_status(filter_status)) {
return false;
}
return (filter_status.value & uint32_t(status)) != 0;
}
void AP_AHRS::update_trim_rotation_matrices()
{
if (_last_trim == _trim.get()) {
return;
}
_last_trim = _trim.get();
_rotation_autopilot_body_to_vehicle_body.from_euler(_last_trim.x, _last_trim.y, _last_trim.z);
_rotation_vehicle_body_to_autopilot_body = _rotation_autopilot_body_to_vehicle_body.transposed();
}
void AP_AHRS::get_quat_body_to_ned(Quaternion &quat) const
{
quat.from_rotation_matrix(get_rotation_body_to_ned());
}
Vector3f AP_AHRS::body_to_earth(const Vector3f &v) const
{
return get_rotation_body_to_ned() * v;
}
Vector3f AP_AHRS::earth_to_body(const Vector3f &v) const
{
return get_rotation_body_to_ned().mul_transpose(v);
}
void AP_AHRS::reset_gyro_drift(void)
{
WITH_SEMAPHORE(_rsem);
#if AP_AHRS_DCM_ENABLED
dcm.reset_gyro_drift();
#endif
#if AP_AHRS_EXTERNAL_ENABLED
external.reset_gyro_drift();
#endif
#if HAL_NAVEKF2_AVAILABLE
EKF2.resetGyroBias();
#endif
#if HAL_NAVEKF3_AVAILABLE
EKF3.resetGyroBias();
#endif
}
void AP_AHRS::update_state(void)
{
const uint8_t primary_gyro = _get_primary_gyro_index();
#if AP_INERTIALSENSOR_ENABLED
if (primary_gyro != state.primary_gyro) {
AP::ins().set_primary(primary_gyro);
}
#endif
state.primary_IMU = _get_primary_IMU_index();
state.primary_gyro = primary_gyro;
state.primary_accel = _get_primary_accel_index();
state.primary_core = _get_primary_core_index();
state.wind_estimate_ok = _wind_estimate(state.wind_estimate);
state.EAS2TAS = AP_AHRS_Backend::get_EAS2TAS();
state.airspeed_EAS_ok = _airspeed_EAS(state.airspeed_EAS, state.airspeed_estimate_type);
state.airspeed_TAS_ok = _airspeed_TAS(state.airspeed_TAS);
state.airspeed_TAS_vec_ok = _airspeed_TAS(state.airspeed_TAS_vec);
state.quat_ok = _get_quaternion(state.quat);
state.secondary_attitude_ok = _get_secondary_attitude(state.secondary_attitude);
state.secondary_quat_ok = _get_secondary_quaternion(state.secondary_quat);
state.location_ok = _get_location(state.location);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (state.location_ok && !state.location.initialised()) {
AP_HAL::panic("uninitialised location returned by _get_location");
}
#endif
state.secondary_pos_ok = _get_secondary_position(state.secondary_pos);
state.ground_speed_vec = _groundspeed_vector();
state.ground_speed = _groundspeed();
_getCorrectedDeltaVelocityNED(state.corrected_dv, state.corrected_dv_dt);
bool origin_ok = _get_origin(state.origin);
if (origin_ok && !state.origin_ok) {
state.origin_ok = origin_ok;
#if HAL_LOGGING_ENABLED
Log_Write_Home_And_Origin();
#endif
GCS_SEND_MESSAGE(MSG_ORIGIN);
record_origin();
}
if (!state.origin_ok) {
use_recorded_origin_maybe();
}
state.velocity_NED_ok = _get_velocity_NED(state.velocity_NED);
}
void AP_AHRS::update(bool skip_ins_update)
{
update_orientation();
if (!skip_ins_update) {
AP::ins().update();
}
WITH_SEMAPHORE(_rsem);
if (!_checked_watchdog_home) {
load_watchdog_home();
_checked_watchdog_home = true;
}
hal.scheduler->boost_end();
update_trim_rotation_matrices();
#if AP_AHRS_DCM_ENABLED
update_DCM();
#endif
update_flags();
#if AP_AHRS_SIM_ENABLED
update_SITL();
#endif
#if AP_AHRS_EXTERNAL_ENABLED
update_external();
#endif
if (_ekf_type == 2) {
#if HAL_NAVEKF2_AVAILABLE
update_EKF2();
#endif
#if HAL_NAVEKF3_AVAILABLE
update_EKF3();
#endif
} else {
#if HAL_NAVEKF3_AVAILABLE
update_EKF3();
#endif
#if HAL_NAVEKF2_AVAILABLE
update_EKF2();
#endif
}
#if AP_MODULE_SUPPORTED
AP_Module::call_hook_AHRS_update(*this);
#endif
if (hal.opticalflow) {
const Vector3f &exported_gyro_bias = get_gyro_drift();
hal.opticalflow->push_gyro_bias(exported_gyro_bias.x, exported_gyro_bias.y);
}
if (_view != nullptr) {
_view->update();
}
update_AOA_SSA();
state.active_EKF = _active_EKF_type();
#if HAL_GCS_ENABLED
if (state.active_EKF != last_active_ekf_type) {
last_active_ekf_type = state.active_EKF;
const char *shortname = "???";
switch ((EKFType)state.active_EKF) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
shortname = "DCM";
break;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
shortname = "SIM";
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
shortname = "External";
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
shortname = "EKF3";
break;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
shortname = "EKF2";
break;
#endif
}
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AHRS: %s active", shortname);
}
#endif
update_state();
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
const auto *sitl = AP::sitl();
if (sitl->loop_time_jitter_us > 0) {
hal.scheduler->delay_microseconds(random() % sitl->loop_time_jitter_us);
}
#endif
}
void AP_AHRS::copy_estimates_from_backend_estimates(const AP_AHRS_Backend::Estimates &results)
{
roll = results.roll_rad;
pitch = results.pitch_rad;
yaw = results.yaw_rad;
state.dcm_matrix = results.dcm_matrix;
state.gyro_estimate = results.gyro_estimate;
state.gyro_drift = results.gyro_drift;
state.accel_ef = results.accel_ef;
state.accel_bias = results.accel_bias;
update_cd_values();
update_trig();
}
#if AP_AHRS_DCM_ENABLED
void AP_AHRS::update_DCM()
{
dcm.update();
dcm.get_results(dcm_estimates);
copy_estimates_from_backend_estimates(dcm_estimates);
}
#endif
#if AP_AHRS_SIM_ENABLED
void AP_AHRS::update_SITL(void)
{
sim.update();
sim.get_results(sim_estimates);
if (_active_EKF_type() == EKFType::SIM) {
copy_estimates_from_backend_estimates(sim_estimates);
}
}
#endif
void AP_AHRS::update_notify_from_filter_status(const nav_filter_status &status)
{
AP_Notify::flags.gps_fusion = status.flags.using_gps;
AP_Notify::flags.gps_glitching = status.flags.gps_glitching;
AP_Notify::flags.have_pos_abs = status.flags.horiz_pos_abs;
}
#if HAL_NAVEKF2_AVAILABLE
void AP_AHRS::update_EKF2(void)
{
if (!_ekf2_started) {
if (start_time_ms == 0) {
start_time_ms = AP_HAL::millis();
}
#if HAL_LOGGING_ENABLED
if (!hal.util->was_watchdog_reset()) {
if (AP_HAL::millis() - start_time_ms < 5000) {
if (!AP::logger().allow_start_ekf()) {
return;
}
}
}
#endif
if (AP_HAL::millis() - start_time_ms > startup_delay_ms) {
_ekf2_started = EKF2.InitialiseFilter();
}
}
if (_ekf2_started) {
EKF2.UpdateFilter();
if (_active_EKF_type() == EKFType::TWO) {
Vector3f eulers;
EKF2.getRotationBodyToNED(state.dcm_matrix);
EKF2.getEulerAngles(eulers);
roll = eulers.x;
pitch = eulers.y;
yaw = eulers.z;
update_cd_values();
update_trig();
const AP_InertialSensor &_ins = AP::ins();
const int8_t primary_imu = EKF2.getPrimaryCoreIMUIndex();
const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_first_usable_gyro();
const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_first_usable_accel();
Vector3f drift;
EKF2.getGyroBias(drift);
state.gyro_drift = -drift;
state.gyro_estimate = _ins.get_gyro(primary_gyro) + state.gyro_drift;
float &abias = state.accel_bias.z;
EKF2.getAccelZBias(abias);
Vector3f accel = _ins.get_accel(primary_accel);
accel.z -= abias;
state.accel_ef = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel;
nav_filter_status filt_state;
EKF2.getFilterStatus(filt_state);
update_notify_from_filter_status(filt_state);
}
if (!done_common_origin) {
Location new_origin;
if (EKF2.getOriginLLH(new_origin)) {
done_common_origin = true;
#if HAL_NAVEKF3_AVAILABLE
EKF3.setOriginLLH(new_origin);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
external.set_origin(new_origin);
#endif
}
}
}
}
#endif
#if HAL_NAVEKF3_AVAILABLE
void AP_AHRS::update_EKF3(void)
{
if (!_ekf3_started) {
if (start_time_ms == 0) {
start_time_ms = AP_HAL::millis();
}
#if HAL_LOGGING_ENABLED
if (!hal.util->was_watchdog_reset()) {
if (AP_HAL::millis() - start_time_ms < 5000) {
if (!AP::logger().allow_start_ekf()) {
return;
}
}
}
#endif
if (AP_HAL::millis() - start_time_ms > startup_delay_ms) {
_ekf3_started = EKF3.InitialiseFilter();
}
}
if (_ekf3_started) {
EKF3.UpdateFilter();
if (_active_EKF_type() == EKFType::THREE) {
Vector3f eulers;
EKF3.getRotationBodyToNED(state.dcm_matrix);
EKF3.getEulerAngles(eulers);
roll = eulers.x;
pitch = eulers.y;
yaw = eulers.z;
update_cd_values();
update_trig();
const AP_InertialSensor &_ins = AP::ins();
const int8_t primary_imu = EKF3.getPrimaryCoreIMUIndex();
const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_first_usable_gyro();
const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_first_usable_accel();
Vector3f drift;
EKF3.getGyroBias(-1, drift);
state.gyro_drift = -drift;
state.gyro_estimate = _ins.get_gyro(primary_gyro) + state.gyro_drift;
Vector3f &abias = state.accel_bias;
EKF3.getAccelBias(-1,abias);
Vector3f accel = _ins.get_accel(primary_accel);
accel -= abias;
state.accel_ef = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel;
nav_filter_status filt_state;
EKF3.getFilterStatus(filt_state);
update_notify_from_filter_status(filt_state);
}
if (!done_common_origin) {
Location new_origin;
if (EKF3.getOriginLLH(new_origin)) {
done_common_origin = true;
#if HAL_NAVEKF2_AVAILABLE
EKF2.setOriginLLH(new_origin);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
external.set_origin(new_origin);
#endif
}
}
}
}
#endif
#if AP_AHRS_EXTERNAL_ENABLED
void AP_AHRS::update_external(void)
{
external.update();
external.get_results(external_estimates);
if (_active_EKF_type() == EKFType::EXTERNAL) {
copy_estimates_from_backend_estimates(external_estimates);
}
if (!done_common_origin) {
Location new_origin;
if (external.get_origin(new_origin)) {
done_common_origin = true;
#if HAL_NAVEKF2_AVAILABLE
EKF2.setOriginLLH(new_origin);
#endif
#if HAL_NAVEKF3_AVAILABLE
EKF3.setOriginLLH(new_origin);
#endif
}
}
}
#endif
void AP_AHRS::reset()
{
WITH_SEMAPHORE(_rsem);
#if AP_AHRS_DCM_ENABLED
dcm.reset();
#endif
#if AP_AHRS_SIM_ENABLED
sim.reset();
#endif
#if AP_AHRS_EXTERNAL_ENABLED
external.reset();
#endif
#if HAL_NAVEKF2_AVAILABLE
if (_ekf2_started) {
_ekf2_started = EKF2.InitialiseFilter();
}
#endif
#if HAL_NAVEKF3_AVAILABLE
if (_ekf3_started) {
_ekf3_started = EKF3.InitialiseFilter();
}
#endif
}
bool AP_AHRS::_get_location(Location &loc) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm_estimates.get_location(loc);
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
if (EKF2.getLLH(loc)) {
return true;
}
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
if (EKF3.getLLH(loc)) {
return true;
}
break;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim_estimates.get_location(loc);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external_estimates.get_location(loc);
#endif
}
#if AP_AHRS_DCM_ENABLED
if (!always_use_EKF()) {
return dcm_estimates.get_location(loc);
}
#endif
return false;
}
float AP_AHRS::get_error_rp(void) const
{
#if AP_AHRS_DCM_ENABLED
return dcm.get_error_rp();
#endif
return 0;
}
float AP_AHRS::get_error_yaw(void) const
{
#if AP_AHRS_DCM_ENABLED
return dcm.get_error_yaw();
#endif
return 0;
}
bool AP_AHRS::_wind_estimate(Vector3f &wind) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm.wind_estimate(wind);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.wind_estimate(wind);
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
EKF2.getWind(wind);
return true;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getWind(wind);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external.wind_estimate(wind);
#endif
}
return false;
}
float AP_AHRS::wind_alignment(const float heading_deg) const
{
Vector3f wind;
if (!wind_estimate(wind)) {
return 0;
}
const float wind_heading_rad = atan2f(-wind.y, -wind.x);
return cosf(wind_heading_rad - radians(heading_deg));
}
float AP_AHRS::head_wind(void) const
{
const float alignment = wind_alignment(get_yaw_deg());
return alignment * wind_estimate().xy().length();
}
bool AP_AHRS::using_airspeed_sensor() const
{
return state.airspeed_estimate_type == AirspeedEstimateType::AIRSPEED_SENSOR;
}
bool AP_AHRS::_should_use_airspeed_sensor(uint8_t airspeed_index) const
{
if (!airspeed_sensor_enabled(airspeed_index)) {
return false;
}
nav_filter_status filter_status;
if (!option_set(Options::DISABLE_AIRSPEED_EKF_CHECK) &&
fly_forward &&
hal.util->get_soft_armed() &&
get_filter_status(filter_status) &&
(filter_status.flags.rejecting_airspeed && !filter_status.flags.dead_reckoning)) {
return false;
}
return true;
}
bool AP_AHRS::_airspeed_EAS(float &airspeed_ret, AirspeedEstimateType &airspeed_estimate_type) const
{
#if AP_AHRS_DCM_ENABLED || (AP_AIRSPEED_ENABLED && AP_GPS_ENABLED)
const uint8_t idx = get_active_airspeed_index();
#endif
#if AP_AIRSPEED_ENABLED && AP_GPS_ENABLED
if (_should_use_airspeed_sensor(idx)) {
airspeed_ret = AP::airspeed()->get_airspeed(idx);
if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
const float gnd_speed = AP::gps().ground_speed();
float true_airspeed = airspeed_ret * get_EAS2TAS();
true_airspeed = constrain_float(true_airspeed,
gnd_speed - _wind_max,
gnd_speed + _wind_max);
airspeed_ret = true_airspeed / get_EAS2TAS();
}
airspeed_estimate_type = AirspeedEstimateType::AIRSPEED_SENSOR;
return true;
}
#endif
if (!get_wind_estimation_enabled()) {
airspeed_estimate_type = AirspeedEstimateType::NO_NEW_ESTIMATE;
return false;
}
Vector3f wind_vel;
bool have_wind = false;
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC;
return dcm.airspeed_EAS(idx, airspeed_ret);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
airspeed_estimate_type = AirspeedEstimateType::SIM;
return sim.airspeed_EAS(airspeed_ret);
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
#if AP_AHRS_DCM_ENABLED
airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC;
return dcm.airspeed_EAS(idx, airspeed_ret);
#else
return false;
#endif
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
have_wind = EKF3.getWind(wind_vel);
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
#if AP_AHRS_DCM_ENABLED
airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC;
return dcm.airspeed_EAS(idx, airspeed_ret);
#else
return false;
#endif
#endif
}
Vector3f nav_vel;
if (have_wind && have_inertial_nav() && get_velocity_NED(nav_vel)) {
Vector3f true_airspeed_vec = nav_vel - wind_vel;
float true_airspeed = true_airspeed_vec.length();
float gnd_speed = nav_vel.length();
if (_wind_max > 0) {
float tas_lim_lower = MAX(0.0f, (gnd_speed - _wind_max));
float tas_lim_upper = MAX(tas_lim_lower, (gnd_speed + _wind_max));
true_airspeed = constrain_float(true_airspeed, tas_lim_lower, tas_lim_upper);
} else {
true_airspeed = MAX(0.0f, true_airspeed);
}
airspeed_ret = true_airspeed / get_EAS2TAS();
airspeed_estimate_type = AirspeedEstimateType::EKF3_SYNTHETIC;
return true;
}
#if AP_AHRS_DCM_ENABLED
airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC;
return dcm.airspeed_EAS(idx, airspeed_ret);
#endif
return false;
}
bool AP_AHRS::_airspeed_TAS(float &airspeed_ret) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm.airspeed_TAS(airspeed_ret);
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
#endif
break;
}
if (!airspeed_EAS(airspeed_ret)) {
return false;
}
airspeed_ret *= get_EAS2TAS();
return true;
}
bool AP_AHRS::_airspeed_TAS(Vector3f &vec) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
break;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.getAirSpdVec(vec);
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getAirSpdVec(vec);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
break;
#endif
}
return false;
}
bool AP_AHRS::airspeed_health_data(uint8_t instance, float &innovation, float &innovationVariance, uint32_t &age_ms) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
break;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getAirSpdHealthData(instance, innovation, innovationVariance, age_ms);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
break;
#endif
}
return false;
}
bool AP_AHRS::use_compass(void)
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
break;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.use_compass();
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.use_compass();
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.use_compass();
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
break;
#endif
}
#if AP_AHRS_DCM_ENABLED
return dcm.use_compass();
#endif
return false;
}
bool AP_AHRS::_get_quaternion(Quaternion &quat) const
{
return _get_quaternion_for_ekf_type(quat, active_EKF_type());
}
bool AP_AHRS::_get_quaternion_for_ekf_type(Quaternion &quat, EKFType type) const
{
switch (type) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
if (!dcm_estimates.attitude_valid) {
return false;
}
quat = dcm_estimates.quaternion;
break;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
if (!_ekf2_started) {
return false;
}
EKF2.getQuaternion(quat);
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
if (!_ekf3_started) {
return false;
}
EKF3.getQuaternion(quat);
break;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
if (!sim_estimates.attitude_valid) {
return false;
}
quat = sim_estimates.quaternion;
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
if (!external_estimates.attitude_valid) {
return false;
}
quat = external_estimates.quaternion;
return true;
#endif
}
quat.rotate(-_trim.get());
return true;
}
bool AP_AHRS::_get_secondary_attitude(Vector3f &eulers) const
{
EKFType secondary_ekf_type;
if (!_get_secondary_EKF_type(secondary_ekf_type)) {
return false;
}
switch (secondary_ekf_type) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
eulers[0] = dcm_estimates.roll_rad;
eulers[1] = dcm_estimates.pitch_rad;
eulers[2] = dcm_estimates.yaw_rad;
return dcm_estimates.attitude_valid;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
EKF2.getEulerAngles(eulers);
return _ekf2_started;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
EKF3.getEulerAngles(eulers);
return _ekf3_started;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
eulers[0] = sim_estimates.roll_rad;
eulers[1] = sim_estimates.pitch_rad;
eulers[2] = sim_estimates.yaw_rad;
return sim_estimates.attitude_valid;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL: {
eulers[0] = external_estimates.roll_rad;
eulers[1] = external_estimates.pitch_rad;
eulers[2] = external_estimates.yaw_rad;
return external_estimates.attitude_valid;
}
#endif
}
return false;
}
bool AP_AHRS::_get_secondary_quaternion(Quaternion &quat) const
{
EKFType secondary_ekf_type;
if (!_get_secondary_EKF_type(secondary_ekf_type)) {
return false;
}
return _get_quaternion_for_ekf_type(quat, secondary_ekf_type);
}
bool AP_AHRS::_get_secondary_position(Location &loc) const
{
EKFType secondary_ekf_type;
if (!_get_secondary_EKF_type(secondary_ekf_type)) {
return false;
}
switch (secondary_ekf_type) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
loc = dcm_estimates.location;
return true;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
EKF2.getLLH(loc);
return _ekf2_started;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
EKF3.getLLH(loc);
return _ekf3_started;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return false;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external_estimates.get_location(loc);
#endif
}
return false;
}
Vector2f AP_AHRS::_groundspeed_vector(void)
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm.groundspeed_vector();
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO: {
Vector3f vec;
EKF2.getVelNED(vec);
return vec.xy();
}
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE: {
Vector3f vec;
EKF3.getVelNED(vec);
return vec.xy();
}
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.groundspeed_vector();
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL: {
return external.groundspeed_vector();
}
#endif
}
return Vector2f();
}
float AP_AHRS::_groundspeed(void)
{
return groundspeed_vector().length();
}
bool AP_AHRS::set_origin(const Location &loc)
{
WITH_SEMAPHORE(_rsem);
#if HAL_NAVEKF2_AVAILABLE
const bool ret2 = EKF2.setOriginLLH(loc);
#endif
#if HAL_NAVEKF3_AVAILABLE
const bool ret3 = EKF3.setOriginLLH(loc);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
const bool ret_ext = external.set_origin(loc);
#endif
bool success = false;
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
break;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
success = ret2;
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
success = ret3;
break;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
success = ret_ext;
break;
#endif
}
return success;
}
void AP_AHRS::record_origin()
{
if (!option_set(Options::RECORD_ORIGIN)) {
return;
}
_origin_lat.set_and_save_ifchanged(state.origin.lat * 1.0e-7);
_origin_lon.set_and_save_ifchanged(state.origin.lng * 1.0e-7);
_origin_alt.set_and_save_ifchanged(state.origin.alt * 1.0e-2);
}
void AP_AHRS::use_recorded_origin_maybe()
{
if (state.origin_ok || !option_set(Options::USE_RECORDED_ORIGIN_FOR_NONGPS)) {
return;
}
if (is_zero(_origin_lat.get()) && is_zero(_origin_lon.get()) && is_zero(_origin_alt.get())) {
return;
}
if (using_gps()) {
return;
}
const Location loc {
int32_t(_origin_lat.get() * 1e7),
int32_t(_origin_lon.get() * 1e7),
int32_t(_origin_alt.get() * 100),
Location::AltFrame::ABSOLUTE
};
if (set_origin(loc)) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AHRS: using recorded origin:%.7f,%.7f,%.1f",
(double)_origin_lat.get(), (double)_origin_lon.get(), (double)_origin_alt.get());
}
}
#if AP_AHRS_POSITION_RESET_ENABLED
bool AP_AHRS::handle_external_position_estimate(const Location &loc, float pos_accuracy, uint32_t timestamp_ms)
{
#if HAL_NAVEKF3_AVAILABLE
return EKF3.setLatLng(loc, pos_accuracy, timestamp_ms);
#endif
return false;
}
#endif
bool AP_AHRS::have_inertial_nav(void) const
{
#if AP_AHRS_DCM_ENABLED
return active_EKF_type() != EKFType::DCM;
#endif
return true;
}
bool AP_AHRS::_get_velocity_NED(Vector3f &vec) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
break;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
EKF2.getVelNED(vec);
return true;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
EKF3.getVelNED(vec);
return true;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim_estimates.get_velocity_NED(vec);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external_estimates.get_velocity_NED(vec);
#endif
}
#if AP_AHRS_DCM_ENABLED
return dcm_estimates.get_velocity_NED(vec);
#endif
return false;
}
bool AP_AHRS::get_mag_field_NED(Vector3f &vec) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return false;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
EKF2.getMagNED(vec);
return true;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
EKF3.getMagNED(vec);
return true;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return false;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return false;
#endif
}
return false;
}
bool AP_AHRS::get_mag_field_correction(Vector3f &vec) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return false;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
EKF2.getMagXYZ(vec);
return true;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
EKF3.getMagXYZ(vec);
return true;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return false;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return false;
#endif
}
return false;
}
bool AP_AHRS::get_velocity_D(float &velD, bool high_vibes) const
{
Vector3f velNED;
if (!high_vibes && get_velocity_NED(velNED)) {
velD = velNED.z;
return true;
}
return get_vert_pos_rate_D(velD);
}
bool AP_AHRS::get_vert_pos_rate_D(float &velocity) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm_estimates.get_vert_pos_rate_D(velocity);
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
velocity = EKF2.getPosDownDerivative();
return true;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
velocity = EKF3.getPosDownDerivative();
return true;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim_estimates.get_vert_pos_rate_D(velocity);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external_estimates.get_vert_pos_rate_D(velocity);
#endif
}
return false;
}
bool AP_AHRS::get_hagl(float &height) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return false;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.getHAGL(height);
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getHAGL(height);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.get_hagl(height);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL: {
return false;
}
#endif
}
return false;
}
bool AP_AHRS::get_relative_position_NED_origin(Vector3p &vec) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm.get_relative_position_NED_origin(vec);
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO: {
Vector2p posNE;
postype_t posD;
if (EKF2.getPosNE(posNE) && EKF2.getPosD(posD)) {
vec.x = posNE.x;
vec.y = posNE.y;
vec.z = posD;
return true;
}
return false;
}
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE: {
Vector2p posNE;
postype_t posD;
if (EKF3.getPosNE(posNE) && EKF3.getPosD(posD)) {
vec.x = posNE.x;
vec.y = posNE.y;
vec.z = posD;
return true;
}
return false;
}
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.get_relative_position_NED_origin(vec);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL: {
return external.get_relative_position_NED_origin(vec);
}
#endif
}
return false;
}
bool AP_AHRS::get_relative_position_NED_origin_float(Vector3f &vec) const
{
Vector3p tmp_posNED;
if (!get_relative_position_NED_origin(tmp_posNED)) {
return false;
}
vec = tmp_posNED.tofloat();
return true;
}
bool AP_AHRS::get_relative_position_NED_home(Vector3f &vec) const
{
Location loc;
if (!_home_is_set ||
!get_location(loc)) {
return false;
}
vec = _home.get_distance_NED(loc);
return true;
}
bool AP_AHRS::get_relative_position_NE_origin(Vector2p &posNE) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm.get_relative_position_NE_origin(posNE);
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO: {
bool position_is_valid = EKF2.getPosNE(posNE);
return position_is_valid;
}
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE: {
bool position_is_valid = EKF3.getPosNE(posNE);
return position_is_valid;
}
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM: {
return sim.get_relative_position_NE_origin(posNE);
}
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external.get_relative_position_NE_origin(posNE);
#endif
}
return false;
}
bool AP_AHRS::get_relative_position_NE_origin_float(Vector2f &posNE) const
{
Vector2p tmp_posNE;
if (!get_relative_position_NE_origin(tmp_posNE)) {
return false;
}
posNE = tmp_posNE.tofloat();
return true;
}
bool AP_AHRS::get_relative_position_NE_home(Vector2f &posNE) const
{
Location loc;
if (!_home_is_set ||
!get_location(loc)) {
return false;
}
posNE = _home.get_distance_NE(loc);
return true;
}
bool AP_AHRS::get_relative_position_D_origin(postype_t &posD) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm.get_relative_position_D_origin(posD);
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO: {
bool position_is_valid = EKF2.getPosD(posD);
return position_is_valid;
}
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE: {
bool position_is_valid = EKF3.getPosD(posD);
return position_is_valid;
}
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.get_relative_position_D_origin(posD);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external.get_relative_position_D_origin(posD);
#endif
}
return false;
}
bool AP_AHRS::get_relative_position_D_origin_float(float &posD) const
{
postype_t tmp_posD;
if (!get_relative_position_D_origin(tmp_posD)) {
return false;
}
posD = float(tmp_posD);
return true;
}
void AP_AHRS::get_relative_position_D_home(float &posD) const
{
if (!_home_is_set) {
posD = -AP::baro().get_altitude();
return;
}
Location originLLH;
postype_t originD;
if (!get_relative_position_D_origin(originD) ||
!_get_origin(originLLH)) {
#if AP_GPS_ENABLED
const auto &gps = AP::gps();
if (_gps_use == GPSUse::EnableWithHeight &&
gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
posD = (_home.alt - gps.location().alt) * 0.01;
return;
}
#endif
posD = -AP::baro().get_altitude();
return;
}
posD = originD - ((originLLH.alt - _home.alt) * 0.01f);
return;
}
AP_AHRS::EKFType AP_AHRS::configured_ekf_type(void) const
{
EKFType type = (EKFType)_ekf_type.get();
switch (type) {
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return type;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return type;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return type;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return type;
#endif
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
if (always_use_EKF()) {
#if HAL_NAVEKF2_AVAILABLE
return EKFType::TWO;
#elif HAL_NAVEKF3_AVAILABLE
return EKFType::THREE;
#endif
}
return EKFType::DCM;
#endif
}
#if HAL_NAVEKF2_AVAILABLE
return EKFType::TWO;
#elif HAL_NAVEKF3_AVAILABLE
return EKFType::THREE;
#elif AP_AHRS_DCM_ENABLED
return EKFType::DCM;
#else
#error "no default backend available"
#endif
}
AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const
{
EKFType ret = fallback_active_EKF_type();
switch (configured_ekf_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return EKFType::DCM;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO: {
if (!_ekf2_started) {
return fallback_active_EKF_type();
}
if (always_use_EKF()) {
uint16_t ekf2_faults;
EKF2.getFilterFaults(ekf2_faults);
if (ekf2_faults == 0) {
ret = EKFType::TWO;
}
} else if (EKF2.healthy()) {
ret = EKFType::TWO;
}
break;
}
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE: {
if (!_ekf3_started) {
return fallback_active_EKF_type();
}
if (always_use_EKF()) {
uint16_t ekf3_faults;
EKF3.getFilterFaults(ekf3_faults);
if (ekf3_faults == 0) {
ret = EKFType::THREE;
}
} else if (EKF3.healthy()) {
ret = EKFType::THREE;
}
break;
}
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
ret = EKFType::SIM;
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
ret = EKFType::EXTERNAL;
break;
#endif
}
#if AP_AHRS_DCM_ENABLED
if (_vehicle_class == VehicleClass::FIXED_WING ||
_vehicle_class == VehicleClass::GROUND) {
bool should_use_gps = true;
nav_filter_status filt_state {};
switch (ret) {
case EKFType::DCM:
break;
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
EKF2.getFilterStatus(filt_state);
should_use_gps = EKF2.configuredToUseGPSForPosXY();
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
EKF3.getFilterStatus(filt_state);
should_use_gps = EKF3.configuredToUseGPSForPosXY();
break;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
get_filter_status(filt_state);
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
get_filter_status(filt_state);
should_use_gps = true;
break;
#endif
}
const bool can_use_dcm = dcm.yaw_source_available() || fly_forward;
const bool can_use_ekf = filt_state.flags.attitude && filt_state.flags.vert_vel && filt_state.flags.vert_pos;
if (!can_use_dcm && can_use_ekf) {
return ret;
} else if (!can_use_ekf) {
return EKFType::DCM;
}
const bool disable_dcm_fallback = fly_forward?
option_set(Options::DISABLE_DCM_FALLBACK_FW) : option_set(Options::DISABLE_DCM_FALLBACK_VTOL);
if (disable_dcm_fallback) {
return ret;
}
if (hal.util->get_soft_armed() &&
(_gps_use != GPSUse::Disable) &&
should_use_gps &&
AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D &&
(!filt_state.flags.using_gps || !filt_state.flags.horiz_pos_abs)) {
return EKFType::DCM;
}
if (hal.util->get_soft_armed() && filt_state.flags.const_pos_mode) {
return EKFType::DCM;
}
if (!filt_state.flags.horiz_vel ||
(!filt_state.flags.horiz_pos_abs && !filt_state.flags.horiz_pos_rel)) {
if ((!AP::compass().use_for_yaw()) &&
AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D &&
AP::gps().ground_speed() < 2) {
if (filt_state.flags.gps_quality_good) {
return ret;
}
}
return EKFType::DCM;
}
}
#endif
return ret;
}
AP_AHRS::EKFType AP_AHRS::fallback_active_EKF_type(void) const
{
#if AP_AHRS_DCM_ENABLED
return EKFType::DCM;
#endif
#if HAL_NAVEKF3_AVAILABLE
if (_ekf3_started) {
return EKFType::THREE;
}
#endif
#if HAL_NAVEKF2_AVAILABLE
if (_ekf2_started) {
return EKFType::TWO;
}
#endif
#if AP_AHRS_EXTERNAL_ENABLED
if (external.healthy()) {
return EKFType::EXTERNAL;
}
#endif
#if HAL_NAVEKF3_AVAILABLE
return EKFType::THREE;
#elif HAL_NAVEKF2_AVAILABLE
return EKFType::TWO;
#elif AP_AHRS_EXTERNAL_ENABLED
return EKFType::EXTERNAL;
#endif
}
bool AP_AHRS::_get_secondary_EKF_type(EKFType &secondary_ekf_type) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
#if HAL_NAVEKF3_AVAILABLE
if ((EKFType)_ekf_type.get() == EKFType::THREE) {
secondary_ekf_type = EKFType::THREE;
return true;
}
#endif
#if HAL_NAVEKF2_AVAILABLE
if ((EKFType)_ekf_type.get() == EKFType::TWO) {
secondary_ekf_type = EKFType::TWO;
return true;
}
#endif
#if AP_AHRS_EXTERNAL_ENABLED
if ((EKFType)_ekf_type.get() == EKFType::EXTERNAL) {
secondary_ekf_type = EKFType::EXTERNAL;
return true;
}
#endif
return false;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
#endif
secondary_ekf_type = fallback_active_EKF_type();
return true;
}
return false;
}
bool AP_AHRS::healthy(void) const
{
switch (configured_ekf_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm.healthy();
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO: {
bool ret = _ekf2_started && EKF2.healthy();
if (!ret) {
return false;
}
if ((_vehicle_class == VehicleClass::FIXED_WING ||
_vehicle_class == VehicleClass::GROUND) &&
active_EKF_type() != EKFType::TWO) {
return false;
}
return true;
}
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE: {
bool ret = _ekf3_started && EKF3.healthy();
if (!ret) {
return false;
}
if ((_vehicle_class == VehicleClass::FIXED_WING ||
_vehicle_class == VehicleClass::GROUND) &&
active_EKF_type() != EKFType::THREE) {
return false;
}
return true;
}
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.healthy();
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external.healthy();
#endif
}
return false;
}
bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const
{
bool ret = true;
if (!healthy()) {
hal.util->snprintf(failure_msg, failure_msg_len, "Not healthy");
ret = false;
}
#if AP_AHRS_EXTERNAL_ENABLED
if (AP::externalAHRS().enabled() || (configured_ekf_type() == EKFType::EXTERNAL)) {
if (!AP::externalAHRS().pre_arm_check(failure_msg, failure_msg_len)) {
return false;
}
}
#endif
if (!attitudes_consistent(failure_msg, failure_msg_len)) {
return false;
}
if (_ekf_type != int8_t(configured_ekf_type()) ||
(configured_ekf_type() != active_EKF_type() && AP::compass().use_for_yaw())) {
hal.util->snprintf(failure_msg, failure_msg_len, "not using configured AHRS type");
return false;
}
switch (configured_ekf_type()) {
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return ret;
#endif
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm.pre_arm_check(requires_position, failure_msg, failure_msg_len) && ret;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external.pre_arm_check(requires_position, failure_msg, failure_msg_len);
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
if (!_ekf2_started) {
hal.util->snprintf(failure_msg, failure_msg_len, "EKF2 not started");
return false;
}
return EKF2.pre_arm_check(failure_msg, failure_msg_len) && ret;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
if (!_ekf3_started) {
hal.util->snprintf(failure_msg, failure_msg_len, "EKF3 not started");
return false;
}
return EKF3.pre_arm_check(requires_position, failure_msg, failure_msg_len) && ret;
#endif
}
hal.util->snprintf(failure_msg, failure_msg_len, "invalid EKF type");
return false;
}
bool AP_AHRS::initialised(void) const
{
switch (configured_ekf_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return true;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return (_ekf2_started && (AP_HAL::millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return (_ekf3_started && (AP_HAL::millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return true;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external.initialised();
#endif
}
return false;
};
bool AP_AHRS::get_filter_status(nav_filter_status &status) const
{
switch (configured_ekf_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm.get_filter_status(status);
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
EKF2.getFilterStatus(status);
return true;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
EKF3.getFilterStatus(status);
return true;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.get_filter_status(status);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external.get_filter_status(status);
#endif
}
return false;
}
void AP_AHRS::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset, float heightOverride)
{
#if HAL_NAVEKF2_AVAILABLE
EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);
#endif
#if EK3_FEATURE_OPTFLOW_FUSION
EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride);
#endif
}
bool AP_AHRS::getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const
{
#if EK3_FEATURE_OPTFLOW_FUSION
return EKF3.getOptFlowSample(timeStamp_ms, flowRate, bodyRate, losPred);
#endif
return false;
}
void AP_AHRS::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset)
{
#if HAL_NAVEKF3_AVAILABLE
EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, delay_ms, posOffset);
#endif
}
void AP_AHRS::writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms)
{
#if HAL_NAVEKF2_AVAILABLE
EKF2.writeExtNavData(pos, quat, posErr, angErr, timeStamp_ms, delay_ms, resetTime_ms);
#endif
#if HAL_NAVEKF3_AVAILABLE
EKF3.writeExtNavData(pos, quat, posErr, angErr, timeStamp_ms, delay_ms, resetTime_ms);
#endif
}
void AP_AHRS::writeDefaultAirSpeed(float airspeed, float uncertainty)
{
#if HAL_NAVEKF2_AVAILABLE
EKF2.writeDefaultAirSpeed(airspeed);
#endif
#if HAL_NAVEKF3_AVAILABLE
EKF3.writeDefaultAirSpeed(airspeed, uncertainty);
#endif
}
void AP_AHRS::writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms)
{
#if HAL_NAVEKF2_AVAILABLE
EKF2.writeExtNavVelData(vel, err, timeStamp_ms, delay_ms);
#endif
#if HAL_NAVEKF3_AVAILABLE
EKF3.writeExtNavVelData(vel, err, timeStamp_ms, delay_ms);
#endif
}
void AP_AHRS::writeTerrainAMSL(float alt_amsl_m)
{
#if EK3_FEATURE_OPTFLOW_SRTM
if (!state.origin_ok) {
return;
}
const float alt_above_origin_m = alt_amsl_m - (state.origin.alt * 0.01f);
EKF3.writeTerrainData(alt_above_origin_m);
#endif
}
void AP_AHRS::getControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
dcm.get_control_limits(ekfGndSpdLimit, ekfNavVelGainScaler);
break;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
EKF2.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
EKF3.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
break;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
sim.get_control_limits(ekfGndSpdLimit, ekfNavVelGainScaler);
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
ekfGndSpdLimit = 400;
ekfNavVelGainScaler = 1;
break;
#endif
}
}
float AP_AHRS::getControlScaleZ(void) const
{
#if AP_AHRS_DCM_ENABLED
if (active_EKF_type() == EKFType::DCM) {
return 0.25;
}
#endif
return 1;
}
bool AP_AHRS::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
{
switch (configured_ekf_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return false;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.getMagOffsets(mag_idx, magOffsets);
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getMagOffsets(mag_idx, magOffsets);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
magOffsets.zero();
return true;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return false;
#endif
}
return false;
}
void AP_AHRS::_getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const
{
int8_t imu_idx = -1;
Vector3f accel_bias;
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
break;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
imu_idx = EKF2.getPrimaryCoreIMUIndex();
EKF2.getAccelZBias(accel_bias.z);
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
imu_idx = EKF3.getPrimaryCoreIMUIndex();
EKF3.getAccelBias(-1,accel_bias);
break;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
break;
#endif
}
ret.zero();
if (imu_idx == -1) {
AP::ins().get_delta_velocity(ret, dt);
return;
}
AP::ins().get_delta_velocity((uint8_t)imu_idx, ret, dt);
ret -= accel_bias*dt;
ret = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * ret;
ret.z += GRAVITY_MSS*dt;
}
void AP_AHRS::set_failure_inconsistent_message(const char *estimator, const char *axis, float diff_rad, char *failure_msg, const uint8_t failure_msg_len) const
{
hal.util->snprintf(failure_msg, failure_msg_len, "%s %s inconsistent %d deg. Wait or reboot", estimator, axis, (int)degrees(diff_rad));
}
bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const
{
Quaternion primary_quat;
get_quat_body_to_ned(primary_quat);
const bool check_yaw = AP::compass().use_for_yaw();
uint8_t total_ekf_cores = 0;
#if HAL_NAVEKF2_AVAILABLE
if (configured_ekf_type() == EKFType::TWO || active_EKF_type() == EKFType::TWO) {
for (uint8_t i = 0; i < EKF2.activeCores(); i++) {
Quaternion ekf2_quat;
EKF2.getQuaternionBodyToNED(i, ekf2_quat);
const float rp_diff_rad = primary_quat.roll_pitch_difference(ekf2_quat);
if (rp_diff_rad > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {
set_failure_inconsistent_message("EKF2", "Roll/Pitch", rp_diff_rad, failure_msg, failure_msg_len);
return false;
}
Vector3f angle_diff;
primary_quat.angular_difference(ekf2_quat).to_axis_angle(angle_diff);
const float yaw_diff = fabsf(angle_diff.z);
if (check_yaw && (yaw_diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {
set_failure_inconsistent_message("EKF2", "Yaw", yaw_diff, failure_msg, failure_msg_len);
return false;
}
}
total_ekf_cores = EKF2.activeCores();
}
#endif
#if HAL_NAVEKF3_AVAILABLE
if (configured_ekf_type() == EKFType::THREE || active_EKF_type() == EKFType::THREE) {
for (uint8_t i = 0; i < EKF3.activeCores(); i++) {
Quaternion ekf3_quat;
EKF3.getQuaternionBodyToNED(i, ekf3_quat);
const float rp_diff_rad = primary_quat.roll_pitch_difference(ekf3_quat);
if (rp_diff_rad > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {
set_failure_inconsistent_message("EKF3", "Roll/Pitch", rp_diff_rad, failure_msg, failure_msg_len);
return false;
}
Vector3f angle_diff;
primary_quat.angular_difference(ekf3_quat).to_axis_angle(angle_diff);
const float yaw_diff = fabsf(angle_diff.z);
if (check_yaw && (yaw_diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {
set_failure_inconsistent_message("EKF3", "Yaw", yaw_diff, failure_msg, failure_msg_len);
return false;
}
}
total_ekf_cores += EKF3.activeCores();
}
#endif
#if AP_AHRS_DCM_ENABLED
if (!always_use_EKF() || (total_ekf_cores == 1)) {
Quaternion dcm_quat;
dcm_quat.from_rotation_matrix(get_DCM_rotation_body_to_ned());
const float rp_diff_rad = primary_quat.roll_pitch_difference(dcm_quat);
if (rp_diff_rad > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {
set_failure_inconsistent_message("DCM", "Roll/Pitch", rp_diff_rad, failure_msg, failure_msg_len);
return false;
}
bool using_noncompass_for_yaw = false;
#if HAL_NAVEKF3_AVAILABLE
using_noncompass_for_yaw = (configured_ekf_type() == EKFType::THREE) && EKF3.using_noncompass_for_yaw();
#endif
if (!always_use_EKF() && !using_noncompass_for_yaw) {
Vector3f angle_diff;
primary_quat.angular_difference(dcm_quat).to_axis_angle(angle_diff);
const float yaw_diff = fabsf(angle_diff.z);
if (check_yaw && (yaw_diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {
set_failure_inconsistent_message("DCM", "Yaw", yaw_diff, failure_msg, failure_msg_len);
return false;
}
}
}
#endif
return true;
}
uint32_t AP_AHRS::getLastYawResetAngle(float &yawAng)
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm.getLastYawResetAngle(yawAng);
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.getLastYawResetAngle(yawAng);
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getLastYawResetAngle(yawAng);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.getLastYawResetAngle(yawAng);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external.getLastYawResetAngle(yawAng);
#endif
}
return 0;
}
uint32_t AP_AHRS::getLastPosNorthEastReset(Vector2f &pos)
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return 0;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.getLastPosNorthEastReset(pos);
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getLastPosNorthEastReset(pos);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.getLastPosNorthEastReset(pos);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return 0;
#endif
}
return 0;
}
uint32_t AP_AHRS::getLastVelNorthEastReset(Vector2f &vel) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return 0;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.getLastVelNorthEastReset(vel);
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getLastVelNorthEastReset(vel);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.getLastVelNorthEastReset(vel);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return 0;
#endif
}
return 0;
}
uint32_t AP_AHRS::getLastPosDownReset(float &posDelta)
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return 0;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.getLastPosDownReset(posDelta);
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getLastPosDownReset(posDelta);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.getLastPosDownReset(posDelta);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return 0;
#endif
}
return 0;
}
void AP_AHRS::resetHeightDatum(void)
{
WITH_SEMAPHORE(_rsem);
#if HAL_NAVEKF3_AVAILABLE
EKF3.resetHeightDatum();
#endif
#if HAL_NAVEKF2_AVAILABLE
EKF2.resetHeightDatum();
#endif
#if AP_AHRS_SIM_ENABLED
sim.resetHeightDatum();
#endif
}
void AP_AHRS::send_ekf_status_report(GCS_MAVLINK &link) const
{
switch (configured_ekf_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
dcm.send_ekf_status_report(link);
break;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
sim.send_ekf_status_report(link);
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL: {
external.send_ekf_status_report(link);
break;
}
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.send_status_report(link);
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.send_status_report(link);
#endif
}
}
bool AP_AHRS::_get_origin(EKFType type, Location &ret) const
{
switch (type) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return dcm.get_origin(ret);
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.getOriginLLH(ret);
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getOriginLLH(ret);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.get_origin(ret);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external.get_origin(ret);
#endif
}
return false;
}
bool AP_AHRS::_get_origin(Location &ret) const
{
if (_get_origin(configured_ekf_type(), ret)) {
return true;
}
if (hal.util->get_soft_armed() && _get_origin(active_EKF_type(), ret)) {
return true;
}
return false;
}
bool AP_AHRS::set_home(const Location &loc)
{
WITH_SEMAPHORE(_rsem);
if (!loc.initialised()) {
return false;
}
if (!loc.check_latlng()) {
return false;
}
Location tmp = loc;
if (!tmp.change_alt_frame(Location::AltFrame::ABSOLUTE)) {
return false;
}
#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && HAL_LOGGING_ENABLED
if (!_home_is_set) {
AP::logger().Write_Event(LogEvent::SET_HOME);
}
#endif
_home = tmp;
_home_is_set = true;
#if HAL_LOGGING_ENABLED
Log_Write_Home_And_Origin();
#endif
GCS_SEND_MESSAGE(MSG_HOME);
GCS_SEND_MESSAGE(MSG_ORIGIN);
AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
pd.home_lat = loc.lat;
pd.home_lon = loc.lng;
pd.home_alt_cm = loc.alt;
#if AP_MISSION_ENABLED
AP_Mission *mission = AP::mission();
if (mission != nullptr) {
mission->write_home_to_storage();
}
#endif
return true;
}
void AP_AHRS::load_watchdog_home()
{
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
if (hal.util->was_watchdog_reset() && (pd.home_lat != 0 || pd.home_lon != 0)) {
_home.lat = pd.home_lat;
_home.lng = pd.home_lon;
_home.set_alt_cm(pd.home_alt_cm, Location::AltFrame::ABSOLUTE);
_home_is_set = true;
_home_locked = true;
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Restored watchdog home");
}
}
bool AP_AHRS::get_hgt_ctrl_limit(float& limit) const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return false;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.getHeightControlLimit(limit);
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getHeightControlLimit(limit);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return false;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return false;
#endif
}
return false;
}
void AP_AHRS::set_terrain_hgt_stable(bool stable)
{
switch (terrainHgtStableState) {
case TriState::UNKNOWN:
break;
case TriState::True:
if (stable) {
return;
}
break;
case TriState::False:
if (!stable) {
return;
}
break;
}
terrainHgtStableState = (TriState)stable;
#if HAL_NAVEKF2_AVAILABLE
EKF2.setTerrainHgtStable(stable);
#endif
#if HAL_NAVEKF3_AVAILABLE
EKF3.setTerrainHgtStable(stable);
#endif
}
bool AP_AHRS::get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
{
switch (configured_ekf_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return false;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov);
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.get_innovations(velInnov, posInnov, magInnov, tasInnov, yawInnov);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return false;
#endif
}
return false;
}
bool AP_AHRS::is_vibration_affected() const
{
switch (configured_ekf_type()) {
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.isVibrationAffected();
#endif
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
#endif
return false;
}
return false;
}
bool AP_AHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const
{
switch (configured_ekf_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return false;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO: {
Vector2f offset;
return EKF2.getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
}
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE: {
Vector2f offset;
return EKF3.getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
}
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.get_variances(velVar, posVar, hgtVar, magVar, tasVar);
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return external.get_variances(velVar, posVar, hgtVar, magVar, tasVar);
#endif
}
return false;
}
bool AP_AHRS::get_vel_innovations_and_variances_for_source(uint8_t source, Vector3f &innovations, Vector3f &variances) const
{
switch (configured_ekf_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return false;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return false;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getVelInnovationsAndVariancesForSource((AP_NavEKF_Source::SourceXY)source, innovations, variances);
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return false;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return false;
#endif
}
return false;
}
uint8_t AP_AHRS::get_active_airspeed_index() const
{
#if AP_AIRSPEED_ENABLED
const auto *airspeed = AP::airspeed();
if (airspeed == nullptr) {
return 0;
}
#if HAL_NAVEKF3_AVAILABLE
if (active_EKF_type() == EKFType::THREE) {
uint8_t ret = EKF3.getActiveAirspeed();
if (ret != UINT8_MAX && airspeed->healthy(ret) && airspeed->use(ret)) {
return ret;
}
}
#endif
return airspeed->get_primary();
#else
return 0;
#endif
}
uint8_t AP_AHRS::_get_primary_IMU_index() const
{
int8_t imu = -1;
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
break;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
imu = EKF2.getPrimaryCoreIMUIndex();
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
imu = EKF3.getPrimaryCoreIMUIndex();
break;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
break;
#endif
}
if (imu == -1) {
imu = AP::ins().get_first_usable_gyro();
}
return imu;
}
int8_t AP_AHRS::_get_primary_core_index() const
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return 0;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return 0;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
return 0;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.getPrimaryCoreIndex();
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.getPrimaryCoreIndex();
#endif
}
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
return -1;
}
uint8_t AP_AHRS::_get_primary_accel_index(void) const
{
return _get_primary_IMU_index();
}
uint8_t AP_AHRS::_get_primary_gyro_index(void) const
{
return _get_primary_IMU_index();
}
void AP_AHRS::check_lane_switch(void)
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
break;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
break;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
EKF2.checkLaneSwitch();
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
EKF3.checkLaneSwitch();
break;
#endif
}
}
void AP_AHRS::request_yaw_reset(void)
{
switch (active_EKF_type()) {
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
break;
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
break;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
break;
#endif
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
EKF2.requestYawReset();
break;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
EKF3.requestYawReset();
break;
#endif
}
}
void AP_AHRS::set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx)
{
#if HAL_NAVEKF3_AVAILABLE
EKF3.setPosVelYawSourceSet((uint8_t)source_set_idx);
#endif
}
uint8_t AP_AHRS::get_posvelyaw_source_set() const
{
#if HAL_NAVEKF3_AVAILABLE
return EKF3.get_active_source_set();
#else
return 0;
#endif
}
void AP_AHRS::Log_Write()
{
#if HAL_NAVEKF2_AVAILABLE
EKF2.Log_Write();
#endif
#if HAL_NAVEKF3_AVAILABLE
EKF3.Log_Write();
#endif
Write_AHRS2();
Write_POS();
#if AP_AHRS_SIM_ENABLED
AP::sitl()->Log_Write_SIMSTATE();
#endif
}
bool AP_AHRS::using_noncompass_for_yaw(void) const
{
switch (active_EKF_type()) {
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.isExtNavUsedForYaw();
#endif
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.using_noncompass_for_yaw();
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
#endif
return false;
}
return false;
}
bool AP_AHRS::using_extnav_for_yaw(void) const
{
switch (active_EKF_type()) {
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.isExtNavUsedForYaw();
#endif
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.using_extnav_for_yaw();
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
#endif
return false;
}
return false;
}
bool AP_AHRS::using_gps(void) const
{
switch (active_EKF_type()) {
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.using_gps();
#endif
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
return _gps_use != GPSUse::Disable;
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.using_gps();
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
#endif
return true;
}
return true;
}
void AP_AHRS::set_alt_measurement_noise(float noise)
{
#if HAL_NAVEKF2_AVAILABLE
EKF2.set_baro_alt_noise(noise);
#endif
#if HAL_NAVEKF3_AVAILABLE
EKF3.set_baro_alt_noise(noise);
#endif
}
const EKFGSF_yaw *AP_AHRS::get_yaw_estimator(void) const
{
switch (active_EKF_type()) {
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
return EKF2.get_yawEstimator();
#endif
#if AP_AHRS_DCM_ENABLED
case EKFType::DCM:
#if HAL_NAVEKF3_AVAILABLE
return EKF3.get_yawEstimator();
#else
return nullptr;
#endif
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
return EKF3.get_yawEstimator();
#endif
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:
#endif
return nullptr;
}
return nullptr;
}
bool AP_AHRS::get_location(Location &loc) const
{
loc = state.location;
return state.location_ok;
}
bool AP_AHRS::wind_estimate(Vector3f &wind) const
{
wind = state.wind_estimate;
return state.wind_estimate_ok;
}
bool AP_AHRS::airspeed_EAS(float &airspeed_ret) const
{
airspeed_ret = state.airspeed_EAS;
return state.airspeed_EAS_ok;
}
bool AP_AHRS::airspeed_EAS(float &airspeed_ret, AP_AHRS::AirspeedEstimateType &type) const
{
airspeed_ret = state.airspeed_EAS;
type = state.airspeed_estimate_type;
return state.airspeed_EAS_ok;
}
bool AP_AHRS::airspeed_TAS(float &airspeed_ret) const
{
airspeed_ret = state.airspeed_TAS;
return state.airspeed_TAS_ok;
}
bool AP_AHRS::airspeed_vector_TAS(Vector3f &vec) const
{
vec = state.airspeed_TAS_vec;
return state.airspeed_TAS_vec_ok;
}
bool AP_AHRS::get_quaternion(Quaternion &quat) const
{
quat = state.quat;
return state.quat_ok;
}
bool AP_AHRS::get_origin(Location &ret) const
{
ret = state.origin;
return state.origin_ok;
}
bool AP_AHRS::get_velocity_NED(Vector3f &vec) const
{
vec = state.velocity_NED;
return state.velocity_NED_ok;
}
bool AP_AHRS::get_location_from_origin_offset_NED(Location &loc, const Vector3p &offset_ned) const
{
if (!get_origin(loc)) {
return false;
}
loc.offset(offset_ned);
return true;
}
bool AP_AHRS::get_location_from_home_offset_NED(Location &loc, const Vector3p &offset_ned) const
{
if (!home_is_set()) {
return false;
}
loc = get_home();
loc.offset(offset_ned);
return true;
}
float AP_AHRS::get_EAS2TAS(void) const
{
if (is_positive(state.EAS2TAS)) {
return state.EAS2TAS;
}
return 1.0;
}
float AP_AHRS::get_air_density_ratio(void) const
{
const float eas2tas = get_EAS2TAS();
return 1.0 / sq(eas2tas);
}
AP_AHRS *AP_AHRS::_singleton;
namespace AP {
AP_AHRS &ahrs()
{
return *AP_AHRS::get_singleton();
}
}
#endif