mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 07:38:28 -04:00
AP_RangeFinder: Rework function structure in TeraRanger driver
This commit is contained in:
parent
b6f1647c31
commit
5577b8b33c
@ -137,17 +137,16 @@ bool AP_RangeFinder_TeraRangerI2C::process_raw_measure(uint16_t raw_distance, ui
|
|||||||
if (raw_distance == 0xFFFF) {
|
if (raw_distance == 0xFFFF) {
|
||||||
// Too far away
|
// Too far away
|
||||||
return false;
|
return false;
|
||||||
}
|
} else if (raw_distance == 0x0000) {
|
||||||
if (raw_distance == 0x0000) {
|
|
||||||
// Too close
|
// Too close
|
||||||
return false;
|
return false;
|
||||||
}
|
} else if (raw_distance == 0x0001) {
|
||||||
if (raw_distance == 0x0001) {
|
|
||||||
// Unable to measure
|
// Unable to measure
|
||||||
return false;
|
return false;
|
||||||
}
|
} else {
|
||||||
output_distance_cm = raw_distance/10;
|
output_distance_cm = raw_distance/10; // Conversion to centimeters
|
||||||
return true;
|
return true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user