mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: Rework function structure in TeraRanger driver
This commit is contained in:
parent
8198235af4
commit
5e328e6276
|
@ -141,17 +141,16 @@ bool AP_RangeFinder_TeraRangerI2C::process_raw_measure(uint16_t raw_distance, ui
|
|||
if (raw_distance == 0xFFFF) {
|
||||
// Too far away
|
||||
return false;
|
||||
}
|
||||
if (raw_distance == 0x0000) {
|
||||
} else if (raw_distance == 0x0000) {
|
||||
// Too close
|
||||
return false;
|
||||
}
|
||||
if (raw_distance == 0x0001) {
|
||||
} else if (raw_distance == 0x0001) {
|
||||
// Unable to measure
|
||||
return false;
|
||||
} else {
|
||||
output_distance_cm = raw_distance/10; // Conversion to centimeters
|
||||
return true;
|
||||
}
|
||||
output_distance_cm = raw_distance/10;
|
||||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue