Browse Source

AP_Rally: tidy creation of Location from RallyLocation

apm_2208
Peter Barker 3 years ago committed by Peter Barker
parent
commit
da2b530ce8
  1. 23
      libraries/AP_Rally/AP_Rally.cpp

23
libraries/AP_Rally/AP_Rally.cpp

@ -122,18 +122,17 @@ bool AP_Rally::set_rally_point_with_index(uint8_t i, const RallyLocation &rallyL
// helper function to translate a RallyLocation to a Location // helper function to translate a RallyLocation to a Location
Location AP_Rally::rally_location_to_location(const RallyLocation &rally_loc) const Location AP_Rally::rally_location_to_location(const RallyLocation &rally_loc) const
{ {
Location ret = {}; //Relative altitudes are relative to HOME point's altitude:
Location ret {
// we return an absolute altitude, as we add homeloc.alt below rally_loc.lat,
ret.relative_alt = false; rally_loc.lng,
rally_loc.alt * 100,
//Currently can't do true AGL on the APM. Relative altitudes are Location::AltFrame::ABOVE_HOME
//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 = (rally_loc.alt*100UL) + AP::ahrs().get_home().alt; // notionally the following call can fail, but we have no facility
// to return that fact here:
ret.lat = rally_loc.lat; ret.change_alt_frame(Location::AltFrame::ABSOLUTE);
ret.lng = rally_loc.lng;
return ret; return ret;
} }

Loading…
Cancel
Save