mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 17:34:01 -04:00
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:
parent
2af5ff896d
commit
6de0566404
@ -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
|
// 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) &&
|
if ((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) &&
|
||||||
(temp.options & MASK_OPTIONS_RELATIVE_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;
|
temp.alt += home.alt;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user