APM: fixed auto-takeoff with zero lat/lng

consider a non-zero altitude to mean that we should use the relative
altitude specified
This commit is contained in:
Andrew Tridgell 2012-10-11 15:03:00 +11:00
parent 2af5ff896d
commit 6de0566404

View File

@ -88,7 +88,7 @@ static struct Location get_cmd_with_index(int16_t i)
// Add on home altitude if we are a nav command (or other command with altitude) and stored alt is relative
if ((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) &&
(temp.options & MASK_OPTIONS_RELATIVE_ALT) &&
(temp.lat != 0 || temp.lng != 0)) {
(temp.lat != 0 || temp.lng != 0 || tmp.alt != 0)) {
temp.alt += home.alt;
}