123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620 |
- #include <AP_HAL/AP_HAL.h>
- #include "AP_NavEKF2_core.h"
- #include <AP_Vehicle/AP_Vehicle.h>
- #include <GCS_MAVLink/GCS.h>
- #include <AP_Logger/AP_Logger.h>
- #include <AP_GPS/AP_GPS.h>
- #include <new>
- #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_Replay)
- #define VELNE_M_NSE_DEFAULT 0.5f
- #define VELD_M_NSE_DEFAULT 0.7f
- #define POSNE_M_NSE_DEFAULT 1.0f
- #define ALT_M_NSE_DEFAULT 3.0f
- #define MAG_M_NSE_DEFAULT 0.05f
- #define GYRO_P_NSE_DEFAULT 3.0E-02f
- #define ACC_P_NSE_DEFAULT 6.0E-01f
- #define GBIAS_P_NSE_DEFAULT 1.0E-04f
- #define GSCALE_P_NSE_DEFAULT 5.0E-04f
- #define ABIAS_P_NSE_DEFAULT 5.0E-03f
- #define MAGB_P_NSE_DEFAULT 1.0E-04f
- #define MAGE_P_NSE_DEFAULT 1.0E-03f
- #define VEL_I_GATE_DEFAULT 500
- #define POS_I_GATE_DEFAULT 500
- #define HGT_I_GATE_DEFAULT 500
- #define MAG_I_GATE_DEFAULT 300
- #define MAG_CAL_DEFAULT 3
- #define GLITCH_RADIUS_DEFAULT 25
- #define FLOW_MEAS_DELAY 10
- #define FLOW_M_NSE_DEFAULT 0.25f
- #define FLOW_I_GATE_DEFAULT 300
- #define CHECK_SCALER_DEFAULT 100
- #define FLOW_USE_DEFAULT 1
- #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
- #define VELNE_M_NSE_DEFAULT 0.5f
- #define VELD_M_NSE_DEFAULT 0.7f
- #define POSNE_M_NSE_DEFAULT 1.0f
- #define ALT_M_NSE_DEFAULT 3.0f
- #define MAG_M_NSE_DEFAULT 0.05f
- #define GYRO_P_NSE_DEFAULT 3.0E-02f
- #define ACC_P_NSE_DEFAULT 6.0E-01f
- #define GBIAS_P_NSE_DEFAULT 1.0E-04f
- #define GSCALE_P_NSE_DEFAULT 5.0E-04f
- #define ABIAS_P_NSE_DEFAULT 5.0E-03f
- #define MAGB_P_NSE_DEFAULT 1.0E-04f
- #define MAGE_P_NSE_DEFAULT 1.0E-03f
- #define VEL_I_GATE_DEFAULT 500
- #define POS_I_GATE_DEFAULT 500
- #define HGT_I_GATE_DEFAULT 500
- #define MAG_I_GATE_DEFAULT 300
- #define MAG_CAL_DEFAULT 2
- #define GLITCH_RADIUS_DEFAULT 25
- #define FLOW_MEAS_DELAY 10
- #define FLOW_M_NSE_DEFAULT 0.25f
- #define FLOW_I_GATE_DEFAULT 300
- #define CHECK_SCALER_DEFAULT 100
- #define FLOW_USE_DEFAULT 1
- #elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
- #define VELNE_M_NSE_DEFAULT 0.5f
- #define VELD_M_NSE_DEFAULT 0.7f
- #define POSNE_M_NSE_DEFAULT 1.0f
- #define ALT_M_NSE_DEFAULT 3.0f
- #define MAG_M_NSE_DEFAULT 0.05f
- #define GYRO_P_NSE_DEFAULT 3.0E-02f
- #define ACC_P_NSE_DEFAULT 6.0E-01f
- #define GBIAS_P_NSE_DEFAULT 1.0E-04f
- #define GSCALE_P_NSE_DEFAULT 5.0E-04f
- #define ABIAS_P_NSE_DEFAULT 5.0E-03f
- #define MAGB_P_NSE_DEFAULT 1.0E-04f
- #define MAGE_P_NSE_DEFAULT 1.0E-03f
- #define VEL_I_GATE_DEFAULT 500
- #define POS_I_GATE_DEFAULT 500
- #define HGT_I_GATE_DEFAULT 500
- #define MAG_I_GATE_DEFAULT 300
- #define MAG_CAL_DEFAULT 0
- #define GLITCH_RADIUS_DEFAULT 25
- #define FLOW_MEAS_DELAY 10
- #define FLOW_M_NSE_DEFAULT 0.15f
- #define FLOW_I_GATE_DEFAULT 500
- #define CHECK_SCALER_DEFAULT 150
- #define FLOW_USE_DEFAULT 2
- #else
- #define VELNE_M_NSE_DEFAULT 0.5f
- #define VELD_M_NSE_DEFAULT 0.7f
- #define POSNE_M_NSE_DEFAULT 1.0f
- #define ALT_M_NSE_DEFAULT 3.0f
- #define MAG_M_NSE_DEFAULT 0.05f
- #define GYRO_P_NSE_DEFAULT 3.0E-02f
- #define ACC_P_NSE_DEFAULT 6.0E-01f
- #define GBIAS_P_NSE_DEFAULT 1.0E-04f
- #define GSCALE_P_NSE_DEFAULT 5.0E-04f
- #define ABIAS_P_NSE_DEFAULT 5.0E-03f
- #define MAGB_P_NSE_DEFAULT 1.0E-04f
- #define MAGE_P_NSE_DEFAULT 1.0E-03f
- #define VEL_I_GATE_DEFAULT 500
- #define POS_I_GATE_DEFAULT 500
- #define HGT_I_GATE_DEFAULT 500
- #define MAG_I_GATE_DEFAULT 300
- #define MAG_CAL_DEFAULT 3
- #define GLITCH_RADIUS_DEFAULT 25
- #define FLOW_MEAS_DELAY 10
- #define FLOW_M_NSE_DEFAULT 0.25f
- #define FLOW_I_GATE_DEFAULT 300
- #define CHECK_SCALER_DEFAULT 100
- #define FLOW_USE_DEFAULT 1
- #endif
- extern const AP_HAL::HAL& hal;
- const AP_Param::GroupInfo NavEKF2::var_info[] = {
-
-
-
-
-
-
- AP_GROUPINFO_FLAGS("ENABLE", 0, NavEKF2, _enable, 1, AP_PARAM_FLAG_ENABLE),
-
-
-
-
-
-
- AP_GROUPINFO("GPS_TYPE", 1, NavEKF2, _fusionModeGPS, 0),
-
-
-
-
-
-
-
- AP_GROUPINFO("VELNE_M_NSE", 2, NavEKF2, _gpsHorizVelNoise, VELNE_M_NSE_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("VELD_M_NSE", 3, NavEKF2, _gpsVertVelNoise, VELD_M_NSE_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("VEL_I_GATE", 4, NavEKF2, _gpsVelInnovGate, VEL_I_GATE_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("POSNE_M_NSE", 5, NavEKF2, _gpsHorizPosNoise, POSNE_M_NSE_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("POS_I_GATE", 6, NavEKF2, _gpsPosInnovGate, POS_I_GATE_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("GLITCH_RAD", 7, NavEKF2, _gpsGlitchRadiusMax, GLITCH_RADIUS_DEFAULT),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("ALT_SOURCE", 9, NavEKF2, _altSource, 0),
-
-
-
-
-
-
-
- AP_GROUPINFO("ALT_M_NSE", 10, NavEKF2, _baroAltNoise, ALT_M_NSE_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("HGT_I_GATE", 11, NavEKF2, _hgtInnovGate, HGT_I_GATE_DEFAULT),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("HGT_DELAY", 12, NavEKF2, _hgtDelay_ms, 60),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("MAG_M_NSE", 13, NavEKF2, _magNoise, MAG_M_NSE_DEFAULT),
-
-
-
-
-
- AP_GROUPINFO("MAG_CAL", 14, NavEKF2, _magCal, MAG_CAL_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("MAG_I_GATE", 15, NavEKF2, _magInnovGate, MAG_I_GATE_DEFAULT),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("EAS_M_NSE", 16, NavEKF2, _easNoise, 1.4f),
-
-
-
-
-
-
- AP_GROUPINFO("EAS_I_GATE", 17, NavEKF2, _tasInnovGate, 400),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("RNG_M_NSE", 18, NavEKF2, _rngNoise, 0.5f),
-
-
-
-
-
-
- AP_GROUPINFO("RNG_I_GATE", 19, NavEKF2, _rngInnovGate, 500),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("MAX_FLOW", 20, NavEKF2, _maxFlowRate, 2.5f),
-
-
-
-
-
-
-
- AP_GROUPINFO("FLOW_M_NSE", 21, NavEKF2, _flowNoise, FLOW_M_NSE_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("FLOW_I_GATE", 22, NavEKF2, _flowInnovGate, FLOW_I_GATE_DEFAULT),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("FLOW_DELAY", 23, NavEKF2, _flowDelay_ms, FLOW_MEAS_DELAY),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("GYRO_P_NSE", 24, NavEKF2, _gyrNoise, GYRO_P_NSE_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("ACC_P_NSE", 25, NavEKF2, _accNoise, ACC_P_NSE_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("GBIAS_P_NSE", 26, NavEKF2, _gyroBiasProcessNoise, GBIAS_P_NSE_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("GSCL_P_NSE", 27, NavEKF2, _gyroScaleProcessNoise, GSCALE_P_NSE_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("ABIAS_P_NSE", 28, NavEKF2, _accelBiasProcessNoise, ABIAS_P_NSE_DEFAULT),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("WIND_P_NSE", 30, NavEKF2, _windVelProcessNoise, 0.1f),
-
-
-
-
-
-
- AP_GROUPINFO("WIND_PSCALE", 31, NavEKF2, _wndVarHgtRateScale, 0.5f),
-
-
-
-
-
- AP_GROUPINFO("GPS_CHECK", 32, NavEKF2, _gpsCheck, 31),
-
-
-
-
-
-
- AP_GROUPINFO("IMU_MASK", 33, NavEKF2, _imuMask, 3),
-
-
-
-
-
-
-
- AP_GROUPINFO("CHECK_SCALE", 34, NavEKF2, _gpsCheckScaler, CHECK_SCALER_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("NOAID_M_NSE", 35, NavEKF2, _noaidHorizNoise, 10.0f),
-
-
-
-
-
-
- AP_GROUPINFO("LOG_MASK", 36, NavEKF2, _logging_mask, 1),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("YAW_M_NSE", 37, NavEKF2, _yawNoise, 0.5f),
-
-
-
-
-
-
- AP_GROUPINFO("YAW_I_GATE", 38, NavEKF2, _yawInnovGate, 300),
-
-
-
-
-
-
-
- AP_GROUPINFO("TAU_OUTPUT", 39, NavEKF2, _tauVelPosOutput, 25),
-
-
-
-
-
-
- AP_GROUPINFO("MAGE_P_NSE", 40, NavEKF2, _magEarthProcessNoise, MAGE_P_NSE_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("MAGB_P_NSE", 41, NavEKF2, _magBodyProcessNoise, MAGB_P_NSE_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("RNG_USE_HGT", 42, NavEKF2, _useRngSwHgt, -1),
-
-
-
-
-
-
- AP_GROUPINFO("TERR_GRAD", 43, NavEKF2, _terrGradMax, 0.1f),
-
-
-
-
-
-
-
- AP_GROUPINFO("BCN_M_NSE", 44, NavEKF2, _rngBcnNoise, 1.0f),
-
-
-
-
-
-
- AP_GROUPINFO("BCN_I_GTE", 45, NavEKF2, _rngBcnInnovGate, 500),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("BCN_DELAY", 46, NavEKF2, _rngBcnDelay_ms, 50),
-
-
-
-
-
-
-
- AP_GROUPINFO("RNG_USE_SPD", 47, NavEKF2, _useRngSwSpd, 2.0f),
-
-
-
-
-
-
- AP_GROUPINFO("MAG_MASK", 48, NavEKF2, _magMask, 0),
-
-
-
-
-
-
- AP_GROUPINFO("OGN_HGT_MASK", 49, NavEKF2, _originHgtMode, 0),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("EXTNAV_DELAY", 50, NavEKF2, _extnavDelay_ms, 10),
-
-
-
-
-
-
- AP_GROUPINFO("FLOW_USE", 51, NavEKF2, _flowUse, FLOW_USE_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("MAG_EF_LIM", 52, NavEKF2, _mag_ef_limit, 50),
-
- AP_GROUPEND
- };
- NavEKF2::NavEKF2(const AP_AHRS *ahrs, const RangeFinder &rng) :
- _ahrs(ahrs),
- _rng(rng)
- {
- AP_Param::setup_object_defaults(this, var_info);
- }
- void NavEKF2::check_log_write(void)
- {
- if (!have_ekf_logging()) {
- return;
- }
- if (logging.log_compass) {
- AP::logger().Write_Compass(imuSampleTime_us);
- logging.log_compass = false;
- }
- if (logging.log_baro) {
- AP::logger().Write_Baro(imuSampleTime_us);
- logging.log_baro = false;
- }
- if (logging.log_imu) {
- AP::logger().Write_IMUDT(imuSampleTime_us, _logging_mask.get());
- logging.log_imu = false;
- }
-
-
- }
- bool NavEKF2::InitialiseFilter(void)
- {
- if (_enable == 0) {
- return false;
- }
- const AP_InertialSensor &ins = AP::ins();
- imuSampleTime_us = AP_HAL::micros64();
-
- _frameTimeUsec = 1e6 / ins.get_sample_rate();
-
- _framesPerPrediction = uint8_t((EKF_TARGET_DT / (_frameTimeUsec * 1.0e-6) + 0.5));
-
- AP_Logger *logger = AP_Logger::get_singleton();
- if (logger != nullptr) {
- logging.enabled = logger->log_replay();
- }
-
- if (core == nullptr) {
-
- uint8_t mask = (1U<<ins.get_accel_count())-1;
- _imuMask.set(_imuMask.get() & mask);
-
-
- num_cores = 0;
- for (uint8_t i=0; i<7; i++) {
- if (_imuMask & (1U<<i)) {
- num_cores++;
- }
- }
-
- if (hal.util->available_memory() < sizeof(NavEKF2_core)*num_cores + 4096) {
- gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF2: not enough memory");
- _enable.set(0);
- return false;
- }
-
- core = (NavEKF2_core*)hal.util->malloc_type(sizeof(NavEKF2_core)*num_cores, AP_HAL::Util::MEM_FAST);
- if (core == nullptr) {
- _enable.set(0);
- gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF2: allocation failed");
- return false;
- }
-
- for (uint8_t i = 0; i < num_cores; i++) {
- new (&core[i]) NavEKF2_core(this);
- }
-
- num_cores = 0;
- for (uint8_t i=0; i<7; i++) {
- if (_imuMask & (1U<<i)) {
- if(!core[num_cores].setup_core(i, num_cores)) {
- return false;
- }
- num_cores++;
- }
- }
-
- primary = 0;
- }
-
- common_origin_valid = false;
-
-
-
- bool ret = true;
- for (uint8_t i=0; i<num_cores; i++) {
- ret &= core[i].InitialiseFilterBootstrap();
- }
-
- memset(&yaw_reset_data, 0, sizeof(yaw_reset_data));
- memset((void *)&pos_reset_data, 0, sizeof(pos_reset_data));
- memset(&pos_down_reset_data, 0, sizeof(pos_down_reset_data));
- check_log_write();
- return ret;
- }
- void NavEKF2::UpdateFilter(void)
- {
- if (!core) {
- return;
- }
- imuSampleTime_us = AP_HAL::micros64();
-
- const AP_InertialSensor &ins = AP::ins();
- bool statePredictEnabled[num_cores];
- for (uint8_t i=0; i<num_cores; i++) {
-
-
-
-
- if (core[i].getFramesSincePredict() < (_framesPerPrediction+3) &&
- (AP_HAL::micros() - ins.get_last_update_usec()) > _frameTimeUsec/3) {
- statePredictEnabled[i] = false;
- } else {
- statePredictEnabled[i] = true;
- }
- core[i].UpdateFilter(statePredictEnabled[i]);
- }
-
-
-
- if (!runCoreSelection) {
- static uint64_t lastUnhealthyTime_us = 0;
- if (!core[primary].healthy() || lastUnhealthyTime_us == 0) {
- lastUnhealthyTime_us = imuSampleTime_us;
- }
- runCoreSelection = (imuSampleTime_us - lastUnhealthyTime_us) > 1E7;
- }
- float primaryErrorScore = core[primary].errorScore();
- if ((primaryErrorScore > 1.0f || !core[primary].healthy()) && runCoreSelection) {
- float lowestErrorScore = 0.67f * primaryErrorScore;
- uint8_t newPrimaryIndex = primary;
- for (uint8_t coreIndex=0; coreIndex<num_cores; coreIndex++) {
- if (coreIndex != primary) {
-
- bool altCoreAvailable = core[coreIndex].healthy() && statePredictEnabled[coreIndex];
-
-
-
- float altErrorScore = core[coreIndex].errorScore();
- if (altCoreAvailable && (!core[newPrimaryIndex].healthy() || altErrorScore < lowestErrorScore)) {
- newPrimaryIndex = coreIndex;
- lowestErrorScore = altErrorScore;
- }
- }
- }
-
- if (newPrimaryIndex != primary) {
- updateLaneSwitchYawResetData(newPrimaryIndex, primary);
- updateLaneSwitchPosResetData(newPrimaryIndex, primary);
- updateLaneSwitchPosDownResetData(newPrimaryIndex, primary);
- primary = newPrimaryIndex;
- lastLaneSwitch_ms = AP_HAL::millis();
- }
- }
- if (primary != 0 && core[0].healthy() && !hal.util->get_soft_armed()) {
-
-
-
-
-
-
-
-
- primary = 0;
- }
- check_log_write();
- }
- void NavEKF2::checkLaneSwitch(void)
- {
- uint32_t now = AP_HAL::millis();
- if (lastLaneSwitch_ms != 0 && now - lastLaneSwitch_ms < 5000) {
-
- return;
- }
- float primaryErrorScore = core[primary].errorScore();
- float lowestErrorScore = primaryErrorScore;
- uint8_t newPrimaryIndex = primary;
- for (uint8_t coreIndex=0; coreIndex<num_cores; coreIndex++) {
- if (coreIndex != primary) {
-
- bool altCoreAvailable = core[coreIndex].healthy();
- float altErrorScore = core[coreIndex].errorScore();
- if (altCoreAvailable &&
- altErrorScore < lowestErrorScore &&
- altErrorScore < 0.9) {
- newPrimaryIndex = coreIndex;
- lowestErrorScore = altErrorScore;
- }
- }
- }
-
- if (newPrimaryIndex != primary) {
- updateLaneSwitchYawResetData(newPrimaryIndex, primary);
- updateLaneSwitchPosResetData(newPrimaryIndex, primary);
- updateLaneSwitchPosDownResetData(newPrimaryIndex, primary);
- primary = newPrimaryIndex;
- lastLaneSwitch_ms = now;
- gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF2: lane switch %u", primary);
- }
- }
- bool NavEKF2::healthy(void) const
- {
- if (!core) {
- return false;
- }
- return core[primary].healthy();
- }
- bool NavEKF2::all_cores_healthy(void) const
- {
- if (!core) {
- return false;
- }
- for (uint8_t i = 0; i < num_cores; i++) {
- if (!core[i].healthy()) {
- return false;
- }
- }
- return true;
- }
- int8_t NavEKF2::getPrimaryCoreIndex(void) const
- {
- if (!core) {
- return -1;
- }
- return primary;
- }
- int8_t NavEKF2::getPrimaryCoreIMUIndex(void) const
- {
- if (!core) {
- return -1;
- }
- return core[primary].getIMUIndex();
- }
- bool NavEKF2::getPosNE(int8_t instance, Vector2f &posNE) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (!core) {
- return false;
- }
- return core[instance].getPosNE(posNE);
- }
- bool NavEKF2::getPosD(int8_t instance, float &posD) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (!core) {
- return false;
- }
- return core[instance].getPosD(posD);
- }
- void NavEKF2::getVelNED(int8_t instance, Vector3f &vel) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getVelNED(vel);
- }
- }
- float NavEKF2::getPosDownDerivative(int8_t instance) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
-
- if (core) {
- return core[instance].getPosDownDerivative();
- }
- return 0.0f;
- }
- void NavEKF2::getAccelNED(Vector3f &accelNED) const
- {
- if (core) {
- core[primary].getAccelNED(accelNED);
- }
- }
- void NavEKF2::getGyroBias(int8_t instance, Vector3f &gyroBias) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getGyroBias(gyroBias);
- }
- }
- void NavEKF2::getGyroScaleErrorPercentage(int8_t instance, Vector3f &gyroScale) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getGyroScaleErrorPercentage(gyroScale);
- }
- }
- void NavEKF2::getTiltError(int8_t instance, float &ang) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getTiltError(ang);
- }
- }
- void NavEKF2::resetGyroBias(void)
- {
- if (core) {
- for (uint8_t i=0; i<num_cores; i++) {
- core[i].resetGyroBias();
- }
- }
- }
- bool NavEKF2::resetHeightDatum(void)
- {
- bool status = true;
- if (core) {
- for (uint8_t i=0; i<num_cores; i++) {
- if (!core[i].resetHeightDatum()) {
- status = false;
- }
- }
- } else {
- status = false;
- }
- return status;
- }
- uint8_t NavEKF2::setInhibitGPS(void)
- {
- if (!core) {
- return 0;
- }
- return core[primary].setInhibitGPS();
- }
- void NavEKF2::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
- {
- if (core) {
- core[primary].getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
- } else {
- ekfGndSpdLimit = 400.0f;
- ekfNavVelGainScaler = 1.0f;
- }
- }
- void NavEKF2::getAccelZBias(int8_t instance, float &zbias) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getAccelZBias(zbias);
- }
- }
- void NavEKF2::getWind(int8_t instance, Vector3f &wind) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getWind(wind);
- }
- }
- void NavEKF2::getMagNED(int8_t instance, Vector3f &magNED) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getMagNED(magNED);
- }
- }
- void NavEKF2::getMagXYZ(int8_t instance, Vector3f &magXYZ) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getMagXYZ(magXYZ);
- }
- }
- uint8_t NavEKF2::getActiveMag(int8_t instance) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- return core[instance].getActiveMag();
- } else {
- return 255;
- }
- }
- bool NavEKF2::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
- {
- if (!core) {
- return false;
- }
-
- if (core[primary].getMagOffsets(mag_idx, magOffsets)) {
- return true;
- }
- for (uint8_t i=0; i<num_cores; i++) {
- if(core[i].getMagOffsets(mag_idx, magOffsets)) {
- return true;
- }
- }
- return false;
- }
- bool NavEKF2::getLLH(struct Location &loc) const
- {
- if (!core) {
- return false;
- }
- return core[primary].getLLH(loc);
- }
- bool NavEKF2::getOriginLLH(int8_t instance, struct Location &loc) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (!core) {
- return false;
- }
- return core[instance].getOriginLLH(loc);
- }
- bool NavEKF2::setOriginLLH(const Location &loc)
- {
- if (_fusionModeGPS != 3) {
-
-
-
- gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 refusing set origin");
- return false;
- }
- if (!core) {
- return false;
- }
- bool ret = false;
- for (uint8_t i=0; i<num_cores; i++) {
- ret |= core[i].setOriginLLH(loc);
- }
-
- return ret;
- }
- bool NavEKF2::getHAGL(float &HAGL) const
- {
- if (!core) {
- return false;
- }
- return core[primary].getHAGL(HAGL);
- }
- void NavEKF2::getEulerAngles(int8_t instance, Vector3f &eulers) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getEulerAngles(eulers);
- }
- }
- void NavEKF2::getRotationBodyToNED(Matrix3f &mat) const
- {
- if (core) {
- core[primary].getRotationBodyToNED(mat);
- }
- }
- void NavEKF2::getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- Matrix3f mat;
- core[instance].getRotationBodyToNED(mat);
- quat.from_rotation_matrix(mat);
- }
- }
- void NavEKF2::getQuaternion(int8_t instance, Quaternion &quat) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getQuaternion(quat);
- }
- }
- void NavEKF2::getInnovations(int8_t instance, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov);
- }
- }
- void NavEKF2::getOutputTrackingError(int8_t instance, Vector3f &error) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getOutputTrackingError(error);
- }
- }
- void NavEKF2::getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
- }
- }
- bool NavEKF2::use_compass(void) const
- {
- if (!core) {
- return false;
- }
- return core[primary].use_compass();
- }
- void NavEKF2::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
- {
- if (core) {
- for (uint8_t i=0; i<num_cores; i++) {
- core[i].writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
- }
- }
- }
- void NavEKF2::getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov,
- float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getFlowDebug(varFlow, gndOffset, flowInnovX, flowInnovY, auxInnov, HAGL, rngInnov, range, gndOffsetErr);
- }
- }
- bool NavEKF2::getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- return core[instance].getRangeBeaconDebug(ID, rng, innov, innovVar, testRatio, beaconPosNED, offsetHigh, offsetLow);
- } else {
- return false;
- }
- }
- void NavEKF2::setTakeoffExpected(bool val)
- {
- if (core) {
- for (uint8_t i=0; i<num_cores; i++) {
- core[i].setTakeoffExpected(val);
- }
- }
- }
- void NavEKF2::setTouchdownExpected(bool val)
- {
- if (core) {
- for (uint8_t i=0; i<num_cores; i++) {
- core[i].setTouchdownExpected(val);
- }
- }
- }
- void NavEKF2::setTerrainHgtStable(bool val)
- {
- if (core) {
- for (uint8_t i=0; i<num_cores; i++) {
- core[i].setTerrainHgtStable(val);
- }
- }
- }
- void NavEKF2::getFilterFaults(int8_t instance, uint16_t &faults) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getFilterFaults(faults);
- } else {
- faults = 0;
- }
- }
- void NavEKF2::getFilterTimeouts(int8_t instance, uint8_t &timeouts) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getFilterTimeouts(timeouts);
- } else {
- timeouts = 0;
- }
- }
- void NavEKF2::getFilterStatus(int8_t instance, nav_filter_status &status) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getFilterStatus(status);
- } else {
- memset(&status, 0, sizeof(status));
- }
- }
- void NavEKF2::getFilterGpsStatus(int8_t instance, nav_gps_status &status) const
- {
- if (instance < 0 || instance >= num_cores) instance = primary;
- if (core) {
- core[instance].getFilterGpsStatus(status);
- } else {
- memset(&status, 0, sizeof(status));
- }
- }
- void NavEKF2::send_status_report(mavlink_channel_t chan)
- {
- if (core) {
- core[primary].send_status_report(chan);
- }
- }
- bool NavEKF2::getHeightControlLimit(float &height) const
- {
- if (!core) {
- return false;
- }
- return core[primary].getHeightControlLimit(height);
- }
- uint32_t NavEKF2::getLastYawResetAngle(float &yawAngDelta)
- {
- if (!core) {
- return 0;
- }
- yawAngDelta = 0.0f;
-
- uint32_t now_time_ms = imuSampleTime_us / 1000;
-
- uint32_t lastYawReset_ms = yaw_reset_data.last_primary_change;
-
-
- if (yaw_reset_data.core_changed || yaw_reset_data.last_function_call == now_time_ms) {
- yawAngDelta = yaw_reset_data.core_delta;
- yaw_reset_data.core_changed = false;
- }
-
- yaw_reset_data.last_function_call = now_time_ms;
-
- float temp_yawAng;
- uint32_t lastCoreYawReset_ms = core[primary].getLastYawResetAngle(temp_yawAng);
- if (lastCoreYawReset_ms > lastYawReset_ms) {
- yawAngDelta = wrap_PI(yawAngDelta + temp_yawAng);
- lastYawReset_ms = lastCoreYawReset_ms;
- }
- return lastYawReset_ms;
- }
- uint32_t NavEKF2::getLastPosNorthEastReset(Vector2f &posDelta)
- {
- if (!core) {
- return 0;
- }
- posDelta.zero();
-
- uint32_t now_time_ms = imuSampleTime_us / 1000;
-
- uint32_t lastPosReset_ms = pos_reset_data.last_primary_change;
-
-
- if (pos_reset_data.core_changed || pos_reset_data.last_function_call == now_time_ms) {
- posDelta = pos_reset_data.core_delta;
- pos_reset_data.core_changed = false;
- }
-
- pos_reset_data.last_function_call = now_time_ms;
-
- Vector2f tempPosDelta;
- uint32_t lastCorePosReset_ms = core[primary].getLastPosNorthEastReset(tempPosDelta);
- if (lastCorePosReset_ms > lastPosReset_ms) {
- posDelta = posDelta + tempPosDelta;
- lastPosReset_ms = lastCorePosReset_ms;
- }
- return lastPosReset_ms;
- }
- uint32_t NavEKF2::getLastVelNorthEastReset(Vector2f &vel) const
- {
- if (!core) {
- return 0;
- }
- return core[primary].getLastVelNorthEastReset(vel);
- }
- const char *NavEKF2::prearm_failure_reason(void) const
- {
- if (!core) {
- return nullptr;
- }
- for (uint8_t i = 0; i < num_cores; i++) {
- const char * failure = core[i].prearm_failure_reason();
- if (failure != nullptr) {
- return failure;
- }
- }
- return nullptr;
- }
- uint32_t NavEKF2::getLastPosDownReset(float &posDelta)
- {
- if (!core) {
- return 0;
- }
- posDelta = 0.0f;
-
- uint32_t now_time_ms = imuSampleTime_us / 1000;
-
- uint32_t lastPosReset_ms = pos_down_reset_data.last_primary_change;
-
-
- if (pos_down_reset_data.core_changed || pos_down_reset_data.last_function_call == now_time_ms) {
- posDelta = pos_down_reset_data.core_delta;
- pos_down_reset_data.core_changed = false;
- }
-
- pos_down_reset_data.last_function_call = now_time_ms;
-
- float tempPosDelta;
- uint32_t lastCorePosReset_ms = core[primary].getLastPosDownReset(tempPosDelta);
- if (lastCorePosReset_ms > lastPosReset_ms) {
- posDelta += tempPosDelta;
- lastPosReset_ms = lastCorePosReset_ms;
- }
- return lastPosReset_ms;
- }
- void NavEKF2::updateLaneSwitchYawResetData(uint8_t new_primary, uint8_t old_primary)
- {
- Vector3f eulers_old_primary, eulers_new_primary;
- float old_yaw_delta;
-
- if (!yaw_reset_data.core_changed) {
- yaw_reset_data.core_delta = 0;
- }
-
- if (core[old_primary].getLastYawResetAngle(old_yaw_delta) > yaw_reset_data.last_function_call) {
- yaw_reset_data.core_delta += old_yaw_delta;
- }
-
-
- core[old_primary].getEulerAngles(eulers_old_primary);
- core[new_primary].getEulerAngles(eulers_new_primary);
- yaw_reset_data.core_delta = wrap_PI(eulers_new_primary.z - eulers_old_primary.z + yaw_reset_data.core_delta);
- yaw_reset_data.last_primary_change = imuSampleTime_us / 1000;
- yaw_reset_data.core_changed = true;
- }
- void NavEKF2::updateLaneSwitchPosResetData(uint8_t new_primary, uint8_t old_primary)
- {
- Vector2f pos_old_primary, pos_new_primary, old_pos_delta;
-
- if (!pos_reset_data.core_changed) {
- pos_reset_data.core_delta.zero();
- }
-
- if (core[old_primary].getLastPosNorthEastReset(old_pos_delta) > pos_reset_data.last_function_call) {
- pos_reset_data.core_delta += old_pos_delta;
- }
-
-
- core[old_primary].getPosNE(pos_old_primary);
- core[new_primary].getPosNE(pos_new_primary);
- pos_reset_data.core_delta = pos_new_primary - pos_old_primary + pos_reset_data.core_delta;
- pos_reset_data.last_primary_change = imuSampleTime_us / 1000;
- pos_reset_data.core_changed = true;
- }
- void NavEKF2::updateLaneSwitchPosDownResetData(uint8_t new_primary, uint8_t old_primary)
- {
- float posDownOldPrimary, posDownNewPrimary, oldPosDownDelta;
-
- if (!pos_down_reset_data.core_changed) {
- pos_down_reset_data.core_delta = 0.0f;
- }
-
- if (core[old_primary].getLastPosDownReset(oldPosDownDelta) > pos_down_reset_data.last_function_call) {
- pos_down_reset_data.core_delta += oldPosDownDelta;
- }
-
-
- core[old_primary].getPosD(posDownOldPrimary);
- core[new_primary].getPosD(posDownNewPrimary);
- pos_down_reset_data.core_delta = posDownNewPrimary - posDownOldPrimary + pos_down_reset_data.core_delta;
- pos_down_reset_data.last_primary_change = imuSampleTime_us / 1000;
- pos_down_reset_data.core_changed = true;
- }
- void NavEKF2::getTimingStatistics(int8_t instance, struct ekf_timing &timing) const
- {
- if (instance < 0 || instance >= num_cores) {
- instance = primary;
- }
- if (core) {
- core[instance].getTimingStatistics(timing);
- } else {
- memset(&timing, 0, sizeof(timing));
- }
- }
- void NavEKF2::writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
- {
- if (core) {
- for (uint8_t i=0; i<num_cores; i++) {
- core[i].writeExtNavData(sensOffset, pos, quat, posErr, angErr, timeStamp_ms, resetTime_ms);
- }
- }
- }
- bool NavEKF2::isExtNavUsedForYaw() const
- {
- if (core) {
- return core[primary].isExtNavUsedForYaw();
- }
- return false;
- }
|