From ffc445098b54e8047a32ba65219fb6f981cba189 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Sat, 28 Mar 2015 16:01:37 -0700 Subject: [PATCH] Copter: remove velocity pre-arm check --- ArduCopter/motors.pde | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 7db56952d2..b684e84405 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -521,16 +521,6 @@ static bool pre_arm_gps_checks(bool display_failure) return false; } - // check speed is below 50cm/s - float speed_cms = inertial_nav.get_velocity().length(); // speed according to inertial nav in cm/s - if (speed_cms == 0 || speed_cms > PREARM_MAX_VELOCITY_CMS) { - if (display_failure) { - gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Bad Velocity")); - } - AP_Notify::flags.pre_arm_gps_check = false; - return false; - } - // check home and EKF origin are not too far if (far_from_EKF_origin(ahrs.get_home())) { if (display_failure) {