mirror of https://github.com/ArduPilot/ardupilot
HAL_Linux: fixed float calc of time for onboard flow
This commit is contained in:
parent
350be1b24f
commit
2c378f4ba0
|
@ -220,7 +220,7 @@ void OpticalFlow_Onboard::push_gyro(float gyro_x, float gyro_y, float dt)
|
|||
_integrated_gyro.x += (gyro_x - _gyro_bias.x) * dt;
|
||||
_integrated_gyro.y += (gyro_y - _gyro_bias.y) * dt;
|
||||
sample.gyro = _integrated_gyro;
|
||||
sample.time_us = 1.0e6 * (ts.tv_sec + (ts.tv_nsec*1.0e-9));
|
||||
sample.time_us = ts.tv_sec*1000000ULL + ts.tv_nsec/1000ULL;
|
||||
|
||||
_gyro_ring_buffer->push(sample);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue