mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AC_PosControl: Enable altitude limit checking.
This commit is contained in:
parent
79cad28a25
commit
02f3f96310
@ -137,8 +137,8 @@ void AC_PosControl::set_alt_target_with_slew(float alt_cm, float dt)
|
||||
void AC_PosControl::set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
|
||||
{
|
||||
// adjust desired alt if motors have not hit their limits
|
||||
// To-Do: add check of _limit.pos_up and _limit.pos_down?
|
||||
if ((climb_rate_cms<0 && (!_motors.limit.throttle_lower || force_descend)) || (climb_rate_cms>0 && !_motors.limit.throttle_upper)) {
|
||||
// To-Do: add check of _limit.pos_down?
|
||||
if ((climb_rate_cms<0 && (!_motors.limit.throttle_lower || force_descend)) || (climb_rate_cms>0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
|
||||
_pos_target.z += climb_rate_cms * dt;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user