mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Rally: tidy creation of Location from RallyLocation
This commit is contained in:
parent
591f43e7d0
commit
da2b530ce8
@ -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 {
|
||||||
|
rally_loc.lat,
|
||||||
|
rally_loc.lng,
|
||||||
|
rally_loc.alt * 100,
|
||||||
|
Location::AltFrame::ABOVE_HOME
|
||||||
|
};
|
||||||
|
|
||||||
// we return an absolute altitude, as we add homeloc.alt below
|
// notionally the following call can fail, but we have no facility
|
||||||
ret.relative_alt = false;
|
// to return that fact here:
|
||||||
|
ret.change_alt_frame(Location::AltFrame::ABSOLUTE);
|
||||||
//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 = (rally_loc.alt*100UL) + AP::ahrs().get_home().alt;
|
|
||||||
|
|
||||||
ret.lat = rally_loc.lat;
|
|
||||||
ret.lng = rally_loc.lng;
|
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user