DataFlash: log compass health

This patch simply logs the health of each compass for easy diagnosis.
This commit is contained in:
Andy Piper 2015-04-18 13:31:48 +01:00 committed by Randy Mackay
parent cebd578403
commit b0937154f5
2 changed files with 10 additions and 6 deletions

View File

@ -425,6 +425,7 @@ struct PACKED log_Compass {
int16_t motor_offset_x;
int16_t motor_offset_y;
int16_t motor_offset_z;
uint8_t health;
};
struct PACKED log_Mode {
@ -556,7 +557,7 @@ Format characters in the format string for binary log messages
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),\
"ATT", "IccccCCCC", "TimeMS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,ErrRP,ErrYaw" }, \
{ LOG_COMPASS_MSG, sizeof(log_Compass), \
"MAG", "Ihhhhhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" }, \
"MAG", "IhhhhhhhhhB", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ,Health" }, \
{ LOG_MODE_MSG, sizeof(log_Mode), \
"MODE", "IMB", "TimeMS,Mode,ModeNum" }
@ -607,9 +608,9 @@ Format characters in the format string for binary log messages
{ LOG_EKF5_MSG, sizeof(log_EKF5), \
"EKF5","IBhhhcccCC","TimeMS,normInnov,FIX,FIY,AFI,HAGL,offset,RI,meaRng,errHAGL" }, \
{ LOG_COMPASS2_MSG, sizeof(log_Compass), \
"MAG2","Ihhhhhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" }, \
"MAG2","IhhhhhhhhhB", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ,Health" }, \
{ LOG_COMPASS3_MSG, sizeof(log_Compass), \
"MAG3","Ihhhhhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" } \
"MAG3","IhhhhhhhhhB", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ,Health" } \
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
#define LOG_COMMON_STRUCTURES LOG_BASE_STRUCTURES, LOG_EXTRA_STRUCTURES

View File

@ -1162,7 +1162,8 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass)
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
motor_offset_z : (int16_t)mag_motor_offsets.z,
health : (uint8_t)compass.healthy(0)
};
WriteBlock(&pkt, sizeof(pkt));
@ -1182,7 +1183,8 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass)
offset_z : (int16_t)mag_offsets2.z,
motor_offset_x : (int16_t)mag_motor_offsets2.x,
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)
};
WriteBlock(&pkt2, sizeof(pkt2));
}
@ -1203,7 +1205,8 @@ void DataFlash_Class::Log_Write_Compass(const Compass &compass)
offset_z : (int16_t)mag_offsets3.z,
motor_offset_x : (int16_t)mag_motor_offsets3.x,
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)
};
WriteBlock(&pkt3, sizeof(pkt3));
}