Copter sometimes flips on auto-land

Hello,

Since upgrading to v4.0 we have seen multiple incidents of copter’s flipping on landing (in auto mode). The copter will touch down, but will not disarm on it’s own and will violently oscillate until it flips.

The really strange part is this: Even when we send a MAV_COMPONENT_ARM_DISARM command to force disarm (with the correct magic packet), the copter still flips. The flips also consistently favor one side of the drone (suggesting that some of the motors are not idling).

We have not seen this issue in previous versions of ArduCopter and have replicated it on 3 drones. When we downgrade to 3.6.11 the issue goes away.

Any help debugging this would be appreciated.

Initial log (more to come soon):

@nikhildixit,

Detecting a landing is quite tough I’m afraid because although it seems simple, there are always edge cases (like updrafts) that mean it’s a balancing act.

I’m not aware of any changes in the heuristics between Copter-3.6.x and Copter-4.0.x so looking forward to a log of Copter-3.6.x working while Copter-4.0 does not. If those could be as close as possible to back-to-back logs that would be really helpful.

I’ve had a quick look at the logs and the only thing that comes to mind is that the MOT_SPIN_ARM and MOT_SPIN_MIN parameters are quite high at 0.15 (15%). Most ESCs can go lower than this.

Your case is similar to my situation

I understand. We have had land detection issues for some time but it has been OK because we’ve used the MAV_COMPONENT_ARM_DISARM command to force the props off, and that has always worked.

What’s scary now is that even the force disarm command itself seems to sometimes cause a flip, and I don’t know how that could be possible.

I’ve been trying to find out in the logs when the copter receives the disarm command from the GCS and what it does after that, but I haven’t been able to do that yet.

Here is another log of a separate drone exhibiting the same issue (note that it again flips in the a similar direction despite being a different drone altogether):

I’ll upload some more direct comparison logs tomorrow.

We’ve used these values for some time now so it is unlikely they’re the root cause. We will try lower values though.

@nikhildixit,

I’ve just done a quick test with Copter-4.0.3-rc1 (and Copter-3.6.12) and it seems to be obeying the force disarm command which is a COMMAND_LONG with the command field set to MAV_COMPONENT_ARM_DISARM and param1 = 0, param2 = 21196.

Can you confirm this is the command you’re sending to disarm?

It’s hard to imagine a way that the arm/disarm command could actually cause a flip. I suspect it’s just a coincidence in timing.

Yep, those are the params I’m sending. Verbatim:

        let mav_cmd_disarm = new mavlink.messages.command_long(
            uas.id,
            1,
            mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
            0,
            0,
            21196,
            0,
            0,
            0,
            0,
            0
        );

I agree this is extremely bizarre. The one thing we did change was to auto-disable the safety switch on disarm. Is it possible that there’s some kind of race between when the motors turn off and the safety switch self-disables?

Here is a video of the event (they all look like this). The pilot force disarmed as soon as the drone was on the ground, and the flip happened right afterwards.

@nikhildixit,

It looks like the vehicle’s system id has been changed to “3” (see the SYSID_THISMAV parameter). I wonder if there could be a mismatch with the command being sent. Maybe try with one of the standard ground stations like MP or MAVProxy?

I’ll have a chat with Leonard Hall (our controls expert) to see if we can come up with any other ideas for improving the landing detection. It’s really not easy though.

It looks like the vehicle’s system id has been changed to “3” (see the SYSID_THISMAV parameter). I wonder if there could be a mismatch with the command being sent.

The 2nd log is for a drone with a SYSID_THISMAV of 3. I believe the GCS is sending the right command since this part of our codebase also hasn’t changed in a while and it’s been working. (the “uas.id” field comes straight from SYSID_THISMAV)

I’ll have a chat with Leonard Hall (our controls expert) to see if we can come up with any other ideas for improving the landing detection. It’s really not easy though.

Understood.

Is it possible from the logs to check when Copter receives the MAV_COMPONENT_ARM_DISARM command? I’d really like to know what the motors outputs go to as soon as that is received.

@nikhildixit,

It looks like the vehicle is rolling over after the motors have shutdown. Below is a graph of the pwm outputs to the motors (scale is on the left) and then the vehicle’s roll and pitch angle on the right.

Is it possible that perhaps the ESCs are not calibrated or some are still providing some thrust after they’ve been shutdown? Maybe the landing gear isn’t wide enough? I’m not sure but just looks like it could be a physical problem rather than a control problem.

Interesting. Just when I thought this couldn’t get any more confusing. The ESCs come factory calibrated, we are physically unable to calibrate them.

Is there some way for us to spool the motors down gently on force disarm? Would MOT_SLEW_DN_TIME work?

No, the forced disarm takes effect immediately so there won’t be any spool down I think. Modifying that MOT_SLEW_DN_TIME might help or perhaps reducing LAND_SPEED to 30cm/s might help.

By the way Leonard and I reviewed the landing detector and we found an issue with the accelerations being used for part of the landing detector (fix is here). This will help in those cases where the vehicle’s vibration levels are a bit higher. In some vehicles vibration levels actually go up when they land because the frame bangs up and down against the ground.