Copter: Improve comments on thrust_loss_check()

Co-authored-by: Iampete1 <iampete@hotmail.co.uk>
This commit is contained in:
Leonard Hall 2024-06-20 11:52:51 +09:30 committed by Randy Mackay
parent ebae1ab10c
commit f0dff02e79

View File

@ -96,7 +96,12 @@ void Copter::crash_check()
}
}
// check for loss of thrust and trigger thrust boost in motors library
// thrust_loss_check - returns true when the aircraft detects for 1 second that it is:
// above 90% demanded thrust or high thrust saturation,,
// less than 15 degrees lean angle target,
// less than 30 degrees of attitude error,
// is descending.
// This check provides a warning that the aircraft is near it's maximum thrust limits and is used trigger thrust boost algorithm in the motors library
void Copter::thrust_loss_check()
{
static uint16_t thrust_loss_counter; // number of iterations vehicle may have been crashed