#pragma once12/*3This program is free software: you can redistribute it and/or modify4it under the terms of the GNU General Public License as published by5the Free Software Foundation, either version 3 of the License, or6(at your option) any later version.78This program is distributed in the hope that it will be useful,9but WITHOUT ANY WARRANTY; without even the implied warranty of10MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the11GNU General Public License for more details.1213You should have received a copy of the GNU General Public License14along with this program. If not, see <http://www.gnu.org/licenses/>.15*/1617/*18* AHRS (Attitude Heading Reference System) frontend interface for19* ArduPilot20*21*/2223#include "AP_AHRS_config.h"2425#include <AP_HAL/Semaphores.h>2627#include "AP_AHRS_Backend.h"28#include <AP_NavEKF2/AP_NavEKF2.h>29#include <AP_NavEKF3/AP_NavEKF3.h>30#include <AP_NavEKF/AP_Nav_Common.h> // definitions shared by inertial and ekf nav filters3132#include "AP_AHRS_DCM.h"33#include "AP_AHRS_SIM.h"34#include "AP_AHRS_External.h"3536// forward declare view class37class AP_AHRS_View;3839#define AP_AHRS_NAVEKF_SETTLE_TIME_MS 20000 // time in milliseconds the ekf needs to settle after being started404142// fwd declare GSF estimator43class EKFGSF_yaw;4445class AP_AHRS {46friend class AP_AHRS_View;47public:4849// copy this into our namespace50using Status = NavFilterStatusBit;5152enum Flags {53FLAG_ALWAYS_USE_EKF = 0x1,54};5556// has_status returns information about the EKF health and57// capabilities. It is currently invalid to call this when a58// backend is in charge which returns false for get_filter_status59// - so this will simply return false for DCM, for example.60bool has_status(Status status) const;6162// Constructor63AP_AHRS(uint8_t flags = 0);6465// initialise66void init(void);6768/* Do not allow copies */69CLASS_NO_COPY(AP_AHRS);7071// get singleton instance72static AP_AHRS *get_singleton() {73return _singleton;74}7576// periodically checks to see if we should update the AHRS77// orientation (e.g. based on the AHRS_ORIENTATION parameter)78// allow for runtime change of orientation79// this makes initial config easier80void update_orientation();8182// allow threads to lock against AHRS update83HAL_Semaphore &get_semaphore(void) {84return _rsem;85}8687// return the smoothed gyro vector corrected for drift88const Vector3f &get_gyro(void) const { return state.gyro_estimate; }8990// return the current drift correction integrator value91const Vector3f &get_gyro_drift(void) const { return state.gyro_drift; }9293// reset the current gyro drift estimate94// should be called if gyro offsets are recalculated95void reset_gyro_drift();9697void update(bool skip_ins_update=false);98void reset();99100// get current location estimate101bool get_location(Location &loc) const;102103// get latest altitude estimate above ground level in meters and validity flag104bool get_hagl(float &hagl) const WARN_IF_UNUSED;105106// status reporting of estimated error107float get_error_rp() const;108float get_error_yaw() const;109110/*111* wind estimation support112*/113114// enable wind estimation115void set_wind_estimation_enabled(bool b) { wind_estimation_enabled = b; }116117// wind_estimation_enabled returns true if wind estimation is enabled118bool get_wind_estimation_enabled() const { return wind_estimation_enabled; }119120// return a wind estimation vector, in m/s; returns 0,0,0 on failure121const Vector3f &wind_estimate() const { return state.wind_estimate; }122123// return a wind estimation vector, in m/s; returns 0,0,0 on failure124bool wind_estimate(Vector3f &wind) const;125126// Determine how aligned heading_deg is with the wind. Return result127// is 1.0 when perfectly aligned heading into wind, -1 when perfectly128// aligned with-wind, and zero when perfect cross-wind. There is no129// distinction between a left or right cross-wind. Wind speed is ignored130float wind_alignment(const float heading_deg) const;131132// returns forward head-wind component in m/s. Negative means tail-wind133float head_wind(void) const;134135// instruct DCM to update its wind estimate:136void estimate_wind() {137#if AP_AHRS_DCM_ENABLED138dcm.estimate_wind();139#endif140}141142#if AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED143void set_external_wind_estimate(float speed, float direction) {144dcm.set_external_wind_estimate(speed, direction);145}146#endif147148// return the parameter AHRS_WIND_MAX in metres per second149uint8_t get_max_wind() const {150return _wind_max;151}152153/*154* airspeed support155*/156157// get apparent to true airspeed ratio158float get_EAS2TAS(void) const;159160// get air density / sea level density - decreases as altitude climbs161float get_air_density_ratio(void) const;162163// return an (equivalent) airspeed estimate if available. return164// true if airspeed_ret is valid. This value may be derived from165// airspeed data or synthesised from other sources.166bool airspeed_EAS(float &airspeed_ret) const;167168enum AirspeedEstimateType : uint8_t {169NO_NEW_ESTIMATE = 0,170AIRSPEED_SENSOR = 1,171DCM_SYNTHETIC = 2,172EKF3_SYNTHETIC = 3,173SIM = 4,174};175176// return an (equivalent) airspeed estimate if available. return177// true if airspeed_ret is valid. This value may be derived from178// airspeed data or synthesised from other sources (the type179// return parameter allows you to distinguish).180bool airspeed_EAS(float &airspeed_ret, AirspeedEstimateType &type) const;181182// return true if the current AHRS airspeed estimate (from airspeed_estimate method) is directly derived from an airspeed sensor183bool using_airspeed_sensor() const;184185// return a true airspeed (navigation airspeed) if186// available. return true if airspeed_ret is valid. This value187// may be derived from actual airspeed sensor data or synthesized188// from other sources.189bool airspeed_TAS(float &airspeed_ret) const;190191// return estimate of true airspeed vector in body frame in m/s192// returns false if estimate is unavailable193bool airspeed_vector_TAS(Vector3f &vec) const;194195// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed for a given sensor instance196// returns false if the data is unavailable197bool airspeed_health_data(uint8_t instance, float &innovation, float &innovationVariance, uint32_t &age_ms) const;198199// return true if a airspeed sensor is enabled200bool airspeed_sensor_enabled(void) const {201// FIXME: make this a method on the active backend202return AP_AHRS_Backend::airspeed_sensor_enabled();203}204205// return true if a airspeed from a specific airspeed sensor is enabled206bool airspeed_sensor_enabled(uint8_t airspeed_index) const {207// FIXME: make this a method on the active backend208return AP_AHRS_Backend::airspeed_sensor_enabled(airspeed_index);209}210211// true if compass is being used212bool use_compass();213214// return the quaternion defining the rotation from NED to XYZ (body) axes215bool get_quaternion(Quaternion &quat) const WARN_IF_UNUSED;216217// return secondary attitude solution if available, as eulers in radians218bool get_secondary_attitude(Vector3f &eulers) const {219eulers = state.secondary_attitude;220return state.secondary_attitude_ok;221}222223// return secondary attitude solution if available, as quaternion224bool get_secondary_quaternion(Quaternion &quat) const {225quat = state.secondary_quat;226return state.secondary_quat_ok;227}228229// return secondary position solution if available230bool get_secondary_position(Location &loc) const {231loc = state.secondary_pos;232return state.secondary_pos_ok;233}234235// EKF has a better ground speed vector estimate236const Vector2f &groundspeed_vector() const { return state.ground_speed_vec; }237238// return ground speed estimate in meters/second. Used by ground vehicles.239float groundspeed(void) const { return state.ground_speed; }240241const Vector3f &get_accel_ef() const {242return state.accel_ef;243}244245// Retrieves the corrected NED delta velocity in use by the inertial navigation246void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const {247ret = state.corrected_dv;248dt = state.corrected_dv_dt;249}250251// set the EKF's origin location in 10e7 degrees. This should only252// be called when the EKF has no absolute position reference (i.e. GPS)253// from which to decide the origin on its own254bool set_origin(const Location &loc) WARN_IF_UNUSED;255256// Set the origin to the last recorded location if option bit set and not using GPS257// This is useful for position controlled modes without GPS258void use_recorded_origin_maybe();259260#if AP_AHRS_POSITION_RESET_ENABLED261// Set the EKF's NE horizontal position states and their corresponding variances from the supplied WGS-84 location262// and 1-sigma horizontal position uncertainty. This can be used when the EKF is dead reckoning to periodically263// correct the position. If the EKF is is still using data from a position sensor such as GPS, the position set264// will not be performed.265// pos_accuracy is the standard deviation of the horizontal position uncertainty in metres.266// The altitude element of the location is not used.267// Returns true if the set was successful.268bool handle_external_position_estimate(const Location &loc, float pos_accuracy, uint32_t timestamp_);269#endif270271// returns the inertial navigation origin in lat/lon/alt272bool get_origin(Location &ret) const WARN_IF_UNUSED;273274bool have_inertial_nav() const;275276// return a ground velocity in meters/second, North/East/Down277// order. Must only be called if have_inertial_nav() is true278bool get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED;279280// return the relative position NED from either home or origin281// return true if the estimate is valid282bool get_relative_position_NED_home(Vector3f &vec) const WARN_IF_UNUSED;283bool get_relative_position_NED_origin(Vector3p &vec) const WARN_IF_UNUSED;284bool get_relative_position_NED_origin_float(Vector3f &vec) const WARN_IF_UNUSED;285286// return the relative position NE from home or origin287// return true if the estimate is valid288bool get_relative_position_NE_home(Vector2f &posNE) const WARN_IF_UNUSED;289bool get_relative_position_NE_origin(Vector2p &posNE) const WARN_IF_UNUSED;290bool get_relative_position_NE_origin_float(Vector2f &posNE) const WARN_IF_UNUSED;291292// return the relative position down from home or origin293// baro will be used for the _home relative one if the EKF isn't294void get_relative_position_D_home(float &posD) const;295bool get_relative_position_D_origin(postype_t &posD) const WARN_IF_UNUSED;296bool get_relative_position_D_origin_float(float &posD) const WARN_IF_UNUSED;297298// return location corresponding to vector relative to the299// vehicle's origin300bool get_location_from_origin_offset_NED(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED;301bool get_location_from_home_offset_NED(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED;302303// get velocity down in m/s. This returns get_velocity_NED.z() if available, otherwise falls back to get_vert_pos_rate_D()304// if high_vibes is true then this is equivalent to get_vert_pos_rate_D305bool get_velocity_D(float &velD, bool high_vibes = false) const WARN_IF_UNUSED;306307// Get a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.308// This is different to the vertical velocity from the EKF which is not always consistent with the vertical position due to the various errors that are being corrected for.309bool get_vert_pos_rate_D(float &velocity) const;310311// write optical flow measurements to EKF312void writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset, const float heightOverride);313314// retrieve latest corrected optical flow samples (used for calibration)315bool getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const;316317// write body odometry measurements to the EKF318void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset);319320// Writes the default equivalent airspeed and its 1-sigma uncertainty in m/s to be used in forward flight if a measured airspeed is required and not available.321void writeDefaultAirSpeed(float airspeed, float uncertainty);322323// Write position and quaternion data from an external navigation system324void writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms);325326// Write velocity data from an external navigation system327void writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms);328329// Write terrain (derived from SRTM) altitude in meters above sea level330void writeTerrainAMSL(float alt_amsl_m);331332// get speed limit333void getControlLimits(float &ekfGndSpdLimit, float &controlScaleXY) const;334float getControlScaleZ(void) const;335336// is the AHRS subsystem healthy?337bool healthy() const;338339// returns false if we fail arming checks, in which case the buffer will be populated with a failure message340// requires_position should be true if horizontal position configuration should be checked341bool pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const;342343// true if the AHRS has completed initialisation344bool initialised() const;345346#if AP_AHRS_DCM_ENABLED347// return true if *DCM* yaw has been initialised348bool dcm_yaw_initialised(void) const {349return dcm.yaw_initialised();350}351#endif352353// get_filter_status - returns filter status as a series of flags354bool get_filter_status(nav_filter_status &status) const;355356// get compass offset estimates357// true if offsets are valid358bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const;359360// return the amount of yaw angle change due to the last yaw angle reset in radians361// returns the time of the last yaw angle reset or 0 if no reset has ever occurred362uint32_t getLastYawResetAngle(float &yawAng);363364// return the amount of NE position change in meters due to the last reset365// returns the time of the last reset or 0 if no reset has ever occurred366uint32_t getLastPosNorthEastReset(Vector2f &pos);367368// return the amount of NE velocity change in meters/sec due to the last reset369// returns the time of the last reset or 0 if no reset has ever occurred370uint32_t getLastVelNorthEastReset(Vector2f &vel) const;371372// return the amount of vertical position change due to the last reset in meters373// returns the time of the last reset or 0 if no reset has ever occurred374uint32_t getLastPosDownReset(float &posDelta);375376// Resets the baro so that it reads zero at the current height377// Resets the EKF height to zero378// Adjusts the EKf origin height so that the EKF height + origin height is the same as before379void resetHeightDatum();380381// send a EKF_STATUS_REPORT for current EKF382void send_ekf_status_report(class GCS_MAVLINK &link) const;383384// get_hgt_ctrl_limit - get maximum height to be observed by the control loops in meters and a validity flag385// this is used to limit height during optical flow navigation386// it will return invalid when no limiting is required387bool get_hgt_ctrl_limit(float &limit) const;388389// Set to true if the terrain underneath is stable enough to be used as a height reference390// this is not related to terrain following391void set_terrain_hgt_stable(bool stable);392393// return the innovations for the specified instance394// An out of range instance (eg -1) returns data for the primary instance395bool get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const;396397// returns true when the state estimates are significantly degraded by vibration398bool is_vibration_affected() const;399400// get_variances - provides the innovations normalised using the innovation variance where a value of 0401// indicates perfect consistency between the measurement and the EKF solution and a value of 1 is the maximum402// inconsistency that will be accepted by the filter403// boolean false is returned if variances are not available404bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const;405406// get a source's velocity innovations407// returns true on success and results are placed in innovations and variances arguments408bool get_vel_innovations_and_variances_for_source(uint8_t source, Vector3f &innovations, Vector3f &variances) const WARN_IF_UNUSED;409410// returns the expected NED magnetic field411bool get_mag_field_NED(Vector3f& ret) const;412413// returns the estimated magnetic field offsets in body frame414bool get_mag_field_correction(Vector3f &ret) const;415416// return the index of the airspeed we should use for airspeed measurements417// with multiple airspeed sensors and airspeed affinity in EKF3, it is possible to have switched418// over to a lane not using the primary airspeed sensor, so AHRS should know which airspeed sensor419// to use, i.e, the one being used by the primary lane. A lane switch could have happened due to an420// airspeed sensor fault, which makes this even more necessary421uint8_t get_active_airspeed_index() const;422423// return the index of the primary core or -1 if no primary core selected424int8_t get_primary_core_index() const { return state.primary_core; }425426// get the index of the current primary accelerometer sensor427uint8_t get_primary_accel_index(void) const { return state.primary_accel; }428429// get the index of the current primary gyro sensor430uint8_t get_primary_gyro_index(void) const { return state.primary_gyro; }431432// see if EKF lane switching is possible to avoid EKF failsafe433void check_lane_switch(void);434435// request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe436void request_yaw_reset(void);437438// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary439void set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx);440441//returns index of active source set used, 0=primary, 1=secondary, 2=tertiary442uint8_t get_posvelyaw_source_set() const;443444void Log_Write();445446// check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed447bool using_noncompass_for_yaw(void) const;448449// check if external nav is providing yaw450bool using_extnav_for_yaw(void) const;451452// check if GPS is being used to estimate position or velocity453// always returns true for External and SIM EKF types454bool using_gps(void) const;455456// set and save the ALT_M_NSE parameter value457void set_alt_measurement_noise(float noise);458459enum class EKFType : uint8_t {460#if AP_AHRS_DCM_ENABLED461DCM = 0,462#endif463#if HAL_NAVEKF3_AVAILABLE464THREE = 3,465#endif466#if HAL_NAVEKF2_AVAILABLE467TWO = 2,468#endif469#if AP_AHRS_SIM_ENABLED470SIM = 10,471#endif472#if AP_AHRS_EXTERNAL_ENABLED473EXTERNAL = 11,474#endif475};476477// returns a canonicalised and valid EKFType, as opposed to the raw478// parameter value which may be any value the user has set479EKFType configured_ekf_type(void) const;480481// set the selected ekf type, for RC aux control482void set_ekf_type(EKFType ahrs_type) {483_ekf_type.set(ahrs_type);484}485486// these are only out here so vehicles can reference them for parameters487#if HAL_NAVEKF2_AVAILABLE488NavEKF2 EKF2;489#endif490#if HAL_NAVEKF3_AVAILABLE491NavEKF3 EKF3;492#endif493494// for holding parameters495static const struct AP_Param::GroupInfo var_info[];496497// create a view498AP_AHRS_View *create_view(enum Rotation rotation, float pitch_trim_deg=0);499500// write AOA and SSA information to dataflash logs:501void Write_AOA_SSA(void) const;502503// return AOA504float getAOA(void) const { return _AOA; }505506// return SSA507float getSSA(void) const { return _SSA; }508509/*510* trim-related functions511*/512513// get trim514const Vector3f &get_trim() const { return _trim.get(); }515516// set trim517void set_trim(const Vector3f &new_trim);518519// add_trim - adjust the roll and pitch trim up to a total of 10 degrees520void add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom = true);521522// trim rotation matrices:523const Matrix3f& get_rotation_autopilot_body_to_vehicle_body(void) const { return _rotation_autopilot_body_to_vehicle_body; }524const Matrix3f& get_rotation_vehicle_body_to_autopilot_body(void) const { return _rotation_vehicle_body_to_autopilot_body; }525526// Logging functions527void Log_Write_Home_And_Origin();528void Write_Attitude(const Vector3f &targets) const;529530enum class LogOriginType {531ekf_origin = 0,532ahrs_home = 1533};534void Write_Origin(LogOriginType origin_type, const Location &loc) const;535void write_video_stabilisation() const;536537// return a smoothed and corrected gyro vector in radians/second538// using the latest ins data (which may not have been consumed by539// the EKF yet)540Vector3f get_gyro_latest(void) const;541542// get yaw rate in earth frame in radians/sec543float get_yaw_rate_earth(void) const {544return get_gyro() * get_rotation_body_to_ned().c;545}546547/*548* home-related functionality549*/550551// get the home location. This is const to prevent any changes to552// home without telling AHRS about the change553const Location &get_home(void) const {554return _home;555}556557// functions to handle locking of home. Some vehicles use this to558// allow GCS to lock in a home location.559void lock_home() {560_home_locked = true;561}562bool home_is_locked() const {563return _home_locked;564}565566// returns true if home is set567bool home_is_set(void) const {568return _home_is_set;569}570571// set the home location in 10e7 degrees. This should be called572// when the vehicle is at this position. It is assumed that the573// current barometer and GPS altitudes correspond to this altitude574bool set_home(const Location &loc) WARN_IF_UNUSED;575576/*577* Attitude-related public methods and attributes:578*/579580#if AP_SCRIPTING_ENABLED581// deprecated functions for accessing rpy. Do not use, these will582// be removed.583float get_roll() const { return roll; }584float get_pitch() const { return pitch; }585float get_yaw() const { return yaw; }586#endif // AP_SCRIPTING_ENABLED587588// roll/pitch/yaw euler angles, all in radians589float get_roll_rad() const { return roll; }590float get_pitch_rad() const { return pitch; }591float get_yaw_rad() const { return yaw; }592593// roll/pitch/yaw euler angles, all in degrees594float get_roll_deg() const { return rpy_deg[0]; }595float get_pitch_deg() const { return rpy_deg[1]; }596float get_yaw_deg() const { return rpy_deg[2]; }597598// helper trig value accessors599float cos_roll() const {600return _cos_roll;601}602float cos_pitch() const {603return _cos_pitch;604}605float cos_yaw() const {606return _cos_yaw;607}608float sin_roll() const {609return _sin_roll;610}611float sin_pitch() const {612return _sin_pitch;613}614float sin_yaw() const {615return _sin_yaw;616}617618// floating point Euler angles (Degrees)619float rpy_deg[3];620621// integer Euler angles (Degrees * 100)622int32_t roll_sensor;623int32_t pitch_sensor;624int32_t yaw_sensor;625626const Matrix3f &get_rotation_body_to_ned(void) const { return state.dcm_matrix; }627628// return a Quaternion representing our current attitude in NED frame629void get_quat_body_to_ned(Quaternion &quat) const;630631#if AP_AHRS_DCM_ENABLED632// get rotation matrix specifically from DCM backend (used for633// compass calibrator)634const Matrix3f &get_DCM_rotation_body_to_ned(void) const {635return dcm_estimates.dcm_matrix;636}637#endif638639// rotate a 2D vector from earth frame to body frame640// in result, x is forward, y is right641Vector2f earth_to_body2D(const Vector2f &ef_vector) const;642643// rotate a 2D vector from earth frame to body frame644// in input, x is forward, y is right645Vector2f body_to_earth2D(const Vector2f &bf) const WARN_IF_UNUSED;646Vector2p body_to_earth2D_p(const Vector2p &bf) const WARN_IF_UNUSED;647648// convert a vector from body to earth frame649Vector3f body_to_earth(const Vector3f &v) const;650651// convert a vector from earth to body frame652Vector3f earth_to_body(const Vector3f &v) const;653654/*655* methods for the benefit of LUA bindings656*/657// return current vibration vector for primary IMU658Vector3f get_vibration(void) const;659660// return primary accels661const Vector3f &get_accel(void) const {662return AP::ins().get_accel(_get_primary_accel_index());663}664665// return primary accel bias. This should be subtracted from666// get_accel() vector to get best current body frame accel667// estimate668const Vector3f &get_accel_bias(void) const {669return state.accel_bias;670}671672/*673* AHRS is used as a transport for vehicle-takeoff-expected and674* vehicle-landing-expected:675*/676void set_takeoff_expected(bool b);677678bool get_takeoff_expected(void) const {679return takeoff_expected;680}681682void set_touchdown_expected(bool b);683684bool get_touchdown_expected(void) const {685return touchdown_expected;686}687688/*689* fly_forward is set by the vehicles to indicate the vehicle690* should generally be moving in the direction of its heading.691* It is an additional piece of information that the backends can692* use to provide additional and/or improved estimates.693*/694void set_fly_forward(bool b) {695fly_forward = b;696}697bool get_fly_forward(void) const {698return fly_forward;699}700701/* we modify our behaviour based on what sort of vehicle the702* vehicle code tells us we are. This information is also pulled703* from AP_AHRS by other libraries704*/705enum class VehicleClass : uint8_t {706UNKNOWN,707GROUND,708COPTER,709FIXED_WING,710SUBMARINE,711};712VehicleClass get_vehicle_class(void) const {713return _vehicle_class;714}715void set_vehicle_class(VehicleClass vclass) {716_vehicle_class = vclass;717}718719// get the view720AP_AHRS_View *get_view(void) const { return _view; };721722// get access to an EKFGSF_yaw estimator723const EKFGSF_yaw *get_yaw_estimator(void) const;724725private:726727// roll/pitch/yaw euler angles, all in radians728float roll;729float pitch;730float yaw;731732// optional view class733AP_AHRS_View *_view;734735static AP_AHRS *_singleton;736737/* we modify our behaviour based on what sort of vehicle the738* vehicle code tells us we are. This information is also pulled739* from AP_AHRS by other libraries740*/741VehicleClass _vehicle_class{VehicleClass::UNKNOWN};742743// multi-thread access support744HAL_Semaphore _rsem;745746/*747* Parameters748*/749AP_Int8 _wind_max;750AP_Int8 _board_orientation;751AP_Enum<EKFType> _ekf_type;752753/*754* DCM-backend parameters; it takes references to these755*/756// settable parameters757AP_Float _kp_yaw;758AP_Float _kp;759AP_Float gps_gain;760761AP_Float beta;762763AP_Enum<GPSUse> _gps_use;764AP_Int8 _gps_minsats;765AP_Float _origin_lat;766AP_Float _origin_lon;767AP_Float _origin_alt;768769EKFType active_EKF_type(void) const { return state.active_EKF; }770771bool always_use_EKF() const {772return _ekf_flags & FLAG_ALWAYS_USE_EKF;773}774775// check all cores providing consistent attitudes for prearm checks776bool attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const;777// convenience method for setting error string:778void set_failure_inconsistent_message(const char *estimator, const char *axis, float diff_rad, char *failure_msg, const uint8_t failure_msg_len) const;779780/*781* Attitude-related private methods and attributes:782*/783// calculate sin/cos of roll/pitch/yaw from rotation784void calc_trig(const Matrix3f &rot,785float &cr, float &cp, float &cy,786float &sr, float &sp, float &sy) const;787788// update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude789// should be called after _dcm_matrix is updated790void update_trig(void);791792// update roll_sensor, pitch_sensor and yaw_sensor793void update_cd_values(void);794795// helper trig variables796float _cos_roll{1.0f};797float _cos_pitch{1.0f};798float _cos_yaw{1.0f};799float _sin_roll;800float _sin_pitch;801float _sin_yaw;802803#if HAL_NAVEKF2_AVAILABLE804void update_EKF2(void);805bool _ekf2_started;806#endif807#if HAL_NAVEKF3_AVAILABLE808bool _ekf3_started;809void update_EKF3(void);810#endif811812const uint16_t startup_delay_ms = 1000;813uint32_t start_time_ms;814uint8_t _ekf_flags; // bitmask from Flags enumeration815816void update_DCM();817818/*819* home-related state820*/821void load_watchdog_home();822bool _checked_watchdog_home;823Location _home;824bool _home_is_set :1;825bool _home_locked :1;826827// avoid setting current state repeatedly across all cores on all EKFs:828enum class TriState {829False = 0,830True = 1,831UNKNOWN = 3,832};833834TriState terrainHgtStableState = TriState::UNKNOWN;835836/*837* private AOA and SSA-related state and methods838*/839float _AOA, _SSA;840uint32_t _last_AOA_update_ms;841void update_AOA_SSA(void);842843EKFType last_active_ekf_type;844845#if AP_AHRS_SIM_ENABLED846void update_SITL(void);847#endif848849#if AP_AHRS_EXTERNAL_ENABLED850void update_external(void);851#endif852853/*854* trim-related state and private methods:855*/856857// a vector to capture the difference between the controller and body frames858AP_Vector3f _trim;859860// cached trim rotations861Vector3f _last_trim;862863Matrix3f _rotation_autopilot_body_to_vehicle_body;864Matrix3f _rotation_vehicle_body_to_autopilot_body;865866// last time orientation was updated from AHRS_ORIENTATION:867uint32_t last_orientation_update_ms;868869// updates matrices responsible for rotating vectors from vehicle body870// frame to autopilot body frame from _trim variables871void update_trim_rotation_matrices();872873/*874* AHRS is used as a transport for vehicle-takeoff-expected and875* vehicle-landing-expected:876*/877// update takeoff/touchdown flags878void update_flags();879bool takeoff_expected; // true if the vehicle is in a state that takeoff might be expected. Ground effect may be in play.880uint32_t takeoff_expected_start_ms;881bool touchdown_expected; // true if the vehicle is in a state that touchdown might be expected. Ground effect may be in play.882uint32_t touchdown_expected_start_ms;883884/*885* wind estimation support886*/887bool wind_estimation_enabled;888889/*890* fly_forward is set by the vehicles to indicate the vehicle891* should generally be moving in the direction of its heading.892* It is an additional piece of information that the backends can893* use to provide additional and/or improved estimates.894*/895bool fly_forward; // true if we can assume the vehicle will be flying forward on its X axis896897// poke AP_Notify based on values from status898void update_notify_from_filter_status(const nav_filter_status &status);899900/*901* copy results from a backend over AP_AHRS canonical results.902* This updates member variables like roll and pitch, as well as903* updating derived values like sin_roll and sin_pitch.904*/905void copy_estimates_from_backend_estimates(const AP_AHRS_Backend::Estimates &results);906907// write out secondary estimates:908void Write_AHRS2(void) const;909// write POS (canonical vehicle position) message out:910void Write_POS(void) const;911912// return an airspeed estimate if available. return true913// if we have an estimate914bool _airspeed_EAS(float &airspeed_ret, AirspeedEstimateType &status) const;915916// return secondary attitude solution if available, as eulers in radians917bool _get_secondary_attitude(Vector3f &eulers) const;918919// return secondary attitude solution if available, as quaternion920bool _get_secondary_quaternion(Quaternion &quat) const;921922// get ground speed 2D923Vector2f _groundspeed_vector(void);924925// get active EKF type926EKFType _active_EKF_type(void) const;927928// return a wind estimation vector, in m/s929bool _wind_estimate(Vector3f &wind) const WARN_IF_UNUSED;930931// return a true airspeed estimate (navigation airspeed) if932// available. return true if we have an estimate933bool _airspeed_TAS(float &airspeed_ret) const;934935// return estimate of true airspeed vector in body frame in m/s936// returns false if estimate is unavailable937bool _airspeed_TAS(Vector3f &vec) const;938939// return the quaternion defining the rotation from NED to XYZ (body) axes940bool _get_quaternion(Quaternion &quat) const WARN_IF_UNUSED;941942// return the quaternion defining the rotation from NED to XYZ943// (body) axes for the passed-in type944bool _get_quaternion_for_ekf_type(Quaternion &quat, EKFType type) const;945946// return secondary position solution if available947bool _get_secondary_position(Location &loc) const;948949// return ground speed estimate in meters/second. Used by ground vehicles.950float _groundspeed(void);951952// Retrieves the corrected NED delta velocity in use by the inertial navigation953void _getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const;954955// returns the inertial navigation origin in lat/lon/alt956bool _get_origin(Location &ret) const WARN_IF_UNUSED;957958// return origin for a specified EKF type959bool _get_origin(EKFType type, Location &ret) const;960961// return a ground velocity in meters/second, North/East/Down962// order. Must only be called if have_inertial_nav() is true963bool _get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED;964965// get secondary EKF type. returns false if no secondary (i.e. only using DCM)966bool _get_secondary_EKF_type(EKFType &secondary_ekf_type) const;967968// return the index of the primary core or -1 if no primary core selected969int8_t _get_primary_core_index() const;970971// get the index of the current primary accelerometer sensor972uint8_t _get_primary_accel_index(void) const;973974// get the index of the current primary gyro sensor975uint8_t _get_primary_gyro_index(void) const;976977// get the index of the current primary IMU978uint8_t _get_primary_IMU_index(void) const;979980// get current location estimate981bool _get_location(Location &loc) const;982983// return true if a airspeed sensor should be used for the AHRS airspeed estimate984bool _should_use_airspeed_sensor(uint8_t airspeed_index) const;985986/*987update state structure988*/989void update_state(void);990991// returns an EKF type to be used as active if we decide the992// primary is not good enough.993EKFType fallback_active_EKF_type(void) const;994995// Record the current valid origin to parameters996// This may save the user from having to set the origin manually when using position controlled modes without GPS997void record_origin();998999/*1000state updated at the end of each update() call1001*/1002struct {1003EKFType active_EKF;1004uint8_t primary_IMU;1005uint8_t primary_gyro;1006uint8_t primary_accel;1007uint8_t primary_core;1008Vector3f gyro_estimate;1009Matrix3f dcm_matrix;1010Vector3f gyro_drift;1011Vector3f accel_ef;1012Vector3f accel_bias;1013Vector3f wind_estimate;1014bool wind_estimate_ok;1015float EAS2TAS;1016bool airspeed_EAS_ok;1017float airspeed_EAS;1018AirspeedEstimateType airspeed_estimate_type;1019bool airspeed_TAS_ok;1020float airspeed_TAS;1021Vector3f airspeed_TAS_vec;1022bool airspeed_TAS_vec_ok;1023Quaternion quat;1024bool quat_ok;1025Vector3f secondary_attitude;1026bool secondary_attitude_ok;1027Quaternion secondary_quat;1028bool secondary_quat_ok;1029Location location;1030bool location_ok;1031Location secondary_pos;1032bool secondary_pos_ok;1033Vector2f ground_speed_vec;1034float ground_speed;1035Vector3f corrected_dv;1036float corrected_dv_dt;1037Location origin;1038bool origin_ok;1039Vector3f velocity_NED;1040bool velocity_NED_ok;1041} state;10421043/*1044* backends (and their results)1045*/1046#if AP_AHRS_DCM_ENABLED1047AP_AHRS_DCM dcm{_kp_yaw, _kp, gps_gain, beta, _gps_use, _gps_minsats};1048struct AP_AHRS_Backend::Estimates dcm_estimates;1049#endif1050#if AP_AHRS_SIM_ENABLED1051#if HAL_NAVEKF3_AVAILABLE1052AP_AHRS_SIM sim{EKF3};1053#else1054AP_AHRS_SIM sim;1055#endif1056struct AP_AHRS_Backend::Estimates sim_estimates;1057#endif10581059#if AP_AHRS_EXTERNAL_ENABLED1060AP_AHRS_External external;1061struct AP_AHRS_Backend::Estimates external_estimates;1062#endif10631064enum class Options : uint16_t {1065DISABLE_DCM_FALLBACK_FW=(1U<<0),1066DISABLE_DCM_FALLBACK_VTOL=(1U<<1),1067DISABLE_AIRSPEED_EKF_CHECK=(1U<<2),1068RECORD_ORIGIN=(1U<<3),1069USE_RECORDED_ORIGIN_FOR_NONGPS=(1U<<4),1070};1071AP_Int16 _options;10721073bool option_set(Options option) const {1074return (_options & uint16_t(option)) != 0;1075}10761077// true when we have completed the common origin setup1078bool done_common_origin;1079};10801081namespace AP {1082AP_AHRS &ahrs();1083};108410851086