Copter: add time to ATT, MAG, CURR dataflash msgs

This commit is contained in:
Randy Mackay 2014-01-13 20:46:54 +09:00
parent df9d1614e2
commit 97b18314ac
1 changed files with 28 additions and 21 deletions

View File

@ -208,12 +208,13 @@ static void Log_Write_AutoTuneDetails(int16_t angle_cd, float rate_cds)
struct PACKED log_Current { struct PACKED log_Current {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
int16_t throttle_out; uint32_t time_ms;
int16_t throttle_out;
uint32_t throttle_integrator; uint32_t throttle_integrator;
int16_t battery_voltage; int16_t battery_voltage;
int16_t current_amps; int16_t current_amps;
uint16_t board_voltage; uint16_t board_voltage;
float current_total; float current_total;
}; };
// Write an Current data packet // Write an Current data packet
@ -221,6 +222,7 @@ static void Log_Write_Current()
{ {
struct log_Current pkt = { struct log_Current pkt = {
LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG), LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG),
time_ms : hal.scheduler->millis(),
throttle_out : g.rc_3.servo_out, throttle_out : g.rc_3.servo_out,
throttle_integrator : throttle_integrator, throttle_integrator : throttle_integrator,
battery_voltage : (int16_t) (battery.voltage() * 100.0f), battery_voltage : (int16_t) (battery.voltage() * 100.0f),
@ -332,15 +334,16 @@ static void Log_Write_Control_Tuning()
struct PACKED log_Compass { struct PACKED log_Compass {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
int16_t mag_x; uint32_t time_ms;
int16_t mag_y; int16_t mag_x;
int16_t mag_z; int16_t mag_y;
int16_t offset_x; int16_t mag_z;
int16_t offset_y; int16_t offset_x;
int16_t offset_z; int16_t offset_y;
int16_t motor_offset_x; int16_t offset_z;
int16_t motor_offset_y; int16_t motor_offset_x;
int16_t motor_offset_z; int16_t motor_offset_y;
int16_t motor_offset_z;
}; };
// Write a Compass packet // Write a Compass packet
@ -351,6 +354,7 @@ static void Log_Write_Compass()
const Vector3f &mag = compass.get_field(0); const Vector3f &mag = compass.get_field(0);
struct log_Compass pkt = { struct log_Compass pkt = {
LOG_PACKET_HEADER_INIT(LOG_COMPASS_MSG), LOG_PACKET_HEADER_INIT(LOG_COMPASS_MSG),
time_ms : hal.scheduler->millis(),
mag_x : (int16_t)mag.x, mag_x : (int16_t)mag.x,
mag_y : (int16_t)mag.y, mag_y : (int16_t)mag.y,
mag_z : (int16_t)mag.z, mag_z : (int16_t)mag.z,
@ -369,6 +373,7 @@ static void Log_Write_Compass()
const Vector3f &mag2 = compass.get_field(1); const Vector3f &mag2 = compass.get_field(1);
struct log_Compass pkt2 = { struct log_Compass pkt2 = {
LOG_PACKET_HEADER_INIT(LOG_COMPASS2_MSG), LOG_PACKET_HEADER_INIT(LOG_COMPASS2_MSG),
time_ms : hal.scheduler->millis(),
mag_x : (int16_t)mag2.x, mag_x : (int16_t)mag2.x,
mag_y : (int16_t)mag2.y, mag_y : (int16_t)mag2.y,
mag_z : (int16_t)mag2.z, mag_z : (int16_t)mag2.z,
@ -446,10 +451,11 @@ static void Log_Write_Cmd(uint8_t num, const struct Location *wp)
struct PACKED log_Attitude { struct PACKED log_Attitude {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
int16_t control_roll; uint32_t time_ms;
int16_t roll; int16_t control_roll;
int16_t control_pitch; int16_t roll;
int16_t pitch; int16_t control_pitch;
int16_t pitch;
uint16_t control_yaw; uint16_t control_yaw;
uint16_t yaw; uint16_t yaw;
}; };
@ -459,6 +465,7 @@ static void Log_Write_Attitude()
{ {
struct log_Attitude pkt = { struct log_Attitude pkt = {
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG), LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
time_ms : hal.scheduler->millis(),
control_roll : (int16_t)control_roll, control_roll : (int16_t)control_roll,
roll : (int16_t)ahrs.roll_sensor, roll : (int16_t)ahrs.roll_sensor,
control_pitch : (int16_t)control_pitch, control_pitch : (int16_t)control_pitch,
@ -703,7 +710,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
"ATDE", "cf", "Angle,Rate" }, "ATDE", "cf", "Angle,Rate" },
#endif #endif
{ LOG_CURRENT_MSG, sizeof(log_Current), { LOG_CURRENT_MSG, sizeof(log_Current),
"CURR", "hIhhhf", "ThrOut,ThrInt,Volt,Curr,Vcc,CurrTot" }, "CURR", "IhIhhhf", "TimeMS,ThrOut,ThrInt,Volt,Curr,Vcc,CurrTot" },
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow), { LOG_OPTFLOW_MSG, sizeof(log_Optflow),
"OF", "hhBccee", "Dx,Dy,SQual,X,Y,Roll,Pitch" }, "OF", "hhBccee", "Dx,Dy,SQual,X,Y,Roll,Pitch" },
{ LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning), { LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning),
@ -711,15 +718,15 @@ static const struct LogStructure log_structure[] PROGMEM = {
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning), { LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
"CTUN", "hcefchhhh", "ThrIn,SonAlt,BarAlt,WPAlt,DesSonAlt,AngBst,CRate,ThrOut,DCRate" }, "CTUN", "hcefchhhh", "ThrIn,SonAlt,BarAlt,WPAlt,DesSonAlt,AngBst,CRate,ThrOut,DCRate" },
{ LOG_COMPASS_MSG, sizeof(log_Compass), { LOG_COMPASS_MSG, sizeof(log_Compass),
"MAG", "hhhhhhhhh", "MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" }, "MAG", "Ihhhhhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" },
{ LOG_COMPASS2_MSG, sizeof(log_Compass), { LOG_COMPASS2_MSG, sizeof(log_Compass),
"MAG2", "hhhhhhhhh", "MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" }, "MAG2","Ihhhhhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" },
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance), { LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "BBHHIhBHB", "RenCnt,RenBlw,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,INAVErr" }, "PM", "BBHHIhBHB", "RenCnt,RenBlw,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,INAVErr" },
{ LOG_CMD_MSG, sizeof(log_Cmd), { LOG_CMD_MSG, sizeof(log_Cmd),
"CMD", "BBBBBeLL", "CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng" }, "CMD", "BBBBBeLL", "CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng" },
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude), { LOG_ATTITUDE_MSG, sizeof(log_Attitude),
"ATT", "ccccCC", "DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw" }, "ATT", "IccccCC", "TimeMS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw" },
{ LOG_INAV_MSG, sizeof(log_INAV), { LOG_INAV_MSG, sizeof(log_INAV),
"INAV", "cccfffiiff", "BAlt,IAlt,IClb,ACorrX,ACorrY,ACorrZ,GLat,GLng,ILat,ILng" }, "INAV", "cccfffiiff", "BAlt,IAlt,IClb,ACorrX,ACorrY,ACorrZ,GLat,GLng,ILat,ILng" },
{ LOG_MODE_MSG, sizeof(log_Mode), { LOG_MODE_MSG, sizeof(log_Mode),