diff --git a/ArduPlane/rally.pde b/ArduPlane/rally.pde index 9764411743..b2508c66fb 100644 --- a/ArduPlane/rally.pde +++ b/ArduPlane/rally.pde @@ -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;