mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 02:58:31 -04:00
DataFlash: added sample timestamp to mag messages
allows for exact mag timings in replay
This commit is contained in:
parent
315d3854db
commit
61da827c16
@ -1648,7 +1648,8 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass)
|
|||||||
motor_offset_x : (int16_t)mag_motor_offsets.x,
|
motor_offset_x : (int16_t)mag_motor_offsets.x,
|
||||||
motor_offset_y : (int16_t)mag_motor_offsets.y,
|
motor_offset_y : (int16_t)mag_motor_offsets.y,
|
||||||
motor_offset_z : (int16_t)mag_motor_offsets.z,
|
motor_offset_z : (int16_t)mag_motor_offsets.z,
|
||||||
health : (uint8_t)compass.healthy(0)
|
health : (uint8_t)compass.healthy(0),
|
||||||
|
SUS : compass.last_update_usec(0)
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt, sizeof(pkt));
|
WriteBlock(&pkt, sizeof(pkt));
|
||||||
|
|
||||||
@ -1668,7 +1669,8 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass)
|
|||||||
motor_offset_x : (int16_t)mag_motor_offsets2.x,
|
motor_offset_x : (int16_t)mag_motor_offsets2.x,
|
||||||
motor_offset_y : (int16_t)mag_motor_offsets2.y,
|
motor_offset_y : (int16_t)mag_motor_offsets2.y,
|
||||||
motor_offset_z : (int16_t)mag_motor_offsets2.z,
|
motor_offset_z : (int16_t)mag_motor_offsets2.z,
|
||||||
health : (uint8_t)compass.healthy(1)
|
health : (uint8_t)compass.healthy(1),
|
||||||
|
SUS : compass.last_update_usec(1)
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt2, sizeof(pkt2));
|
WriteBlock(&pkt2, sizeof(pkt2));
|
||||||
}
|
}
|
||||||
@ -1689,7 +1691,8 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass)
|
|||||||
motor_offset_x : (int16_t)mag_motor_offsets3.x,
|
motor_offset_x : (int16_t)mag_motor_offsets3.x,
|
||||||
motor_offset_y : (int16_t)mag_motor_offsets3.y,
|
motor_offset_y : (int16_t)mag_motor_offsets3.y,
|
||||||
motor_offset_z : (int16_t)mag_motor_offsets3.z,
|
motor_offset_z : (int16_t)mag_motor_offsets3.z,
|
||||||
health : (uint8_t)compass.healthy(2)
|
health : (uint8_t)compass.healthy(2),
|
||||||
|
SUS : compass.last_update_usec(2)
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt3, sizeof(pkt3));
|
WriteBlock(&pkt3, sizeof(pkt3));
|
||||||
}
|
}
|
||||||
|
@ -438,6 +438,7 @@ struct PACKED log_Compass {
|
|||||||
int16_t motor_offset_y;
|
int16_t motor_offset_y;
|
||||||
int16_t motor_offset_z;
|
int16_t motor_offset_z;
|
||||||
uint8_t health;
|
uint8_t health;
|
||||||
|
uint32_t SUS;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PACKED log_Mode {
|
struct PACKED log_Mode {
|
||||||
@ -749,7 +750,7 @@ Format characters in the format string for binary log messages
|
|||||||
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),\
|
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),\
|
||||||
"ATT", "QccccCCCC", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,ErrRP,ErrYaw" }, \
|
"ATT", "QccccCCCC", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,ErrRP,ErrYaw" }, \
|
||||||
{ LOG_COMPASS_MSG, sizeof(log_Compass), \
|
{ LOG_COMPASS_MSG, sizeof(log_Compass), \
|
||||||
"MAG", "QhhhhhhhhhB", "TimeUS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ,Health" }, \
|
"MAG", "QhhhhhhhhhBI", "TimeUS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ,Health,S" }, \
|
||||||
{ LOG_MODE_MSG, sizeof(log_Mode), \
|
{ LOG_MODE_MSG, sizeof(log_Mode), \
|
||||||
"MODE", "QMBB", "TimeUS,Mode,ModeNum,Rsn" }, \
|
"MODE", "QMBB", "TimeUS,Mode,ModeNum,Rsn" }, \
|
||||||
{ LOG_RFND_MSG, sizeof(log_RFND), \
|
{ LOG_RFND_MSG, sizeof(log_RFND), \
|
||||||
@ -832,9 +833,9 @@ Format characters in the format string for binary log messages
|
|||||||
{ LOG_ESC8_MSG, sizeof(log_Esc), \
|
{ LOG_ESC8_MSG, sizeof(log_Esc), \
|
||||||
"ESC8", "Qcccc", "TimeUS,RPM,Volt,Curr,Temp" }, \
|
"ESC8", "Qcccc", "TimeUS,RPM,Volt,Curr,Temp" }, \
|
||||||
{ LOG_COMPASS2_MSG, sizeof(log_Compass), \
|
{ LOG_COMPASS2_MSG, sizeof(log_Compass), \
|
||||||
"MAG2","QhhhhhhhhhB", "TimeUS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ,Health" }, \
|
"MAG2","QhhhhhhhhhBI", "TimeUS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ,Health,S" }, \
|
||||||
{ LOG_COMPASS3_MSG, sizeof(log_Compass), \
|
{ LOG_COMPASS3_MSG, sizeof(log_Compass), \
|
||||||
"MAG3","QhhhhhhhhhB", "TimeUS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ,Health" }, \
|
"MAG3","QhhhhhhhhhBI", "TimeUS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ,Health,S" }, \
|
||||||
{ LOG_ACC1_MSG, sizeof(log_ACCEL), \
|
{ LOG_ACC1_MSG, sizeof(log_ACCEL), \
|
||||||
"ACC1", "QQfff", "TimeUS,SampleUS,AccX,AccY,AccZ" }, \
|
"ACC1", "QQfff", "TimeUS,SampleUS,AccX,AccY,AccZ" }, \
|
||||||
{ LOG_ACC2_MSG, sizeof(log_ACCEL), \
|
{ LOG_ACC2_MSG, sizeof(log_ACCEL), \
|
||||||
|
Loading…
Reference in New Issue
Block a user