Browse Source

AP_NavEKF : Update names in optical flow debug logging

master
priseborough 11 years ago committed by Andrew Tridgell
parent
commit
a20729f60f
  1. 10
      libraries/AP_NavEKF/AP_NavEKF.cpp
  2. 2
      libraries/AP_NavEKF/AP_NavEKF.h

10
libraries/AP_NavEKF/AP_NavEKF.cpp

@ -3557,13 +3557,13 @@ bool NavEKF::getLLH(struct Location &loc) const @@ -3557,13 +3557,13 @@ bool NavEKF::getLLH(struct Location &loc) const
}
// 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];
obsX = flowRadXY[0];
obsY = flowRadXY[1];
innovX = omegaAcrossFlowTime.x;//innovOptFlow[0];
innovY = omegaAcrossFlowTime.y;//innovOptFlow[1];
flowX = flowRadXY[0];
flowY = flowRadXY[1];
omegaX = omegaAcrossFlowTime.x;;
omegaY = omegaAcrossFlowTime.y;;
gndPos = flowStates[1];
quality = flowQuality;
}

2
libraries/AP_NavEKF/AP_NavEKF.h

@ -163,7 +163,7 @@ public: @@ -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 &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

Loading…
Cancel
Save