From c7ccd22d96f2430b6edc64fe1deaa90024ef33ab Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Sun, 11 May 2014 19:19:01 -0400 Subject: [PATCH] TradHeli: Set main loop rate time in motors class. --- ArduCopter/heli.pde | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/heli.pde b/ArduCopter/heli.pde index c0f418384f..abd9303456 100644 --- a/ArduCopter/heli.pde +++ b/ArduCopter/heli.pde @@ -17,6 +17,7 @@ static int8_t heli_dynamic_flight_counter; static void heli_init() { attitude_control.update_feedforward_filter_rates(MAIN_LOOP_SECONDS); + motors.set_dt(MAIN_LOOP_SECONDS); } // get_pilot_desired_collective - converts pilot input (from 0 ~ 1000) to a value that can be fed into the g.rc_3.servo_out function