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

@ -351,35 +351,38 @@ static void set_servos(void)
radio_out[CH_THROTTLE] = radio_max(CH_THROTTLE) + radio_min(CH_THROTTLE) - radio_out[CH_THROTTLE]; radio_out[CH_THROTTLE] = radio_max(CH_THROTTLE) + radio_min(CH_THROTTLE) - radio_out[CH_THROTTLE];
#endif #endif
*/ */
throttle_slew_limit(); throttle_slew_limit();
} }
if(control_mode < FLY_BY_WIRE_B) { // Auto flap deployment
// only use radio_in if the channel is not used as flight_mode_channel if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) {
if (g_rc_function[RC_Channel_aux::k_flap_auto] != rc_array[g.flight_mode_channel-1]) { if(control_mode < FLY_BY_WIRE_B) {
G_RC_AUX(k_flap_auto)->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_in; // only use radio_in if the channel is not used as flight_mode_channel
} else { 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_trim; g_rc_function[RC_Channel_aux::k_flap_auto]->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_in;
} } else {
} else if (control_mode >= FLY_BY_WIRE_B) { g_rc_function[RC_Channel_aux::k_flap_auto]->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_trim;
if (control_mode == FLY_BY_WIRE_B) { }
flapSpeedSource = airspeed_fbwB/100; } else if (control_mode >= FLY_BY_WIRE_B) {
} else if (g.airspeed_enabled == true) { if (control_mode == FLY_BY_WIRE_B) {
flapSpeedSource = g.airspeed_cruise/100; flapSpeedSource = airspeed_fbwB/100;
} else { } else if (g.airspeed_enabled == true) {
flapSpeedSource = g.throttle_cruise; flapSpeedSource = g.airspeed_cruise/100;
} else {
flapSpeedSource = g.throttle_cruise;
}
if ( flapSpeedSource > g.flap_1_speed) {
g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = 0;
} else if (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;
}
g_rc_function[RC_Channel_aux::k_flap_auto]->calc_pwm();
} }
if ( flapSpeedSource > g.flap_1_speed) {
G_RC_AUX(k_flap_auto)->servo_out = 0;
} else if (flapSpeedSource > g.flap_2_speed) {
G_RC_AUX(k_flap_auto)->servo_out = g.flap_1_percent;
} else {
G_RC_AUX(k_flap_auto)->servo_out = g.flap_2_percent;
}
G_RC_AUX(k_flap_auto)->calc_pwm();
} }
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS #if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS
// send values to the PWM timers for output // send values to the PWM timers for output
// ---------------------------------------- // ----------------------------------------
@ -393,7 +396,7 @@ static void set_servos(void)
g.rc_7.output_ch(CH_7); g.rc_7.output_ch(CH_7);
g.rc_8.output_ch(CH_8); g.rc_8.output_ch(CH_8);
#endif #endif
} }
static void demo_servos(byte i) { static void demo_servos(byte i) {