mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: Give back semaphore on whoami error
This commit is contained in:
parent
92791821c1
commit
4769055c4a
|
@ -80,6 +80,7 @@ bool AP_RangeFinder_TeraRangerI2C::init(void)
|
|||
uint8_t whoami;
|
||||
if (!dev->read_registers(TR_WHOAMI, &whoami, 1) ||
|
||||
whoami != TR_WHOAMI_VALUE) {
|
||||
dev->get_semaphore()->give();
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue