diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 6be34de803..f77ea3551c 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -252,7 +252,7 @@ void AP_AHRS::init() #if AP_AHRS_DCM_ENABLED dcm.init(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED external.init(); #endif @@ -321,7 +321,7 @@ void AP_AHRS::reset_gyro_drift(void) #if AP_AHRS_DCM_ENABLED dcm.reset_gyro_drift(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED external.reset_gyro_drift(); #endif @@ -400,7 +400,7 @@ void AP_AHRS::update(bool skip_ins_update) update_SITL(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED update_external(); #endif @@ -458,7 +458,7 @@ void AP_AHRS::update(bool skip_ins_update) shortname = "SIM"; break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: shortname = "External"; break; @@ -685,7 +685,7 @@ void AP_AHRS::update_EKF3(void) } #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED void AP_AHRS::update_external(void) { external.update(); @@ -695,7 +695,7 @@ void AP_AHRS::update_external(void) copy_estimates_from_backend_estimates(external_estimates); } } -#endif // HAL_EXTERNAL_AHRS_ENABLED +#endif // AP_AHRS_EXTERNAL_ENABLED void AP_AHRS::reset() { @@ -709,7 +709,7 @@ void AP_AHRS::reset() sim.reset(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED external.reset(); #endif @@ -754,7 +754,7 @@ bool AP_AHRS::_get_location(Location &loc) const return sim_estimates.get_location(loc); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external_estimates.get_location(loc); #endif @@ -812,7 +812,7 @@ bool AP_AHRS::_wind_estimate(Vector3f &wind) const return EKF3.getWind(wind); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.wind_estimate(wind); #endif @@ -942,7 +942,7 @@ bool AP_AHRS::_airspeed_estimate(float &airspeed_ret, AirspeedEstimateType &airs break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #if AP_AHRS_DCM_ENABLED airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC; @@ -996,7 +996,7 @@ bool AP_AHRS::_airspeed_estimate_true(float &airspeed_ret) const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif break; @@ -1033,7 +1033,7 @@ bool AP_AHRS::_airspeed_vector_true(Vector3f &vec) const break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -1065,7 +1065,7 @@ bool AP_AHRS::airspeed_health_data(float &innovation, float &innovationVariance, break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -1108,7 +1108,7 @@ bool AP_AHRS::use_compass(void) return sim.use_compass(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -1155,7 +1155,7 @@ bool AP_AHRS::_get_quaternion(Quaternion &quat) const } break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: // we assume the external AHRS isn't trimmed with the autopilot! return external.get_quaternion(quat); @@ -1206,7 +1206,7 @@ bool AP_AHRS::_get_secondary_attitude(Vector3f &eulers) const return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: { // External is secondary eulers[0] = external_estimates.roll_rad; @@ -1267,7 +1267,7 @@ bool AP_AHRS::_get_secondary_quaternion(Quaternion &quat) const return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: // External is secondary return external.get_quaternion(quat); @@ -1319,7 +1319,7 @@ bool AP_AHRS::_get_secondary_position(Location &loc) const return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: // External is secondary return external_estimates.get_location(loc); @@ -1359,7 +1359,7 @@ Vector2f AP_AHRS::_groundspeed_vector(void) case EKFType::SIM: return sim.groundspeed_vector(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: { return external.groundspeed_vector(); } @@ -1383,7 +1383,7 @@ float AP_AHRS::_groundspeed(void) case EKFType::THREE: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif @@ -1431,7 +1431,7 @@ bool AP_AHRS::set_origin(const Location &loc) // simulation backend return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: // don't allow origin set with external AHRS return false; @@ -1485,7 +1485,7 @@ bool AP_AHRS::_get_velocity_NED(Vector3f &vec) const case EKFType::SIM: return sim.get_velocity_NED(vec); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.get_velocity_NED(vec); #endif @@ -1520,7 +1520,7 @@ bool AP_AHRS::get_mag_field_NED(Vector3f &vec) const case EKFType::SIM: return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -1552,7 +1552,7 @@ bool AP_AHRS::get_mag_field_correction(Vector3f &vec) const case EKFType::SIM: return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -1587,7 +1587,7 @@ bool AP_AHRS::get_vert_pos_rate_D(float &velocity) const case EKFType::SIM: return sim.get_vert_pos_rate_D(velocity); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.get_vert_pos_rate_D(velocity); #endif @@ -1618,7 +1618,7 @@ bool AP_AHRS::get_hagl(float &height) const case EKFType::SIM: return sim.get_hagl(height); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: { return false; } @@ -1672,7 +1672,7 @@ bool AP_AHRS::get_relative_position_NED_origin(Vector3f &vec) const case EKFType::SIM: return sim.get_relative_position_NED_origin(vec); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: { return external.get_relative_position_NED_origin(vec); } @@ -1725,7 +1725,7 @@ bool AP_AHRS::get_relative_position_NE_origin(Vector2f &posNE) const return sim.get_relative_position_NE_origin(posNE); } #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.get_relative_position_NE_origin(posNE); #endif @@ -1780,7 +1780,7 @@ bool AP_AHRS::get_relative_position_D_origin(float &posD) const case EKFType::SIM: return sim.get_relative_position_D_origin(posD); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.get_relative_position_D_origin(posD); #endif @@ -1832,7 +1832,7 @@ AP_AHRS::EKFType AP_AHRS::ekf_type(void) const case EKFType::SIM: return type; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return type; #endif @@ -1923,7 +1923,7 @@ AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const ret = EKFType::SIM; break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: ret = EKFType::EXTERNAL; break; @@ -1957,7 +1957,7 @@ AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const get_filter_status(filt_state); break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: get_filter_status(filt_state); should_use_gps = true; @@ -2053,7 +2053,7 @@ AP_AHRS::EKFType AP_AHRS::fallback_active_EKF_type(void) const } #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED if (external.healthy()) { return EKFType::EXTERNAL; } @@ -2064,7 +2064,7 @@ AP_AHRS::EKFType AP_AHRS::fallback_active_EKF_type(void) const return EKFType::THREE; #elif HAL_NAVEKF2_AVAILABLE return EKFType::TWO; -#elif HAL_EXTERNAL_AHRS_ENABLED +#elif AP_AHRS_EXTERNAL_ENABLED return EKFType::EXTERNAL; #endif } @@ -2089,7 +2089,7 @@ bool AP_AHRS::_get_secondary_EKF_type(EKFType &secondary_ekf_type) const return true; } #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED if ((EKFType)_ekf_type.get() == EKFType::EXTERNAL) { secondary_ekf_type = EKFType::EXTERNAL; return true; @@ -2106,7 +2106,7 @@ bool AP_AHRS::_get_secondary_EKF_type(EKFType &secondary_ekf_type) const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif // DCM is secondary @@ -2171,7 +2171,7 @@ bool AP_AHRS::healthy(void) const case EKFType::SIM: return sim.healthy(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.healthy(); #endif @@ -2192,7 +2192,7 @@ bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t f ret = false; } -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED // Always check external AHRS if enabled // it is a source for IMU data even if not being used as direct AHRS replacement if (AP::externalAHRS().enabled() || (ekf_type() == EKFType::EXTERNAL)) { @@ -2223,7 +2223,7 @@ bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t f return dcm.pre_arm_check(requires_position, failure_msg, failure_msg_len) && ret; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.pre_arm_check(requires_position, failure_msg, failure_msg_len); #endif @@ -2277,7 +2277,7 @@ bool AP_AHRS::initialised(void) const case EKFType::SIM: return true; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.initialised(); #endif @@ -2310,7 +2310,7 @@ bool AP_AHRS::get_filter_status(nav_filter_status &status) const case EKFType::SIM: return sim.get_filter_status(status); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.get_filter_status(status); #endif @@ -2407,7 +2407,7 @@ void AP_AHRS::getControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler sim.get_control_limits(ekfGndSpdLimit, ekfNavVelGainScaler); break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: // no limit on gains, large vel limit ekfGndSpdLimit = 400; @@ -2455,7 +2455,7 @@ bool AP_AHRS::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const case EKFType::SIM: return sim.get_mag_offsets(mag_idx, magOffsets); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -2490,7 +2490,7 @@ void AP_AHRS::_getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const case EKFType::SIM: break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -2634,7 +2634,7 @@ uint32_t AP_AHRS::getLastYawResetAngle(float &yawAng) case EKFType::SIM: return sim.getLastYawResetAngle(yawAng); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.getLastYawResetAngle(yawAng); #endif @@ -2667,7 +2667,7 @@ uint32_t AP_AHRS::getLastPosNorthEastReset(Vector2f &pos) case EKFType::SIM: return sim.getLastPosNorthEastReset(pos); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return 0; #endif @@ -2700,7 +2700,7 @@ uint32_t AP_AHRS::getLastVelNorthEastReset(Vector2f &vel) const case EKFType::SIM: return sim.getLastVelNorthEastReset(vel); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return 0; #endif @@ -2733,7 +2733,7 @@ uint32_t AP_AHRS::getLastPosDownReset(float &posDelta) case EKFType::SIM: return sim.getLastPosDownReset(posDelta); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return 0; #endif @@ -2784,7 +2784,7 @@ bool AP_AHRS::resetHeightDatum(void) case EKFType::SIM: return sim.resetHeightDatum(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -2808,7 +2808,7 @@ void AP_AHRS::send_ekf_status_report(GCS_MAVLINK &link) const break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: { external.send_ekf_status_report(link); break; @@ -2851,7 +2851,7 @@ bool AP_AHRS::_get_origin(EKFType type, Location &ret) const case EKFType::SIM: return sim.get_origin(ret); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.get_origin(ret); #endif @@ -2960,7 +2960,7 @@ bool AP_AHRS::get_hgt_ctrl_limit(float& limit) const case EKFType::SIM: return sim.get_hgt_ctrl_limit(limit); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -3027,7 +3027,7 @@ bool AP_AHRS::get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f & return sim.get_innovations(velInnov, posInnov, magInnov, tasInnov, yawInnov); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -3053,7 +3053,7 @@ bool AP_AHRS::is_vibration_affected() const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif return false; @@ -3095,7 +3095,7 @@ bool AP_AHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3 return sim.get_variances(velVar, posVar, hgtVar, magVar, tasVar); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -3133,7 +3133,7 @@ bool AP_AHRS::get_vel_innovations_and_variances_for_source(uint8_t source, Vecto return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -3194,7 +3194,7 @@ uint8_t AP_AHRS::_get_primary_IMU_index() const case EKFType::SIM: break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -3219,7 +3219,7 @@ int8_t AP_AHRS::_get_primary_core_index() const // we have only one core return 0; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: // we have only one core return 0; @@ -3267,7 +3267,7 @@ void AP_AHRS::check_lane_switch(void) break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -3299,7 +3299,7 @@ void AP_AHRS::request_yaw_reset(void) break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -3371,7 +3371,7 @@ bool AP_AHRS::using_noncompass_for_yaw(void) const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif return false; @@ -3398,7 +3398,7 @@ bool AP_AHRS::using_extnav_for_yaw(void) const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif return false; @@ -3441,7 +3441,7 @@ const EKFGSF_yaw *AP_AHRS::get_yaw_estimator(void) const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif return nullptr; diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index abb36f2e13..a4bd0c3979 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -443,7 +443,7 @@ public: #if AP_AHRS_SIM_ENABLED SIM = 10, #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED EXTERNAL = 11, #endif }; @@ -800,7 +800,7 @@ private: void update_SITL(void); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED void update_external(void); #endif @@ -1002,7 +1002,7 @@ private: struct AP_AHRS_Backend::Estimates sim_estimates; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED AP_AHRS_External external; struct AP_AHRS_Backend::Estimates external_estimates; #endif diff --git a/libraries/AP_AHRS/AP_AHRS_External.cpp b/libraries/AP_AHRS/AP_AHRS_External.cpp index 0c4be3d5bd..8cdf8ecb52 100644 --- a/libraries/AP_AHRS/AP_AHRS_External.cpp +++ b/libraries/AP_AHRS/AP_AHRS_External.cpp @@ -1,6 +1,6 @@ #include "AP_AHRS_External.h" -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED #include #include diff --git a/libraries/AP_AHRS/AP_AHRS_External.h b/libraries/AP_AHRS/AP_AHRS_External.h index 4d63a07029..6ca69f73f8 100644 --- a/libraries/AP_AHRS/AP_AHRS_External.h +++ b/libraries/AP_AHRS/AP_AHRS_External.h @@ -21,9 +21,11 @@ * */ -#include "AP_AHRS_Backend.h" +#include "AP_AHRS_config.h" -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED + +#include "AP_AHRS_Backend.h" class AP_AHRS_External : public AP_AHRS_Backend { public: diff --git a/libraries/AP_AHRS/AP_AHRS_config.h b/libraries/AP_AHRS/AP_AHRS_config.h index fd56a5f6de..3b27e78606 100644 --- a/libraries/AP_AHRS/AP_AHRS_config.h +++ b/libraries/AP_AHRS/AP_AHRS_config.h @@ -2,6 +2,7 @@ #include #include +#include #ifndef AP_AHRS_ENABLED #define AP_AHRS_ENABLED 1 @@ -15,6 +16,10 @@ #define AP_AHRS_DCM_ENABLED AP_AHRS_BACKEND_DEFAULT_ENABLED && AP_INERTIALSENSOR_ENABLED #endif +#ifndef AP_AHRS_EXTERNAL_ENABLED +#define AP_AHRS_EXTERNAL_ENABLED AP_AHRS_BACKEND_DEFAULT_ENABLED && HAL_EXTERNAL_AHRS_ENABLED +#endif + #ifndef HAL_NAVEKF2_AVAILABLE // EKF2 slated compiled out by default in 4.5, slated to be removed. #define HAL_NAVEKF2_AVAILABLE 0