mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Plane: added time to most plane log messages
This commit is contained in:
parent
1fb636d57f
commit
ae8ef344bf
@ -162,6 +162,7 @@ process_logs(uint8_t argc, const Menu::arg *argv)
|
||||
|
||||
struct PACKED log_Attitude {
|
||||
LOG_PACKET_HEADER;
|
||||
uint32_t time_ms;
|
||||
int16_t roll;
|
||||
int16_t pitch;
|
||||
uint16_t yaw;
|
||||
@ -172,6 +173,7 @@ static void Log_Write_Attitude(void)
|
||||
{
|
||||
struct log_Attitude pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
roll : (int16_t)ahrs.roll_sensor,
|
||||
pitch : (int16_t)ahrs.pitch_sensor,
|
||||
yaw : (uint16_t)ahrs.yaw_sensor
|
||||
@ -297,6 +299,7 @@ static void Log_Write_Startup(uint8_t type)
|
||||
|
||||
struct PACKED log_Control_Tuning {
|
||||
LOG_PACKET_HEADER;
|
||||
uint32_t time_ms;
|
||||
int16_t nav_roll_cd;
|
||||
int16_t roll;
|
||||
int16_t nav_pitch_cd;
|
||||
@ -312,6 +315,7 @@ static void Log_Write_Control_Tuning()
|
||||
Vector3f accel = ins.get_accel();
|
||||
struct log_Control_Tuning pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
nav_roll_cd : (int16_t)nav_roll_cd,
|
||||
roll : (int16_t)ahrs.roll_sensor,
|
||||
nav_pitch_cd : (int16_t)nav_pitch_cd,
|
||||
@ -331,6 +335,7 @@ static void Log_Write_TECS_Tuning(void)
|
||||
|
||||
struct PACKED log_Nav_Tuning {
|
||||
LOG_PACKET_HEADER;
|
||||
uint32_t time_ms;
|
||||
uint16_t yaw;
|
||||
uint32_t wp_distance;
|
||||
uint16_t target_bearing_cd;
|
||||
@ -346,6 +351,7 @@ static void Log_Write_Nav_Tuning()
|
||||
{
|
||||
struct log_Nav_Tuning pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
yaw : (uint16_t)ahrs.yaw_sensor,
|
||||
wp_distance : wp_distance,
|
||||
target_bearing_cd : (uint16_t)nav_controller->target_bearing_cd(),
|
||||
@ -360,6 +366,7 @@ static void Log_Write_Nav_Tuning()
|
||||
|
||||
struct PACKED log_Mode {
|
||||
LOG_PACKET_HEADER;
|
||||
uint32_t time_ms;
|
||||
uint8_t mode;
|
||||
uint8_t mode_num;
|
||||
};
|
||||
@ -369,6 +376,7 @@ static void Log_Write_Mode(uint8_t mode)
|
||||
{
|
||||
struct log_Mode pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_MODE_MSG),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
mode : mode,
|
||||
mode_num : mode
|
||||
};
|
||||
@ -377,6 +385,7 @@ static void Log_Write_Mode(uint8_t mode)
|
||||
|
||||
struct PACKED log_Current {
|
||||
LOG_PACKET_HEADER;
|
||||
uint32_t time_ms;
|
||||
int16_t throttle_in;
|
||||
int16_t battery_voltage;
|
||||
int16_t current_amps;
|
||||
@ -388,6 +397,7 @@ static void Log_Write_Current()
|
||||
{
|
||||
struct log_Current pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
throttle_in : channel_throttle->control_in,
|
||||
battery_voltage : (int16_t)(battery.voltage() * 100.0),
|
||||
current_amps : (int16_t)(battery.current_amps() * 100.0),
|
||||
@ -400,15 +410,13 @@ static void Log_Write_Current()
|
||||
|
||||
struct PACKED log_Compass {
|
||||
LOG_PACKET_HEADER;
|
||||
uint32_t time_ms;
|
||||
int16_t mag_x;
|
||||
int16_t mag_y;
|
||||
int16_t mag_z;
|
||||
int16_t offset_x;
|
||||
int16_t offset_y;
|
||||
int16_t offset_z;
|
||||
int16_t motor_offset_x;
|
||||
int16_t motor_offset_y;
|
||||
int16_t motor_offset_z;
|
||||
};
|
||||
|
||||
// Write a Compass packet. Total length : 15 bytes
|
||||
@ -418,15 +426,13 @@ static void Log_Write_Compass()
|
||||
Vector3f mag_motor_offsets = compass.get_motor_offsets();
|
||||
struct log_Compass pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_COMPASS_MSG),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
mag_x : compass.mag_x,
|
||||
mag_y : compass.mag_y,
|
||||
mag_z : compass.mag_z,
|
||||
offset_x : (int16_t)mag_offsets.x,
|
||||
offset_y : (int16_t)mag_offsets.y,
|
||||
offset_z : (int16_t)mag_offsets.z,
|
||||
motor_offset_x : (int16_t)mag_motor_offsets.x,
|
||||
motor_offset_y : (int16_t)mag_motor_offsets.y,
|
||||
motor_offset_z : (int16_t)mag_motor_offsets.z
|
||||
offset_z : (int16_t)mag_offsets.z
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
@ -444,7 +450,7 @@ static void Log_Write_IMU()
|
||||
static const struct LogStructure log_structure[] PROGMEM = {
|
||||
LOG_COMMON_STRUCTURES,
|
||||
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
|
||||
"ATT", "ccC", "Roll,Pitch,Yaw" },
|
||||
"ATT", "IccC", "TimeMS,Roll,Pitch,Yaw" },
|
||||
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
||||
"PM", "IHIBBBhhhB", "LTime,MLC,gDt,RNCnt,RNBl,GPScnt,GDx,GDy,GDz,I2CErr" },
|
||||
{ LOG_CMD_MSG, sizeof(log_Cmd),
|
||||
@ -454,15 +460,15 @@ static const struct LogStructure log_structure[] PROGMEM = {
|
||||
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
||||
"STRT", "BB", "SType,CTot" },
|
||||
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
|
||||
"CTUN", "cccchhf", "NavRoll,Roll,NavPitch,Pitch,ThrOut,RdrOut,AccY" },
|
||||
"CTUN", "Icccchhf", "TimeMS,NavRoll,Roll,NavPitch,Pitch,ThrOut,RdrOut,AccY" },
|
||||
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
|
||||
"NTUN", "CICCccfI", "Yaw,WpDist,TargBrg,NavBrg,AltErr,Arspd,Alt,GSpdCM" },
|
||||
"NTUN", "ICICCccfI", "TimeMS,Yaw,WpDist,TargBrg,NavBrg,AltErr,Arspd,Alt,GSpdCM" },
|
||||
{ LOG_MODE_MSG, sizeof(log_Mode),
|
||||
"MODE", "MB", "Mode,ModeNum" },
|
||||
"MODE", "IMB", "TimeMS,Mode,ModeNum" },
|
||||
{ LOG_CURRENT_MSG, sizeof(log_Current),
|
||||
"CURR", "hhhHf", "Thr,Volt,Curr,Vcc,CurrTot" },
|
||||
"CURR", "IhhhHf", "TimeMS,Thr,Volt,Curr,Vcc,CurrTot" },
|
||||
{ LOG_COMPASS_MSG, sizeof(log_Compass),
|
||||
"MAG", "hhhhhhhhh", "MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" },
|
||||
"MAG", "Ihhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ" },
|
||||
TECS_LOG_FORMAT(LOG_TECS_MSG),
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user