mirror of https://github.com/ArduPilot/ardupilot
Plane: added secondary elevator support
This commit is contained in:
parent
5d91b06de3
commit
b9a5be6c8b
|
@ -447,11 +447,18 @@ 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);
|
||||
|
||||
// setup extra elevator channel following the same logic
|
||||
int16_t elevator_in = g.channel_pitch.pwm_to_angle_dz(0);
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_elevator, elevator_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);
|
||||
|
||||
// do the same for the corresponding elevator variant
|
||||
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_elevator_with_input);
|
||||
|
||||
// copy flap control from transmitter
|
||||
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_flap_auto);
|
||||
|
||||
|
@ -466,6 +473,10 @@ static void set_servos(void)
|
|||
// 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);
|
||||
|
||||
// both types of secondary elevator are slaved to the pitch servo out
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_elevator, g.channel_pitch.servo_out);
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_elevator_with_input, g.channel_pitch.servo_out);
|
||||
}else{
|
||||
/*Elevon mode*/
|
||||
float ch1;
|
||||
|
|
|
@ -48,5 +48,6 @@ void failsafe_check(uint32_t tnow)
|
|||
}
|
||||
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_manual, true);
|
||||
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_aileron_with_input, true);
|
||||
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_elevator_with_input, true);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -183,10 +183,11 @@ static void trim_control_surfaces()
|
|||
g.channel_pitch.radio_trim = g.channel_pitch.radio_in;
|
||||
}
|
||||
|
||||
// the secondary aileron is trimmed only if it has a
|
||||
// the secondary aileron/elevator 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);
|
||||
RC_Channel_aux::set_radio_trim(RC_Channel_aux::k_elevator_with_input);
|
||||
} else{
|
||||
if (ch1_temp != 0) {
|
||||
elevon1_trim = ch1_temp;
|
||||
|
|
Loading…
Reference in New Issue