28 #if AP_AHRS_NAVEKF_AVAILABLE 92 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 108 #if AP_MODULE_SUPPORTED 110 AP_Module::call_hook_AHRS_update(*
this);
119 if (
_view !=
nullptr) {
181 if (primary_imu == -1) {
196 if (i == primary_imu) {
254 if (primary_imu == -1) {
288 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 291 if (
_sitl ==
nullptr) {
293 if (
_sitl ==
nullptr) {
330 const float quality = 100.0f;
349 #endif // CONFIG_HAL_BOARD 406 loc.
alt = origin.
alt - ned_pos.
z*100;
414 loc.
alt = origin.
alt - ned_pos.
z*100;
419 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 422 memset(&loc, 0,
sizeof(loc));
456 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 493 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 581 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 606 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 642 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 667 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 690 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 714 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 738 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 783 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 810 vec.
x = originNED.
x - offset.
x;
811 vec.
y = originNED.
y - offset.
y;
812 vec.
z = originNED.
z - offset.
z;
827 return position_is_valid;
832 return position_is_valid;
835 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 859 posNE.
x = originNE.
x - offset.
x;
860 posNE.
y = originNE.
y - offset.
y;
878 return position_is_valid;
883 return position_is_valid;
886 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 918 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 923 if ((
always_use_EKF() && (type == 0)) || (type == 1) || (type > 3)) {
943 uint16_t ekf2_faults;
945 if (ekf2_faults == 0) {
960 uint16_t ekf3_faults;
962 if (ekf3_faults == 0) {
971 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 995 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1079 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1109 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1132 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1134 memset(&status, 0,
sizeof(status));
1183 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1204 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1207 ekfGndSpdLimit = 400.0f;
1208 ekfNavVelGainScaler = 1.0f;
1228 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1251 if (imu_idx == -1) {
1260 ret -= accel_bias*dt;
1299 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1320 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1341 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1361 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1389 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1403 mavlink_msg_ekf_status_report_send(chan, 0, 0, 0, 0, 0, 0, 0);
1406 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1409 mavlink_msg_ekf_status_report_send(chan, 0, 0, 0, 0, 0, 0, 0);
1444 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1470 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1493 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1522 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1547 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1566 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 1645 #endif // AP_AHRS_NAVEKF_AVAILABLE
void get_relative_position_D_home(float &posD) const override
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
bool get_soft_armed() const
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
static AP_Param * find_object(const char *name)
Vector2< float > Vector2f
bool initialised() const override
bool get_relative_position_D_origin(float &posD) const override
bool use_compass() override
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
uint8_t get_primary_IMU_index(void) const
bool resetHeightDatum(void)
void send_ekf_status_report(mavlink_channel_t chan) const
Vector3< float > Vector3f
const Vector3f & get_accel_ef_blended() const override
float get_error_rp() const override
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
bool resetHeightDatum() override
float get_error_yaw() const override
bool getHAGL(float &HAGL) const
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
void getMagNED(int8_t instance, Vector3f &magNED) const
virtual void getCorrectedDeltaVelocityNED(Vector3f &ret, float &dt) const
bool get_secondary_attitude(Vector3f &eulers) const override
void send_status_report(mavlink_channel_t chan)
const Vector3f & get_gyro(void) const override
virtual const Vector3f & get_accel_ef_blended(void) const
virtual void boost_end(void)
bool use_compass() override
bool getPosNE(int8_t instance, Vector2f &posNE) const
void setTakeoffExpected(bool val)
bool have_inertial_nav() const override
void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
uint32_t getLastYawResetAngle(float &yawAngDelta)
bool setOriginLLH(const Location &loc)
bool healthy() const override
bool get_secondary_position(struct Location &loc) const override
const Vector3f & get_gyro(uint8_t i) const
float get_error_rp() const override
bool get_filter_status(nav_filter_status &status) const
Interface definition for the various Ground Control System.
bool getGpsGlitchStatus() const
const struct Location & get_home(void) const
bool getOriginLLH(int8_t instance, struct Location &loc) const
uint8_t ekf_type(void) const
bool use_compass(void) const
uint8_t get_primary_gyro(void) const
AP_AHRS_NavEKF(NavEKF2 &_EKF2, NavEKF3 &_EKF3, Flags flags=FLAG_NONE)
void getGyroBias(int8_t instance, Vector3f &gyroBias) const
bool get_hagl(float &hagl) const override
bool get_mag_field_correction(Vector3f &ret) const override
bool set_origin(const Location &loc) override
bool setOriginLLH(const Location &loc)
void getFilterStatus(int8_t instance, nav_filter_status &status) const
bool InitialiseFilter(void)
const char * prearm_failure_reason(void) const
void getEulerAngles(int8_t instance, Vector3f &eulers) const
bool have_ekf_logging(void) const
bool getPosD(int8_t instance, float &posD) const
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
void getMagXYZ(int8_t instance, Vector3f &magXYZ) const
void setTakeoffExpected(bool val)
bool getHeightControlLimit(float &height) const
bool get_location(struct Location &loc) const
AHRS_VehicleClass _vehicle_class
void getGyroBias(int8_t instance, Vector3f &gyroBias) const
void from_euler(float roll, float pitch, float yaw)
bool InitialiseFilter(void)
void update(bool skip_ins_update=false) override
const Vector3f & get_gyro() const override
void getRotationBodyToNED(Matrix3f &mat) const
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
void reset_attitude(const float &roll, const float &pitch, const float &yaw) override
void reset_attitude(const float &roll, const float &pitch, const float &yaw) override
void reset_gyro_drift() override
virtual Vector2f groundspeed_vector(void)
bool getHeightControlLimit(float &height) const
void from_rotation_matrix(const Matrix3f &m)
int32_t lat
param 3 - Latitude * 10**7
bool get_origin(Location &ret) const override
Vector3f _accel_ef_ekf_blended
virtual const Vector3f & get_accel_ef(void) const
void getQuaternion(int8_t instance, Quaternion &quat) const
void getRotationBodyToNED(Matrix3f &mat) const
uint32_t getLastYawResetAngle(float &yawAng) const override
const Vector3f & get_accel(uint8_t i) const
void setTouchdownExpected(bool val)
const Vector3f & get_gyro_drift() const override
Matrix3< T > transposed(void) const
uint8_t get_primary_accel(void) const
void getWind(int8_t instance, Vector3f &wind) const
bool get_relative_position_NED_home(Vector3f &vec) const override
int8_t getPrimaryCoreIMUIndex(void) const
uint32_t getLastYawResetAngle(float &yawAngDelta)
bool healthy() const override
void setTakeoffExpected(bool val)
bool airspeed_estimate(float *airspeed_ret) const override
bool airspeed_estimate(float *airspeed_ret) const override
bool getLLH(struct Location &loc) const
const char * prearm_failure_reason(void) const override
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
void getVelNED(int8_t instance, Vector3f &vel) const
AP_HAL::OpticalFlow * opticalflow
const Vector3f & get_accel_ef() const override
uint32_t getLastPosNorthEastReset(Vector2f &posDelta)
float ground_speed(uint8_t instance) const
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
uint32_t getLastPosDownReset(float &posDelta)
virtual bool get_position(struct Location &loc) const override
void update_cd_values(void)
void update(bool skip_ins_update=false)
void reset(bool recover_eulers=false) override
void getCorrectedDeltaVelocityNED(Vector3f &ret, float &dt) const override
bool getPosD(int8_t instance, float &posD) const
int8_t getPrimaryCoreIMUIndex(void) const
void getEulerAngles(int8_t instance, Vector3f &eulers) const
bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const override
uint8_t get_primary_accel_index(void) const override
uint32_t getLastPosNorthEastReset(Vector2f &posDelta)
void update(bool skip_ins_update=false) override
Vector3f _accel_ef_ekf[INS_MAX_INSTANCES]
#define AP_AHRS_NAVEKF_SETTLE_TIME_MS
void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
uint32_t getLastPosDownReset(float &posDelta) const override
void rotation_matrix(Matrix3f &m) const
const Matrix3f & get_rotation_body_to_ned() const override
bool get_position(struct Location &loc) const override
void send_status_report(mavlink_channel_t chan)
uint8_t setInhibitGPS(void)
bool get_relative_position_NE_origin(Vector2f &posNE) const override
float get_error_yaw() const override
void getFilterFaults(int8_t instance, uint16_t &faults) const
bool resetHeightDatum(void)
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
GPS_Status status(uint8_t instance) const
Query GPS status.
bool have_ekf_logging(void) const override
uint32_t getLastPosDownReset(float &posDelta)
bool use_compass(void) const
Vector3f wind_estimate() const override
const Matrix3f & get_rotation_autopilot_body_to_vehicle_body(void) const
uint32_t _last_body_odm_update_ms
struct nav_filter_status::@138 flags
void getFilterFaults(int8_t instance, uint16_t &faults) const
bool get_vert_pos_rate(float &velocity) const
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
float get_altitude(void) const
bool getHAGL(float &HAGL) const
int32_t lng
param 4 - Longitude * 10**7
void getMagNED(int8_t instance, Vector3f &magNED) const
uint8_t setInhibitGPS(void)
bool getPosNE(int8_t instance, Vector2f &posNE) const
Vector3f location_3d_diff_NED(const struct Location &loc1, const struct Location &loc2)
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
Vector3f wind_estimate() const override
static constexpr float radians(float deg)
float get_delta_velocity_dt(uint8_t i) const
static struct notify_flags_and_values_type flags
void getVelNED(int8_t instance, Vector3f &vel) const
uint8_t get_primary_gyro_index(void) const override
bool always_use_EKF() const
virtual void push_gyro_bias(float gyro_bias_x, float gyro_bias_y)=0
AP_HAL::AnalogSource * chan
const Matrix3f & get_rotation_body_to_ned(void) const override
bool getOriginLLH(int8_t instance, struct Location &loc) const
uint8_t setInhibitGPS(void)
void reset(bool recover_eulers=false) override
void reset_gyro_drift() override
EKF_TYPE active_EKF_type(void) const
bool get_mag_field_NED(Vector3f &ret) const
uint32_t getLastVelNorthEastReset(Vector2f &vel) const override
bool get_relative_position_NED_origin(Vector3f &vec) const override
AP_InertialSensor & ins()
struct AP_AHRS::ahrs_flags _flags
void setTouchdownExpected(bool val)
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
Receiving valid messages and 3D lock.
float getPosDownDerivative(int8_t instance) const
void getAccelBias(int8_t instance, Vector3f &accelBias) const
void getWind(int8_t instance, Vector3f &wind) const
#define INS_MAX_INSTANCES
float getPosDownDerivative(int8_t instance) const
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
bool get_secondary_quaternion(Quaternion &quat) const override
void set_ekf_use(bool setting)
void getFilterStatus(int8_t instance, nav_filter_status &status) const
bool have_ekf_logging(void) const
void getAccelZBias(int8_t instance, float &zbias) const
bool get_relative_position_NE_home(Vector2f &posNE) const override
Vector2f groundspeed_vector() override
bool get_velocity_NED(Vector3f &vec) const override
const uint16_t startup_delay_ms
void getMagXYZ(int8_t instance, Vector3f &magXYZ) const
bool get_hgt_ctrl_limit(float &limit) const override
void setTouchdownExpected(bool val)
bool getLLH(struct Location &loc) const
void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
const char * prearm_failure_reason(void) const
AP_HAL::Scheduler * scheduler
uint8_t get_accel_count(void) const
void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms) override
const Vector3f & get_gyro_drift(void) const override
bool get_accel_health(uint8_t instance) const
uint32_t getLastPosNorthEastReset(Vector2f &pos) const override
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
void update_DCM(bool skip_ins_update)