3 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 77 for (uint8_t index=22; index<=23; index++) {
82 for (uint8_t index=22; index<=23; index++) {
83 P[index][index] =
sq(5.0
f);
97 bool magCalRequested =
108 bool setMagInhibit = !magCalRequested || magCalDenied;
125 for (uint8_t index=18; index<=21; index++) {
148 P[14][14] =
P[13][13];
149 P[15][15] =
P[13][13];
159 P[11][11] =
P[10][10];
160 P[12][12] =
P[10][10];
228 }
else if (flowFusionTimeout && bodyOdmFusionTimeout) {
254 bool attAiding = gpsPosUsed || gpsVelUsed || optFlowUsed || airSpdUsed || rngBcnUsed || bodyOdmUsed;
257 bool velAiding = gpsVelUsed || airSpdUsed || optFlowUsed || bodyOdmUsed;
260 bool posAiding = gpsPosUsed || rngBcnUsed;
263 bool attAidLossCritical =
false;
273 bool posAidLossCritical =
false;
275 uint16_t maxLossTime_ms;
281 posAidLossCritical = (
imuSampleTime_ms - lastRngBcnPassTime_ms > maxLossTime_ms) &&
285 if (attAidLossCritical) {
293 }
else if (posAidLossCritical) {
332 gcs().
send_text(MAV_SEVERITY_INFO,
"EKF3 IMU%u started relative aiding",(
unsigned)imu_index);
351 gcs().
send_text(MAV_SEVERITY_INFO,
"EKF3 IMU%u is using GPS",(
unsigned)imu_index);
356 gcs().
send_text(MAV_SEVERITY_INFO,
"EKF3 IMU%u is using range beacons",(
unsigned)imu_index);
392 if ((angleErrVarVec.
x + angleErrVarVec.
y) <
sq(0.05235
f)) {
436 return (visoDataGood || wencDataGood)
515 (
P[11][11] <= delAngBiasVarMax) &&
516 (
P[12][12] <= delAngBiasVarMax);
567 #endif // HAL_CPU_CLASS
void to_euler(float &roll, float &pitch, float &yaw) const
bool get_soft_armed() const
void setWindMagStateLearningMode()
uint32_t lastPosPassTime_ms
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
baro_elements baroDataDelayed
uint32_t prevFlowFuseTime_ms
bool magStateInitComplete
void updateStateIndexLim(void)
bool expectGndEffectTouchdown
bool setOriginLLH(const Location &loc)
Interface definition for the various Ground Control System.
bool assume_zero_sideslip(void) const
const struct Location & get_home(void) const
uint32_t wheelOdmMeasTime_ms
AHRS_VehicleClass get_vehicle_class(void) const
float InitialGyroBiasUncertainty(void) const
bool readyToUseBodyOdm(void) const
uint32_t lastVelPassTime_ms
uint32_t lastTasPassTime_ms
void checkGyroCalStatus(void)
uint32_t lastbodyVelPassTime_ms
tas_elements tasDataDelayed
uint8_t effective_magCal(void) const
const Location & location(uint8_t instance) const
uint32_t lastRngBcnPassTime_ms
uint32_t flowValidMeaTime_ms
int32_t lat
param 3 - Latitude * 10**7
bool readyToUseOptFlow(void) const
uint8_t setInhibitGPS(void)
struct NavEKF3_core::state_elements & stateStruct
bool inhibitDelAngBiasStates
const Compass * get_compass() const
bool use_compass(void) const
void controlFilterModes()
Vector3f calcRotVecVariances(void)
bool readyToUseGPS(void) const
bool readyToUseRangeBeacon(void) const
Vector2f lastKnownPositionNE
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
AidingMode PV_AidingModePrev
bool expectGndEffectTakeoff
resetDataSource velResetSource
Vector3f earthMagFieldVar
void updateFilterStatus(void)
#define ACCEL_BIAS_LIM_SCALER
resetDataSource posResetSource
void send_text(MAV_SEVERITY severity, const char *fmt,...)
vel_odm_elements bodyOdmDataNew
bool inhibitDelVelBiasStates
struct nav_filter_status::@138 flags
float constrain_float(const float amt, const float low, const float high)
static constexpr float radians(float deg)
void calcEarthRateNED(Vector3f &omega, int32_t latitude) const
void checkAttitudeAlignmentStatus()
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
bool rngBcnAlignmentCompleted
bool get_fly_forward(void) const
void alignMagStateDeclination()
const uint16_t posRetryTimeNoVel_ms
bool airspeed_sensor_enabled(void) const
float get_EAS2TAS(void) const
const uint16_t tiltDriftTimeMax_ms
bool finalInflightMagInit
const uint16_t posRetryTimeUseVel_ms
struct Location EKF_origin
uint32_t bodyOdmMeasTime_ms
nav_filter_status filterStatus
bool useRngFinder(void) const
uint32_t imuSampleTime_ms
uint32_t prevBodyVelFuseTime_ms
bool finalInflightYawInit
bool useAirspeed(void) const