navigator takeoff alt check use altitude acceptance (#8480)

This commit is contained in:
Daniel Agar 2017-12-17 01:39:53 -05:00 committed by GitHub
parent 28d1ec8afe
commit e8624f8afe
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
1 changed files with 2 additions and 2 deletions

View File

@ -870,11 +870,11 @@ Mission::do_need_vertical_takeoff()
/* force takeoff if landed (additional protection) */
_need_takeoff = true;
} else if (_navigator->get_global_position()->alt > takeoff_alt - _navigator->get_acceptance_radius()) {
} else if (_navigator->get_global_position()->alt > takeoff_alt - _navigator->get_altitude_acceptance_radius()) {
/* if in-air and already above takeoff height, don't do takeoff */
_need_takeoff = false;
} else if (_navigator->get_global_position()->alt <= takeoff_alt - _navigator->get_acceptance_radius()
} else if (_navigator->get_global_position()->alt <= takeoff_alt - _navigator->get_altitude_acceptance_radius()
&& (_mission_item.nav_cmd == NAV_CMD_TAKEOFF
|| _mission_item.nav_cmd == NAV_CMD_VTOL_TAKEOFF)) {
/* if in-air but below takeoff height and we have a takeoff item */