mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_InertialSensor: use 64-bit timestamps in dataflash logs
This commit is contained in:
parent
9ae85ed9ab
commit
f489f6b696
@ -135,8 +135,7 @@ void loop(void)
|
||||
|
||||
struct log_ACCEL pkt = {
|
||||
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_ACC1_MSG+i)),
|
||||
timestamp : (uint32_t)(accel_report.timestamp/1000),
|
||||
timestamp_us : (uint32_t)accel_report.timestamp,
|
||||
time_us : accel_report.timestamp,
|
||||
AccX : accel_report.x,
|
||||
AccY : accel_report.y,
|
||||
AccZ : accel_report.z
|
||||
@ -159,8 +158,7 @@ void loop(void)
|
||||
|
||||
struct log_GYRO pkt = {
|
||||
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GYR1_MSG+i)),
|
||||
timestamp : (uint32_t)(gyro_report.timestamp/1000),
|
||||
timestamp_us : (uint32_t)gyro_report.timestamp,
|
||||
time_us : gyro_report.timestamp,
|
||||
GyrX : gyro_report.x,
|
||||
GyrY : gyro_report.y,
|
||||
GyrZ : gyro_report.z
|
||||
|
Loading…
Reference in New Issue
Block a user