From 13cccdfe9536f2da3441ea38c9eb6b29892916e3 Mon Sep 17 00:00:00 2001 From: Phil <philcole1234@gmail.com> Date: Tue, 27 Dec 2011 00:42:50 -0800 Subject: [PATCH] Fix rudder in elevon mode. Don't know what to do about the reversing switch. --- ArduPlane/APM_Config.h | 2 +- ArduPlane/Attitude.pde | 2 +- ArduPlane/radio.pde | 5 ++--- ArduPlane/test.pde | 1 + 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduPlane/APM_Config.h b/ArduPlane/APM_Config.h index 88ceaf7f8..472e77123 100644 --- a/ArduPlane/APM_Config.h +++ b/ArduPlane/APM_Config.h @@ -37,4 +37,4 @@ #define THROTTLE_FAILSAFE ENABLED */ -# define CONFIG_APM_HARDWARE APM_HARDWARE_APM1 +//# define CONFIG_APM_HARDWARE APM_HARDWARE_APM1 diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 08a950213..e8b0e7021 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -314,7 +314,6 @@ static void set_servos(void) if (g.mix_mode == 0) { g.channel_roll.calc_pwm(); g.channel_pitch.calc_pwm(); - g.channel_rudder.calc_pwm(); if (g_rc_function[RC_Channel_aux::k_aileron]) { g_rc_function[RC_Channel_aux::k_aileron]->servo_out = g.channel_roll.servo_out; g_rc_function[RC_Channel_aux::k_aileron]->calc_pwm(); @@ -329,6 +328,7 @@ static void set_servos(void) g.channel_roll.radio_out = elevon1_trim + (BOOL_TO_SIGN(g.reverse_ch1_elevon) * (ch1 * 500.0/ SERVO_MAX)); g.channel_pitch.radio_out = elevon2_trim + (BOOL_TO_SIGN(g.reverse_ch2_elevon) * (ch2 * 500.0/ SERVO_MAX)); } + g.channel_rudder.calc_pwm(); #if THROTTLE_OUT == 0 g.channel_throttle.servo_out = 0; diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index e0a8b870b..0db507a17 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -158,7 +158,6 @@ 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; - g.channel_rudder.radio_trim = g.channel_rudder.radio_in; G_RC_AUX(k_aileron)->radio_trim = g_rc_function[RC_Channel_aux::k_aileron]->radio_in; // Second aileron channel }else{ @@ -170,6 +169,7 @@ static void trim_control_surfaces() g.channel_roll.radio_trim = center; g.channel_pitch.radio_trim = center; } + g.channel_rudder.radio_trim = g.channel_rudder.radio_in; // save to eeprom g.channel_roll.save_eeprom(); @@ -191,7 +191,6 @@ static void trim_radio() g.channel_roll.radio_trim = g.channel_roll.radio_in; g.channel_pitch.radio_trim = g.channel_pitch.radio_in; //g.channel_throttle.radio_trim = g.channel_throttle.radio_in; - g.channel_rudder.radio_trim = g.channel_rudder.radio_in; G_RC_AUX(k_aileron)->radio_trim = g_rc_function[RC_Channel_aux::k_aileron]->radio_in; // Second aileron channel } else { @@ -200,8 +199,8 @@ static void trim_radio() 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; } + g.channel_rudder.radio_trim = g.channel_rudder.radio_in; // save to eeprom g.channel_roll.save_eeprom(); diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde index e4ebfdcfa..8f0259dfc 100644 --- a/ArduPlane/test.pde +++ b/ArduPlane/test.pde @@ -432,6 +432,7 @@ test_dipswitches(uint8_t argc, const Menu::arg *argv) (int)g.reverse_elevons, (int)g.reverse_ch1_elevon, (int)g.reverse_ch2_elevon); + //(int)g.channel_rudder.get_reverse()); No reversing switch for rudder in elevon mode. } if(Serial.available() > 0){ return (0); -- GitLab