3 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 53 const float tiltErrThreshold = 0.05f;
60 void NavEKF2_core::getFlowDebug(
float &varFlow,
float &gndOffset,
float &flowInnovX,
float &flowInnovY,
float &auxInnov,
float &HAGL,
float &rngInnov,
float &
range,
float &gndOffsetErr)
const 70 gndOffsetErr = sqrtf(
Popt);
140 gyroScale.
x = gyroScale.
y = gyroScale.
z = 0;
258 posNE.
x = tempPosNE.
x;
259 posNE.
y = tempPosNE.
y;
373 ekfGndSpdLimit = 400.0f;
374 ekfNavVelGainScaler = 1.0f;
414 const float maxMagVar = 5E-6
f;
415 bool variancesConverged = (
P[19][19] < maxMagVar) && (
P[20][20] < maxMagVar) && (
P[21][21] < maxMagVar);
420 variancesConverged) {
445 magInnov.
y = 1e3f*innovMag[1];
446 magInnov.
z = 1e3f*innovMag[2];
544 flags |= EKF_ATTITUDE;
547 flags |= EKF_VELOCITY_HORIZ;
550 flags |= EKF_VELOCITY_VERT;
553 flags |= EKF_POS_HORIZ_REL;
556 flags |= EKF_POS_HORIZ_ABS;
559 flags |= EKF_POS_VERT_ABS;
562 flags |= EKF_POS_VERT_AGL;
565 flags |= EKF_CONST_POS_MODE;
568 flags |= EKF_PRED_POS_HORIZ_REL;
571 flags |= EKF_PRED_POS_HORIZ_ABS;
575 float velVar, posVar, hgtVar, tasVar;
578 getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
591 mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVar.
length(), temp, tasVar);
618 #endif // HAL_CPU_CLASS
void to_euler(float &roll, float &pitch, float &yaw) const
struct nav_gps_status::@139 flags
uint32_t getLastPosDownReset(float &posD) const
const Vector3f & get_trim() const
void getAccelZBias(float &zbias) const
void getWind(Vector3f &wind) const
bool getLLH(struct Location &loc) const
char prearm_fail_string[40]
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
uint32_t getLastPosNorthEastReset(Vector2f &pos) const
output_elements outputDataNew
bool getRangeBeaconDebug(uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow)
void getRotationBodyToNED(Matrix3f &mat) const
const char * prearm_failure_reason(void) const
bool finalInflightMagInit
void getFilterFaults(uint16_t &faults) const
bool getHeightControlLimit(float &height) const
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
void getVelNED(Vector3f &vel) const
const Location & location(uint8_t instance) const
bool getPosNE(Vector2f &posNE) const
bool rngBcnAlignmentStarted
struct NavEKF2_core::state_elements & stateStruct
uint32_t lastGpsVelFail_ms
uint32_t imuSampleTime_ms
int32_t lat
param 3 - Latitude * 10**7
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
void getFilterGpsStatus(nav_gps_status &status) const
const Compass * get_compass() const
void getMagNED(Vector3f &magNED) const
uint32_t framesSincePredict
void getAccelNED(Vector3f &accelNED) const
void send_status_report(mavlink_channel_t chan)
uint32_t getLastYawResetAngle(float &yawAng) const
struct NavEKF2_core::@145 faultStatus
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
uint8_t rngBcnFuseDataReportIndex
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
void getMagXYZ(Vector3f &magXYZ) const
void getGyroBias(Vector3f &gyroBias) const
struct NavEKF2_core::@146 gpsCheckStatus
const Vector3f & get_offsets(uint8_t i) const
bool getOriginLLH(struct Location &loc) const
uint8_t getFramesSincePredict(void) const
const Matrix3f & get_rotation_vehicle_body_to_autopilot_body(void) const
int16_t max_distance_cm_orient(enum Rotation orientation) const
void rotation_matrix(Matrix3f &m) const
bool healthy[COMPASS_MAX_INSTANCES]
Receiving valid messages and 2D lock.
float getPosDownDerivative(void) const
void getFilterTimeouts(uint8_t &timeouts) const
GPS_Status status(uint8_t instance) const
Query GPS status.
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
bool getHAGL(float &HAGL) const
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
void getOutputTrackingError(Vector3f &error) const
void getEulerAngles(Vector3f &eulers) const
struct nav_filter_status::@138 flags
void getFlowDebug(float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
void getQuaternion(Quaternion &quat) const
void getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
int32_t lng
param 4 - Longitude * 10**7
void getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
struct Location EKF_origin
float errorScore(void) const
nav_filter_status filterStatus
AP_HAL::AnalogSource * chan
#define error(fmt, args ...)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Vector3f outputTrackError
uint8_t getActiveMag() const
Receiving valid messages and 3D lock.
void getGyroScaleErrorPercentage(Vector3f &gyroScale) const
range_elements rangeDataDelayed
void getFilterStatus(nav_filter_status &status) const
struct NavEKF2_core::@144 rngBcnFusionReport[10]
Vector2f lastKnownPositionNE
void getTiltError(float &ang) const
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
bool getPosD(float &posD) const
uint32_t lastPosResetD_ms