mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-17 21:17:35 +08:00
Add const modifier and increase matrix library usage
This commit is contained in:
committed by
Mathieu Bresciani
parent
d9afc2f1e8
commit
c2801eb488
@@ -101,9 +101,7 @@ void Ekf::fuseOptFlow()
|
|||||||
// calculate optical LOS rates using optical flow rates that have had the body angular rate contribution removed
|
// calculate optical LOS rates using optical flow rates that have had the body angular rate contribution removed
|
||||||
// correct for gyro bias errors in the data used to do the motion compensation
|
// correct for gyro bias errors in the data used to do the motion compensation
|
||||||
// Note the sign convention used: A positive LOS rate is a RH rotation of the scene about that axis.
|
// Note the sign convention used: A positive LOS rate is a RH rotation of the scene about that axis.
|
||||||
Vector2f opt_flow_rate;
|
const Vector2f opt_flow_rate = _flow_compensated_XY_rad / _flow_sample_delayed.dt + Vector2f(_flow_gyro_bias);
|
||||||
opt_flow_rate(0) = _flow_compensated_XY_rad(0) / _flow_sample_delayed.dt + _flow_gyro_bias(0);
|
|
||||||
opt_flow_rate(1) = _flow_compensated_XY_rad(1) / _flow_sample_delayed.dt + _flow_gyro_bias(1);
|
|
||||||
|
|
||||||
if (opt_flow_rate.norm() < _flow_max_rate) {
|
if (opt_flow_rate.norm() < _flow_max_rate) {
|
||||||
_flow_innov[0] = vel_body(1) / range - opt_flow_rate(0); // flow around the X axis
|
_flow_innov[0] = vel_body(1) / range - opt_flow_rate(0); // flow around the X axis
|
||||||
|
|||||||
Reference in New Issue
Block a user