mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: fixed VibTest example build
This commit is contained in:
parent
feb928dcd3
commit
e91bfdfc1c
|
@ -135,7 +135,8 @@ void loop(void)
|
|||
|
||||
struct log_ACCEL pkt = {
|
||||
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_ACC1_MSG+i)),
|
||||
time_us : accel_report.timestamp,
|
||||
time_us : hal.scheduler->micros64(),
|
||||
sample_us : accel_report.timestamp,
|
||||
AccX : accel_report.x,
|
||||
AccY : accel_report.y,
|
||||
AccZ : accel_report.z
|
||||
|
@ -158,7 +159,8 @@ void loop(void)
|
|||
|
||||
struct log_GYRO pkt = {
|
||||
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GYR1_MSG+i)),
|
||||
time_us : gyro_report.timestamp,
|
||||
time_us : hal.scheduler->micros64(),
|
||||
sample_us : gyro_report.timestamp,
|
||||
GyrX : gyro_report.x,
|
||||
GyrY : gyro_report.y,
|
||||
GyrZ : gyro_report.z
|
||||
|
|
Loading…
Reference in New Issue