mirror of https://github.com/ArduPilot/ardupilot
APM: fixed additional aileron channels in manual mode
This commit is contained in:
parent
024e5c3cc7
commit
8c0296b27a
|
@ -358,9 +358,9 @@ static void set_servos(void)
|
||||||
}
|
}
|
||||||
g.channel_throttle.radio_out = g.channel_throttle.radio_in;
|
g.channel_throttle.radio_out = g.channel_throttle.radio_in;
|
||||||
g.channel_rudder.radio_out = g.channel_rudder.radio_in;
|
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 ?
|
// ensure flaps and extra aileron channels are updated
|
||||||
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_aileron);
|
RC_Channel_aux::set_radio(RC_Channel_aux::k_aileron, g.channel_roll.radio_out);
|
||||||
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_flap_auto);
|
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_flap_auto);
|
||||||
//RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_dspoiler1);
|
//RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_dspoiler1);
|
||||||
//RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_dspoiler2);
|
//RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_dspoiler2);
|
||||||
|
|
Loading…
Reference in New Issue