APM: fixed default flap speed

the default of 255 translates to -1 as a AP_Int8, so use zero to mean
no flaps
This commit is contained in:
Andrew Tridgell 2012-08-08 13:04:21 +10:00
parent 67f076a9db
commit 7d9e4a7559
2 changed files with 4 additions and 4 deletions

View File

@ -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;

View File

@ -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