mirror of https://github.com/ArduPilot/ardupilot
DCM: added a small amount of accel smoothing to update_DCM_fast()
This commit is contained in:
parent
a0ce202d87
commit
6ba6e11e7b
|
@ -57,7 +57,7 @@ AP_DCM::update_DCM_fast(void)
|
||||||
_gyro_vector = _imu->get_gyro(); // Get current values for IMU sensors
|
_gyro_vector = _imu->get_gyro(); // Get current values for IMU sensors
|
||||||
|
|
||||||
accel = _imu->get_accel();
|
accel = _imu->get_accel();
|
||||||
_accel_vector = (_accel_vector * 0.0) + (accel * 1.0);
|
_accel_vector = (_accel_vector * 0.5) + (accel * 0.5);
|
||||||
|
|
||||||
delta_t = _imu->get_delta_time();
|
delta_t = _imu->get_delta_time();
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue