This commit is contained in:
Michael Oborne 2011-10-09 21:30:56 +08:00
commit c1854eeb32
1 changed files with 29 additions and 26 deletions

View File

@ -355,12 +355,14 @@ static void set_servos(void)
throttle_slew_limit(); throttle_slew_limit();
} }
// Auto flap deployment
if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) {
if(control_mode < FLY_BY_WIRE_B) { if(control_mode < FLY_BY_WIRE_B) {
// only use radio_in if the channel is not used as flight_mode_channel // only use radio_in if the channel is not used as flight_mode_channel
if (g_rc_function[RC_Channel_aux::k_flap_auto] != rc_array[g.flight_mode_channel-1]) { if (g_rc_function[RC_Channel_aux::k_flap_auto] != rc_array[g.flight_mode_channel-1]) {
G_RC_AUX(k_flap_auto)->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_in; g_rc_function[RC_Channel_aux::k_flap_auto]->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_in;
} else { } else {
G_RC_AUX(k_flap_auto)->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_trim; g_rc_function[RC_Channel_aux::k_flap_auto]->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_trim;
} }
} else if (control_mode >= FLY_BY_WIRE_B) { } else if (control_mode >= FLY_BY_WIRE_B) {
if (control_mode == FLY_BY_WIRE_B) { if (control_mode == FLY_BY_WIRE_B) {
@ -371,13 +373,14 @@ static void set_servos(void)
flapSpeedSource = g.throttle_cruise; flapSpeedSource = g.throttle_cruise;
} }
if ( flapSpeedSource > g.flap_1_speed) { if ( flapSpeedSource > g.flap_1_speed) {
G_RC_AUX(k_flap_auto)->servo_out = 0; g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = 0;
} else if (flapSpeedSource > g.flap_2_speed) { } else if (flapSpeedSource > g.flap_2_speed) {
G_RC_AUX(k_flap_auto)->servo_out = g.flap_1_percent; g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = g.flap_1_percent;
} else { } else {
G_RC_AUX(k_flap_auto)->servo_out = g.flap_2_percent; g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = g.flap_2_percent;
}
g_rc_function[RC_Channel_aux::k_flap_auto]->calc_pwm();
} }
G_RC_AUX(k_flap_auto)->calc_pwm();
} }
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS #if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS