mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AC_WPNav: use rangefinder for terrain offset even if terrain not available
This commit is contained in:
parent
ab68e4fe8b
commit
fa0b315374
@ -973,17 +973,16 @@ void AC_WPNav::calc_spline_pos_vel(float spline_time, Vector3f& position, Vector
|
||||
// get terrain's altitude (in cm above the ekf origin) at the current position (+ve means terrain below vehicle is above ekf origin's altitude)
|
||||
bool AC_WPNav::get_terrain_offset(float& offset_cm)
|
||||
{
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
// use range finder if connected
|
||||
if (_rangefinder_available && _rangefinder_use) {
|
||||
if (_rangefinder_healthy) {
|
||||
offset_cm = _inav.get_altitude() - _rangefinder_alt_cm;
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
// use terrain database
|
||||
float terr_alt = 0.0f;
|
||||
if (_terrain != nullptr && _terrain->height_above_terrain(terr_alt, true)) {
|
||||
|
Loading…
Reference in New Issue
Block a user