Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

EKF3: allow earth-frame fields to be estimated with an origin but no GPS #25666

Merged
merged 1 commit into from
Jul 3, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
21 changes: 21 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -668,6 +668,20 @@ bool NavEKF3_core::setOriginLLH(const Location &loc)
return setOrigin(loc);
}

// populates the Earth magnetic field table using the given location
void NavEKF3_core::setEarthFieldFromLocation(const Location &loc)
{
const auto &compass = dal.compass();
if (compass.have_scale_factor(magSelectIndex) &&
compass.auto_declination_enabled()) {
getEarthFieldTable(loc);
if (frontend->_mag_ef_limit > 0) {
// initialise earth field from tables
stateStruct.earth_magfield = table_earth_field_ga;
}
}
}

// sets the local NED origin using a LLH location (latitude, longitude, height)
// returns false is the origin has already been set
bool NavEKF3_core::setOrigin(const Location &loc)
Expand All @@ -682,6 +696,13 @@ 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;

// 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();
setEarthFieldFromLocation(EKF_origin);
}

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

if (!frontend->common_origin_valid) {
Expand Down
10 changes: 1 addition & 9 deletions libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -690,15 +690,7 @@ void NavEKF3_core::readGpsData()
}

if (gpsGoodToAlign && !have_table_earth_field) {
const auto &compass = dal.compass();
if (compass.have_scale_factor(magSelectIndex) &&
compass.auto_declination_enabled()) {
getEarthFieldTable(gpsloc);
if (frontend->_mag_ef_limit > 0) {
// initialise earth field from tables
stateStruct.earth_magfield = table_earth_field_ga;
}
}
setEarthFieldFromLocation(gpsloc);
}

// convert GPS measurements to local NED and save to buffer to be fused later if we have a valid origin
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_core.h
Original file line number Diff line number Diff line change
Expand Up @@ -233,6 +233,9 @@ class NavEKF3_core : public NavEKF_core_common
// Returns true if the set was successful
bool setLatLng(const Location &loc, float posAccuracy, uint32_t timestamp_ms);

// Popoluates the WMM data structure with the field at the given location
void setEarthFieldFromLocation(const Location &loc);

// return estimated height above ground level
// return false if ground height is not being estimated.
bool getHAGL(float &HAGL) const;
Expand Down
Loading