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;
123 for (uint8_t index=18; index<=21; index++) {
173 if(canUseGPS || canUseRangeBeacon || canUseExtNav) {
190 }
else if (flowSensorTimeout || flowFusionTimeout) {
214 bool attAiding = posUsed || gpsVelUsed || optFlowUsed || airSpdUsed || rngBcnUsed;
217 bool velAiding = gpsVelUsed || airSpdUsed || optFlowUsed;
220 bool posAiding = posUsed || rngBcnUsed;
223 bool attAidLossCritical =
false;
233 bool posAidLossCritical =
false;
235 uint16_t maxLossTime_ms;
241 posAidLossCritical = (
imuSampleTime_ms - lastRngBcnPassTime_ms > maxLossTime_ms) &&
245 if (attAidLossCritical) {
253 }
else if (posAidLossCritical) {
292 gcs().
send_text(MAV_SEVERITY_INFO,
"EKF2 IMU%u is using optical flow",(
unsigned)imu_index);
307 gcs().
send_text(MAV_SEVERITY_INFO,
"EKF2 IMU%u is using GPS",(
unsigned)imu_index);
312 if (canUseRangeBeacon) {
313 gcs().
send_text(MAV_SEVERITY_INFO,
"EKF2 IMU%u is using range beacons",(
unsigned)imu_index);
315 gcs().
send_text(MAV_SEVERITY_INFO,
"EKF2 IMU%u initial beacon pos D offset = %3.1f (m)",(
unsigned)imu_index,(
double)
bcnPosOffset);
319 gcs().
send_text(MAV_SEVERITY_INFO,
"EKF2 IMU%u is using external nav data",(
unsigned)imu_index);
470 (
P[10][10] <= delAngBiasVarMax) &&
471 (
P[11][11] <= delAngBiasVarMax);
526 #endif // HAL_CPU_CLASS void to_euler(float &roll, float &pitch, float &yaw) const
uint32_t lastVelPassTime_ms
bool get_soft_armed() const
uint8_t effective_magCal(void) const
void controlMagYawReset()
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
bool extNavYawResetRequest
Interface definition for the various Ground Control System.
bool assume_zero_sideslip(void) const
const uint16_t posRetryTimeNoVel_ms
const struct Location & get_home(void) const
AHRS_VehicleClass get_vehicle_class(void) const
bool finalInflightMagInit
void updateFilterStatus(void)
const Location & location(uint8_t instance) const
const uint16_t posRetryTimeUseVel_ms
struct NavEKF2_core::state_elements & stateStruct
uint32_t imuSampleTime_ms
int32_t lat
param 3 - Latitude * 10**7
const Compass * get_compass() const
imu_elements imuDataDelayed
uint8_t setInhibitGPS(void)
Vector3f earthMagFieldVar
bool readyToUseGPS(void) const
bool readyToUseRangeBeacon(void) const
baro_elements baroDataDelayed
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
bool optFlowDataPresent(void) const
bool readyToUseExtNav(void) const
uint32_t prevFlowFuseTime_ms
const uint16_t tiltDriftTimeMax_ms
bool useAirspeed(void) const
void setWindMagStateLearningMode()
AidingMode PV_AidingModePrev
bool useRngFinder(void) const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
bool use_compass(void) const
bool magStateInitComplete
struct nav_filter_status::@138 flags
void calcEarthRateNED(Vector3f &omega, int32_t latitude) const
bool finalInflightYawInit
float constrain_float(const float amt, const float low, const float high)
struct Location EKF_origin
nav_filter_status filterStatus
bool setOriginLLH(const Location &loc)
ext_nav_elements extNavDataDelayed
uint32_t lastRngBcnPassTime_ms
static constexpr float radians(float deg)
void alignMagStateDeclination()
bool get_fly_forward(void) const
bool expectGndEffectTouchdown
void controlFilterModes()
bool airspeed_sensor_enabled(void) const
float get_EAS2TAS(void) const
bool expectGndEffectTakeoff
uint32_t lastPosPassTime_ms
uint32_t lastTasPassTime_ms
tas_elements tasDataDelayed
void checkAttitudeAlignmentStatus()
uint32_t flowValidMeaTime_ms
Vector2f lastKnownPositionNE
bool checkGyroCalStatus(void)