Copter: increase Alt Disparity check to 2m
This commit is contained in:
parent
9bbf40109e
commit
d8d1b38a52
@ -298,7 +298,7 @@
|
|||||||
|
|
||||||
// pre-arm baro vs inertial nav max alt disparity
|
// pre-arm baro vs inertial nav max alt disparity
|
||||||
#ifndef PREARM_MAX_ALT_DISPARITY_CM
|
#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
|
#endif
|
||||||
|
|
||||||
// pre-arm check max velocity
|
// pre-arm check max velocity
|
||||||
|
Loading…
Reference in New Issue
Block a user