AP_RangeFinder: Clean TeraRanger driver
This commit is contained in:
parent
d162afb790
commit
4d45b68fa3
@ -110,11 +110,10 @@ bool AP_RangeFinder_TeraRangerI2C::measure()
|
|||||||
return dev->transfer(&cmd, 1, nullptr, 0);
|
return dev->transfer(&cmd, 1, nullptr, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// collect - return last value measured by sensor
|
// collect_raw() - return last value measured by sensor
|
||||||
bool AP_RangeFinder_TeraRangerI2C::collect_raw(uint16_t &raw_distance)
|
bool AP_RangeFinder_TeraRangerI2C::collect_raw(uint16_t &raw_distance)
|
||||||
{
|
{
|
||||||
uint8_t d[3];
|
uint8_t d[3];
|
||||||
uint16_t distance = 0;
|
|
||||||
|
|
||||||
// Take range reading
|
// Take range reading
|
||||||
if (!dev->transfer(nullptr, 0, d, sizeof(d))) {
|
if (!dev->transfer(nullptr, 0, d, sizeof(d))) {
|
||||||
@ -135,11 +134,11 @@ bool AP_RangeFinder_TeraRangerI2C::check_measure(uint16_t raw_distance, uint16_t
|
|||||||
{
|
{
|
||||||
// Check for error codes
|
// Check for error codes
|
||||||
if (raw_distance == 0xFFFF) {
|
if (raw_distance == 0xFFFF) {
|
||||||
// too far away
|
// Too far away
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (raw_distance == 0x0000) {
|
if (raw_distance == 0x0000) {
|
||||||
// too close
|
// Too close
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (raw_distance == 0x0001) {
|
if (raw_distance == 0x0001) {
|
||||||
|
Loading…
Reference in New Issue
Block a user