mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_OpticalFlow - small bug fix to ensure init attempts to read the product id 3 times before giving up
This commit is contained in:
parent
ab16a33313
commit
99cdc69110
@ -75,7 +75,7 @@ AP_OpticalFlow_ADNS3080::init(bool initCommAPI)
|
||||
}
|
||||
|
||||
// check the sensor is functioning
|
||||
if( retry < 3 ) {
|
||||
while( retry < 3 ) {
|
||||
if( read_register(ADNS3080_PRODUCT_ID) == 0x17 )
|
||||
return true;
|
||||
retry++;
|
||||
|
Loading…
Reference in New Issue
Block a user