AP_NavEKF : Update names in optical flow debug logging

This commit is contained in:
priseborough 2014-09-10 19:32:43 +10:00 committed by Andrew Tridgell
parent 235b3bebda
commit a20729f60f
2 changed files with 6 additions and 6 deletions

View File

@ -3557,13 +3557,13 @@ bool NavEKF::getLLH(struct Location &loc) const
} }
// return data for debugging optical flow fusion // return data for debugging optical flow fusion
void NavEKF::getFlowDebug(float &scaleFactor, float &obsX, float &obsY, float &innovX, float &innovY, float &gndPos, uint8_t &quality) const void NavEKF::getFlowDebug(float &scaleFactor, float &gndPos, float &flowX, float &flowY, float &omegaX, float &omegaY, uint8_t &quality) const
{ {
scaleFactor = flowStates[0]; scaleFactor = flowStates[0];
obsX = flowRadXY[0]; flowX = flowRadXY[0];
obsY = flowRadXY[1]; flowY = flowRadXY[1];
innovX = omegaAcrossFlowTime.x;//innovOptFlow[0]; omegaX = omegaAcrossFlowTime.x;;
innovY = omegaAcrossFlowTime.y;//innovOptFlow[1]; omegaY = omegaAcrossFlowTime.y;;
gndPos = flowStates[1]; gndPos = flowStates[1];
quality = flowQuality; quality = flowQuality;
} }

View File

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