mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-07 00:18:29 -04:00
Copter: Improve comments on thrust_loss_check()
Co-authored-by: Iampete1 <iampete@hotmail.co.uk>
This commit is contained in:
parent
ebae1ab10c
commit
f0dff02e79
@ -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()
|
void Copter::thrust_loss_check()
|
||||||
{
|
{
|
||||||
static uint16_t thrust_loss_counter; // number of iterations vehicle may have been crashed
|
static uint16_t thrust_loss_counter; // number of iterations vehicle may have been crashed
|
||||||
|
Loading…
Reference in New Issue
Block a user