GND_EFFECT_COMP not working as good as in Copter-4.0

My CubeOrange is running Copter-4.1-beta1 and I’ve tried the autoland several times but every single time my quad was bouncing back up in the air after the first touchdown. The ground effect compensation was working wonderfully with Copter-4.0 using the exact same drone frame and configuration. What’s different now? Do I have to adjust some parameters to get it working as before? Here goes one example log in case you need to analyze it:
https://1drv.ms/u/s!ArMDLLLI-Jmi9ykNhmDfK3nrZKu3?e=OI4fTZ

1 Like

Hi @terseven,

Thanks very much for the report. I’ve added it to the list of issues to be investigated for 4.1 so it won’t be forgotten. We’ve changed the default EKF from EKF2 to EKF3 so it’s possible EKF3 has an issue with the ground effect compensation… we will check!

The EKF solution status XKF4[0].SS during takeoff and touchdown shows that the takeoff and touchdown expected flags are not being set by the copter code. it is supposed to be set here: https://github.com/ArduPilot/ardupilot/blob/9a538ba15bd78d2040aab29f4ce3dfca83fa607d/ArduCopter/baro_ground_effect.cpp#L3

1 Like

Ok, I’ve found the issue so I don’t think it will take us long to fix it!

1 Like

@rmackay9 it seems to me to have yet some problems with GND_EFFECT_COMP on my 3 inch copter with MatekH743 Mini and ArduCopter V4.1.0-dev (3f77c527).
Little indoor flight in AltHold then Land. Problematic takeoff and two bounce on landing.

log:
https://drive.google.com/file/d/1CfdPEaiy8S-AgEbJYcV4trWtoohWp5up/view?usp=sharing

Hi @anbello,

Thanks for the testing and log file. Below is a graph showing when the takeoff expected flag (used to enable ground effect compensation) is on or off and we can see it is turned off just before the vehicle really needed it.

The logic for setting the flags is here in baro_ground_effect.cpp but in short it is:

  • takeoff-expected is set while the vehicle is landed (e.g. while the throttle is at zero)
  • takeoff-expected is unset once the EKF’s estimated altitude has climbed 0.5m or 5 seconds has passed (whichever is sooner)

In this case the problem is that the EKF altitude (shown in red) is climbing quite quickly before takeoff. I’m not sure why but it could be IMU warming or maybe the EKF just needed more time to calculate the “biases” (change in accelerometer offsets compared with when it was calibrated).

I suspect if you waited a little longer before takeoff the EKF altitude would have stabilized and it would have worked OK. I can imagine that we could improve things by ensuring the takeoff-expected flag is never unset in less than 2 seconds. BTW, I think this behaviour is unchanged vs 4.0.x.

By the way, if you want to see this yourself the important bits are the XKF4’s SS field’s 11th and 12th bits (where the first bit is the zeroth bit). Bit 11 is the “takeoff expected” flag and bit 12 is “landing expected”. If either of these is set then baro ground effect compensation will be active. I use this online decimal->binary converter to see the individual bits.

So “67749” is “10000100010100101” meaning “landing expected” is unset, “takeoff expected” is set.

1 Like

Thanks for the explanation @rmackay9, I understand the problem but I don’t see a possible solution.

For the temperature issue I had already done the IMU calibration.

For the bias I tried different values for EK3_ABIAS_P_NSE parameter without great improvement.

Ok cool i was going to report this as well its been a few months now with the ground scraps and mini bumps into the Tarmac.
Notice a fix was in the works. Suspect this had to do with auto landings of VTOLs and the odd jump during landing. But now Copter seems to wants to land once next to the ground then flying the ground effect. thanks for looking at this. BTW I normally had good landings no jumps but now ground effect is fighting me.

Here is a cut of Ground effect working perfectly going down a 30% grade sweeping the dust off the asphalt.

I only move the stick a little when reversing but not really necessary. . You can see just how smooth the Ground effect was. Cool Video effect as well.

Side Note: For me landing in stable normally I cut the throttle a 1/2 sec before landing.

@anbello,

I think the simple solution is to wait longer before taking off. If the vehicle was given another 30 seconds before takeoff I think it would have been ok. Could you try this?

Ground effect compensation should work as well in 4.1 as it did in 4.0 so I’m pretty sure you would have seen the same issue in 4.0 but please correct me if I’m wrong.

@Quadzilla,

Txs for the testing. The fixed ground effect compensation will be released in beta4 which will probably be out next week.

1 Like

@rmackay9 sorry for late reply, if I do as you suggested the takeoff is OK, the bit “takeoff expected” is on for the right time, but on landing I always have several bounce and the bit “landing expected” is never set.

Moreover after takeoff and stabilizing altitude in AltHold I always see the copter slowly climbing with throttle at 1500.

Regard to 4.0 vs 4.1 I can’t say I always used 4.1 with this Copter.

plot and log:

link to log
https://drive.google.com/file/d/1luUU8iSYVoMBIiF4PW5XrPTtQBf3r6Ai/view?usp=sharing

Anecdotally this is very similar to the poor AltHold and takeoff/landing performance that I see in 4.1 (I have lots of problems in 4.1 with landing not being detected). I definitely think there is a new issue here, likely candidate is EK3 vs EK2

1 Like

I have similar behavior of poor AltHold also with EK2. This test are all done indoor hence without GPS, when I test outdoor with GPS the things goes better.