Copter: set inav alt to zero when arming

This commit is contained in:
Randy Mackay 2014-06-06 18:14:28 +09:00
parent 28ce66f314
commit f5f206b055

View File

@ -169,6 +169,9 @@ static void init_arm_motors()
// fast baro calibration to reset ground pressure
init_barometer(false);
// reset inertial nav alt to zero
inertial_nav.set_altitude(0.0f);
// go back to normal AHRS gains
ahrs.set_fast_gains(false);