Optimize the code a bit more, only perform calculations if they are necessary

This commit is contained in:
Amilcar Lucas 2011-10-09 15:25:20 +02:00
parent 02f023a9ec
commit 282722eae6

View File

@ -355,12 +355,14 @@ static void set_servos(void)
throttle_slew_limit();
}
// Auto flap deployment
if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) {
if(control_mode < FLY_BY_WIRE_B) {
// 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]) {
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 {
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) {
if (control_mode == FLY_BY_WIRE_B) {
@ -370,7 +372,6 @@ static void set_servos(void)
} else {
flapSpeedSource = g.throttle_cruise;
}
if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) {
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) {
@ -395,7 +396,7 @@ static void set_servos(void)
g.rc_7.output_ch(CH_7);
g.rc_8.output_ch(CH_8);
#endif
}
}
static void demo_servos(byte i) {