From 2934b4173baf1fbdf3310769cbeee10710ca3ba4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 26 Mar 2012 12:58:19 +1100 Subject: [PATCH] APM: set_centripetal() is now set_fly_forward() this controls more than just centripetal correction --- ArduPlane/system.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index a17f74667e..36608a11ac 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -253,7 +253,7 @@ static void init_ardupilot() //read_EEPROM_airstart_critical(); #if HIL_MODE != HIL_MODE_ATTITUDE imu.init(IMU::WARM_START, mavlink_delay, flash_leds, &timer_scheduler); - ahrs.set_centripetal(1); + ahrs.set_fly_forward(true); #endif // This delay is important for the APM_RC library to work. @@ -458,7 +458,7 @@ static void startup_IMU_ground(bool force_accel_level) // it once via the ground station imu.init_accel(mavlink_delay, flash_leds); } - ahrs.set_centripetal(1); + ahrs.set_fly_forward(true); ahrs.reset(); // read Baro pressure at ground