From 1f2b9df2903d5815b9478896eb44d93b2a69337b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 5 Feb 2024 14:38:40 +1100 Subject: [PATCH] HAL_Linux: fixed float calc of time for onboard flow --- libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp b/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp index 981afc77bb..9f597ace53 100644 --- a/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp +++ b/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp @@ -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); }