|
|
|
@ -1009,23 +1009,25 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled)
@@ -1009,23 +1009,25 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled)
|
|
|
|
|
// Write fifth EKF packet
|
|
|
|
|
if (optFlowEnabled) { |
|
|
|
|
float fscale; |
|
|
|
|
float gndPos; |
|
|
|
|
float estHAGL; |
|
|
|
|
float flowInnovX, flowInnovY; |
|
|
|
|
float augFlowInnovX, augFlowInnovY; |
|
|
|
|
float flowVarX, flowVarY; |
|
|
|
|
float rngInnov; |
|
|
|
|
float range; |
|
|
|
|
ahrs.get_NavEKF().getFlowDebug(fscale, gndPos, flowInnovX, flowInnovY, augFlowInnovX, augFlowInnovY, rngInnov, range); |
|
|
|
|
float gndOffsetErr; |
|
|
|
|
ahrs.get_NavEKF().getFlowDebug(fscale, estHAGL, flowInnovX, flowInnovY, flowVarX, flowVarY, rngInnov, range, gndOffsetErr); |
|
|
|
|
struct log_EKF5 pkt5 = { |
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_EKF5_MSG), |
|
|
|
|
time_ms : hal.scheduler->millis(), |
|
|
|
|
FIX : (int16_t)(1000*flowInnovX), |
|
|
|
|
FIY : (int16_t)(1000*flowInnovY), |
|
|
|
|
AFIX : (int16_t)(1000*augFlowInnovX), |
|
|
|
|
AFIY : (int16_t)(1000*augFlowInnovY), |
|
|
|
|
gndPos : (int16_t)(100*gndPos), |
|
|
|
|
normInnovFX : min((uint8_t)(100*flowVarX),255), |
|
|
|
|
normInnovFY : min((uint8_t)(100*flowVarY),255), |
|
|
|
|
estHAGL : (uint16_t)(100*estHAGL), |
|
|
|
|
scaler: (uint8_t)(100*fscale), |
|
|
|
|
RI : (int16_t)(100*rngInnov), |
|
|
|
|
range : (uint16_t)(100*range) |
|
|
|
|
meaRng : (uint16_t)(100*range), |
|
|
|
|
errHAGL : (uint16_t)(100*gndOffsetErr) |
|
|
|
|
}; |
|
|
|
|
WriteBlock(&pkt5, sizeof(pkt5)); |
|
|
|
|
} |
|
|
|
|