AP_NavEKF3/ArduCopter: hover Z-bias learning for vibration rectification#32041
AP_NavEKF3/ArduCopter: hover Z-bias learning for vibration rectification#32041andyp1per wants to merge 9 commits intoArduPilot:masterfrom
Conversation
d7e2632 to
26d8a59
Compare
|
I noticed this Z bias on some flight logs. Can you explain why we need to do this and what happens with the EKF currently just dealing with the Z bias? |
To control Z-bias well you need a Z velocity source, which basically means GPS. Indoors not so much, Z-bias is only weakly observable via the Baro and Baro is often problematic at takeoff - in fact you essentially can't use it at takeoff because of ground effect - so at takeoff indoors if your Z-bias is off you will have problems. The accel calibration is supposed to calibrate the Z-bias but I have found that even on really well setup quads with good temperature calibration of the IMUs there is still a discernible - but fixed - DC offset once the motors start running which must be down to VRF. Being on the ground makes things worse, so part of this PR is to not learn bad offsets at times when bad offsets will almost certainly be learnt. |
26d8a59 to
6e4ace9
Compare
| // Note: We fuse zero velocity whenever on ground, not just when fuseHgtData is true, | ||
| // because height fusion only happens at baro rate (~10Hz) but we want continuous | ||
| // velocity correction while stationary. | ||
| const bool onGroundNotFlying2 = onGround || dal.get_takeoff_expected(); |
There was a problem hiding this comment.
I’m concerned here about fusing a confident zero-velocity measurement based solely on onGround (which I think is always true for Copter when disarmed)
onGround == true might not imply the vehicle is stationary. There might be use-cases where the vehicle can be moving while still on ground and disarmed (e.g. copter on a moving boat deck, plane taxiing, vehicle being carried by hand). In these cases, injecting a low-noise zero vel introduces a strong measurement that conflicts with real motion.
If this happens (I think) the EKF will attempt to satisfy v = 0 by distorting other states (most likely accelerometer bias, attitude).
Maybe you should consider using "onGroundNotMoving" flag?
| } else if (fusingStationaryZeroVel) { | ||
| // Fusing synthetic zero velocity while stationary on ground - use small noise | ||
| // since we are confident velocity is zero when disarmed and on ground | ||
| R_OBS[0] = sq(0.5f); |
There was a problem hiding this comment.
I feel we should be more conservative here; after all, it's not a real measurement. Maybe this needs to be a function of some of the logic used in calculating " onGroundNotMoving".
| R_OBS[2] = R_OBS[0]; | ||
| for (uint8_t i=0; i<=2; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i]; | ||
| // Position noise still uses normal sensor values since position may be fused from actual sensors | ||
| R_OBS[3] = sq(constrain_ftype(frontend->_gpsHorizPosNoise, 0.1f, 10.0f)); |
There was a problem hiding this comment.
I am not sure I understand this. Wy _gpsHorizPosNoise? Could be any other position aiding sensor?
|
|
||
| // @Param: ACC_ZBIAS_LEARN | ||
| // @DisplayName: Accel Z-axis Bias Learning | ||
| // @Description: Bitmask controlling accelerometer Z-axis bias learning during hover to compensate for vibration rectification. Bit 0: Learn bias during hover and save to EEPROM on disarm. Bit 1: Use saved bias values (apply correction to EKF). Bit 2: Disable EKF bias learning while disarmed (don't use zero velocity assumption on ground). |
There was a problem hiding this comment.
Do we need clarification that this stuff is only valid if EK3 is active? I.e not when DCM/Ek2/ExtAHRS is used
33cfbd2 to
984aaf9
Compare
|
I need to go through the EKF changes in more detail, but a few comments: The hover offset seems like a work around for bad HW setups , so should be optionally enabled via EK3_OPTIONS parameter IMO We have protection against baro ground effect spike, but it only works in one direction, ie ardupilot/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp Lines 1025 to 1035 in 6a6d1fe Does this need to be modified to handle altitude errors that go the other way? |
|
Looks like there's a lot of stuff in here about ground effect, should that be a separate PR? |
I would like to see the baro error handling spit out. |
|
Not all vehicle types takeoff with the Z axis aligned with the gravity vector. Tailsitters will have the X axis aligned with the gravity vector. |
Will do separate PR's when stuff is working and we have some agreeent about what is sane and what is not. |
Good point. How do we handle this currently? |
Currently it's a copter parameter, so disabled by default.
So far all the logs I have for actual takeoff the ground effect only goes in one direction, but after takeoff can go in the other (so on takeoff the floor dominates and after takeof the airflow in the frame dominates). So I am not sure this needs to support both directions, but will get more logs to verify |
Note its not really a fix for bad setups - the EKF will learn the bias eventually anyway so I suspect if you look closely you will see the effect on many (most?) vehicles. The problem is the learning takes too long and is too noisy without a GPS as a reference so this basically gives the EKF a head start to a known good state. Even with a GPS you can see this effect very clearly in small quads. When you hover outside you will initially get a good hover and then the copter will start to descend and then ascend again until it is stable again. This is all the Z-bias learning going on. |
Fuse zero velocity observations when the vehicle is stationary on the ground to improve EKF state estimation before takeoff. This makes accel bias observable and prevents velocity drift from motor-induced accelerometer offsets. Use onGroundNotMoving instead of onGround to avoid fusing zero velocity when the vehicle is being moved (e.g. on a boat or carried by hand). Remove yaw source gate from updateMovementCheck to prevent spurious movement detection with external yaw sources.
Add INS_ACC_VRFB_Z parameter array to store per-IMU vibration rectification Z-axis bias values. These are saved by ArduCopter's hover Z-bias learning feature and loaded by EKF3 at init to correct accelerometer readings from the first prediction cycle.
Add AP::ins() link stub to DAL_Standalone build so it can link against AP_NavEKF3 code that now calls AP::ins() to load hover Z-bias corrections from INS parameters at filter init.
Add pass-through methods on AP_AHRS for ArduCopter to set and get hover Z-bias corrections and learning inhibit state on the EKF3 backend.
Add TKOFF_GNDEFF_ALT and TKOFF_GNDEFF_TMO parameters for improved ground effect detection during takeoff and landing. TKOFF_GNDEFF_ALT sets the altitude threshold above which ground effect compensation is disabled and re-enables it on descent. TKOFF_GNDEFF_TMO requires both a timeout and altitude threshold before disabling ground effect. Touchdown detection is also limited to below TKOFF_GNDEFF_ALT to allow EKF bias learning when hovering at altitude.
Add ACC_ZBIAS_LEARN bitmask parameter (default 0, EK3-only) to control hover Z-bias learning for vibration rectification compensation: bit 0: learn and save bias during stable hover bit 1: use saved bias values from INS_ACC_VRFB_Z bit 2: inhibit EKF bias learning while disarmed Measures vibration rectification bias during stable hover and saves corrections to INS_ACC_VRFB_Z params for EKF3 to apply from first prediction cycle on next boot. Learning is inhibited during ground effect to avoid learning motor thrust offset as bias.
Inhibit EKF accel bias learning while in acro mode with motors at full throttle, since high-G maneuvers can cause unwanted bias learning. Re-enable on mode exit.
Add VibrationRectificationBiasLearning and TakeoffGroundEffect tests to ArduCopter autotest suite. Tests verify hover Z-bias learning, parameter saving, ground effect detection, and bias application after reboot.
984aaf9 to
6782946
Compare
Summary
This PR adds a hover Z-axis accelerometer bias learning system to compensate for vibration rectification — a DC offset in AccZ caused by motor vibration that only exists when motors are running. This bias differs between ground and flight, making it unobservable to the EKF during static calibration.
Key changes:
correctDeltaVelocity(), surviving EKF lane switches and resetsTKOFF_GNDEFF_ALTsets altitude threshold,TKOFF_GNDEFF_TMOrequires both time AND altitude before clearing ground effectACC_ZBIAS_LEARNdisables EKF zero velocity assumption when disarmedArchitecture
The system is split across layers with clear separation of concerns:
AP_NavEKF3AP_InertialSensorACC_VRF_BZ) as persistent parametersAP_AHRSArduCopterParameters
TKOFF_GNDEFF_ALTTKOFF_GNDEFF_TMOACC_ZBIAS_LEARNINSx_ACC_VRFB_ZACC_ZBIAS_LEARN Bitmask
Common values: 0=disabled, 3=learn+use (default), 7=learn+use+inhibit ground learning
Test plan
./waf coptercompiles clean