mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-16 21:57:36 +08:00
integrationtests: mavros/mission_test.py bump yaw_error_std threshold (heading init is delayed, but not wrong)
This commit is contained in:
committed by
Mathieu Bresciani
parent
5173830718
commit
bb5dfc7d51
@@ -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);
|
||||
|
||||
Reference in New Issue
Block a user