Browse Source

AP_InertialSensor: use 64-bit timestamps in dataflash logs

mission-4.1.18
Peter Barker 10 years ago committed by Andrew Tridgell
parent
commit
f489f6b696
  1. 6
      libraries/AP_InertialSensor/examples/VibTest/VibTest.pde

6
libraries/AP_InertialSensor/examples/VibTest/VibTest.pde

@ -135,8 +135,7 @@ void loop(void) @@ -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) @@ -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…
Cancel
Save