mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_RangeFinder: Remove range enforcement on out of range
This commit is contained in:
parent
5577b8b33c
commit
e62ed19759
@ -135,11 +135,12 @@ bool AP_RangeFinder_TeraRangerI2C::process_raw_measure(uint16_t raw_distance, ui
|
||||
{
|
||||
// Check for error codes
|
||||
if (raw_distance == 0xFFFF) {
|
||||
// Too far away
|
||||
// Too far away is unreliable so we dont enforce max range here
|
||||
return false;
|
||||
} else if (raw_distance == 0x0000) {
|
||||
// Too close
|
||||
return false;
|
||||
output_distance_cm = state.min_distance_cm;
|
||||
return true;
|
||||
} else if (raw_distance == 0x0001) {
|
||||
// Unable to measure
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user