2 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 15 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_Replay) 17 #define VELNE_M_NSE_DEFAULT 0.5f 18 #define VELD_M_NSE_DEFAULT 0.7f 19 #define POSNE_M_NSE_DEFAULT 1.0f 20 #define ALT_M_NSE_DEFAULT 3.0f 21 #define MAG_M_NSE_DEFAULT 0.05f 22 #define GYRO_P_NSE_DEFAULT 3.0E-02f 23 #define ACC_P_NSE_DEFAULT 6.0E-01f 24 #define GBIAS_P_NSE_DEFAULT 1.0E-04f 25 #define GSCALE_P_NSE_DEFAULT 5.0E-04f 26 #define ABIAS_P_NSE_DEFAULT 5.0E-03f 27 #define MAGB_P_NSE_DEFAULT 1.0E-04f 28 #define MAGE_P_NSE_DEFAULT 1.0E-03f 29 #define VEL_I_GATE_DEFAULT 500 30 #define POS_I_GATE_DEFAULT 500 31 #define HGT_I_GATE_DEFAULT 500 32 #define MAG_I_GATE_DEFAULT 300 33 #define MAG_CAL_DEFAULT 3 34 #define GLITCH_RADIUS_DEFAULT 25 35 #define FLOW_MEAS_DELAY 10 36 #define FLOW_M_NSE_DEFAULT 0.25f 37 #define FLOW_I_GATE_DEFAULT 300 38 #define CHECK_SCALER_DEFAULT 100 40 #elif APM_BUILD_TYPE(APM_BUILD_APMrover2) 42 #define VELNE_M_NSE_DEFAULT 0.5f 43 #define VELD_M_NSE_DEFAULT 0.7f 44 #define POSNE_M_NSE_DEFAULT 1.0f 45 #define ALT_M_NSE_DEFAULT 3.0f 46 #define MAG_M_NSE_DEFAULT 0.05f 47 #define GYRO_P_NSE_DEFAULT 3.0E-02f 48 #define ACC_P_NSE_DEFAULT 6.0E-01f 49 #define GBIAS_P_NSE_DEFAULT 1.0E-04f 50 #define GSCALE_P_NSE_DEFAULT 5.0E-04f 51 #define ABIAS_P_NSE_DEFAULT 5.0E-03f 52 #define MAGB_P_NSE_DEFAULT 1.0E-04f 53 #define MAGE_P_NSE_DEFAULT 1.0E-03f 54 #define VEL_I_GATE_DEFAULT 500 55 #define POS_I_GATE_DEFAULT 500 56 #define HGT_I_GATE_DEFAULT 500 57 #define MAG_I_GATE_DEFAULT 300 58 #define MAG_CAL_DEFAULT 2 59 #define GLITCH_RADIUS_DEFAULT 25 60 #define FLOW_MEAS_DELAY 10 61 #define FLOW_M_NSE_DEFAULT 0.25f 62 #define FLOW_I_GATE_DEFAULT 300 63 #define CHECK_SCALER_DEFAULT 100 65 #elif APM_BUILD_TYPE(APM_BUILD_ArduPlane) 67 #define VELNE_M_NSE_DEFAULT 0.5f 68 #define VELD_M_NSE_DEFAULT 0.7f 69 #define POSNE_M_NSE_DEFAULT 1.0f 70 #define ALT_M_NSE_DEFAULT 3.0f 71 #define MAG_M_NSE_DEFAULT 0.05f 72 #define GYRO_P_NSE_DEFAULT 3.0E-02f 73 #define ACC_P_NSE_DEFAULT 6.0E-01f 74 #define GBIAS_P_NSE_DEFAULT 1.0E-04f 75 #define GSCALE_P_NSE_DEFAULT 5.0E-04f 76 #define ABIAS_P_NSE_DEFAULT 5.0E-03f 77 #define MAGB_P_NSE_DEFAULT 1.0E-04f 78 #define MAGE_P_NSE_DEFAULT 1.0E-03f 79 #define VEL_I_GATE_DEFAULT 500 80 #define POS_I_GATE_DEFAULT 500 81 #define HGT_I_GATE_DEFAULT 500 82 #define MAG_I_GATE_DEFAULT 300 83 #define MAG_CAL_DEFAULT 0 84 #define GLITCH_RADIUS_DEFAULT 25 85 #define FLOW_MEAS_DELAY 10 86 #define FLOW_M_NSE_DEFAULT 0.25f 87 #define FLOW_I_GATE_DEFAULT 300 88 #define CHECK_SCALER_DEFAULT 150 92 #define VELNE_M_NSE_DEFAULT 0.5f 93 #define VELD_M_NSE_DEFAULT 0.7f 94 #define POSNE_M_NSE_DEFAULT 1.0f 95 #define ALT_M_NSE_DEFAULT 3.0f 96 #define MAG_M_NSE_DEFAULT 0.05f 97 #define GYRO_P_NSE_DEFAULT 3.0E-02f 98 #define ACC_P_NSE_DEFAULT 6.0E-01f 99 #define GBIAS_P_NSE_DEFAULT 1.0E-04f 100 #define GSCALE_P_NSE_DEFAULT 5.0E-04f 101 #define ABIAS_P_NSE_DEFAULT 5.0E-03f 102 #define MAGB_P_NSE_DEFAULT 1.0E-04f 103 #define MAGE_P_NSE_DEFAULT 1.0E-03f 104 #define VEL_I_GATE_DEFAULT 500 105 #define POS_I_GATE_DEFAULT 500 106 #define HGT_I_GATE_DEFAULT 500 107 #define MAG_I_GATE_DEFAULT 300 108 #define MAG_CAL_DEFAULT 3 109 #define GLITCH_RADIUS_DEFAULT 25 110 #define FLOW_MEAS_DELAY 10 111 #define FLOW_M_NSE_DEFAULT 0.25f 112 #define FLOW_I_GATE_DEFAULT 300 113 #define CHECK_SCALER_DEFAULT 100 115 #endif // APM_BUILD_DIRECTORY 613 if (dataflash !=
nullptr) {
617 if (
core ==
nullptr) {
625 for (uint8_t i=0; i<7; i++) {
633 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"NavEKF2: not enough memory");
640 if (
core ==
nullptr) {
642 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"NavEKF2: allocation failed");
645 for (uint8_t i = 0; i <
num_cores; i++) {
652 for (uint8_t i=0; i<7; i++) {
654 if(!
core[num_cores].setup_core(
this, i, num_cores)) {
700 statePredictEnabled[i] =
false;
702 statePredictEnabled[i] =
true;
711 static uint64_t lastUnhealthyTime_us = 0;
719 float lowestErrorScore = 0.67f * primaryErrorScore;
720 uint8_t newPrimaryIndex =
primary;
721 for (uint8_t coreIndex=0; coreIndex<
num_cores; coreIndex++) {
725 bool altCoreAvailable =
core[coreIndex].
healthy() && statePredictEnabled[coreIndex];
731 if (altCoreAvailable && (!
core[
primary].
healthy() || altErrorScore < lowestErrorScore)) {
732 newPrimaryIndex = coreIndex;
733 lowestErrorScore = altErrorScore;
738 if (newPrimaryIndex !=
primary) {
1072 core[instance].
getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
1103 void NavEKF2::getFlowDebug(int8_t instance,
float &varFlow,
float &gndOffset,
float &flowInnovX,
float &flowInnovY,
float &auxInnov,
1104 float &HAGL,
float &rngInnov,
float &
range,
float &gndOffsetErr)
const 1108 core[instance].
getFlowDebug(varFlow, gndOffset, flowInnovX, flowInnovY, auxInnov, HAGL, rngInnov, range, gndOffsetErr);
1117 return core[instance].
getRangeBeaconDebug(ID, rng, innov, innovVar, testRatio, beaconPosNED, offsetHigh, offsetLow);
1209 memset(&status, 0,
sizeof(status));
1222 memset(&status, 0,
sizeof(status));
1275 if (lastCoreYawReset_ms > lastYawReset_ms) {
1276 yawAngDelta =
wrap_PI(yawAngDelta + temp_yawAng);
1277 lastYawReset_ms = lastCoreYawReset_ms;
1280 return lastYawReset_ms;
1313 if (lastCorePosReset_ms > lastPosReset_ms) {
1314 posDelta = posDelta + tempPosDelta;
1315 lastPosReset_ms = lastCorePosReset_ms;
1318 return lastPosReset_ms;
1370 if (lastCorePosReset_ms > lastPosReset_ms) {
1371 posDelta += tempPosDelta;
1372 lastPosReset_ms = lastCorePosReset_ms;
1375 return lastPosReset_ms;
1381 Vector3f eulers_old_primary, eulers_new_primary;
1382 float old_yaw_delta;
1407 Vector2f pos_old_primary, pos_new_primary, old_pos_delta;
1434 float posDownOldPrimary, posDownNewPrimary, oldPosDownDelta;
1461 if (instance < 0 || instance >=
num_cores) {
1467 memset(&timing, 0,
sizeof(timing));
1486 core[i].
writeExtNavData(sensOffset, pos, quat, posErr, angErr, timeStamp_ms, resetTime_ms);
1491 #endif //HAL_CPU_CLASS
virtual uint32_t available_memory(void)
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
uint32_t get_last_update_usec(void) const
uint32_t getLastPosDownReset(float &posD) const
void getInnovations(int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
#define AP_PARAM_FLAG_ENABLE
void getAccelZBias(float &zbias) const
bool getHAGL(float &HAGL) const
uint8_t getActiveMag(int8_t instance) const
void getTiltError(int8_t instance, float &ang) const
void getWind(Vector3f &wind) const
NavEKF2(const AP_AHRS *ahrs, const RangeFinder &rng)
bool getLLH(struct Location &loc) const
#define POS_I_GATE_DEFAULT
void getMagNED(int8_t instance, Vector3f &magNED) const
#define VEL_I_GATE_DEFAULT
friend class NavEKF2_core
#define GBIAS_P_NSE_DEFAULT
bool getPosNE(int8_t instance, Vector2f &posNE) const
void setTakeoffExpected(bool val)
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
uint32_t getLastYawResetAngle(float &yawAngDelta)
uint32_t getLastPosNorthEastReset(Vector2f &pos) const
void getGyroScaleErrorPercentage(int8_t instance, Vector3f &gyroScale) const
bool getRangeBeaconDebug(uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow)
uint64_t imuSampleTime_us
Interface definition for the various Ground Control System.
void getOutputTrackingError(int8_t instance, Vector3f &error) const
void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const
bool getOriginLLH(int8_t instance, struct Location &loc) const
#define AP_GROUPINFO(name, idx, clazz, element, def)
void updateLaneSwitchPosDownResetData(uint8_t new_primary, uint8_t old_primary)
bool setOriginLLH(const Location &loc)
bool InitialiseFilter(void)
void getRotationBodyToNED(Matrix3f &mat) const
void getTimingStatistics(struct ekf_timing &timing)
#define FLOW_I_GATE_DEFAULT
void getEulerAngles(int8_t instance, Vector3f &eulers) const
bool getPosD(int8_t instance, float &posD) const
const char * prearm_failure_reason(void) const
void getGyroBias(int8_t instance, Vector3f &gyroBias) const
#define MAGE_P_NSE_DEFAULT
void getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
void getRotationBodyToNED(Matrix3f &mat) const
#define ABIAS_P_NSE_DEFAULT
void getFilterFaults(uint16_t &faults) const
void Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask)
bool getHeightControlLimit(float &height) const
void getVelNED(Vector3f &vel) const
#define GSCALE_P_NSE_DEFAULT
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define MAG_I_GATE_DEFAULT
bool getPosNE(Vector2f &posNE) const
bool getHeightControlLimit(float &height) const
bool InitialiseFilterBootstrap(void)
void getQuaternion(int8_t instance, Quaternion &quat) const
void getFilterGpsStatus(nav_gps_status &status) const
const Compass * get_compass() const
#define POSNE_M_NSE_DEFAULT
static AP_InertialSensor ins
uint8_t setInhibitGPS(void)
void getMagNED(Vector3f &magNED) const
void getAccelNED(Vector3f &accelNED) const
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
void setTakeoffExpected(bool val)
void send_status_report(mavlink_channel_t chan)
void getWind(int8_t instance, Vector3f &wind) const
int8_t getPrimaryCoreIMUIndex(void) const
#define CHECK_SCALER_DEFAULT
uint32_t getLastYawResetAngle(float &yawAng) const
uint8_t _framesPerPrediction
float wrap_PI(const T radian)
void Log_Write_Compass(const Compass &compass, uint64_t time_us=0)
static const struct AP_Param::GroupInfo var_info[]
uint32_t getLastPosNorthEastReset(Vector2f &posDelta)
uint32_t getLastPosDownReset(float &posDelta)
void getMagXYZ(Vector3f &magXYZ) const
void getGyroBias(Vector3f &gyroBias) const
uint8_t getIMUIndex(void) const
void updateLaneSwitchPosResetData(uint8_t new_primary, uint8_t old_primary)
bool getOriginLLH(struct Location &loc) const
static DataFlash_Class * instance(void)
struct NavEKF2::@142 pos_reset_data
void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
int8_t getPrimaryCoreIndex(void) const
#define MAG_M_NSE_DEFAULT
#define GYRO_P_NSE_DEFAULT
void send_status_report(mavlink_channel_t chan)
float getPosDownDerivative(void) const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void getFilterTimeouts(uint8_t &timeouts) const
bool resetHeightDatum(void)
uint16_t get_sample_rate(void) const
#define ALT_M_NSE_DEFAULT
void setTerrainHgtStable(bool val)
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
#define FLOW_M_NSE_DEFAULT
bool getHAGL(float &HAGL) const
void getOutputTrackingError(Vector3f &error) const
bool use_compass(void) const
bool use_compass(void) const
void UpdateFilter(bool predict)
void Log_Write_GPS(uint8_t instance, uint64_t time_us=0)
void getFilterGpsStatus(int8_t instance, nav_gps_status &faults) const
void getEulerAngles(Vector3f &eulers) const
#define VELD_M_NSE_DEFAULT
struct NavEKF2::@143 pos_down_reset_data
void getFlowDebug(float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
void getFilterFaults(int8_t instance, uint16_t &faults) const
void getQuaternion(Quaternion &quat) const
struct NavEKF2::@141 yaw_reset_data
void getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
virtual void * malloc_type(size_t size, Memory_Type mem_type)
void updateLaneSwitchYawResetData(uint8_t new_primary, uint8_t old_primary)
void getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
uint8_t setInhibitGPS(void)
float errorScore(void) const
bool setOriginLLH(const Location &loc)
#define MAGB_P_NSE_DEFAULT
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
#define ACC_P_NSE_DEFAULT
void getVelNED(int8_t instance, Vector3f &vel) const
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
AP_HAL::AnalogSource * chan
void getTimingStatistics(int8_t instance, struct ekf_timing &timing) const
#define error(fmt, args ...)
uint8_t getActiveMag() const
#define GLITCH_RADIUS_DEFAULT
AP_InertialSensor & ins()
#define VELNE_M_NSE_DEFAULT
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
#define HGT_I_GATE_DEFAULT
void getGyroScaleErrorPercentage(Vector3f &gyroScale) const
void check_log_write(void)
float getPosDownDerivative(int8_t instance) const
void setTouchdownExpected(bool val)
void getFilterStatus(int8_t instance, nav_filter_status &status) const
bool have_ekf_logging(void) const
void getAccelZBias(int8_t instance, float &zbias) const
void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
void getMagXYZ(int8_t instance, Vector3f &magXYZ) const
void setTouchdownExpected(bool val)
void getFilterStatus(nav_filter_status &status) const
void setTerrainHgtStable(bool val)
bool getLLH(struct Location &loc) const
void getTiltError(float &ang) const
bool getPosD(float &posD) const
void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
void Log_Write_Baro(uint64_t time_us=0)
const char * prearm_failure_reason(void) const
bool getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow) const
uint8_t get_accel_count(void) const
struct NavEKF2::@140 logging
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
void getAccelNED(Vector3f &accelNED) const