mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -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
40fcfa294f
commit
90fcdeadfd
@ -75,7 +75,7 @@ AP_OpticalFlow_ADNS3080::init(bool initCommAPI)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// check the sensor is functioning
|
// check the sensor is functioning
|
||||||
if( retry < 3 ) {
|
while( retry < 3 ) {
|
||||||
if( read_register(ADNS3080_PRODUCT_ID) == 0x17 )
|
if( read_register(ADNS3080_PRODUCT_ID) == 0x17 )
|
||||||
return true;
|
return true;
|
||||||
retry++;
|
retry++;
|
||||||
|
Loading…
Reference in New Issue
Block a user