AP_HAL_SITL: populate first rangefinder distance if unused

This commit is contained in:
Iampete1 2020-07-29 09:26:36 +01:00 committed by Andrew Tridgell
parent 123d7e4683
commit a1eb284349

View File

@ -65,6 +65,11 @@ void SITL_State::_update_rangefinder(float range_value)
}
}
// if not populated also fill out the STIL rangefinder array
if (is_equal(_sitl->state.rangefinder_m[0],-1.0f)) {
_sitl->state.rangefinder_m[0] = altitude;
}
sonar_pin_value = 1023 * (voltage / 5.0f);
}