Skip to content
Snippets Groups Projects
Commit 294b6699 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

Plane: fixed rally altitude to be in meters

this matches the docs
parent ede927f6
No related branches found
Tags ArduCopter-3.1.0-rc4
No related merge requests found
......@@ -73,7 +73,7 @@ static Location rally_location_to_location(const RallyLocation &r_loc, const Loc
//Currently can't do true AGL on the APM. Relative altitudes are
//relative to HOME point's altitude. Terrain on the board is inbound
//for the PX4, though. This line will need to be updated when that happens:
ret.alt = r_loc.alt + homeloc.alt;
ret.alt = (r_loc.alt*100UL) + homeloc.alt;
ret.lat = r_loc.lat;
ret.lng = r_loc.lng;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment