mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_InertialSensor: fixed logic bug in MPU6000 init
thanks to coverity
This commit is contained in:
parent
248bf8c5a3
commit
4eab27abe9
@ -236,8 +236,6 @@ bool AP_InertialSensor_MPU6000::_init_sensor(void)
|
||||
if (_data_ready()) {
|
||||
_spi_sem->give();
|
||||
break;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
_spi_sem->give();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user