diff --git a/integrationtests/python_src/px4_it/mavros/mission_test.py b/integrationtests/python_src/px4_it/mavros/mission_test.py index 8d7f6e6478..a9dccf7284 100755 --- a/integrationtests/python_src/px4_it/mavros/mission_test.py +++ b/integrationtests/python_src/px4_it/mavros/mission_test.py @@ -308,7 +308,7 @@ class MavrosMissionTest(MavrosTestCommon): self.assertTrue(res['pitch_error_std'] < 5.0, str(res)) # TODO: fix by excluding initial heading init and reset preflight - self.assertTrue(res['yaw_error_std'] < 10.0, str(res)) + self.assertTrue(res['yaw_error_std'] < 13.0, str(res)) if __name__ == '__main__': diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index a919032d8f..5bf9965040 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -150,7 +150,7 @@ void Ekf::controlMagFusion() const bool starting_conditions_passing = continuing_conditions_passing && checkMagField(mag_sample.mag) - && (_mag_counter > 5) // wait until we have more than a few samples through the filter + && (_mag_counter > 3) // wait until we have more than a few samples through the filter && (_control_status.flags.yaw_align == _control_status_prev.flags.yaw_align) // no yaw alignment change this frame && (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset && isNewestSampleRecent(_time_last_mag_buffer_push, MAG_MAX_INTERVAL);