AP_NavEKF : Update optical flow debug logging

This commit is contained in:
priseborough 2014-11-01 13:27:22 +11:00 committed by Andrew Tridgell
parent 1791dec622
commit 06c19a3a4d
2 changed files with 7 additions and 7 deletions

View File

@ -3622,15 +3622,15 @@ bool NavEKF::getLLH(struct Location &loc) const
}
// return data for debugging optical flow fusion
void NavEKF::getFlowDebug(float &scaleFactor, float &gndPos, float &flowX, float &flowY, float &omegaX, float &omegaY, uint8_t &quality, float &range) const
void NavEKF::getFlowDebug(float &scaleFactor, float &gndPos, float &flowInnovX, float &flowInnovY, float &augFlowInnovX, float &augFlowInnovY, float &rngInnov, float &range) const
{
scaleFactor = flowStates[0];
flowX = flowRadXY[0];
flowY = flowRadXY[1];
omegaX = omegaAcrossFlowTime.x;;
omegaY = omegaAcrossFlowTime.y;;
gndPos = flowStates[1];
quality = flowQuality;
flowInnovX = innovOptFlow[0];
flowInnovY = innovOptFlow[1];
augFlowInnovX = auxFlowObsInnov[0];
augFlowInnovY = auxFlowObsInnov[1];
rngInnov = innovRng;
range = rngMea;
}

View File

@ -163,7 +163,7 @@ public:
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, uint8_t &rangeHealth, float &rawSonarRange);
// return data for debugging optical flow fusion
void getFlowDebug(float &scaleFactor, float &gndPos, float &flowX, float &flowY, float &omegaX, float &omegaY, uint8_t &quality, float &range) const;
void getFlowDebug(float &scaleFactor, float &gndPos, float &flowInnovX, float &flowInnovY, float &augFlowInnovX, float &augFlowInnovY, float &rngInnov, float &range) const;
/*
return the filter fault status as a bitmasked integer