mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
More optimizations
I forgot these ones.
This commit is contained in:
parent
42431fd227
commit
ea27d1604a
@ -287,14 +287,18 @@ static void set_servos(void)
|
||||
g.channel_rudder.radio_out = g.channel_rudder.radio_in;
|
||||
// FIXME To me it does not make sense to control the aileron using radio_in in manual mode
|
||||
// Doug could you please take a look at this ?
|
||||
if (g_rc_function[RC_Channel_aux::k_aileron]) {
|
||||
if (g_rc_function[RC_Channel_aux::k_aileron] != rc_array[g.flight_mode_channel-1]) {
|
||||
G_RC_AUX(k_aileron)->radio_out = g_rc_function[RC_Channel_aux::k_aileron]->radio_in;
|
||||
g_rc_function[RC_Channel_aux::k_aileron]->radio_out = g_rc_function[RC_Channel_aux::k_aileron]->radio_in;
|
||||
}
|
||||
}
|
||||
// only use radio_in if the channel is not used as flight_mode_channel
|
||||
if (g_rc_function[RC_Channel_aux::k_flap_auto]) {
|
||||
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 (g.mix_mode == 0) {
|
||||
|
Loading…
Reference in New Issue
Block a user