mirror of https://github.com/ArduPilot/ardupilot
Copter: Match type to set value
This commit is contained in:
parent
ba51b56865
commit
a6feb97668
|
@ -20,7 +20,7 @@
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
static struct {
|
static struct {
|
||||||
uint8_t fail_count; // number of iterations ekf or dcm have been out of tolerances
|
uint8_t fail_count; // number of iterations ekf or dcm have been out of tolerances
|
||||||
uint8_t bad_variance : 1; // true if ekf should be considered untrusted (fail_count has exceeded EKF_CHECK_ITERATIONS_MAX)
|
bool bad_variance; // true if ekf should be considered untrusted (fail_count has exceeded EKF_CHECK_ITERATIONS_MAX)
|
||||||
bool has_ever_passed; // true if the ekf checks have ever passed
|
bool has_ever_passed; // true if the ekf checks have ever passed
|
||||||
uint32_t last_warn_time; // system time of last warning in milliseconds. Used to throttle text warnings sent to GCS
|
uint32_t last_warn_time; // system time of last warning in milliseconds. Used to throttle text warnings sent to GCS
|
||||||
} ekf_check_state;
|
} ekf_check_state;
|
||||||
|
|
Loading…
Reference in New Issue