mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RangeFinder: a to close reading is not the minimum distance
This commit is contained in:
parent
8b20c82a18
commit
7bc1f4ff9b
@ -143,8 +143,7 @@ bool AP_RangeFinder_TeraRangerI2C::process_raw_measure(uint16_t raw_distance, ui
|
|||||||
return false;
|
return false;
|
||||||
} else if (raw_distance == 0x0000) {
|
} else if (raw_distance == 0x0000) {
|
||||||
// Too close
|
// Too close
|
||||||
output_distance_cm = params.min_distance_cm;
|
return false;
|
||||||
return true;
|
|
||||||
} else if (raw_distance == 0x0001) {
|
} else if (raw_distance == 0x0001) {
|
||||||
// Unable to measure
|
// Unable to measure
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user