mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AHRS_DCM: integrate INS use_accel
This commit is contained in:
parent
0b981d38e8
commit
7f46cc9059
@ -571,7 +571,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
||||
|
||||
//update _accel_ef_blended
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
if (_ins.get_accel_count() == 2 && _ins.get_accel_health(0) && _ins.get_accel_health(1)) {
|
||||
if (_ins.get_accel_count() == 2 && _ins.use_accel(0) && _ins.use_accel(1)) {
|
||||
float imu1_weight_target = _active_accel_instance == 0 ? 1.0f : 0.0f;
|
||||
// slew _imu1_weight over one second
|
||||
_imu1_weight += constrain_float(imu1_weight_target-_imu1_weight, -deltat, deltat);
|
||||
|
Loading…
Reference in New Issue
Block a user