From 2114acddf1ee3509e6e8cd807c29e7adf499aeca Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 8 Aug 2012 13:04:21 +1000 Subject: [PATCH] APM: fixed default flap speed the default of 255 translates to -1 as a AP_Int8, so use zero to mean no flaps --- ArduPlane/Attitude.pde | 4 ++-- ArduPlane/config.h | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 30aa38b061..0d1d5a525c 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -398,9 +398,9 @@ static void set_servos(void) } else { flapSpeedSource = g.throttle_cruise; } - if ( flapSpeedSource > g.flap_1_speed) { + if ( g.flap_1_speed != 0 && flapSpeedSource > g.flap_1_speed) { g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = 0; - } else if (flapSpeedSource > g.flap_2_speed) { + } else if (g.flap_2_speed != 0 && flapSpeedSource > g.flap_2_speed) { g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = g.flap_1_percent; } else { g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = g.flap_2_percent; diff --git a/ArduPlane/config.h b/ArduPlane/config.h index db2a39312c..d06528e327 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -317,13 +317,13 @@ # define FLAP_1_PERCENT 0 #endif #ifndef FLAP_1_SPEED -# define FLAP_1_SPEED 255 +# define FLAP_1_SPEED 0 #endif #ifndef FLAP_2_PERCENT # define FLAP_2_PERCENT 0 #endif #ifndef FLAP_2_SPEED -# define FLAP_2_SPEED 255 +# define FLAP_2_SPEED 0 #endif ////////////////////////////////////////////////////////////////////////////// // FLIGHT_MODE