AP_InertialNav: increase baro delay to 0.5 sec (was 0.2sec) to allow slower baro updates on APM1

This commit is contained in:
rmackay9 2012-12-28 16:21:13 +09:00
parent 57702b7c31
commit 07a3a7d4bb
3 changed files with 3 additions and 3 deletions

View File

@ -787,7 +787,7 @@ static void Log_Read_Attitude()
} }
// Write an INAV packet. Total length : 52 Bytes // 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 #if INERTIAL_NAV_XY == ENABLED || INERTIAL_NAV_Z == ENABLED
Vector3f accel_corr = inertial_nav.accel_correction.get(); Vector3f accel_corr = inertial_nav.accel_correction.get();

View File

@ -13,7 +13,7 @@ static void read_inertia()
log_counter_inav++; log_counter_inav++;
if( log_counter_inav >= 10 ) { if( log_counter_inav >= 10 ) {
log_counter_inav = 0; log_counter_inav = 0;
Log_Write_INAV(G_Dt); Log_Write_INAV();
} }
} }
#endif #endif

View File

@ -342,7 +342,7 @@ void AP_InertialNav::correct_with_baro(float baro_alt, float dt)
float accel_ef_z_correction; float accel_ef_z_correction;
// discard samples where dt is too large // discard samples where dt is too large
if( dt > 0.2 ) { if( dt > 0.5 ) {
return; return;
} }