Skip to content

Commit

Permalink
EKF3: allow earth-frame fields to be estimated with an origin but no GPS
Browse files Browse the repository at this point in the history
  • Loading branch information
Williangalvani committed Jul 1, 2024
1 parent 868a650 commit bdb281f
Showing 1 changed file with 16 additions and 0 deletions.
16 changes: 16 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -682,6 +682,22 @@ bool NavEKF3_core::setOrigin(const Location &loc)
// define Earth rotation vector in the NED navigation frame at the origin
calcEarthRateNED(earthRateNED, EKF_origin.lat);
validOrigin = true;

// this section is similar to what is in AP_NavEKF3_Measurements.cpp's NavEKF3_core::readGpsData()
// but we do want to populate the WMM table even if we don't have a GPS at all
if (!stateStruct.quat.is_zero()) {
alignMagStateDeclination();
const auto &compass = dal.compass();
if (compass.have_scale_factor(magSelectIndex) &&
compass.auto_declination_enabled()) {
getEarthFieldTable(EKF_origin);
if (frontend->_mag_ef_limit > 0) {
// initialise earth field from tables
stateStruct.earth_magfield = table_earth_field_ga;
}
}
}

GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF3 IMU%u origin set",(unsigned)imu_index);

if (!frontend->common_origin_valid) {
Expand Down

0 comments on commit bdb281f

Please sign in to comment.