DataFlash: log temperature of IMUs

this is the first step towards supporting temperature calibration of
IMUs
This commit is contained in:
Andrew Tridgell 2015-03-17 13:33:26 +11:00
parent 23272e4013
commit ecd2a6f515
2 changed files with 10 additions and 6 deletions

View File

@ -203,6 +203,7 @@ struct PACKED log_IMU {
float gyro_x, gyro_y, gyro_z;
float accel_x, accel_y, accel_z;
uint32_t gyro_error, accel_error;
float temperature;
};
struct PACKED log_RCIN {
@ -529,7 +530,7 @@ Format characters in the format string for binary log messages
{ LOG_GPS_MSG, sizeof(log_GPS), \
"GPS", "BIHBcLLeeEefI", "Status,TimeMS,Week,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs,VZ,T" }, \
{ LOG_IMU_MSG, sizeof(log_IMU), \
"IMU", "IffffffII", "TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA" }, \
"IMU", "IffffffIIf", "TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA,Temp" }, \
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
"MSG", "Z", "Message"}, \
{ LOG_RCIN_MSG, sizeof(log_RCIN), \
@ -564,9 +565,9 @@ Format characters in the format string for binary log messages
{ LOG_GPS2_MSG, sizeof(log_GPS2), \
"GPS2", "BIHBcLLeEefIBI", "Status,TimeMS,Week,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,T,DSc,DAg" }, \
{ LOG_IMU2_MSG, sizeof(log_IMU), \
"IMU2", "IffffffII", "TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA" }, \
"IMU2", "IffffffIIf", "TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA,Temp" }, \
{ LOG_IMU3_MSG, sizeof(log_IMU), \
"IMU3", "IffffffII", "TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA" }, \
"IMU3", "IffffffIIf", "TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA,Temp" }, \
{ LOG_AHR2_MSG, sizeof(log_AHRS), \
"AHR2","IccCfLL","TimeMS,Roll,Pitch,Yaw,Alt,Lat,Lng" }, \
{ LOG_SIMSTATE_MSG, sizeof(log_AHRS), \

View File

@ -800,7 +800,8 @@ void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor &ins)
accel_y : accel.y,
accel_z : accel.z,
gyro_error : ins.get_gyro_error_count(0),
accel_error : ins.get_accel_error_count(0)
accel_error : ins.get_accel_error_count(0),
temperature : ins.get_temperature(0)
};
WriteBlock(&pkt, sizeof(pkt));
if (ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) {
@ -819,7 +820,8 @@ void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor &ins)
accel_y : accel2.y,
accel_z : accel2.z,
gyro_error : ins.get_gyro_error_count(1),
accel_error : ins.get_accel_error_count(1)
accel_error : ins.get_accel_error_count(1),
temperature : ins.get_temperature(1)
};
WriteBlock(&pkt2, sizeof(pkt2));
if (ins.get_gyro_count() < 3 && ins.get_accel_count() < 3) {
@ -837,7 +839,8 @@ void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor &ins)
accel_y : accel3.y,
accel_z : accel3.z,
gyro_error : ins.get_gyro_error_count(2),
accel_error : ins.get_accel_error_count(2)
accel_error : ins.get_accel_error_count(2),
temperature : ins.get_temperature(2)
};
WriteBlock(&pkt3, sizeof(pkt3));
#endif