Copter: fixed comment on get_pilot_desired_yaw_rate

This commit is contained in:
Andrew Tridgell 2015-07-27 12:03:48 +10:00 committed by Randy Mackay
parent 1b1bc9f3b1
commit 954cfde741
1 changed files with 3 additions and 3 deletions

View File

@ -36,9 +36,9 @@ void Copter::get_pilot_desired_lean_angles(float roll_in, float pitch_in, float
pitch_out = pitch_in;
}
// get_pilot_desired_heading - transform pilot's yaw input into a desired heading
// returns desired angle in centi-degrees
// To-Do: return heading as a float?
// get_pilot_desired_heading - transform pilot's yaw input into a
// desired yaw rate
// returns desired yaw rate in centi-degrees per second
float Copter::get_pilot_desired_yaw_rate(int16_t stick_angle)
{
// convert pilot input to the desired yaw rate