From e1900f646f59720176f5feb4789071e0ffc35d04 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 30 Mar 2015 18:08:34 -0700 Subject: [PATCH] Copter: remove PREARM_MAX_VELOCITY definition --- ArduCopter/config.h | 5 ----- 1 file changed, 5 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index f4a9534761..032400775a 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -243,11 +243,6 @@ # define PREARM_MAX_ALT_DISPARITY_CM 100 // barometer and inertial nav altitude must be within this many centimeters #endif -// pre-arm check max velocity -#ifndef PREARM_MAX_VELOCITY_CMS - # define PREARM_MAX_VELOCITY_CMS 50.0f // vehicle must be travelling under 50cm/s before arming -#endif - // arming check's maximum acceptable accelerometer vector difference (in m/s/s) between primary and backup accelerometers #ifndef PREARM_MAX_ACCEL_VECTOR_DIFF #define PREARM_MAX_ACCEL_VECTOR_DIFF 0.70f // pre arm accel check will fail if primary and backup accelerometer vectors differ by 0.7m/s/s