From 07a3a7d4bb245ccf64517792912fa20cd344920d Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Fri, 28 Dec 2012 16:21:13 +0900 Subject: [PATCH] AP_InertialNav: increase baro delay to 0.5 sec (was 0.2sec) to allow slower baro updates on APM1 --- ArduCopter/Log.pde | 2 +- ArduCopter/inertia.pde | 2 +- libraries/AP_InertialNav/AP_InertialNav.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index 9ebd23689a..30521573a6 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -787,7 +787,7 @@ static void Log_Read_Attitude() } // Write an INAV packet. Total length : 52 Bytes -static void Log_Write_INAV(float delta_t) +static void Log_Write_INAV() { #if INERTIAL_NAV_XY == ENABLED || INERTIAL_NAV_Z == ENABLED Vector3f accel_corr = inertial_nav.accel_correction.get(); diff --git a/ArduCopter/inertia.pde b/ArduCopter/inertia.pde index 752191e93b..7892788f4c 100644 --- a/ArduCopter/inertia.pde +++ b/ArduCopter/inertia.pde @@ -13,7 +13,7 @@ static void read_inertia() log_counter_inav++; if( log_counter_inav >= 10 ) { log_counter_inav = 0; - Log_Write_INAV(G_Dt); + Log_Write_INAV(); } } #endif diff --git a/libraries/AP_InertialNav/AP_InertialNav.cpp b/libraries/AP_InertialNav/AP_InertialNav.cpp index e2cbe9a147..e909e4460d 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav.cpp @@ -342,7 +342,7 @@ void AP_InertialNav::correct_with_baro(float baro_alt, float dt) float accel_ef_z_correction; // discard samples where dt is too large - if( dt > 0.2 ) { + if( dt > 0.5 ) { return; }