mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: fix rangefinder correction when terrain follow is off
This commit is contained in:
parent
dc8335dfd6
commit
bdc08ba354
@ -711,9 +711,8 @@ void Plane::rangefinder_height_update(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (rangefinder_state.in_range) {
|
if (rangefinder_state.in_range) {
|
||||||
// base correction is the difference between baro altitude and
|
// If not using terrain data, we expect zero correction when our height above target is equal to our rangefinder measurement
|
||||||
// rangefinder estimate
|
float correction = height_above_target() - rangefinder_state.height_estimate;
|
||||||
float correction = adjusted_relative_altitude_cm()*0.01 - rangefinder_state.height_estimate;
|
|
||||||
|
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE
|
||||||
// if we are terrain following then correction is based on terrain data
|
// if we are terrain following then correction is based on terrain data
|
||||||
|
Loading…
Reference in New Issue
Block a user