From e1902e2289e7486bf4f8e52ad9a676d2c8ddac28 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Fri, 26 Jun 2015 16:19:17 -0400 Subject: [PATCH] AP_MotorsHeli: Remove unused _dt variable. --- libraries/AP_Motors/AP_MotorsHeli.h | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 305fc5319d..d6b3244e95 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -313,7 +313,6 @@ private: float _rsc_runup_increment; // the amount we can increase the rotor's estimated speed during each 100hz iteration float _rotor_speed_estimate; // estimated speed of the main rotor (0~1000) int16_t _tail_direct_drive_out; // current ramped speed of output on ch7 when using direct drive variable pitch tail type - float _dt; // main loop time int16_t _delta_phase_angle; // phase angle dynamic compensation int16_t _roll_radio_passthrough; // roll control PWM direct from radio, used for manual control int16_t _pitch_radio_passthrough; // pitch control PWM direct from radio, used for manual control