Skip to content

Commit

Permalink
mag_cal: fix mag bias estimate to mag cal
Browse files Browse the repository at this point in the history
- since last_us is set to 0 every time the bias is not observable, the
  total time was also reset -> needed 30 consecutive seconds in mag 3D
  to be declared "stable"
- after landing, the mag_aligned_in_flight flag is reset. Using this for
  bias validity makes it invalid before we have a chance to save it to
  the calibration.
  • Loading branch information
bresch authored and dagar committed Jul 11, 2023
1 parent 69aa868 commit 2f52926
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 5 deletions.
2 changes: 1 addition & 1 deletion src/lib/sensor_calibration/Magnetometer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ void Magnetometer::SensorCorrectionsUpdate(bool force)

bool Magnetometer::set_offset(const Vector3f &offset)
{
if (Vector3f(_offset - offset).longerThan(0.01f)) {
if (Vector3f(_offset - offset).longerThan(0.005f)) {
if (offset.isAllFinite()) {
_offset = offset;
_calibration_count++;
Expand Down
7 changes: 4 additions & 3 deletions src/modules/ekf2/EKF2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2456,8 +2456,10 @@ void EKF2::UpdateCalibration(const hrt_abstime &timestamp, InFlightCalibration &
// consider bias estimates stable when all checks pass consistently and bias hasn't changed more than 10% of the limit
const float bias_change_limit = 0.1f * bias_limit;

if ((cal.last_us != 0) && !(cal.bias - bias).longerThan(bias_change_limit)) {
cal.total_time_us += timestamp - cal.last_us;
if (!(cal.bias - bias).longerThan(bias_change_limit)) {
if (cal.last_us != 0) {
cal.total_time_us += timestamp - cal.last_us;
}

if (cal.total_time_us > 30_s) {
cal.cal_available = true;
Expand Down Expand Up @@ -2517,7 +2519,6 @@ void EKF2::UpdateGyroCalibration(const hrt_abstime &timestamp)
void EKF2::UpdateMagCalibration(const hrt_abstime &timestamp)
{
const bool bias_valid = (_ekf.control_status_flags().mag_hdg || _ekf.control_status_flags().mag_3D)
&& _ekf.control_status_flags().mag_aligned_in_flight
&& !_ekf.control_status_flags().mag_fault
&& !_ekf.control_status_flags().mag_field_disturbed;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -329,7 +329,7 @@ void VehicleMagnetometer::UpdateMagCalibration()

if (_calibration[mag_index].set_offset(mag_cal_offset)) {

PX4_INFO("%d (%" PRIu32 ") EST:%d offset: [%.2f, %.2f, %.2f]->[%.2f, %.2f, %.2f] (full [%.3f, %.3f, %.3f])",
PX4_INFO("%d (%" PRIu32 ") EST:%d offset: [%.3f, %.3f, %.3f]->[%.3f, %.3f, %.3f] (full [%.3f, %.3f, %.3f])",
mag_index, _calibration[mag_index].device_id(), i,
(double)mag_cal_orig(0), (double)mag_cal_orig(1), (double)mag_cal_orig(2),
(double)mag_cal_offset(0), (double)mag_cal_offset(1), (double)mag_cal_offset(2),
Expand Down

0 comments on commit 2f52926

Please sign in to comment.