From c49a914597a98a961adf497d0960367d0d895137 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 2 Feb 2016 21:27:42 +0900 Subject: [PATCH] AC_AttControlHeli: remove unnecessary virtual declaration --- libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h index f8a2994267..d738ab740d 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h @@ -96,7 +96,7 @@ private: // rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target body-frame rate (in radians/sec) for roll, pitch and yaw // outputs are sent directly to motor class void rate_bf_to_motor_roll_pitch(float rate_roll_target_rads, float rate_pitch_target_rads); - virtual float rate_bf_to_motor_yaw(float rate_yaw_rads); + float rate_bf_to_motor_yaw(float rate_yaw_rads); // // throttle methods