|
|
|
@ -894,7 +894,7 @@ void DataFlash_Class::Log_Write_AHRS2(AP_AHRS &ahrs)
@@ -894,7 +894,7 @@ void DataFlash_Class::Log_Write_AHRS2(AP_AHRS &ahrs)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if AP_AHRS_NAVEKF_AVAILABLE |
|
|
|
|
void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs) |
|
|
|
|
void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled) |
|
|
|
|
{ |
|
|
|
|
// Write first EKF packet
|
|
|
|
|
Vector3f euler; |
|
|
|
@ -1005,27 +1005,30 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs)
@@ -1005,27 +1005,30 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs)
|
|
|
|
|
}; |
|
|
|
|
WriteBlock(&pkt4, sizeof(pkt4)); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// Write fifth EKF packet
|
|
|
|
|
float fscale; |
|
|
|
|
float gndPos; |
|
|
|
|
float flowInnovX, flowInnovY; |
|
|
|
|
float augFlowInnovX, augFlowInnovY; |
|
|
|
|
float rngInnov; |
|
|
|
|
float range; |
|
|
|
|
ahrs.get_NavEKF().getFlowDebug(fscale, gndPos, flowInnovX, flowInnovY, augFlowInnovX, augFlowInnovY, rngInnov, range); |
|
|
|
|
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), |
|
|
|
|
scaler: (uint8_t)(100*fscale), |
|
|
|
|
RI : (int16_t)(100*rngInnov), |
|
|
|
|
range : (uint16_t)(100*range) |
|
|
|
|
}; |
|
|
|
|
WriteBlock(&pkt5, sizeof(pkt5)); |
|
|
|
|
if (optFlowEnabled) { |
|
|
|
|
float fscale; |
|
|
|
|
float gndPos; |
|
|
|
|
float flowInnovX, flowInnovY; |
|
|
|
|
float augFlowInnovX, augFlowInnovY; |
|
|
|
|
float rngInnov; |
|
|
|
|
float range; |
|
|
|
|
ahrs.get_NavEKF().getFlowDebug(fscale, gndPos, flowInnovX, flowInnovY, augFlowInnovX, augFlowInnovY, rngInnov, range); |
|
|
|
|
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), |
|
|
|
|
scaler: (uint8_t)(100*fscale), |
|
|
|
|
RI : (int16_t)(100*rngInnov), |
|
|
|
|
range : (uint16_t)(100*range) |
|
|
|
|
}; |
|
|
|
|
WriteBlock(&pkt5, sizeof(pkt5)); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|