Skip to content

Commit

Permalink
Copter: Improve comments on thrust_loss_check()
Browse files Browse the repository at this point in the history
  • Loading branch information
lthall committed Jun 20, 2024
1 parent 89cd17d commit 16c7a4c
Showing 1 changed file with 6 additions and 1 deletion.
7 changes: 6 additions & 1 deletion ArduCopter/crash_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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% thrust,
// 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
Expand Down

0 comments on commit 16c7a4c

Please sign in to comment.