mirror of https://github.com/ArduPilot/ardupilot
APM: added a new type of auxilary aileron, with rc input
a AileronWithInput assumes you have setup your RC transmitter to give the right trim and input on the secondary aileron
This commit is contained in:
parent
5eeb6638f2
commit
3cf492a637
|
@ -368,6 +368,11 @@ static void set_servos(void)
|
|||
int16_t aileron_in = g.channel_roll.pwm_to_angle_dz(0);
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_aileron, aileron_in);
|
||||
|
||||
// this aileron variant assumes you have the corresponding
|
||||
// input channel setup in your transmitter for manual control
|
||||
// of the 2nd aileron
|
||||
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_aileron_with_input);
|
||||
|
||||
// copy flap control from transmitter
|
||||
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_flap_auto);
|
||||
|
||||
|
@ -379,7 +384,9 @@ static void set_servos(void)
|
|||
}
|
||||
} else {
|
||||
if (g.mix_mode == 0) {
|
||||
// both types of secondary aileron are slaved to the roll servo out
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_aileron, g.channel_roll.servo_out);
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_aileron_with_input, g.channel_roll.servo_out);
|
||||
}else{
|
||||
/*Elevon mode*/
|
||||
float ch1;
|
||||
|
|
|
@ -169,7 +169,11 @@ static void trim_control_surfaces()
|
|||
if(g.mix_mode == 0) {
|
||||
g.channel_roll.radio_trim = g.channel_roll.radio_in;
|
||||
g.channel_pitch.radio_trim = g.channel_pitch.radio_in;
|
||||
RC_Channel_aux::set_radio_trim(RC_Channel_aux::k_aileron);
|
||||
|
||||
// the secondary aileron is trimmed only if it has a
|
||||
// corresponding transmitter input channel, which k_aileron
|
||||
// doesn't have
|
||||
RC_Channel_aux::set_radio_trim(RC_Channel_aux::k_aileron_with_input);
|
||||
} else{
|
||||
elevon1_trim = ch1_temp;
|
||||
elevon2_trim = ch2_temp;
|
||||
|
|
Loading…
Reference in New Issue