mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_InertialSensor: fix data_ready return for L3GD20
This commit is contained in:
parent
21ff578cb0
commit
12239de00d
@ -286,6 +286,8 @@ bool AP_InertialSensor_L3GD20::_data_ready()
|
||||
if (_drdy_pin) {
|
||||
return _drdy_pin->read() != 0;
|
||||
}
|
||||
// TODO: read status register
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
|
Loading…
Reference in New Issue
Block a user