AP_RangeFinder: MaxsonarI2C reports no data after 300ms
This commit is contained in:
parent
4b4e66e2bd
commit
98e87db274
@ -133,6 +133,7 @@ void AP_RangeFinder_MaxsonarI2CXL::_timer(void)
|
|||||||
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||||
distance = d;
|
distance = d;
|
||||||
new_distance = true;
|
new_distance = true;
|
||||||
|
last_update_ms = AP_HAL::millis();
|
||||||
_sem->give();
|
_sem->give();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -148,7 +149,8 @@ void AP_RangeFinder_MaxsonarI2CXL::update(void)
|
|||||||
state.distance_cm = distance;
|
state.distance_cm = distance;
|
||||||
new_distance = false;
|
new_distance = false;
|
||||||
update_status();
|
update_status();
|
||||||
} else {
|
} else if (AP_HAL::millis() - last_update_ms > 300) {
|
||||||
|
// if no updates for 0.3 seconds set no-data
|
||||||
set_status(RangeFinder::RangeFinder_NoData);
|
set_status(RangeFinder::RangeFinder_NoData);
|
||||||
}
|
}
|
||||||
_sem->give();
|
_sem->give();
|
||||||
|
@ -39,6 +39,7 @@ private:
|
|||||||
|
|
||||||
uint16_t distance;
|
uint16_t distance;
|
||||||
bool new_distance;
|
bool new_distance;
|
||||||
|
uint32_t last_update_ms;
|
||||||
|
|
||||||
// start a reading
|
// start a reading
|
||||||
bool start_reading(void);
|
bool start_reading(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user