AP_AHRS : temporary mods to test use of flow sensor internal gyro data

This commit is contained in:
priseborough 2014-08-16 18:41:28 +10:00 committed by Andrew Tridgell
parent 635e593d55
commit 12b012a00e
2 changed files with 3 additions and 3 deletions

View File

@ -318,9 +318,9 @@ bool AP_AHRS_NavEKF::initialised(void) const
};
// write optical flow data to EKF
void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, float &rawSonarRange, uint32_t &msecFlowMeas)
void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, float &rawSonarRange, uint32_t &msecFlowMeas)
{
EKF.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawSonarRange, msecFlowMeas);
EKF.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, rawSonarRange, msecFlowMeas);
}
#endif // AP_AHRS_NAVEKF_AVAILABLE

View File

@ -102,7 +102,7 @@ public:
bool get_relative_position_NED(Vector3f &vec) const;
// write optical flow measurements to EKF
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, float &rawSonarRange, uint32_t &msecFlowMeas);
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, float &rawSonarRange, uint32_t &msecFlowMeas);
void set_ekf_use(bool setting) { _ekf_use.set(setting); }