mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_NavEKF : Modify optical flow data interface
Sign conventions have changed
This commit is contained in:
parent
a72b6b179b
commit
9ea97c1a38
@ -4022,8 +4022,8 @@ void NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, V
|
||||
Tnb_flow = Tbn_flow.transposed();
|
||||
// write uncorrected flow rate measurements that will be used by the focal length scale factor estimator
|
||||
// note correction for different axis and sign conventions used by the px4flow sensor
|
||||
flowRadXY[0] = + rawFlowRates.y; // raw (non motion compensated) optical flow angular rate about the X axis (rad/sec)
|
||||
flowRadXY[1] = - rawFlowRates.x; // raw (non motion compensated) optical flow angular rate about the Y axis (rad/sec)
|
||||
flowRadXY[0] = - rawFlowRates.x; // raw (non motion compensated) optical flow angular rate about the X axis (rad/sec)
|
||||
flowRadXY[1] = - rawFlowRates.y; // raw (non motion compensated) optical flow angular rate about the Y axis (rad/sec)
|
||||
// write flow rate measurements corrected for focal length scale factor errors and body rates
|
||||
flowRadXYcomp[0] = flowStates[0]*flowRadXY[0] + omegaAcrossFlowTime.x;
|
||||
flowRadXYcomp[1] = flowStates[0]*flowRadXY[1] + omegaAcrossFlowTime.y;
|
||||
|
Loading…
Reference in New Issue
Block a user