Update ecl to geo_lookup, SymPy covariance, bugfixes

Co-authored-by: Matthias Grob <maetugr@gmail.com>
This commit is contained in:
Daniel Agar 2020-08-02 12:26:48 -04:00 committed by GitHub
parent e2a9b68fc7
commit 1191a0efe6
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
3 changed files with 5 additions and 5 deletions

View File

@ -71,9 +71,9 @@ void FakeMagnetometer::Run()
const double lon = gps.lon / 1.e7;
// magnetic field data returned by the geo library using the current GPS position
const float mag_declination_gps = math::radians(get_mag_declination(lat, lon));
const float mag_inclination_gps = math::radians(get_mag_inclination(lat, lon));
const float mag_strength_gps = 0.01f * get_mag_strength(lat, lon); // centi-Gauss (micro-Tesla) -> Gauss
const float mag_declination_gps = get_mag_declination_radians(lat, lon);
const float mag_inclination_gps = get_mag_inclination_radians(lat, lon);
const float mag_strength_gps = get_mag_strength_gauss(lat, lon);
_mag_earth_pred = Dcmf(Eulerf(0, -mag_inclination_gps, mag_declination_gps)) * Vector3f(mag_strength_gps, 0, 0);

@ -1 +1 @@
Subproject commit 5356077a3244a9a29adfae4aeaaab900cd28e9e8
Subproject commit 77b11129fa567160a2ec442438ed513cb9de89e7

View File

@ -316,7 +316,7 @@ AttitudeEstimatorQ::Run()
if (_gps_sub.copy(&gps)) {
if (_param_att_mag_decl_a.get() && (gps.eph < 20.0f)) {
/* set magnetic declination automatically */
update_mag_declination(math::radians(get_mag_declination(gps.lat, gps.lon)));
update_mag_declination(get_mag_declination_radians(gps.lat, gps.lon));
}
}
}