mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AP_InertialSensor: poll for new data in num_samples_available()
this lowers the latency for new data
This commit is contained in:
parent
4ab1cddd15
commit
f48790a56e
@ -600,6 +600,7 @@ float AP_InertialSensor_MPU6000::get_gyro_drift_rate(void)
|
||||
// get number of samples read from the sensors
|
||||
uint16_t AP_InertialSensor_MPU6000::num_samples_available()
|
||||
{
|
||||
_poll_data(0);
|
||||
return _count;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user