Browse Source

AP_HAL_SITL: populate first rangefinder distance if unused

c415-sdk
Iampete1 5 years ago committed by Andrew Tridgell
parent
commit
a1eb284349
  1. 5
      libraries/AP_HAL_SITL/sitl_rangefinder.cpp

5
libraries/AP_HAL_SITL/sitl_rangefinder.cpp

@ -65,6 +65,11 @@ void SITL_State::_update_rangefinder(float range_value) @@ -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);
}

Loading…
Cancel
Save