mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: don't change trims if radio_in is zero
This commit is contained in:
parent
9b4c75c66b
commit
9178022a73
@ -176,23 +176,33 @@ static void trim_control_surfaces()
|
||||
// Store control surface trim values
|
||||
// ---------------------------------
|
||||
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;
|
||||
if (g.channel_roll.radio_in != 0) {
|
||||
g.channel_roll.radio_trim = g.channel_roll.radio_in;
|
||||
}
|
||||
if (g.channel_pitch.radio_in != 0) {
|
||||
g.channel_pitch.radio_trim = g.channel_pitch.radio_in;
|
||||
}
|
||||
|
||||
// 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;
|
||||
if (ch1_temp != 0) {
|
||||
elevon1_trim = ch1_temp;
|
||||
}
|
||||
if (ch2_temp != 0) {
|
||||
elevon2_trim = ch2_temp;
|
||||
}
|
||||
//Recompute values here using new values for elevon1_trim and elevon2_trim
|
||||
//We cannot use radio_in[CH_ROLL] and radio_in[CH_PITCH] values from read_radio() because the elevon trim values have changed
|
||||
uint16_t center = 1500;
|
||||
g.channel_roll.radio_trim = center;
|
||||
g.channel_pitch.radio_trim = center;
|
||||
}
|
||||
g.channel_rudder.radio_trim = g.channel_rudder.radio_in;
|
||||
if (g.channel_rudder.radio_in != 0) {
|
||||
g.channel_rudder.radio_trim = g.channel_rudder.radio_in;
|
||||
}
|
||||
|
||||
// save to eeprom
|
||||
g.channel_roll.save_eeprom();
|
||||
|
Loading…
Reference in New Issue
Block a user