Copter: remove baro init on arming
This commit is contained in:
parent
558018d839
commit
e5ddd276fd
@ -156,9 +156,6 @@ static bool init_arm_motors(bool arming_from_gcs)
|
|||||||
did_ground_start = true;
|
did_ground_start = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// fast baro calibration to reset ground pressure
|
|
||||||
init_barometer(false);
|
|
||||||
|
|
||||||
// go back to normal AHRS gains
|
// go back to normal AHRS gains
|
||||||
ahrs.set_fast_gains(false);
|
ahrs.set_fast_gains(false);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user