From bf7ab052c14e00140e7b640f4663ef118cf227e5 Mon Sep 17 00:00:00 2001 From: AndersonRayner Date: Sun, 29 May 2016 01:09:18 +1000 Subject: [PATCH] AP_Vehicle: Removed unused airspeed_min and airspeed_max as now part of AP_Airspeed. --- libraries/AP_Vehicle/AP_Vehicle.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index 889994bc16..db1b4472e2 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -33,8 +33,6 @@ public: AP_Int8 throttle_slewrate; AP_Int8 throttle_cruise; AP_Int8 takeoff_throttle_max; - AP_Int16 airspeed_min; - AP_Int16 airspeed_max; AP_Int16 roll_limit_cd; AP_Int16 pitch_limit_max_cd; AP_Int16 pitch_limit_min_cd;