ArduPlane: make rangefinder ranges m rather than cm

This commit is contained in:
Sebastian Quilter 2021-10-18 16:45:34 +11:00 committed by Peter Barker
parent 0276c165ed
commit 013de11916
1 changed files with 1 additions and 1 deletions

View File

@ -643,7 +643,7 @@ void Plane::rangefinder_terrain_correction(float &height)
*/
void Plane::rangefinder_height_update(void)
{
float distance = rangefinder.distance_cm_orient(ROTATION_PITCH_270)*0.01f;
float distance = rangefinder.distance_orient(ROTATION_PITCH_270);
if ((rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::Good) && ahrs.home_is_set()) {
if (!rangefinder_state.have_initial_reading) {