Copter: Reduce prearm alt disparity check back to 1m

This commit is contained in:
Jonathan Challinger 2014-10-12 16:44:46 -07:00 committed by Randy Mackay
parent 3296eb24b3
commit 5fc02bdbc4

View File

@ -324,7 +324,7 @@
// pre-arm baro vs inertial nav max alt disparity
#ifndef PREARM_MAX_ALT_DISPARITY_CM
# define PREARM_MAX_ALT_DISPARITY_CM 200 // barometer and inertial nav altitude must be within this many centimeters
# define PREARM_MAX_ALT_DISPARITY_CM 100 // barometer and inertial nav altitude must be within this many centimeters
#endif
// pre-arm check max velocity