mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_RangeFinder_MaxsonarI2CXL: Fix driver after I2CDevice conversion
* Simplify semaphore releasing logic * Fix typo
This commit is contained in:
parent
c167364fa0
commit
f2d5eb9a97
@ -30,7 +30,7 @@
|
|||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
The constructor also initialises the rangefinder. Note that this
|
The constructor also initializes the rangefinder. Note that this
|
||||||
constructor is not called until detect() returns true, so we
|
constructor is not called until detect() returns true, so we
|
||||||
already know that we should setup the rangefinder
|
already know that we should setup the rangefinder
|
||||||
*/
|
*/
|
||||||
@ -75,40 +75,34 @@ bool AP_RangeFinder_MaxsonarI2CXL::start_reading()
|
|||||||
uint8_t tosend[] = {AP_RANGE_FINDER_MAXSONARI2CXL_COMMAND_TAKE_RANGE_READING};
|
uint8_t tosend[] = {AP_RANGE_FINDER_MAXSONARI2CXL_COMMAND_TAKE_RANGE_READING};
|
||||||
|
|
||||||
// send command to take reading
|
// send command to take reading
|
||||||
if (!_dev->transfer(tosend, sizeof(tosend), nullptr, 0)) {
|
bool ret = _dev->transfer(tosend, sizeof(tosend), nullptr, 0);
|
||||||
_dev->get_semaphore()->give();
|
_dev->get_semaphore()->give();
|
||||||
return false;
|
return ret;
|
||||||
}
|
|
||||||
|
|
||||||
// return semaphore
|
|
||||||
_dev->get_semaphore()->give();
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// read - return last value measured by sensor
|
// read - return last value measured by sensor
|
||||||
bool AP_RangeFinder_MaxsonarI2CXL::get_reading(uint16_t &reading_cm)
|
bool AP_RangeFinder_MaxsonarI2CXL::get_reading(uint16_t &reading_cm)
|
||||||
{
|
{
|
||||||
|
uint8_t buff[2];
|
||||||
|
|
||||||
// exit immediately if we can't take the semaphore
|
// exit immediately if we can't take the semaphore
|
||||||
if (!_dev->get_semaphore()->take(1)) {
|
if (!_dev->get_semaphore()->take(1)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t buff[2];
|
|
||||||
// take range reading and read back results
|
// take range reading and read back results
|
||||||
if (!_dev->transfer(nullptr, 0, buff, sizeof(buff))) {
|
bool ret = _dev->transfer(nullptr, 0, buff, sizeof(buff));
|
||||||
_dev->get_semaphore()->give();
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
_dev->get_semaphore()->give();
|
_dev->get_semaphore()->give();
|
||||||
|
|
||||||
|
if (ret) {
|
||||||
// combine results into distance
|
// combine results into distance
|
||||||
reading_cm = ((uint16_t)buff[0]) << 8 | buff[1];
|
reading_cm = ((uint16_t)buff[0]) << 8 | buff[1];
|
||||||
|
|
||||||
// trigger a new reading
|
// trigger a new reading
|
||||||
start_reading();
|
start_reading();
|
||||||
|
}
|
||||||
|
|
||||||
return true;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user