mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: populate last_reading_ms in the backend for some sensors
This commit is contained in:
parent
230269bed8
commit
28e472f6d2
|
@ -99,7 +99,7 @@ void AP_RangeFinder_HC_SR04::update(void)
|
||||||
const uint32_t now = AP_HAL::millis();
|
const uint32_t now = AP_HAL::millis();
|
||||||
if (value_us == 0) {
|
if (value_us == 0) {
|
||||||
// no reading; check for timeout:
|
// no reading; check for timeout:
|
||||||
if (now - last_reading_ms > 1000) {
|
if (now - state.last_reading_ms > 1000) {
|
||||||
// no reading for a second - something is broken
|
// no reading for a second - something is broken
|
||||||
state.distance_m = 0.0f;
|
state.distance_m = 0.0f;
|
||||||
}
|
}
|
||||||
|
@ -125,7 +125,7 @@ void AP_RangeFinder_HC_SR04::update(void)
|
||||||
glitch_count = 0;
|
glitch_count = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
last_reading_ms = now;
|
state.last_reading_ms = now;
|
||||||
}
|
}
|
||||||
|
|
||||||
// update range_valid state based on distance measured
|
// update range_valid state based on distance measured
|
||||||
|
|
|
@ -34,7 +34,6 @@ private:
|
||||||
void check_trigger_pin();
|
void check_trigger_pin();
|
||||||
|
|
||||||
int8_t trigger_pin;
|
int8_t trigger_pin;
|
||||||
uint32_t last_reading_ms; // system time of last read (used for health reporting)
|
|
||||||
float last_distance_m; // last distance reported (used to prevent glitches in measurement)
|
float last_distance_m; // last distance reported (used to prevent glitches in measurement)
|
||||||
uint8_t glitch_count; // glitch counter
|
uint8_t glitch_count; // glitch counter
|
||||||
|
|
||||||
|
|
|
@ -468,6 +468,7 @@ void AP_RangeFinder_LightWareI2C::legacy_timer(void)
|
||||||
if (legacy_get_reading(state.distance_m)) {
|
if (legacy_get_reading(state.distance_m)) {
|
||||||
// update range_valid state based on distance measured
|
// update range_valid state based on distance measured
|
||||||
update_status();
|
update_status();
|
||||||
|
state.last_reading_ms = AP_HAL::millis();
|
||||||
} else {
|
} else {
|
||||||
set_status(RangeFinder::Status::NoData);
|
set_status(RangeFinder::Status::NoData);
|
||||||
}
|
}
|
||||||
|
@ -478,6 +479,7 @@ void AP_RangeFinder_LightWareI2C::sf20_timer(void)
|
||||||
if (sf20_get_reading(state.distance_m)) {
|
if (sf20_get_reading(state.distance_m)) {
|
||||||
// update range_valid state based on distance measured
|
// update range_valid state based on distance measured
|
||||||
update_status();
|
update_status();
|
||||||
|
state.last_reading_ms = AP_HAL::millis();
|
||||||
} else {
|
} else {
|
||||||
set_status(RangeFinder::Status::NoData);
|
set_status(RangeFinder::Status::NoData);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue