mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: Remove range enforcement on out of range
This commit is contained in:
parent
ec21de5ed9
commit
ffe854063b
|
@ -135,11 +135,12 @@ bool AP_RangeFinder_TeraRangerI2C::process_raw_measure(uint16_t raw_distance, ui
|
||||||
{
|
{
|
||||||
// Check for error codes
|
// Check for error codes
|
||||||
if (raw_distance == 0xFFFF) {
|
if (raw_distance == 0xFFFF) {
|
||||||
// Too far away
|
// Too far away is unreliable so we dont enforce max range here
|
||||||
return false;
|
return false;
|
||||||
} else if (raw_distance == 0x0000) {
|
} else if (raw_distance == 0x0000) {
|
||||||
// Too close
|
// Too close
|
||||||
return false;
|
output_distance_cm = state.min_distance_cm;
|
||||||
|
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