AP_InertialSensor: fixed timing of PX4 sensor samples

This commit is contained in:
Andrew Tridgell 2013-10-13 22:15:50 +11:00
parent c4d62f6b92
commit 8532e2bff8
2 changed files with 6 additions and 6 deletions

View File

@ -108,7 +108,7 @@ bool AP_InertialSensor_PX4::update(void)
_last_filter_hz = _mpu6000_filter;
}
_num_samples_available = 0;
_have_sample_available = false;
return true;
}
@ -145,11 +145,11 @@ void AP_InertialSensor_PX4::_get_sample(void)
bool AP_InertialSensor_PX4::sample_available(void)
{
uint64_t tnow = hrt_absolute_time();
if (tnow - _last_sample_timestamp > _sample_time_usec) {
_num_samples_available++;
_last_sample_timestamp = tnow;
while (tnow - _last_sample_timestamp > _sample_time_usec) {
_have_sample_available = true;
_last_sample_timestamp += _sample_time_usec;
}
return _num_samples_available > 0;
return _have_sample_available;
}
bool AP_InertialSensor_PX4::wait_for_sample(uint16_t timeout_ms)

View File

@ -36,7 +36,7 @@ private:
uint64_t _last_accel_timestamp;
uint64_t _last_gyro_timestamp;
uint64_t _last_sample_timestamp;
uint16_t _num_samples_available;
bool _have_sample_available;
uint32_t _sample_time_usec;
// support for updating filter at runtime