Stumped on wayward track to Home

My APM 2.5 has been working great for over a year. On the last three flights it has exhibited curious final WP (home) track behavior.
Plane is an EZ Star
External Compass
Latest 2.78b FW

The plane tracks all WPs like it was on a rail EXCEPT the final WP0 (home). From the WP before home to home it veers to the right and can’t really seem to get back on course.
I have checked CLI tests and they all pass. I have reloaded FW. I have calibrated.
Any ideas or help would be greatly appreciated.
Steven

Hi Steven,

I’m moving this post to the APM:Plane, 2.8 subforum where I believe you will get a better support with this issue.

Steven, my guess is you need to add a land command but please post a log. Without that it is impossible to help you.

Attached, please find my tlog from this flight. One thing that is apparent and was not an issue before, is that the NAV_ROLL and ROLL are very much divergent. I’m not sure what would cause this. There is sufficient I in the PID that this should not occur. The Pitch is dead nuts and tracks very well.
Again, for the whole Mission, except for the final run home, the plane is like it is on rails. Why the huge off course issue occurs on the home run, I have no idea.
Any help much appreciated.
Steven

[quote=“Steven G”]Attached, please find my tlog from this flight. One thing that is apparent and was not an issue before, is that the NAV_ROLL and ROLL are very much divergent. I’m not sure what would cause this. There is sufficient I in the PID that this should not occur. The Pitch is dead nuts and tracks very well.
Again, for the whole Mission, except for the final run home, the plane is like it is on rails. Why the huge off course issue occurs on the home run, I have no idea.
Any help much appreciated.
Steven[/quote]

I see nothing wrong with your path… I’ll look at the roll vs nav roll.

You are constantly offset by ~10 degrees… The integrator should be making it go away, and I don’t know why it is not. Try making the gain bigger (it can safely be much higher than it is). Also (separately) see if increasing IMAX makes a difference.

Get back to me if you can’t get this roll offset to go away. It could be a numerical bug (I don’t see any stray integers that could be causing that) or it might think that it doesn’t have an airspeed estimate:

    // Get an airspeed estimate - default to zero if none available
    float aspeed;
    if (!_ahrs.airspeed_estimate(&aspeed)) {
        aspeed = 0.0f;
    }

Oh, I was looking at your path backwards. Now I see the problem. I’m guessing we reset some integrators that we shouldn’t be resetting on RTL, and that combined with your roll offset to produce this issue. It looks like it was going to make it home, just not on the straightest possible path.

Edit: I am revising my guess. There isn’t any integrator in the L1 controller - if it did, you wouldn’t have these slight crosstrack errors to the right on all legs. it appears to me that the RTL at the end of the mission isn’t doing crosstracking at all, and is therefore making a spiraling path towards home… I need to look into this further.

Edit2: Yes, I have confirmed this. Here’s what we do when we run out of commands (waypoints):

static void handle_no_commands() { gcs_send_text_fmt(PSTR("Returning to Home")); next_nav_command = rally_find_best_location(current_loc, home); next_nav_command.id = MAV_CMD_NAV_LOITER_UNLIM; nav_command_ID = MAV_CMD_NAV_LOITER_UNLIM; non_nav_command_ID = WAIT_COMMAND; handle_process_nav_cmd(); }

As you can see, it sets the mode to loiter over home. It does not try to fly a line to home. So, your issue is a combination of:

  • your roll offset (good eye)
  • you didn’t set a final waypoint near home
  • we don’t crosstrack on our way home (we could do better)

Thanks for the analysis. The question that I have is it was working fine before. I can’t say for sure I did a FW upgrade when this unusual behavior started. I am sure, that my NAV_ROLL and ROLL used to be about 1 degree apart on the average. Now the offset is huge. I can increase I but I think something else is wrong.
Thanks,
Steven

[quote=“Steven G”]Thanks for the analysis. The question that I have is it was working fine before. I can’t say for sure I did a FW upgrade when this unusual behavior started. I am sure, that my NAV_ROLL and ROLL used to be about 1 degree apart on the average. Now the offset is huge. I can increase I but I think something else is wrong.
Thanks,
Steven[/quote]

A pull request has been made that fixes this bug. The problem was that the airspeed_estimate function in AP_AHRS_DCM was not const, which meant that it was calling the airspeed_estimate function in the parent class AP_AHRS.

Note: I am not a c++ genius. Kevin Hester helped me find the problem.

So, in the meantime, you can fix the problem by either making the code change yourself, or by putting an airspeed sensor on your airplane.

Hi,
Thanks for the effort and help. Is there another way to fix this issue without buying an airspeed sensor?
Best,
Steven

I’m hoping the next release is soon.
Thank you,
Steven

[quote=“Steven G”]Hi,
Thanks for the effort and help. Is there another way to fix this issue without buying an airspeed sensor?
Best,
Steven[/quote]
Hi Steven, sorry for not getting back to you on this. I can also backport the fix to the current version if you like.

I highly recommend an airspeed sensor.