From ff71b0fa35eefc134b090fb46e6322fb2eea6c76 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Fri, 9 May 2014 17:07:52 -0400 Subject: [PATCH] TradHeli: Create new function to move data between AP_MotorsHeli and AP_AttitudeControl. --- ArduCopter/ArduCopter.pde | 4 ++++ ArduCopter/heli.pde | 14 ++++++++++---- 2 files changed, 14 insertions(+), 4 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 94b6669092..b19f205b3d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -988,6 +988,10 @@ static void fast_loop() // run low level rate controllers that only require IMU data attitude_control.rate_controller_run(); + +#if FRAME_CONFIG == HELI_FRAME + update_heli_control_dynamics(); +#endif //HELI_FRAME // write out the servo PWM values // ------------------------------ diff --git a/ArduCopter/heli.pde b/ArduCopter/heli.pde index 0a354e1f3a..17b2257c5f 100644 --- a/ArduCopter/heli.pde +++ b/ArduCopter/heli.pde @@ -68,8 +68,6 @@ static void check_dynamic_flight(void) if (heli_dynamic_flight_counter >= 100) { heli_flags.dynamic_flight = true; heli_dynamic_flight_counter = 100; - // update attitude control's leaky i term setting - attitude_control.use_leaky_i(!heli_flags.dynamic_flight); } } }else{ @@ -79,13 +77,21 @@ static void check_dynamic_flight(void) heli_dynamic_flight_counter--; }else{ heli_flags.dynamic_flight = false; - // update attitude control's leaky i term setting - attitude_control.use_leaky_i(!heli_flags.dynamic_flight); } } } } +// update_heli_control_dynamics - pushes several important factors up into AP_MotorsHeli. +// should be run between the rate controller and the servo updates. +static void update_heli_control_dynamics(void) +{ + // Use Leaky_I if we are not moving fast + attitude_control.use_leaky_i(!heli_flags.dynamic_flight); + + // To-Do: Update dynamic phase angle of swashplate +} + // heli_update_landing_swash - sets swash plate flag so higher minimum is used when landed or landing // should be called soon after update_land_detector in main code static void heli_update_landing_swash()