Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_AHRS/AP_AHRS.h
Views: 1798
#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:4849enum Flags {50FLAG_ALWAYS_USE_EKF = 0x1,51};5253// Constructor54AP_AHRS(uint8_t flags = 0);5556// initialise57void init(void);5859/* Do not allow copies */60CLASS_NO_COPY(AP_AHRS);6162// get singleton instance63static AP_AHRS *get_singleton() {64return _singleton;65}6667// periodically checks to see if we should update the AHRS68// orientation (e.g. based on the AHRS_ORIENTATION parameter)69// allow for runtime change of orientation70// this makes initial config easier71void update_orientation();7273// allow threads to lock against AHRS update74HAL_Semaphore &get_semaphore(void) {75return _rsem;76}7778// return the smoothed gyro vector corrected for drift79const Vector3f &get_gyro(void) const { return state.gyro_estimate; }8081// return the current drift correction integrator value82const Vector3f &get_gyro_drift(void) const { return state.gyro_drift; }8384// reset the current gyro drift estimate85// should be called if gyro offsets are recalculated86void reset_gyro_drift();8788void update(bool skip_ins_update=false);89void reset();9091// get current location estimate92bool get_location(Location &loc) const;9394// get latest altitude estimate above ground level in meters and validity flag95bool get_hagl(float &hagl) const WARN_IF_UNUSED;9697// status reporting of estimated error98float get_error_rp() const;99float get_error_yaw() const;100101/*102* wind estimation support103*/104105// enable wind estimation106void set_wind_estimation_enabled(bool b) { wind_estimation_enabled = b; }107108// wind_estimation_enabled returns true if wind estimation is enabled109bool get_wind_estimation_enabled() const { return wind_estimation_enabled; }110111// return a wind estimation vector, in m/s; returns 0,0,0 on failure112const Vector3f &wind_estimate() const { return state.wind_estimate; }113114// return a wind estimation vector, in m/s; returns 0,0,0 on failure115bool wind_estimate(Vector3f &wind) const;116117// Determine how aligned heading_deg is with the wind. Return result118// is 1.0 when perfectly aligned heading into wind, -1 when perfectly119// aligned with-wind, and zero when perfect cross-wind. There is no120// distinction between a left or right cross-wind. Wind speed is ignored121float wind_alignment(const float heading_deg) const;122123// returns forward head-wind component in m/s. Negative means tail-wind124float head_wind(void) const;125126// instruct DCM to update its wind estimate:127void estimate_wind() {128#if AP_AHRS_DCM_ENABLED129dcm.estimate_wind();130#endif131}132133#if AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED134void set_external_wind_estimate(float speed, float direction) {135dcm.set_external_wind_estimate(speed, direction);136}137#endif138139// return the parameter AHRS_WIND_MAX in metres per second140uint8_t get_max_wind() const {141return _wind_max;142}143144/*145* airspeed support146*/147148// get apparent to true airspeed ratio149float get_EAS2TAS(void) const;150151// get air density / sea level density - decreases as altitude climbs152float get_air_density_ratio(void) const;153154// return an (equivalent) airspeed estimate if available. return true155// if we have an estimate156bool airspeed_estimate(float &airspeed_ret) const;157158enum AirspeedEstimateType : uint8_t {159NO_NEW_ESTIMATE = 0,160AIRSPEED_SENSOR = 1,161DCM_SYNTHETIC = 2,162EKF3_SYNTHETIC = 3,163SIM = 4,164};165166// return an airspeed estimate if available. return true167// if we have an estimate168bool airspeed_estimate(float &airspeed_ret, AirspeedEstimateType &type) const;169170// return true if the current AHRS airspeed estimate (from airspeed_estimate method) is directly derived from an airspeed sensor171bool using_airspeed_sensor() const;172173// return a true airspeed estimate (navigation airspeed) if174// available. return true if we have an estimate175bool airspeed_estimate_true(float &airspeed_ret) const;176177// return estimate of true airspeed vector in body frame in m/s178// returns false if estimate is unavailable179bool airspeed_vector_true(Vector3f &vec) const;180181// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed182// returns false if the data is unavailable183bool airspeed_health_data(float &innovation, float &innovationVariance, uint32_t &age_ms) const;184185// return true if a airspeed sensor is enabled186bool airspeed_sensor_enabled(void) const {187// FIXME: make this a method on the active backend188return AP_AHRS_Backend::airspeed_sensor_enabled();189}190191// return true if a airspeed from a specific airspeed sensor is enabled192bool airspeed_sensor_enabled(uint8_t airspeed_index) const {193// FIXME: make this a method on the active backend194return AP_AHRS_Backend::airspeed_sensor_enabled(airspeed_index);195}196197// return a synthetic (equivalent) airspeed estimate (one derived from sensors198// other than an actual airspeed sensor), if available. return199// true if we have a synthetic airspeed. ret will not be modified200// on failure.201bool synthetic_airspeed(float &ret) const WARN_IF_UNUSED;202203// true if compass is being used204bool use_compass();205206// return the quaternion defining the rotation from NED to XYZ (body) axes207bool get_quaternion(Quaternion &quat) const WARN_IF_UNUSED;208209// return secondary attitude solution if available, as eulers in radians210bool get_secondary_attitude(Vector3f &eulers) const {211eulers = state.secondary_attitude;212return state.secondary_attitude_ok;213}214215// return secondary attitude solution if available, as quaternion216bool get_secondary_quaternion(Quaternion &quat) const {217quat = state.secondary_quat;218return state.secondary_quat_ok;219}220221// return secondary position solution if available222bool get_secondary_position(Location &loc) const {223loc = state.secondary_pos;224return state.secondary_pos_ok;225}226227// EKF has a better ground speed vector estimate228const Vector2f &groundspeed_vector() const { return state.ground_speed_vec; }229230// return ground speed estimate in meters/second. Used by ground vehicles.231float groundspeed(void) const { return state.ground_speed; }232233const Vector3f &get_accel_ef() const {234return state.accel_ef;235}236237// Retrieves the corrected NED delta velocity in use by the inertial navigation238void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const {239ret = state.corrected_dv;240dt = state.corrected_dv_dt;241}242243// set the EKF's origin location in 10e7 degrees. This should only244// be called when the EKF has no absolute position reference (i.e. GPS)245// from which to decide the origin on its own246bool set_origin(const Location &loc) WARN_IF_UNUSED;247248#if AP_AHRS_POSITION_RESET_ENABLED249// Set the EKF's NE horizontal position states and their corresponding variances from the supplied WGS-84 location250// and 1-sigma horizontal position uncertainty. This can be used when the EKF is dead reckoning to periodically251// correct the position. If the EKF is is still using data from a postion sensor such as GPS, the position set252// will not be performed.253// pos_accuracy is the standard deviation of the horizontal position uncertainty in metres.254// The altitude element of the location is not used.255// Returns true if the set was successful.256bool handle_external_position_estimate(const Location &loc, float pos_accuracy, uint32_t timestamp_);257#endif258259// returns the inertial navigation origin in lat/lon/alt260bool get_origin(Location &ret) const WARN_IF_UNUSED;261262bool have_inertial_nav() const;263264// return a ground velocity in meters/second, North/East/Down265// order. Must only be called if have_inertial_nav() is true266bool get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED;267268// return the relative position NED from either home or origin269// return true if the estimate is valid270bool get_relative_position_NED_home(Vector3f &vec) const WARN_IF_UNUSED;271bool get_relative_position_NED_origin(Vector3f &vec) const WARN_IF_UNUSED;272273// return the relative position NE from home or origin274// return true if the estimate is valid275bool get_relative_position_NE_home(Vector2f &posNE) const WARN_IF_UNUSED;276bool get_relative_position_NE_origin(Vector2f &posNE) const WARN_IF_UNUSED;277278// return the relative position down from home or origin279// baro will be used for the _home relative one if the EKF isn't280void get_relative_position_D_home(float &posD) const;281bool get_relative_position_D_origin(float &posD) const WARN_IF_UNUSED;282283// return location corresponding to vector relative to the284// vehicle's origin285bool get_location_from_origin_offset_NED(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED;286bool get_location_from_home_offset_NED(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED;287288// Get a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.289// 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.290bool get_vert_pos_rate_D(float &velocity) const;291292// write optical flow measurements to EKF293void writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset, const float heightOverride);294295// retrieve latest corrected optical flow samples (used for calibration)296bool getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const;297298// write body odometry measurements to the EKF299void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset);300301// 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.302void writeDefaultAirSpeed(float airspeed, float uncertainty);303304// Write position and quaternion data from an external navigation system305void writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms);306307// Write velocity data from an external navigation system308void writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms);309310// get speed limit311void getControlLimits(float &ekfGndSpdLimit, float &controlScaleXY) const;312float getControlScaleZ(void) const;313314// is the AHRS subsystem healthy?315bool healthy() const;316317// returns false if we fail arming checks, in which case the buffer will be populated with a failure message318// requires_position should be true if horizontal position configuration should be checked319bool pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const;320321// true if the AHRS has completed initialisation322bool initialised() const;323324#if AP_AHRS_DCM_ENABLED325// return true if *DCM* yaw has been initialised326bool dcm_yaw_initialised(void) const {327return dcm.yaw_initialised();328}329#endif330331// get_filter_status - returns filter status as a series of flags332bool get_filter_status(nav_filter_status &status) const;333334// get compass offset estimates335// true if offsets are valid336bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const;337338// return the amount of yaw angle change due to the last yaw angle reset in radians339// returns the time of the last yaw angle reset or 0 if no reset has ever occurred340uint32_t getLastYawResetAngle(float &yawAng);341342// return the amount of NE position change in meters due to the last reset343// returns the time of the last reset or 0 if no reset has ever occurred344uint32_t getLastPosNorthEastReset(Vector2f &pos);345346// return the amount of NE velocity change in meters/sec due to the last reset347// returns the time of the last reset or 0 if no reset has ever occurred348uint32_t getLastVelNorthEastReset(Vector2f &vel) const;349350// return the amount of vertical position change due to the last reset in meters351// returns the time of the last reset or 0 if no reset has ever occurred352uint32_t getLastPosDownReset(float &posDelta);353354// Resets the baro so that it reads zero at the current height355// Resets the EKF height to zero356// Adjusts the EKf origin height so that the EKF height + origin height is the same as before357// Returns true if the height datum reset has been performed358// If using a range finder for height no reset is performed and it returns false359bool resetHeightDatum();360361// send a EKF_STATUS_REPORT for current EKF362void send_ekf_status_report(class GCS_MAVLINK &link) const;363364// get_hgt_ctrl_limit - get maximum height to be observed by the control loops in meters and a validity flag365// this is used to limit height during optical flow navigation366// it will return invalid when no limiting is required367bool get_hgt_ctrl_limit(float &limit) const;368369// Set to true if the terrain underneath is stable enough to be used as a height reference370// this is not related to terrain following371void set_terrain_hgt_stable(bool stable);372373// return the innovations for the specified instance374// An out of range instance (eg -1) returns data for the primary instance375bool get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const;376377// returns true when the state estimates are significantly degraded by vibration378bool is_vibration_affected() const;379380// get_variances - provides the innovations normalised using the innovation variance where a value of 0381// indicates perfect consistency between the measurement and the EKF solution and a value of 1 is the maximum382// inconsistency that will be accepted by the filter383// boolean false is returned if variances are not available384bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const;385386// get a source's velocity innovations387// returns true on success and results are placed in innovations and variances arguments388bool get_vel_innovations_and_variances_for_source(uint8_t source, Vector3f &innovations, Vector3f &variances) const WARN_IF_UNUSED;389390// returns the expected NED magnetic field391bool get_mag_field_NED(Vector3f& ret) const;392393// returns the estimated magnetic field offsets in body frame394bool get_mag_field_correction(Vector3f &ret) const;395396// return the index of the airspeed we should use for airspeed measurements397// with multiple airspeed sensors and airspeed affinity in EKF3, it is possible to have switched398// over to a lane not using the primary airspeed sensor, so AHRS should know which airspeed sensor399// to use, i.e, the one being used by the primary lane. A lane switch could have happened due to an400// airspeed sensor fault, which makes this even more necessary401uint8_t get_active_airspeed_index() const;402403// return the index of the primary core or -1 if no primary core selected404int8_t get_primary_core_index() const { return state.primary_core; }405406// get the index of the current primary accelerometer sensor407uint8_t get_primary_accel_index(void) const { return state.primary_accel; }408409// get the index of the current primary gyro sensor410uint8_t get_primary_gyro_index(void) const { return state.primary_gyro; }411412// see if EKF lane switching is possible to avoid EKF failsafe413void check_lane_switch(void);414415// request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe416void request_yaw_reset(void);417418// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary419void set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx);420421//returns index of active source set used, 0=primary, 1=secondary, 2=tertiary422uint8_t get_posvelyaw_source_set() const;423424void Log_Write();425426// check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed427bool using_noncompass_for_yaw(void) const;428429// check if external nav is providing yaw430bool using_extnav_for_yaw(void) const;431432// set and save the ALT_M_NSE parameter value433void set_alt_measurement_noise(float noise);434435// get the selected ekf type, for allocation decisions436int8_t get_ekf_type(void) const {437return _ekf_type;438}439440enum class EKFType : uint8_t {441#if AP_AHRS_DCM_ENABLED442DCM = 0,443#endif444#if HAL_NAVEKF3_AVAILABLE445THREE = 3,446#endif447#if HAL_NAVEKF2_AVAILABLE448TWO = 2,449#endif450#if AP_AHRS_SIM_ENABLED451SIM = 10,452#endif453#if AP_AHRS_EXTERNAL_ENABLED454EXTERNAL = 11,455#endif456};457458// set the selected ekf type, for RC aux control459void set_ekf_type(EKFType ahrs_type) {460_ekf_type.set(ahrs_type);461}462463// these are only out here so vehicles can reference them for parameters464#if HAL_NAVEKF2_AVAILABLE465NavEKF2 EKF2;466#endif467#if HAL_NAVEKF3_AVAILABLE468NavEKF3 EKF3;469#endif470471// for holding parameters472static const struct AP_Param::GroupInfo var_info[];473474// create a view475AP_AHRS_View *create_view(enum Rotation rotation, float pitch_trim_deg=0);476477// write AOA and SSA information to dataflash logs:478void Write_AOA_SSA(void) const;479480// return AOA481float getAOA(void) const { return _AOA; }482483// return SSA484float getSSA(void) const { return _SSA; }485486/*487* trim-related functions488*/489490// get trim491const Vector3f &get_trim() const { return _trim.get(); }492493// set trim494void set_trim(const Vector3f &new_trim);495496// add_trim - adjust the roll and pitch trim up to a total of 10 degrees497void add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom = true);498499// trim rotation matrices:500const Matrix3f& get_rotation_autopilot_body_to_vehicle_body(void) const { return _rotation_autopilot_body_to_vehicle_body; }501const Matrix3f& get_rotation_vehicle_body_to_autopilot_body(void) const { return _rotation_vehicle_body_to_autopilot_body; }502503// Logging functions504void Log_Write_Home_And_Origin();505void Write_Attitude(const Vector3f &targets) const;506507enum class LogOriginType {508ekf_origin = 0,509ahrs_home = 1510};511void Write_Origin(LogOriginType origin_type, const Location &loc) const;512void write_video_stabilisation() const;513514// return a smoothed and corrected gyro vector in radians/second515// using the latest ins data (which may not have been consumed by516// the EKF yet)517Vector3f get_gyro_latest(void) const;518519// get yaw rate in earth frame in radians/sec520float get_yaw_rate_earth(void) const {521return get_gyro() * get_rotation_body_to_ned().c;522}523524/*525* home-related functionality526*/527528// get the home location. This is const to prevent any changes to529// home without telling AHRS about the change530const Location &get_home(void) const {531return _home;532}533534// functions to handle locking of home. Some vehicles use this to535// allow GCS to lock in a home location.536void lock_home() {537_home_locked = true;538}539bool home_is_locked() const {540return _home_locked;541}542543// returns true if home is set544bool home_is_set(void) const {545return _home_is_set;546}547548// set the home location in 10e7 degrees. This should be called549// when the vehicle is at this position. It is assumed that the550// current barometer and GPS altitudes correspond to this altitude551bool set_home(const Location &loc) WARN_IF_UNUSED;552553/*554* Attitude-related public methods and attributes:555*/556557// roll/pitch/yaw euler angles, all in radians558float get_roll() const { return roll; }559float get_pitch() const { return pitch; }560float get_yaw() const { return yaw; }561562// helper trig value accessors563float cos_roll() const {564return _cos_roll;565}566float cos_pitch() const {567return _cos_pitch;568}569float cos_yaw() const {570return _cos_yaw;571}572float sin_roll() const {573return _sin_roll;574}575float sin_pitch() const {576return _sin_pitch;577}578float sin_yaw() const {579return _sin_yaw;580}581582// integer Euler angles (Degrees * 100)583int32_t roll_sensor;584int32_t pitch_sensor;585int32_t yaw_sensor;586587const Matrix3f &get_rotation_body_to_ned(void) const { return state.dcm_matrix; }588589// return a Quaternion representing our current attitude in NED frame590void get_quat_body_to_ned(Quaternion &quat) const;591592#if AP_AHRS_DCM_ENABLED593// get rotation matrix specifically from DCM backend (used for594// compass calibrator)595const Matrix3f &get_DCM_rotation_body_to_ned(void) const {596return dcm_estimates.dcm_matrix;597}598#endif599600// rotate a 2D vector from earth frame to body frame601// in result, x is forward, y is right602Vector2f earth_to_body2D(const Vector2f &ef_vector) const;603604// rotate a 2D vector from earth frame to body frame605// in input, x is forward, y is right606Vector2f body_to_earth2D(const Vector2f &bf) const;607608// convert a vector from body to earth frame609Vector3f body_to_earth(const Vector3f &v) const;610611// convert a vector from earth to body frame612Vector3f earth_to_body(const Vector3f &v) const;613614/*615* methods for the benefit of LUA bindings616*/617// return current vibration vector for primary IMU618Vector3f get_vibration(void) const;619620// return primary accels621const Vector3f &get_accel(void) const {622return AP::ins().get_accel(_get_primary_accel_index());623}624625// return primary accel bias. This should be subtracted from626// get_accel() vector to get best current body frame accel627// estimate628const Vector3f &get_accel_bias(void) const {629return state.accel_bias;630}631632/*633* AHRS is used as a transport for vehicle-takeoff-expected and634* vehicle-landing-expected:635*/636void set_takeoff_expected(bool b);637638bool get_takeoff_expected(void) const {639return takeoff_expected;640}641642void set_touchdown_expected(bool b);643644bool get_touchdown_expected(void) const {645return touchdown_expected;646}647648/*649* fly_forward is set by the vehicles to indicate the vehicle650* should generally be moving in the direction of its heading.651* It is an additional piece of information that the backends can652* use to provide additional and/or improved estimates.653*/654void set_fly_forward(bool b) {655fly_forward = b;656}657bool get_fly_forward(void) const {658return fly_forward;659}660661/* we modify our behaviour based on what sort of vehicle the662* vehicle code tells us we are. This information is also pulled663* from AP_AHRS by other libraries664*/665enum class VehicleClass : uint8_t {666UNKNOWN,667GROUND,668COPTER,669FIXED_WING,670SUBMARINE,671};672VehicleClass get_vehicle_class(void) const {673return _vehicle_class;674}675void set_vehicle_class(VehicleClass vclass) {676_vehicle_class = vclass;677}678679// get the view680AP_AHRS_View *get_view(void) const { return _view; };681682// get access to an EKFGSF_yaw estimator683const EKFGSF_yaw *get_yaw_estimator(void) const;684685private:686687// roll/pitch/yaw euler angles, all in radians688float roll;689float pitch;690float yaw;691692// optional view class693AP_AHRS_View *_view;694695static AP_AHRS *_singleton;696697/* we modify our behaviour based on what sort of vehicle the698* vehicle code tells us we are. This information is also pulled699* from AP_AHRS by other libraries700*/701VehicleClass _vehicle_class{VehicleClass::UNKNOWN};702703// multi-thread access support704HAL_Semaphore _rsem;705706/*707* Parameters708*/709AP_Int8 _wind_max;710AP_Int8 _board_orientation;711AP_Enum<EKFType> _ekf_type;712713/*714* DCM-backend parameters; it takes references to these715*/716// settable parameters717AP_Float _kp_yaw;718AP_Float _kp;719AP_Float gps_gain;720721AP_Float beta;722723AP_Enum<GPSUse> _gps_use;724AP_Int8 _gps_minsats;725726EKFType active_EKF_type(void) const { return state.active_EKF; }727728bool always_use_EKF() const {729return _ekf_flags & FLAG_ALWAYS_USE_EKF;730}731732// check all cores providing consistent attitudes for prearm checks733bool attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const;734// convenience method for setting error string:735void set_failure_inconsistent_message(const char *estimator, const char *axis, float diff_rad, char *failure_msg, const uint8_t failure_msg_len) const;736737/*738* Attitude-related private methods and attributes:739*/740// calculate sin/cos of roll/pitch/yaw from rotation741void calc_trig(const Matrix3f &rot,742float &cr, float &cp, float &cy,743float &sr, float &sp, float &sy) const;744745// update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude746// should be called after _dcm_matrix is updated747void update_trig(void);748749// update roll_sensor, pitch_sensor and yaw_sensor750void update_cd_values(void);751752// helper trig variables753float _cos_roll{1.0f};754float _cos_pitch{1.0f};755float _cos_yaw{1.0f};756float _sin_roll;757float _sin_pitch;758float _sin_yaw;759760#if HAL_NAVEKF2_AVAILABLE761void update_EKF2(void);762bool _ekf2_started;763#endif764#if HAL_NAVEKF3_AVAILABLE765bool _ekf3_started;766void update_EKF3(void);767#endif768769const uint16_t startup_delay_ms = 1000;770uint32_t start_time_ms;771uint8_t _ekf_flags; // bitmask from Flags enumeration772773EKFType ekf_type(void) const;774void update_DCM();775776/*777* home-related state778*/779void load_watchdog_home();780bool _checked_watchdog_home;781Location _home;782bool _home_is_set :1;783bool _home_locked :1;784785// avoid setting current state repeatedly across all cores on all EKFs:786enum class TriState {787False = 0,788True = 1,789UNKNOWN = 3,790};791792TriState terrainHgtStableState = TriState::UNKNOWN;793794/*795* private AOA and SSA-related state and methods796*/797float _AOA, _SSA;798uint32_t _last_AOA_update_ms;799void update_AOA_SSA(void);800801EKFType last_active_ekf_type;802803#if AP_AHRS_SIM_ENABLED804void update_SITL(void);805#endif806807#if AP_AHRS_EXTERNAL_ENABLED808void update_external(void);809#endif810811/*812* trim-related state and private methods:813*/814815// a vector to capture the difference between the controller and body frames816AP_Vector3f _trim;817818// cached trim rotations819Vector3f _last_trim;820821Matrix3f _rotation_autopilot_body_to_vehicle_body;822Matrix3f _rotation_vehicle_body_to_autopilot_body;823824// last time orientation was updated from AHRS_ORIENTATION:825uint32_t last_orientation_update_ms;826827// updates matrices responsible for rotating vectors from vehicle body828// frame to autopilot body frame from _trim variables829void update_trim_rotation_matrices();830831/*832* AHRS is used as a transport for vehicle-takeoff-expected and833* vehicle-landing-expected:834*/835// update takeoff/touchdown flags836void update_flags();837bool takeoff_expected; // true if the vehicle is in a state that takeoff might be expected. Ground effect may be in play.838uint32_t takeoff_expected_start_ms;839bool touchdown_expected; // true if the vehicle is in a state that touchdown might be expected. Ground effect may be in play.840uint32_t touchdown_expected_start_ms;841842/*843* wind estimation support844*/845bool wind_estimation_enabled;846847/*848* fly_forward is set by the vehicles to indicate the vehicle849* should generally be moving in the direction of its heading.850* It is an additional piece of information that the backends can851* use to provide additional and/or improved estimates.852*/853bool fly_forward; // true if we can assume the vehicle will be flying forward on its X axis854855// poke AP_Notify based on values from status856void update_notify_from_filter_status(const nav_filter_status &status);857858/*859* copy results from a backend over AP_AHRS canonical results.860* This updates member variables like roll and pitch, as well as861* updating derived values like sin_roll and sin_pitch.862*/863void copy_estimates_from_backend_estimates(const AP_AHRS_Backend::Estimates &results);864865// write out secondary estimates:866void Write_AHRS2(void) const;867// write POS (canonical vehicle position) message out:868void Write_POS(void) const;869870// return an airspeed estimate if available. return true871// if we have an estimate872bool _airspeed_EAS(float &airspeed_ret, AirspeedEstimateType &status) const;873874// return secondary attitude solution if available, as eulers in radians875bool _get_secondary_attitude(Vector3f &eulers) const;876877// return secondary attitude solution if available, as quaternion878bool _get_secondary_quaternion(Quaternion &quat) const;879880// get ground speed 2D881Vector2f _groundspeed_vector(void);882883// get active EKF type884EKFType _active_EKF_type(void) const;885886// return a wind estimation vector, in m/s887bool _wind_estimate(Vector3f &wind) const WARN_IF_UNUSED;888889// return a true airspeed estimate (navigation airspeed) if890// available. return true if we have an estimate891bool _airspeed_TAS(float &airspeed_ret) const;892893// return estimate of true airspeed vector in body frame in m/s894// returns false if estimate is unavailable895bool _airspeed_TAS(Vector3f &vec) const;896897// return the quaternion defining the rotation from NED to XYZ (body) axes898bool _get_quaternion(Quaternion &quat) const WARN_IF_UNUSED;899900// return secondary position solution if available901bool _get_secondary_position(Location &loc) const;902903// return ground speed estimate in meters/second. Used by ground vehicles.904float _groundspeed(void);905906// Retrieves the corrected NED delta velocity in use by the inertial navigation907void _getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const;908909// returns the inertial navigation origin in lat/lon/alt910bool _get_origin(Location &ret) const WARN_IF_UNUSED;911912// return origin for a specified EKF type913bool _get_origin(EKFType type, Location &ret) const;914915// return a ground velocity in meters/second, North/East/Down916// order. Must only be called if have_inertial_nav() is true917bool _get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED;918919// get secondary EKF type. returns false if no secondary (i.e. only using DCM)920bool _get_secondary_EKF_type(EKFType &secondary_ekf_type) const;921922// return the index of the primary core or -1 if no primary core selected923int8_t _get_primary_core_index() const;924925// get the index of the current primary accelerometer sensor926uint8_t _get_primary_accel_index(void) const;927928// get the index of the current primary gyro sensor929uint8_t _get_primary_gyro_index(void) const;930931// get the index of the current primary IMU932uint8_t _get_primary_IMU_index(void) const;933934// get current location estimate935bool _get_location(Location &loc) const;936937// return true if a airspeed sensor should be used for the AHRS airspeed estimate938bool _should_use_airspeed_sensor(uint8_t airspeed_index) const;939940/*941update state structure942*/943void update_state(void);944945// returns an EKF type to be used as active if we decide the946// primary is not good enough.947EKFType fallback_active_EKF_type(void) const;948949/*950state updated at the end of each update() call951*/952struct {953EKFType active_EKF;954uint8_t primary_IMU;955uint8_t primary_gyro;956uint8_t primary_accel;957uint8_t primary_core;958Vector3f gyro_estimate;959Matrix3f dcm_matrix;960Vector3f gyro_drift;961Vector3f accel_ef;962Vector3f accel_bias;963Vector3f wind_estimate;964bool wind_estimate_ok;965float EAS2TAS;966bool airspeed_ok;967float airspeed;968AirspeedEstimateType airspeed_estimate_type;969bool airspeed_true_ok;970float airspeed_true;971Vector3f airspeed_vec;972bool airspeed_vec_ok;973Quaternion quat;974bool quat_ok;975Vector3f secondary_attitude;976bool secondary_attitude_ok;977Quaternion secondary_quat;978bool secondary_quat_ok;979Location location;980bool location_ok;981Location secondary_pos;982bool secondary_pos_ok;983Vector2f ground_speed_vec;984float ground_speed;985Vector3f corrected_dv;986float corrected_dv_dt;987Location origin;988bool origin_ok;989Vector3f velocity_NED;990bool velocity_NED_ok;991} state;992993/*994* backends (and their results)995*/996#if AP_AHRS_DCM_ENABLED997AP_AHRS_DCM dcm{_kp_yaw, _kp, gps_gain, beta, _gps_use, _gps_minsats};998struct AP_AHRS_Backend::Estimates dcm_estimates;999#endif1000#if AP_AHRS_SIM_ENABLED1001#if HAL_NAVEKF3_AVAILABLE1002AP_AHRS_SIM sim{EKF3};1003#else1004AP_AHRS_SIM sim;1005#endif1006struct AP_AHRS_Backend::Estimates sim_estimates;1007#endif10081009#if AP_AHRS_EXTERNAL_ENABLED1010AP_AHRS_External external;1011struct AP_AHRS_Backend::Estimates external_estimates;1012#endif10131014enum class Options : uint16_t {1015DISABLE_DCM_FALLBACK_FW=(1U<<0),1016DISABLE_DCM_FALLBACK_VTOL=(1U<<1),1017DISABLE_AIRSPEED_EKF_CHECK=(1U<<2),1018};1019AP_Int16 _options;10201021bool option_set(Options option) const {1022return (_options & uint16_t(option)) != 0;1023}10241025// true when we have completed the common origin setup1026bool done_common_origin;1027};10281029namespace AP {1030AP_AHRS &ahrs();1031};103210331034