Browse Source

AP_Common: remove weird cast of location object

c415-sdk
Peter Barker 4 years ago committed by Andrew Tridgell
parent
commit
4abf854c45
  1. 2
      libraries/AP_Common/Location.cpp

2
libraries/AP_Common/Location.cpp

@ -120,7 +120,7 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const @@ -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

Loading…
Cancel
Save