mirror of https://github.com/ArduPilot/ardupilot
RangeFinder_PulsedLight: set status
This commit is contained in:
parent
aa04bef5af
commit
e212ebb0d0
|
@ -109,5 +109,10 @@ bool AP_RangeFinder_PulsedLightLRF::get_reading(uint16_t &reading_cm)
|
|||
*/
|
||||
void AP_RangeFinder_PulsedLightLRF::update(void)
|
||||
{
|
||||
state.healthy = get_reading(state.distance_cm);
|
||||
if (get_reading(state.distance_cm)) {
|
||||
// update range_valid state based on distance measured
|
||||
update_status();
|
||||
} else {
|
||||
set_status(RangeFinder::RangeFinder_NoData);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue