We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
There was an error while loading. Please reload this page.
1 parent 44bd77d commit 9e08a98Copy full SHA for 9e08a98
ArduPlane/altitude.cpp
@@ -711,9 +711,8 @@ void Plane::rangefinder_height_update(void)
711
}
712
713
if (rangefinder_state.in_range) {
714
- // base correction is the difference between baro altitude and
715
- // rangefinder estimate
716
- float correction = adjusted_relative_altitude_cm()*0.01 - rangefinder_state.height_estimate;
+ // If not using terrain data, we expect zero correction when our height above target is equal to our rangefinder measurement
+ float correction = height_above_target() - rangefinder_state.height_estimate;
717
718
#if AP_TERRAIN_AVAILABLE
719
// if we are terrain following then correction is based on terrain data
0 commit comments