mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Fix bug preventing use of optical flow with multiple IMU's
This commit is contained in:
parent
01766e7069
commit
ca31ced2b4
|
@ -823,7 +823,9 @@ bool NavEKF2::use_compass(void) const
|
|||
void NavEKF2::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas)
|
||||
{
|
||||
if (core) {
|
||||
core[primary].writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas);
|
||||
for (uint8_t i=0; i<num_cores; i++) {
|
||||
core[i].writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue