From 61f2e18e2eece48cbef43ee08c7d1628c8b7a105 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 21 Nov 2012 13:19:32 +1100 Subject: [PATCH] APM: allow ailerons to move fully during servo demo --- ArduPlane/Attitude.pde | 4 ++++ ArduPlane/failsafe.pde | 6 +++++- 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 3e3f991873..6fc9691e61 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -508,10 +508,13 @@ static void set_servos(void) #endif } +static bool demoing_servos; + static void demo_servos(byte i) { while(i > 0) { gcs_send_text_P(SEVERITY_LOW,PSTR("Demo Servos!")); + demoing_servos = true; #if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS APM_RC.OutputCh(1, 1400); mavlink_delay(400); @@ -519,6 +522,7 @@ static void demo_servos(byte i) { mavlink_delay(200); APM_RC.OutputCh(1, 1500); #endif + demoing_servos = false; mavlink_delay(400); i--; } diff --git a/ArduPlane/failsafe.pde b/ArduPlane/failsafe.pde index 50c267f92e..1aa2048152 100644 --- a/ArduPlane/failsafe.pde +++ b/ArduPlane/failsafe.pde @@ -39,7 +39,11 @@ void failsafe_check(uint32_t tnow) // pass RC inputs to outputs every 20ms last_timestamp = tnow; APM_RC.clearOverride(); - for (uint8_t ch=0; ch<4; ch++) { + uint8_t start_ch = 0; + if (demoing_servos) { + start_ch = 1; + } + for (uint8_t ch=start_ch; ch<4; ch++) { APM_RC.OutputCh(ch, APM_RC.InputCh(ch)); } RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_manual);