mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_NAvEKF3: use #define value for bad IMU hold time
This commit is contained in:
parent
00806ac9fb
commit
fb6de9ad9d
@ -693,7 +693,7 @@ void NavEKF3_core::FuseVelPosNED()
|
||||
} else {
|
||||
goodIMUdata_ms = imuSampleTime_ms;
|
||||
}
|
||||
if (imuSampleTime_ms - badIMUdata_ms < 10000) {
|
||||
if (imuSampleTime_ms - badIMUdata_ms < BAD_IMU_DATA_HOLD_MS) {
|
||||
badIMUdata = true;
|
||||
} else {
|
||||
badIMUdata = false;
|
||||
|
@ -102,6 +102,9 @@
|
||||
// Number of milliseconds of bad IMU data before a reset to vertical position and velocity height sources is performed
|
||||
#define BAD_IMU_DATA_TIMEOUT_MS 1000
|
||||
|
||||
// number of milliseconds the bad IMU data response settings will be held after the last bad IMU data is detected
|
||||
#define BAD_IMU_DATA_HOLD_MS 10000
|
||||
|
||||
class NavEKF3_core : public NavEKF_core_common
|
||||
{
|
||||
public:
|
||||
|
Loading…
Reference in New Issue
Block a user