mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Only use radio_in values if the channel is not used as flight_mode_channel
This commit is contained in:
parent
b98c681a92
commit
6a5d6889b7
@ -263,6 +263,17 @@ static void set_servos(void)
|
||||
{
|
||||
int flapSpeedSource = 0;
|
||||
|
||||
// vectorize the rc channels
|
||||
RC_Channel_aux* rc_array[NUM_CHANNELS];
|
||||
rc_array[CH_1] = NULL;
|
||||
rc_array[CH_2] = NULL;
|
||||
rc_array[CH_3] = NULL;
|
||||
rc_array[CH_4] = NULL;
|
||||
rc_array[CH_5] = &g.rc_5;
|
||||
rc_array[CH_6] = &g.rc_6;
|
||||
rc_array[CH_7] = &g.rc_7;
|
||||
rc_array[CH_8] = &g.rc_8;
|
||||
|
||||
if(control_mode == MANUAL){
|
||||
// do a direct pass through of radio values
|
||||
if (g.mix_mode == 0){
|
||||
@ -274,9 +285,15 @@ static void set_servos(void)
|
||||
}
|
||||
g.channel_throttle.radio_out = g.channel_throttle.radio_in;
|
||||
g.channel_rudder.radio_out = g.channel_rudder.radio_in;
|
||||
G_RC_AUX(k_aileron)->radio_out = g_rc_function[RC_Channel_aux::k_aileron]->radio_in;
|
||||
G_RC_AUX(k_flap_auto)->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->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] != rc_array[g.flight_mode_channel-1])
|
||||
G_RC_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] != 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;
|
||||
else
|
||||
G_RC_AUX(k_flap_auto)->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_trim;
|
||||
} else {
|
||||
if (g.mix_mode == 0) {
|
||||
g.channel_roll.calc_pwm();
|
||||
@ -337,7 +354,11 @@ static void set_servos(void)
|
||||
}
|
||||
|
||||
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
|
||||
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;
|
||||
else
|
||||
G_RC_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) {
|
||||
flapSpeedSource = airspeed_fbwB/100;
|
||||
|
Loading…
Reference in New Issue
Block a user