AP_Common: remove weird cast of location object

This commit is contained in:
Peter Barker 2021-06-08 09:31:58 +10:00 committed by Andrew Tridgell
parent 27089b4d2b
commit 4abf854c45

View File

@ -120,7 +120,7 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
float alt_terr_cm = 0;
if (frame == AltFrame::ABOVE_TERRAIN || desired_frame == AltFrame::ABOVE_TERRAIN) {
#if AP_TERRAIN_AVAILABLE
if (_terrain == nullptr || !_terrain->height_amsl(*(Location *)this, alt_terr_cm, true)) {
if (_terrain == nullptr || !_terrain->height_amsl(*this, alt_terr_cm, true)) {
return false;
}
// convert terrain alt to cm