DataFlash: Don't log EKF optical flow data if not required

This commit is contained in:
priseborough 2014-12-24 07:39:23 +11:00 committed by Randy Mackay
parent b6d300db19
commit b99b3c7b9d
2 changed files with 25 additions and 22 deletions

View File

@ -69,7 +69,7 @@ public:
void Log_Write_Power(void); void Log_Write_Power(void);
void Log_Write_AHRS2(AP_AHRS &ahrs); void Log_Write_AHRS2(AP_AHRS &ahrs);
#if AP_AHRS_NAVEKF_AVAILABLE #if AP_AHRS_NAVEKF_AVAILABLE
void Log_Write_EKF(AP_AHRS_NavEKF &ahrs); void Log_Write_EKF(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled);
#endif #endif
void Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t& mav_cmd); void Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t& mav_cmd);
void Log_Write_Radio(const mavlink_radio_t &packet); void Log_Write_Radio(const mavlink_radio_t &packet);

View File

@ -894,7 +894,7 @@ void DataFlash_Class::Log_Write_AHRS2(AP_AHRS &ahrs)
} }
#if AP_AHRS_NAVEKF_AVAILABLE #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 // Write first EKF packet
Vector3f euler; Vector3f euler;
@ -1005,7 +1005,9 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs)
}; };
WriteBlock(&pkt4, sizeof(pkt4)); WriteBlock(&pkt4, sizeof(pkt4));
// Write fifth EKF packet // Write fifth EKF packet
if (optFlowEnabled) {
float fscale; float fscale;
float gndPos; float gndPos;
float flowInnovX, flowInnovY; float flowInnovX, flowInnovY;
@ -1027,6 +1029,7 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs)
}; };
WriteBlock(&pkt5, sizeof(pkt5)); WriteBlock(&pkt5, sizeof(pkt5));
} }
}
#endif #endif
// Write a command processing packet // Write a command processing packet