From 238a1ced2c8dc778f44e20fa0ae433c519e3c524 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Thu, 7 Jun 2012 22:55:47 -0400 Subject: [PATCH] TradHeli adding ramp up time to Ch8 Throttle Pass-through. --- libraries/AP_Motors/AP_MotorsHeli.cpp | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index 71b97c89d6..133e258818 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -490,10 +490,16 @@ void AP_MotorsHeli::ext_esc_control() switch ( AP_MOTORS_ESC_MODE_PASSTHROUGH ) { case AP_MOTORS_ESC_MODE_PASSTHROUGH: - if( armed() ){ - _rc->OutputCh(AP_MOTORS_HELI_EXT_ESC, _rc_8->radio_in); - } else { + if( armed() && _rc_8->control_in > 10 ){ + if (ext_esc_ramp < AP_MOTORS_EXT_ESC_RAMP_UP){ + ext_esc_ramp++; + ext_esc_output = map(ext_esc_ramp, 0, AP_MOTORS_EXT_ESC_RAMP_UP, 1000, _rc_8->control_in); + } else { + ext_esc_output = _rc_8->control_in; + } + } else if( !armed() ) { _rc->OutputCh(AP_MOTORS_HELI_EXT_ESC, _rc_8->radio_min); + ext_esc_ramp = 0; //Return ESC Ramp to 0 } break;