mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_AHRS: prevent a large delta_t from affecting DCM solution
this should fix large changes in attitude directly after arming ArduCopter
This commit is contained in:
parent
a523c319ce
commit
e28cbed1e9
@ -43,6 +43,15 @@ AP_AHRS_DCM::update(void)
|
|||||||
// ask the IMU how much time this sensor reading represents
|
// ask the IMU how much time this sensor reading represents
|
||||||
delta_t = _ins->get_delta_time();
|
delta_t = _ins->get_delta_time();
|
||||||
|
|
||||||
|
// if the update call took more than 0.2 seconds then discard it,
|
||||||
|
// otherwise we may move too far. This happens when arming motors
|
||||||
|
// in ArduCopter
|
||||||
|
if (delta_t > 0.2) {
|
||||||
|
_ra_sum.zero();
|
||||||
|
_ra_deltat = 0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
// Get current values for gyros
|
// Get current values for gyros
|
||||||
_gyro_vector = _ins->get_gyro();
|
_gyro_vector = _ins->get_gyro();
|
||||||
_accel_vector = _ins->get_accel();
|
_accel_vector = _ins->get_accel();
|
||||||
|
Loading…
Reference in New Issue
Block a user