mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
GeoFence: fixed default return altitude units
off by 100x!
This commit is contained in:
parent
1b98bddaae
commit
85332ff85b
@ -261,7 +261,7 @@ static void geofence_check(bool altitude_check_only)
|
||||
// min and max
|
||||
if (g.fence_minalt >= g.fence_maxalt) {
|
||||
// invalid min/max, use RTL_altitude
|
||||
guided_WP.alt = home.alt + (g.RTL_altitude * 100);
|
||||
guided_WP.alt = home.alt + g.RTL_altitude;
|
||||
} else {
|
||||
guided_WP.alt = home.alt + 100*(g.fence_minalt + g.fence_maxalt)/2;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user