mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_AHRS: remove pointless zeroing of gyro_estimate vector
This value is assigned to in the following "if" block in both the for and against cases, and isn't used to determine the new value.
This commit is contained in:
parent
73bad9fd2d
commit
29aed55a74
@ -457,7 +457,6 @@ void AP_AHRS::update_EKF2(void)
|
||||
_gyro_drift = -_gyro_drift;
|
||||
|
||||
// calculate corrected gyro estimate for get_gyro()
|
||||
_gyro_estimate.zero();
|
||||
if (primary_imu == -1 || !_ins.get_gyro_health(primary_imu)) {
|
||||
// the primary IMU is undefined so use an uncorrected default value from the INS library
|
||||
_gyro_estimate = _ins.get_gyro();
|
||||
@ -537,7 +536,6 @@ void AP_AHRS::update_EKF3(void)
|
||||
_gyro_drift = -_gyro_drift;
|
||||
|
||||
// calculate corrected gyro estimate for get_gyro()
|
||||
_gyro_estimate.zero();
|
||||
if (primary_imu == -1 || !_ins.get_gyro_health(primary_imu)) {
|
||||
// the primary IMU is undefined so use an uncorrected default value from the INS library
|
||||
_gyro_estimate = _ins.get_gyro();
|
||||
|
Loading…
Reference in New Issue
Block a user