TradHeli: Set main loop rate time in motors class.

This commit is contained in:
Robert Lefebvre 2014-05-11 19:19:01 -04:00 committed by Randy Mackay
parent 0680b88abd
commit c7ccd22d96

View File

@ -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