AC_AttControlHeli: remove unnecessary virtual declaration

This commit is contained in:
Randy Mackay 2016-02-02 21:27:42 +09:00
parent 2b123ee15d
commit c49a914597
1 changed files with 1 additions and 1 deletions

View File

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