Copter: increase Alt Disparity check to 2m

This commit is contained in:
Randy Mackay 2014-09-20 12:24:36 +09:00
parent 9bbf40109e
commit d8d1b38a52

View File

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