DataFlash : Update EKF debug logging

This commit is contained in:
priseborough 2014-11-01 13:27:52 +11:00 committed by Andrew Tridgell
parent 06c19a3a4d
commit 4616721b0d
2 changed files with 17 additions and 17 deletions

View File

@ -350,13 +350,13 @@ struct PACKED log_EKF4 {
struct PACKED log_EKF5 { struct PACKED log_EKF5 {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint32_t time_ms; uint32_t time_ms;
float flowX; int16_t FIX;
float flowY; int16_t FIY;
float omegaX; int16_t AFIX;
float omegaY; int16_t AFIY;
float gndPos; int16_t gndPos;
uint8_t scaler; uint8_t scaler;
uint8_t quality; int16_t RI;
uint16_t range; uint16_t range;
}; };
@ -529,7 +529,7 @@ struct PACKED log_Esc {
{ LOG_ESC8_MSG, sizeof(log_Esc), \ { LOG_ESC8_MSG, sizeof(log_Esc), \
"ESC8", "Icccc", "TimeMS,RPM,Volt,Curr,Temp" }, \ "ESC8", "Icccc", "TimeMS,RPM,Volt,Curr,Temp" }, \
{ LOG_EKF5_MSG, sizeof(log_EKF5), \ { LOG_EKF5_MSG, sizeof(log_EKF5), \
"EKF5","IfffffBBc","TimeMS,flowX,flowY,omegaX,omegaY,gndPos,fScaler,flowQual,rng" } "EKF5","IhhhhcBcC","TimeMS,FIX,FIY,AFIX,AFIY,gndPos,fScaler,RI,rng" }
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
#define LOG_COMMON_STRUCTURES LOG_BASE_STRUCTURES, LOG_EXTRA_STRUCTURES #define LOG_COMMON_STRUCTURES LOG_BASE_STRUCTURES, LOG_EXTRA_STRUCTURES

View File

@ -996,21 +996,21 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs)
// Write fifth EKF packet // Write fifth EKF packet
float fscale; float fscale;
float gndPos; float gndPos;
float flowX, flowY; float flowInnovX, flowInnovY;
float omegaX, omegaY; float augFlowInnovX, augFlowInnovY;
float rngInnov;
float range; float range;
uint8_t flowQual; ahrs.get_NavEKF().getFlowDebug(fscale, gndPos, flowInnovX, flowInnovY, flowInnovY, augFlowInnovY, rngInnov, range);
ahrs.get_NavEKF().getFlowDebug(fscale, gndPos, flowX, flowY, omegaX, omegaY, flowQual, range);
struct log_EKF5 pkt5 = { struct log_EKF5 pkt5 = {
LOG_PACKET_HEADER_INIT(LOG_EKF5_MSG), LOG_PACKET_HEADER_INIT(LOG_EKF5_MSG),
time_ms : hal.scheduler->millis(), time_ms : hal.scheduler->millis(),
flowX : (float)(flowX), FIX : (int16_t)(1000*flowInnovX),
flowY : (float)(flowY), FIY : (int16_t)(1000*flowInnovY),
omegaX : (float)(omegaX), AFIX : (int16_t)(1000*flowInnovY),
omegaY : (float)(omegaY), AFIY : (int16_t)(1000*augFlowInnovY),
gndPos : (float)(gndPos), gndPos : (int16_t)(100*gndPos),
scaler: (uint8_t)(100*fscale), scaler: (uint8_t)(100*fscale),
quality : (uint8_t)(flowQual), RI : (int16_t)(100*rngInnov),
range : (uint16_t)(100*range) range : (uint16_t)(100*range)
}; };
WriteBlock(&pkt5, sizeof(pkt5)); WriteBlock(&pkt5, sizeof(pkt5));