1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552155315541555155615571558155915601561156215631564156515661567156815691570157115721573157415751576157715781579158015811582158315841585158615871588158915901591159215931594159515961597159815991600160116021603160416051606160716081609161016111612161316141615161616171618161916201621162216231624162516261627162816291630163116321633163416351636163716381639164016411642164316441645164616471648164916501651165216531654165516561657165816591660166116621663166416651666166716681669167016711672167316741675167616771678167916801681168216831684168516861687168816891690169116921693169416951696169716981699170017011702170317041705170617071708170917101711171217131714171517161717171817191720172117221723172417251726172717281729173017311732173317341735173617371738173917401741174217431744174517461747174817491750175117521753175417551756175717581759176017611762176317641765176617671768176917701771177217731774177517761777177817791780178117821783178417851786178717881789179017911792179317941795179617971798179918001801180218031804180518061807180818091810181118121813181418151816181718181819182018211822182318241825182618271828182918301831183218331834183518361837 |
- #include <AP_HAL/AP_HAL.h>
- #include "AP_AHRS.h"
- #include "AP_AHRS_View.h"
- #include <AP_Vehicle/AP_Vehicle.h>
- #include <GCS_MAVLink/GCS.h>
- #include <AP_Module/AP_Module.h>
- #include <AP_GPS/AP_GPS.h>
- #include <AP_Baro/AP_Baro.h>
- #if AP_AHRS_NAVEKF_AVAILABLE
- #define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10)
- #define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20)
- extern const AP_HAL::HAL& hal;
- AP_AHRS_NavEKF::AP_AHRS_NavEKF(NavEKF2 &_EKF2,
- NavEKF3 &_EKF3,
- Flags flags) :
- AP_AHRS_DCM(),
- EKF2(_EKF2),
- EKF3(_EKF3),
- _ekf_flags(flags)
- {
- _dcm_matrix.identity();
- }
- const Vector3f &AP_AHRS_NavEKF::get_gyro(void) const
- {
- if (!active_EKF_type()) {
- return AP_AHRS_DCM::get_gyro();
- }
- return _gyro_estimate;
- }
- const Matrix3f &AP_AHRS_NavEKF::get_rotation_body_to_ned(void) const
- {
- if (!active_EKF_type()) {
- return AP_AHRS_DCM::get_rotation_body_to_ned();
- }
- return _dcm_matrix;
- }
- const Vector3f &AP_AHRS_NavEKF::get_gyro_drift(void) const
- {
- if (!active_EKF_type()) {
- return AP_AHRS_DCM::get_gyro_drift();
- }
- return _gyro_drift;
- }
- void AP_AHRS_NavEKF::reset_gyro_drift(void)
- {
-
- WITH_SEMAPHORE(_rsem);
-
-
- AP_AHRS_DCM::reset_gyro_drift();
-
- EKF2.resetGyroBias();
- EKF3.resetGyroBias();
- }
- void AP_AHRS_NavEKF::update(bool skip_ins_update)
- {
-
- WITH_SEMAPHORE(_rsem);
-
-
-
- hal.scheduler->boost_end();
-
-
- if (_ekf_type == 1) {
- _ekf_type.set(2);
- }
- update_DCM(skip_ins_update);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- update_SITL();
- #endif
- if (_ekf_type == 2) {
-
-
- update_EKF2();
- update_EKF3();
- } else {
-
- update_EKF3();
- update_EKF2();
- }
- #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(skip_ins_update);
- }
- #if !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE
-
- update_nmea_out();
- #endif
- }
- void AP_AHRS_NavEKF::update_DCM(bool skip_ins_update)
- {
-
-
-
- roll = _dcm_attitude.x;
- pitch = _dcm_attitude.y;
- yaw = _dcm_attitude.z;
- update_cd_values();
- AP_AHRS_DCM::update(skip_ins_update);
-
- _dcm_attitude(roll, pitch, yaw);
- }
- void AP_AHRS_NavEKF::update_EKF2(void)
- {
- if (!_ekf2_started) {
-
- if (start_time_ms == 0) {
- start_time_ms = AP_HAL::millis();
- }
- if (AP_HAL::millis() - start_time_ms > startup_delay_ms || _force_ekf) {
- _ekf2_started = EKF2.InitialiseFilter();
- if (_force_ekf) {
- return;
- }
- }
- }
- if (_ekf2_started) {
- EKF2.UpdateFilter();
- if (active_EKF_type() == EKF_TYPE2) {
- Vector3f eulers;
- EKF2.getRotationBodyToNED(_dcm_matrix);
- EKF2.getEulerAngles(-1,eulers);
- roll = eulers.x;
- pitch = eulers.y;
- yaw = eulers.z;
- update_cd_values();
- update_trig();
-
- const int8_t primary_imu = EKF2.getPrimaryCoreIMUIndex();
- const AP_InertialSensor &_ins = AP::ins();
-
-
- _gyro_drift.zero();
- EKF2.getGyroBias(-1,_gyro_drift);
- _gyro_drift = -_gyro_drift;
-
- _gyro_estimate.zero();
- if (primary_imu == -1 || !_ins.get_gyro_health(primary_imu)) {
-
- _gyro_estimate = _ins.get_gyro();
- } else {
-
- _gyro_estimate = _ins.get_gyro(primary_imu) + _gyro_drift;
- }
-
- float abias = 0;
- EKF2.getAccelZBias(-1,abias);
-
- for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
- Vector3f accel = _ins.get_accel(i);
- if (i == primary_imu) {
- accel.z -= abias;
- }
- if (_ins.get_accel_health(i)) {
- _accel_ef_ekf[i] = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel;
- }
- }
- _accel_ef_ekf_blended = _accel_ef_ekf[primary_imu>=0?primary_imu:_ins.get_primary_accel()];
- nav_filter_status filt_state;
- EKF2.getFilterStatus(-1,filt_state);
- AP_Notify::flags.gps_fusion = filt_state.flags.using_gps;
- AP_Notify::flags.gps_glitching = filt_state.flags.gps_glitching;
- AP_Notify::flags.have_pos_abs = filt_state.flags.horiz_pos_abs;
- }
- }
- }
- void AP_AHRS_NavEKF::update_EKF3(void)
- {
- if (!_ekf3_started) {
-
- if (start_time_ms == 0) {
- start_time_ms = AP_HAL::millis();
- }
- if (AP_HAL::millis() - start_time_ms > startup_delay_ms || _force_ekf) {
- _ekf3_started = EKF3.InitialiseFilter();
- if (_force_ekf) {
- return;
- }
- }
- }
- if (_ekf3_started) {
- EKF3.UpdateFilter();
- if (active_EKF_type() == EKF_TYPE3) {
- Vector3f eulers;
- EKF3.getRotationBodyToNED(_dcm_matrix);
- EKF3.getEulerAngles(-1,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();
-
-
- _gyro_drift.zero();
- EKF3.getGyroBias(-1,_gyro_drift);
- _gyro_drift = -_gyro_drift;
-
- _gyro_estimate.zero();
- if (primary_imu == -1 || !_ins.get_gyro_health(primary_imu)) {
-
- _gyro_estimate = _ins.get_gyro();
- } else {
-
- _gyro_estimate = _ins.get_gyro(primary_imu) + _gyro_drift;
- }
-
- Vector3f abias;
- EKF3.getAccelBias(-1,abias);
-
-
-
- for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
- Vector3f accel = _ins.get_accel(i);
- if (i==_ins.get_primary_accel()) {
- accel -= abias;
- }
- if (_ins.get_accel_health(i)) {
- _accel_ef_ekf[i] = _dcm_matrix * accel;
- }
- }
- _accel_ef_ekf_blended = _accel_ef_ekf[_ins.get_primary_accel()];
- nav_filter_status filt_state;
- EKF3.getFilterStatus(-1,filt_state);
- AP_Notify::flags.gps_fusion = filt_state.flags.using_gps;
- AP_Notify::flags.gps_glitching = filt_state.flags.gps_glitching;
- AP_Notify::flags.have_pos_abs = filt_state.flags.horiz_pos_abs;
- }
- }
- }
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- void AP_AHRS_NavEKF::update_SITL(void)
- {
- if (_sitl == nullptr) {
- _sitl = AP::sitl();
- if (_sitl == nullptr) {
- return;
- }
- }
- const struct SITL::sitl_fdm &fdm = _sitl->state;
- const AP_InertialSensor &_ins = AP::ins();
- if (active_EKF_type() == EKF_TYPE_SITL) {
- fdm.quaternion.rotation_matrix(_dcm_matrix);
- _dcm_matrix = _dcm_matrix * get_rotation_vehicle_body_to_autopilot_body();
- _dcm_matrix.to_euler(&roll, &pitch, &yaw);
- update_cd_values();
- update_trig();
- _gyro_drift.zero();
- _gyro_estimate = _ins.get_gyro();
- for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
- const Vector3f &accel = _ins.get_accel(i);
- _accel_ef_ekf[i] = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel;
- }
- _accel_ef_ekf_blended = _accel_ef_ekf[0];
- }
- if (_sitl->odom_enable) {
-
- uint32_t timeStamp_ms = AP_HAL::millis();
- if (timeStamp_ms - _last_body_odm_update_ms > 50) {
- const float quality = 100.0f;
- const Vector3f posOffset(0.0f, 0.0f, 0.0f);
- const float delTime = 0.001f * (timeStamp_ms - _last_body_odm_update_ms);
- _last_body_odm_update_ms = timeStamp_ms;
- timeStamp_ms -= (timeStamp_ms - _last_body_odm_update_ms)/2;
- Vector3f delAng = _ins.get_gyro();
-
- delAng *= delTime;
-
- Matrix3f Tbn;
- Tbn.from_euler(radians(fdm.rollDeg),radians(fdm.pitchDeg),radians(fdm.yawDeg));
- const Vector3f earth_vel(fdm.speedN,fdm.speedE,fdm.speedD);
- const Vector3f delPos = Tbn.transposed() * (earth_vel * delTime);
-
- EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, posOffset);
- }
- }
- }
- #endif
- const Vector3f &AP_AHRS_NavEKF::get_accel_ef(uint8_t i) const
- {
- if (active_EKF_type() == EKF_TYPE_NONE) {
- return AP_AHRS_DCM::get_accel_ef(i);
- }
- return _accel_ef_ekf[i];
- }
- const Vector3f &AP_AHRS_NavEKF::get_accel_ef_blended(void) const
- {
- if (active_EKF_type() == EKF_TYPE_NONE) {
- return AP_AHRS_DCM::get_accel_ef_blended();
- }
- return _accel_ef_ekf_blended;
- }
- void AP_AHRS_NavEKF::reset(bool recover_eulers)
- {
-
- WITH_SEMAPHORE(_rsem);
-
- AP_AHRS_DCM::reset(recover_eulers);
- _dcm_attitude(roll, pitch, yaw);
- if (_ekf2_started) {
- _ekf2_started = EKF2.InitialiseFilter();
- }
- if (_ekf3_started) {
- _ekf3_started = EKF3.InitialiseFilter();
- }
- }
- void AP_AHRS_NavEKF::reset_attitude(const float &_roll, const float &_pitch, const float &_yaw)
- {
-
- WITH_SEMAPHORE(_rsem);
-
- AP_AHRS_DCM::reset_attitude(_roll, _pitch, _yaw);
- _dcm_attitude(roll, pitch, yaw);
- if (_ekf2_started) {
- _ekf2_started = EKF2.InitialiseFilter();
- }
- if (_ekf3_started) {
- _ekf3_started = EKF3.InitialiseFilter();
- }
- }
- bool AP_AHRS_NavEKF::get_position(struct Location &loc) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- return AP_AHRS_DCM::get_position(loc);
- case EKF_TYPE2:
- if (EKF2.getLLH(loc)) {
- return true;
- }
- break;
- case EKF_TYPE3:
- if (EKF3.getLLH(loc)) {
- return true;
- }
- break;
-
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL: {
- if (_sitl) {
- const struct SITL::sitl_fdm &fdm = _sitl->state;
- loc = {};
- loc.lat = fdm.latitude * 1e7;
- loc.lng = fdm.longitude * 1e7;
- loc.alt = fdm.altitude*100;
- return true;
- }
- break;
- }
- #endif
-
- default:
- break;
- }
- return AP_AHRS_DCM::get_position(loc);
- }
- float AP_AHRS_NavEKF::get_error_rp(void) const
- {
- return AP_AHRS_DCM::get_error_rp();
- }
- float AP_AHRS_NavEKF::get_error_yaw(void) const
- {
- return AP_AHRS_DCM::get_error_yaw();
- }
- Vector3f AP_AHRS_NavEKF::wind_estimate(void) const
- {
- Vector3f wind;
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- wind = AP_AHRS_DCM::wind_estimate();
- break;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- wind.zero();
- break;
- #endif
- case EKF_TYPE2:
- EKF2.getWind(-1,wind);
- break;
- case EKF_TYPE3:
- EKF3.getWind(-1,wind);
- break;
- }
- return wind;
- }
- bool AP_AHRS_NavEKF::airspeed_estimate(float *airspeed_ret) const
- {
- return AP_AHRS_DCM::airspeed_estimate(airspeed_ret);
- }
- bool AP_AHRS_NavEKF::use_compass(void)
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- break;
- case EKF_TYPE2:
- return EKF2.use_compass();
- case EKF_TYPE3:
- return EKF3.use_compass();
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return true;
- #endif
- }
- return AP_AHRS_DCM::use_compass();
- }
- bool AP_AHRS_NavEKF::get_secondary_attitude(Vector3f &eulers) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
-
- EKF2.getEulerAngles(-1, eulers);
- return _ekf2_started;
- case EKF_TYPE2:
- case EKF_TYPE3:
- default:
-
- eulers = _dcm_attitude;
- return true;
- }
- }
- bool AP_AHRS_NavEKF::get_secondary_quaternion(Quaternion &quat) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
-
- EKF2.getQuaternion(-1, quat);
- return _ekf2_started;
- case EKF_TYPE2:
- case EKF_TYPE3:
- default:
-
- quat.from_rotation_matrix(AP_AHRS_DCM::get_rotation_body_to_ned());
- return true;
- }
- }
- bool AP_AHRS_NavEKF::get_secondary_position(struct Location &loc) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
-
- EKF2.getLLH(loc);
- return _ekf2_started;
- case EKF_TYPE2:
- case EKF_TYPE3:
- default:
-
- AP_AHRS_DCM::get_position(loc);
- return true;
- }
- }
- Vector2f AP_AHRS_NavEKF::groundspeed_vector(void)
- {
- Vector3f vec;
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- return AP_AHRS_DCM::groundspeed_vector();
- case EKF_TYPE2:
- default:
- EKF2.getVelNED(-1,vec);
- return Vector2f(vec.x, vec.y);
- case EKF_TYPE3:
- EKF3.getVelNED(-1,vec);
- return Vector2f(vec.x, vec.y);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL: {
- if (_sitl) {
- const struct SITL::sitl_fdm &fdm = _sitl->state;
- return Vector2f(fdm.speedN, fdm.speedE);
- } else {
- return AP_AHRS_DCM::groundspeed_vector();
- }
- }
- #endif
- }
- }
- bool AP_AHRS_NavEKF::set_origin(const Location &loc)
- {
- const bool ret2 = EKF2.setOriginLLH(loc);
- const bool ret3 = EKF3.setOriginLLH(loc);
-
- switch (active_EKF_type()) {
- case EKF_TYPE2:
- return ret2;
- case EKF_TYPE3:
- return ret3;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- if (_sitl) {
- struct SITL::sitl_fdm &fdm = _sitl->state;
- fdm.home = loc;
- return true;
- } else {
- return false;
- }
- #endif
- default:
- return false;
- }
- }
- bool AP_AHRS_NavEKF::have_inertial_nav(void) const
- {
- return active_EKF_type() != EKF_TYPE_NONE;
- }
- bool AP_AHRS_NavEKF::get_velocity_NED(Vector3f &vec) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- return AP_AHRS_DCM::get_velocity_NED(vec);
- case EKF_TYPE2:
- default:
- EKF2.getVelNED(-1,vec);
- return true;
- case EKF_TYPE3:
- EKF3.getVelNED(-1,vec);
- return true;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- if (!_sitl) {
- return false;
- }
- const struct SITL::sitl_fdm &fdm = _sitl->state;
- vec = Vector3f(fdm.speedN, fdm.speedE, fdm.speedD);
- return true;
- #endif
- }
- }
- bool AP_AHRS_NavEKF::get_mag_field_NED(Vector3f &vec) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- return false;
- case EKF_TYPE2:
- default:
- EKF2.getMagNED(-1,vec);
- return true;
- case EKF_TYPE3:
- EKF3.getMagNED(-1,vec);
- return true;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return false;
- #endif
- }
- }
- bool AP_AHRS_NavEKF::get_mag_field_correction(Vector3f &vec) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- return false;
- case EKF_TYPE2:
- default:
- EKF2.getMagXYZ(-1,vec);
- return true;
- case EKF_TYPE3:
- EKF3.getMagXYZ(-1,vec);
- return true;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return false;
- #endif
- }
- }
- bool AP_AHRS_NavEKF::get_vert_pos_rate(float &velocity) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- return false;
- case EKF_TYPE2:
- default:
- velocity = EKF2.getPosDownDerivative(-1);
- return true;
- case EKF_TYPE3:
- velocity = EKF3.getPosDownDerivative(-1);
- return true;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- if (_sitl) {
- const struct SITL::sitl_fdm &fdm = _sitl->state;
- velocity = fdm.speedD;
- return true;
- } else {
- return false;
- }
- #endif
- }
- }
- bool AP_AHRS_NavEKF::get_hagl(float &height) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- return false;
- case EKF_TYPE2:
- default:
- return EKF2.getHAGL(height);
-
- case EKF_TYPE3:
- return EKF3.getHAGL(height);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL: {
- if (!_sitl) {
- return false;
- }
- const struct SITL::sitl_fdm &fdm = _sitl->state;
- height = fdm.altitude - get_home().alt*0.01f;
- return true;
- }
- #endif
- }
- }
- bool AP_AHRS_NavEKF::get_relative_position_NED_origin(Vector3f &vec) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- return false;
- case EKF_TYPE2:
- default: {
- Vector2f posNE;
- float posD;
- if (EKF2.getPosNE(-1,posNE) && EKF2.getPosD(-1,posD)) {
-
- vec.x = posNE.x;
- vec.y = posNE.y;
- vec.z = posD;
- return true;
- }
- return false;
- }
- case EKF_TYPE3: {
- Vector2f posNE;
- float posD;
- if (EKF3.getPosNE(-1,posNE) && EKF3.getPosD(-1,posD)) {
-
- vec.x = posNE.x;
- vec.y = posNE.y;
- vec.z = posD;
- return true;
- }
- return false;
- }
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL: {
- if (!_sitl) {
- return false;
- }
- Location loc;
- get_position(loc);
- const Vector2f diff2d = get_home().get_distance_NE(loc);
- const struct SITL::sitl_fdm &fdm = _sitl->state;
- vec = Vector3f(diff2d.x, diff2d.y,
- -(fdm.altitude - get_home().alt*0.01f));
- return true;
- }
- #endif
- }
- }
- bool AP_AHRS_NavEKF::get_relative_position_NED_home(Vector3f &vec) const
- {
- Location originLLH;
- Vector3f originNED;
- if (!get_relative_position_NED_origin(originNED) ||
- !get_origin(originLLH)) {
- return false;
- }
- const Vector3f offset = originLLH.get_distance_NED(_home);
- vec.x = originNED.x - offset.x;
- vec.y = originNED.y - offset.y;
- vec.z = originNED.z - offset.z;
- return true;
- }
- bool AP_AHRS_NavEKF::get_relative_position_NE_origin(Vector2f &posNE) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- return false;
- case EKF_TYPE2:
- default: {
- bool position_is_valid = EKF2.getPosNE(-1,posNE);
- return position_is_valid;
- }
- case EKF_TYPE3: {
- bool position_is_valid = EKF3.getPosNE(-1,posNE);
- return position_is_valid;
- }
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL: {
- Location loc;
- get_position(loc);
- posNE = get_home().get_distance_NE(loc);
- return true;
- }
- #endif
- }
- }
- bool AP_AHRS_NavEKF::get_relative_position_NE_home(Vector2f &posNE) const
- {
- Location originLLH;
- Vector2f originNE;
- if (!get_relative_position_NE_origin(originNE) ||
- !get_origin(originLLH)) {
- return false;
- }
- const Vector2f offset = originLLH.get_distance_NE(_home);
- posNE.x = originNE.x - offset.x;
- posNE.y = originNE.y - offset.y;
- return true;
- }
- bool AP_AHRS_NavEKF::get_relative_position_D_origin(float &posD) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- return false;
- case EKF_TYPE2:
- default: {
- bool position_is_valid = EKF2.getPosD(-1,posD);
- return position_is_valid;
- }
- case EKF_TYPE3: {
- bool position_is_valid = EKF3.getPosD(-1,posD);
- return position_is_valid;
- }
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL: {
- if (!_sitl) {
- return false;
- }
- const struct SITL::sitl_fdm &fdm = _sitl->state;
- posD = -(fdm.altitude - get_home().alt*0.01f);
- return true;
- }
- #endif
- }
- }
- void AP_AHRS_NavEKF::get_relative_position_D_home(float &posD) const
- {
- Location originLLH;
- float originD;
- if (!get_relative_position_D_origin(originD) ||
- !get_origin(originLLH)) {
- posD = -AP::baro().get_altitude();
- return;
- }
- posD = originD - ((originLLH.alt - _home.alt) * 0.01f);
- return;
- }
- uint8_t AP_AHRS_NavEKF::ekf_type(void) const
- {
- uint8_t type = _ekf_type;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- if (type == EKF_TYPE_SITL) {
- return type;
- }
- #endif
- if ((always_use_EKF() && (type == 0)) || (type == 1) || (type > 3)) {
- type = 2;
- }
- return type;
- }
- AP_AHRS_NavEKF::EKF_TYPE AP_AHRS_NavEKF::active_EKF_type(void) const
- {
- EKF_TYPE ret = EKF_TYPE_NONE;
- switch (ekf_type()) {
- case 0:
- return EKF_TYPE_NONE;
- case 2: {
-
- if (!_ekf2_started) {
- return EKF_TYPE_NONE;
- }
- if (always_use_EKF()) {
- uint16_t ekf2_faults;
- EKF2.getFilterFaults(-1,ekf2_faults);
- if (ekf2_faults == 0) {
- ret = EKF_TYPE2;
- }
- } else if (EKF2.healthy()) {
- ret = EKF_TYPE2;
- }
- break;
- }
- case 3: {
-
- if (!_ekf3_started) {
- return EKF_TYPE_NONE;
- }
- if (always_use_EKF()) {
- uint16_t ekf3_faults;
- EKF3.getFilterFaults(-1,ekf3_faults);
- if (ekf3_faults == 0) {
- ret = EKF_TYPE3;
- }
- } else if (EKF3.healthy()) {
- ret = EKF_TYPE3;
- }
- break;
- }
-
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- ret = EKF_TYPE_SITL;
- break;
- #endif
- }
-
- if (ret != EKF_TYPE_NONE &&
- (_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
- _vehicle_class == AHRS_VEHICLE_GROUND) &&
- (_flags.fly_forward || !hal.util->get_soft_armed())) {
- nav_filter_status filt_state;
- if (ret == EKF_TYPE2) {
- EKF2.getFilterStatus(-1,filt_state);
- } else if (ret == EKF_TYPE3) {
- EKF3.getFilterStatus(-1,filt_state);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- } else if (ret == EKF_TYPE_SITL) {
- get_filter_status(filt_state);
- #endif
- }
- if (hal.util->get_soft_armed() && !filt_state.flags.using_gps && AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
-
-
-
-
- return EKF_TYPE_NONE;
- }
- if (hal.util->get_soft_armed() && filt_state.flags.const_pos_mode) {
- return EKF_TYPE_NONE;
- }
- if (!filt_state.flags.attitude ||
- !filt_state.flags.vert_vel ||
- !filt_state.flags.vert_pos) {
- return EKF_TYPE_NONE;
- }
- if (!filt_state.flags.horiz_vel ||
- (!filt_state.flags.horiz_pos_abs && !filt_state.flags.horiz_pos_rel)) {
- if ((!_compass || !_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 EKF_TYPE_NONE;
- }
- }
- return ret;
- }
- bool AP_AHRS_NavEKF::healthy(void) const
- {
-
-
-
- switch (ekf_type()) {
- case 0:
- return AP_AHRS_DCM::healthy();
- case 2: {
- bool ret = _ekf2_started && EKF2.healthy();
- if (!ret) {
- return false;
- }
- if ((_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
- _vehicle_class == AHRS_VEHICLE_GROUND) &&
- active_EKF_type() != EKF_TYPE2) {
-
-
- return false;
- }
- return true;
- }
- case 3: {
- bool ret = _ekf3_started && EKF3.healthy();
- if (!ret) {
- return false;
- }
- if ((_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
- _vehicle_class == AHRS_VEHICLE_GROUND) &&
- active_EKF_type() != EKF_TYPE3) {
-
-
- return false;
- }
- return true;
- }
-
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return true;
- #endif
- }
- return AP_AHRS_DCM::healthy();
- }
- bool AP_AHRS_NavEKF::prearm_healthy(void) const
- {
- bool prearm_health = false;
- switch (ekf_type()) {
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- #endif
- case EKF_TYPE_NONE:
- prearm_health = true;
- break;
- case EKF_TYPE2:
- default:
- if (_ekf2_started && EKF2.all_cores_healthy()) {
- prearm_health = true;
- }
- break;
- case EKF_TYPE3:
- if (_ekf3_started && EKF3.all_cores_healthy()) {
- prearm_health = true;
- }
- break;
- }
- return prearm_health && healthy();
- }
- void AP_AHRS_NavEKF::set_ekf_use(bool setting)
- {
- _ekf_type.set(setting?1:0);
- }
- bool AP_AHRS_NavEKF::initialised(void) const
- {
- switch (ekf_type()) {
- case 0:
- return true;
- case 2:
- default:
-
- return (_ekf2_started && (AP_HAL::millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));
- case 3:
-
- return (_ekf3_started && (AP_HAL::millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return true;
- #endif
- }
- };
- bool AP_AHRS_NavEKF::get_filter_status(nav_filter_status &status) const
- {
- switch (ekf_type()) {
- case EKF_TYPE_NONE:
- return false;
- case EKF_TYPE2:
- default:
- EKF2.getFilterStatus(-1,status);
- return true;
- case EKF_TYPE3:
- EKF3.getFilterStatus(-1,status);
- return true;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- memset(&status, 0, sizeof(status));
- status.flags.attitude = 1;
- status.flags.horiz_vel = 1;
- status.flags.vert_vel = 1;
- status.flags.horiz_pos_rel = 1;
- status.flags.horiz_pos_abs = 1;
- status.flags.vert_pos = 1;
- status.flags.pred_horiz_pos_rel = 1;
- status.flags.pred_horiz_pos_abs = 1;
- status.flags.using_gps = 1;
- return true;
- #endif
- }
- }
- void AP_AHRS_NavEKF::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
- {
- EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
- EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
- }
- void AP_AHRS_NavEKF::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
- {
- EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, posOffset);
- }
- void AP_AHRS_NavEKF::writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
- {
- EKF2.writeExtNavData(sensOffset, pos, quat, posErr, angErr, timeStamp_ms, resetTime_ms);
- }
- uint8_t AP_AHRS_NavEKF::setInhibitGPS(void)
- {
- switch (ekf_type()) {
- case 0:
- case 2:
- default:
- return EKF2.setInhibitGPS();
- case 3:
- return EKF3.setInhibitGPS();
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return false;
- #endif
- }
- }
- void AP_AHRS_NavEKF::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
- {
- switch (ekf_type()) {
- case 0:
- case 2:
- EKF2.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
- break;
- case 3:
- EKF3.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
- break;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
-
- ekfGndSpdLimit = 400.0f;
- ekfNavVelGainScaler = 1.0f;
- break;
- #endif
- }
- }
- bool AP_AHRS_NavEKF::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
- {
- switch (ekf_type()) {
- case 0:
- case 2:
- default:
- return EKF2.getMagOffsets(mag_idx, magOffsets);
- case 3:
- return EKF3.getMagOffsets(mag_idx, magOffsets);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- magOffsets.zero();
- return true;
- #endif
- }
- }
- void AP_AHRS_NavEKF::getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const
- {
- const EKF_TYPE type = active_EKF_type();
- if (type == EKF_TYPE2 || type == EKF_TYPE3) {
- int8_t imu_idx = 0;
- Vector3f accel_bias;
- if (type == EKF_TYPE2) {
- accel_bias.zero();
- imu_idx = EKF2.getPrimaryCoreIMUIndex();
- EKF2.getAccelZBias(-1,accel_bias.z);
- } else if (type == EKF_TYPE3) {
- imu_idx = EKF3.getPrimaryCoreIMUIndex();
- EKF3.getAccelBias(-1,accel_bias);
- }
- if (imu_idx == -1) {
-
- AP_AHRS::getCorrectedDeltaVelocityNED(ret, dt);
- return;
- }
- ret.zero();
- const AP_InertialSensor &_ins = AP::ins();
- _ins.get_delta_velocity((uint8_t)imu_idx, ret);
- dt = _ins.get_delta_velocity_dt((uint8_t)imu_idx);
- ret -= accel_bias*dt;
- ret = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * ret;
- ret.z += GRAVITY_MSS*dt;
- } else {
- AP_AHRS::getCorrectedDeltaVelocityNED(ret, dt);
- }
- }
- const char *AP_AHRS_NavEKF::prearm_failure_reason(void) const
- {
- switch (ekf_type()) {
- case 0:
- return nullptr;
- case 2:
- default:
- return EKF2.prearm_failure_reason();
- case 3:
- return EKF3.prearm_failure_reason();
- }
- return nullptr;
- }
- bool AP_AHRS_NavEKF::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const
- {
-
- Quaternion primary_quat;
- get_quat_body_to_ned(primary_quat);
-
- bool check_yaw = _compass && _compass->use_for_yaw();
-
- for (uint8_t i = 0; i < EKF2.activeCores(); i++) {
- Quaternion ekf2_quat;
- Vector3f angle_diff;
- EKF2.getQuaternionBodyToNED(i, ekf2_quat);
- primary_quat.angular_difference(ekf2_quat).to_axis_angle(angle_diff);
- float diff = safe_sqrt(sq(angle_diff.x)+sq(angle_diff.y));
- if (diff > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {
- hal.util->snprintf(failure_msg, failure_msg_len, "EKF2 Roll/Pitch inconsistent by %d deg", (int)degrees(diff));
- return false;
- }
- diff = fabsf(angle_diff.z);
- if (check_yaw && (diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {
- hal.util->snprintf(failure_msg, failure_msg_len, "EKF2 Yaw inconsistent by %d deg", (int)degrees(diff));
- return false;
- }
- }
-
- for (uint8_t i = 0; i < EKF3.activeCores(); i++) {
- Quaternion ekf3_quat;
- Vector3f angle_diff;
- EKF3.getQuaternionBodyToNED(i, ekf3_quat);
- primary_quat.angular_difference(ekf3_quat).to_axis_angle(angle_diff);
- float diff = safe_sqrt(sq(angle_diff.x)+sq(angle_diff.y));
- if (diff > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {
- hal.util->snprintf(failure_msg, failure_msg_len, "EKF3 Roll/Pitch inconsistent by %d deg", (int)degrees(diff));
- return false;
- }
- diff = fabsf(angle_diff.z);
- if (check_yaw && (diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {
- hal.util->snprintf(failure_msg, failure_msg_len, "EKF3 Yaw inconsistent by %d deg", (int)degrees(diff));
- return false;
- }
- }
-
- Quaternion dcm_quat;
- Vector3f angle_diff;
- dcm_quat.from_rotation_matrix(get_DCM_rotation_body_to_ned());
- primary_quat.angular_difference(dcm_quat).to_axis_angle(angle_diff);
- float diff = safe_sqrt(sq(angle_diff.x)+sq(angle_diff.y));
- if (diff > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {
- hal.util->snprintf(failure_msg, failure_msg_len, "DCM Roll/Pitch inconsistent by %d deg", (int)degrees(diff));
- return false;
- }
- diff = fabsf(angle_diff.z);
- if (check_yaw && (diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {
- hal.util->snprintf(failure_msg, failure_msg_len, "DCM Yaw inconsistent by %d deg", (int)degrees(diff));
- return false;
- }
- return true;
- }
- uint32_t AP_AHRS_NavEKF::getLastYawResetAngle(float &yawAng) const
- {
- switch (ekf_type()) {
- case 2:
- default:
- return EKF2.getLastYawResetAngle(yawAng);
- case 3:
- return EKF3.getLastYawResetAngle(yawAng);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return 0;
- #endif
- }
- return 0;
- }
- uint32_t AP_AHRS_NavEKF::getLastPosNorthEastReset(Vector2f &pos) const
- {
- switch (ekf_type()) {
- case 2:
- default:
- return EKF2.getLastPosNorthEastReset(pos);
- case 3:
- return EKF3.getLastPosNorthEastReset(pos);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return 0;
- #endif
- }
- return 0;
- }
- uint32_t AP_AHRS_NavEKF::getLastVelNorthEastReset(Vector2f &vel) const
- {
- switch (ekf_type()) {
- case 2:
- default:
- return EKF2.getLastVelNorthEastReset(vel);
- case 3:
- return EKF3.getLastVelNorthEastReset(vel);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return 0;
- #endif
- }
- return 0;
- }
- uint32_t AP_AHRS_NavEKF::getLastPosDownReset(float &posDelta) const
- {
- switch (ekf_type()) {
- case EKF_TYPE2:
- return EKF2.getLastPosDownReset(posDelta);
- case EKF_TYPE3:
- return EKF3.getLastPosDownReset(posDelta);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return 0;
- #endif
- }
- return 0;
- }
- bool AP_AHRS_NavEKF::resetHeightDatum(void)
- {
-
- WITH_SEMAPHORE(_rsem);
-
- switch (ekf_type()) {
- case 2:
- default: {
- EKF3.resetHeightDatum();
- return EKF2.resetHeightDatum();
- }
- case 3: {
- EKF2.resetHeightDatum();
- return EKF3.resetHeightDatum();
- }
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return false;
- #endif
- }
- return false;
- }
- void AP_AHRS_NavEKF::send_ekf_status_report(mavlink_channel_t chan) const
- {
- switch (ekf_type()) {
- case EKF_TYPE_NONE:
-
- mavlink_msg_ekf_status_report_send(chan, 0, 0, 0, 0, 0, 0, 0);
- break;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- {
-
- const uint16_t flags =
- EKF_ATTITUDE |
- EKF_VELOCITY_HORIZ |
- EKF_VELOCITY_VERT |
- EKF_POS_HORIZ_REL |
- EKF_POS_HORIZ_ABS |
- EKF_POS_VERT_ABS |
- EKF_POS_VERT_AGL |
-
- EKF_PRED_POS_HORIZ_REL |
- EKF_PRED_POS_HORIZ_ABS;
- mavlink_msg_ekf_status_report_send(chan, flags, 0, 0, 0, 0, 0, 0);
- }
- break;
- #endif
-
- case EKF_TYPE2:
- return EKF2.send_status_report(chan);
- case EKF_TYPE3:
- return EKF3.send_status_report(chan);
- }
- }
- bool AP_AHRS_NavEKF::get_origin(Location &ret) const
- {
- switch (ekf_type()) {
- case EKF_TYPE_NONE:
- return false;
- case EKF_TYPE2:
- default:
- if (!EKF2.getOriginLLH(-1,ret)) {
- return false;
- }
- return true;
- case EKF_TYPE3:
- if (!EKF3.getOriginLLH(-1,ret)) {
- return false;
- }
- return true;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- if (!_sitl) {
- return false;
- }
- const struct SITL::sitl_fdm &fdm = _sitl->state;
- ret = fdm.home;
- return true;
- #endif
- }
- }
- bool AP_AHRS_NavEKF::get_hgt_ctrl_limit(float& limit) const
- {
- switch (ekf_type()) {
- case EKF_TYPE_NONE:
-
- return false;
- case EKF_TYPE2:
- default:
- return EKF2.getHeightControlLimit(limit);
- case EKF_TYPE3:
- return EKF3.getHeightControlLimit(limit);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return false;
- #endif
- }
- }
- bool AP_AHRS_NavEKF::get_location(struct Location &loc) const
- {
- switch (ekf_type()) {
- case EKF_TYPE_NONE:
-
- return false;
- case EKF_TYPE2:
- default:
- return EKF2.getLLH(loc);
- case EKF_TYPE3:
- return EKF3.getLLH(loc);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- return get_position(loc);
- #endif
- }
- }
- bool AP_AHRS_NavEKF::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
- {
- switch (ekf_type()) {
- case EKF_TYPE_NONE:
-
- return false;
- case EKF_TYPE2:
- default:
-
- EKF2.getVariances(-1,velVar, posVar, hgtVar, magVar, tasVar, offset);
- return true;
- case EKF_TYPE3:
-
- EKF3.getVariances(-1,velVar, posVar, hgtVar, magVar, tasVar, offset);
- return true;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- velVar = 0;
- posVar = 0;
- hgtVar = 0;
- magVar.zero();
- tasVar = 0;
- offset.zero();
- return true;
- #endif
- }
- }
- void AP_AHRS_NavEKF::setTakeoffExpected(bool val)
- {
- switch (ekf_type()) {
- case EKF_TYPE2:
- default:
- EKF2.setTakeoffExpected(val);
- break;
- case EKF_TYPE3:
- EKF3.setTakeoffExpected(val);
- break;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- break;
- #endif
- }
- }
- void AP_AHRS_NavEKF::setTouchdownExpected(bool val)
- {
- switch (ekf_type()) {
- case EKF_TYPE2:
- default:
- EKF2.setTouchdownExpected(val);
- break;
- case EKF_TYPE3:
- EKF3.setTouchdownExpected(val);
- break;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- break;
- #endif
- }
- }
- bool AP_AHRS_NavEKF::getGpsGlitchStatus() const
- {
- nav_filter_status ekf_status {};
- if (!get_filter_status(ekf_status)) {
- return false;
- }
- return ekf_status.flags.gps_glitching;
- }
- bool AP_AHRS_NavEKF::have_ekf_logging(void) const
- {
- switch (ekf_type()) {
- case 2:
- return EKF2.have_ekf_logging();
- case 3:
- return EKF3.have_ekf_logging();
- default:
- break;
- }
- return false;
- }
- uint8_t AP_AHRS_NavEKF::get_primary_IMU_index() const
- {
- int8_t imu = -1;
- switch (ekf_type()) {
- case 2:
-
- imu = EKF2.getPrimaryCoreIMUIndex();
- break;
- case 3:
-
- imu = EKF3.getPrimaryCoreIMUIndex();
- break;
- default:
- break;
- }
- if (imu == -1) {
- imu = AP::ins().get_primary_accel();
- }
- return imu;
- }
- const Vector3f &AP_AHRS_NavEKF::get_accel_ef() const
- {
- return get_accel_ef(get_primary_accel_index());
- }
- uint8_t AP_AHRS_NavEKF::get_primary_accel_index(void) const
- {
- if (ekf_type() != 0) {
- return get_primary_IMU_index();
- }
- return AP::ins().get_primary_accel();
- }
- uint8_t AP_AHRS_NavEKF::get_primary_gyro_index(void) const
- {
- if (ekf_type() != 0) {
- return get_primary_IMU_index();
- }
- return AP::ins().get_primary_gyro();
- }
- void AP_AHRS_NavEKF::check_lane_switch(void)
- {
- switch (active_EKF_type()) {
- case EKF_TYPE_NONE:
- break;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- case EKF_TYPE_SITL:
- break;
- #endif
- case EKF_TYPE2:
- EKF2.checkLaneSwitch();
- break;
- case EKF_TYPE3:
- EKF3.checkLaneSwitch();
- break;
- }
- }
- void AP_AHRS_NavEKF::Log_Write()
- {
- get_NavEKF2().Log_Write();
- get_NavEKF3().Log_Write();
- }
- AP_AHRS_NavEKF &AP::ahrs_navekf()
- {
- return static_cast<AP_AHRS_NavEKF&>(*AP_AHRS::get_singleton());
- }
- bool AP_AHRS_NavEKF::is_ext_nav_used_for_yaw(void) const
- {
- switch (active_EKF_type()) {
- case EKF_TYPE2:
- return EKF2.isExtNavUsedForYaw();
-
- default:
- return false;
- }
- }
- #endif
|