mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_Common: remove weird cast of location object
This commit is contained in:
parent
27089b4d2b
commit
4abf854c45
@ -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…
Reference in New Issue
Block a user