mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
APM: fixed typo
This commit is contained in:
parent
6de0566404
commit
9226d94902
@ -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 || tmp.alt != 0)) {
|
||||
(temp.lat != 0 || temp.lng != 0 || temp.alt != 0)) {
|
||||
temp.alt += home.alt;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user