mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
VibTest: fixed gyro timestamps in logs
it was using the accel timestamps
This commit is contained in:
parent
179d854a26
commit
2c8240dbb4
@ -147,8 +147,8 @@ void loop(void)
|
|||||||
|
|
||||||
struct log_GYRO pkt = {
|
struct log_GYRO pkt = {
|
||||||
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GYR1_MSG+i)),
|
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GYR1_MSG+i)),
|
||||||
timestamp : (uint32_t)(accel_report.timestamp/1000),
|
timestamp : (uint32_t)(gyro_report.timestamp/1000),
|
||||||
timestamp_us : (uint32_t)accel_report.timestamp,
|
timestamp_us : (uint32_t)gyro_report.timestamp,
|
||||||
GyrX : gyro_report.x,
|
GyrX : gyro_report.x,
|
||||||
GyrY : gyro_report.y,
|
GyrY : gyro_report.y,
|
||||||
GyrZ : gyro_report.z
|
GyrZ : gyro_report.z
|
||||||
|
Loading…
Reference in New Issue
Block a user