mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF : Reduce ripple in estimates that can cause copter motor 'pulsing'
This patch reduces the level of 5Hz and 10Hz 'pulsing' heard in motors due to GPS and altimeter fusion which cause a small 5Hz and 10Hz ripple on the output under some conditions. Attitude, velocity and position state corrections from GPS, altimeter and magnetometer measurements are applied incrementally in the interval from receiving the measurement to the predicted time of receipt of the next measurement. Averaging of attitude state corrections is not performed during periods of rapid rotation. Time stamps are now explicitly initialised to the current IMU time to avoid unwanted activation of timeout logic on filter start and the various calls to the hal.scheduler->millis() object have been consolidated. Unused variables have been removed
This commit is contained in:
parent
dcb252cc05
commit
13df6fb1c9
|
@ -428,6 +428,8 @@ void NavEKF::ResetPosition(void)
|
|||
storedStates[i].position[0] = state.position[0];
|
||||
storedStates[i].position[1] = state.position[1];
|
||||
}
|
||||
// reset the glitch ofset correction states
|
||||
gpsPosGlitchOffsetNE.zero();
|
||||
}
|
||||
|
||||
// resets velocity states to last GPS measurement or to zero if in static mode
|
||||
|
|
Loading…
Reference in New Issue