AC_PosControl: Enable altitude limit checking.

This commit is contained in:
Robert Lefebvre 2015-01-28 16:29:18 -05:00 committed by Randy Mackay
parent 79cad28a25
commit 02f3f96310
1 changed files with 2 additions and 2 deletions

View File

@ -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) 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 // adjust desired alt if motors have not hit their limits
// To-Do: add check of _limit.pos_up and _limit.pos_down? // 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)) { 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; _pos_target.z += climb_rate_cms * dt;
} }