ardupilot icon indicating copy to clipboard operation
ardupilot copied to clipboard

Weird execution order for DO commands immediately after jump

Open robertlong13 opened this issue 6 months ago • 3 comments

Bug report

DO commands placed after a finite-loop DO_JUMP get executed at the start of the last loop. Here is a screenshot of what I mean:

Image

This is the order of execution:

2025-06-17 1:00:48 PM : Mission: 1 VTOLTakeoff
2025-06-17 1:01:21 PM : Mission: 2 WP
2025-06-17 1:01:43 PM : Mission: 3 WP
2025-06-17 1:01:54 PM : Mission: 4 AuxFunction
2025-06-17 1:01:54 PM : Mission: 5 Jump 1/2
2025-06-17 1:01:54 PM : Mission: 2 WP
2025-06-17 1:02:12 PM : Mission: 3 WP
2025-06-17 1:02:27 PM : Mission: 4 AuxFunction
2025-06-17 1:02:27 PM : Mission: 5 Jump 2/2
2025-06-17 1:02:27 PM : Mission: 2 WP
2025-06-17 1:02:27 PM : Mission: 6 AuxFunction    !!!
2025-06-17 1:02:43 PM : Mission: 3 WP
2025-06-17 1:02:58 PM : Mission: 4 AuxFunction
2025-06-17 1:02:58 PM : Mission: 7 LoitTurns
2025-06-17 1:03:31 PM : Mission: 8 LoitAltitude
2025-06-17 1:04:20 PM : Mission: 9 LoitTurns
2025-06-17 1:04:36 PM : Mission: 10 VTOLLand

Where I'd expect to see this

2025-06-17 1:00:48 PM : Mission: 1 VTOLTakeoff
2025-06-17 1:01:21 PM : Mission: 2 WP
2025-06-17 1:01:43 PM : Mission: 3 WP
2025-06-17 1:01:54 PM : Mission: 4 AuxFunction
2025-06-17 1:01:54 PM : Mission: 5 Jump 1/2
2025-06-17 1:01:54 PM : Mission: 2 WP
2025-06-17 1:02:12 PM : Mission: 3 WP
2025-06-17 1:02:27 PM : Mission: 4 AuxFunction
2025-06-17 1:02:27 PM : Mission: 5 Jump 2/2
2025-06-17 1:02:27 PM : Mission: 2 WP
2025-06-17 1:02:43 PM : Mission: 3 WP
2025-06-17 1:02:58 PM : Mission: 4 AuxFunction
2025-06-17 1:02:27 PM : Mission: 6 AuxFunction    <- here instead
2025-06-17 1:02:58 PM : Mission: 7 LoitTurns
2025-06-17 1:03:31 PM : Mission: 8 LoitAltitude
2025-06-17 1:04:20 PM : Mission: 9 LoitTurns
2025-06-17 1:04:36 PM : Mission: 10 VTOLLand

DoJumpWeirdOrder.waypoints.txt

I spent most of the day trying to wrap my head around this and fix it, and I learned a bit about the cause, but I'm at a loss as for how to fix it. I'm half-leaning toward documenting it and thus upgrading it to "feature".

Cause

We doesn't immediately execute the DO commands we come across while advancing the mission. We store it in _do_cmd and move on. Each call to update() we execute the _do_cmd and load up the next one. This repeats until a nav command is hit (or the end of the mission, whatever). When the last jump executes, and the NAV command is sent back for the last time, the DO_JUMP is marked as complete, and when update() goes to advance to the next DO, it runs past it. This is why they all run at the beginning of the last loop.

Version Discovered on master, but willing to bet this is long-standing behavior

Platform [ ] All [ ] AntennaTracker [ x ] Copter [ x ] Plane [ x ] Rover [ x ] Submarine

robertlong13 avatar Jun 17 '25 04:06 robertlong13

Please test on c9661c27a4ead02baaf57cd69b7203e5999f25c0~1

peterbarker avatar Jun 17 '25 05:06 peterbarker

@peterbarker is referring to this recent PR https://github.com/ArduPilot/ardupilot/pull/29763 which did affect this section of the code

rmackay9 avatar Jun 17 '25 05:06 rmackay9

I came across that PR during my investigation, and it's not the cause. Without that PR (or with that option bit set), I'm pretty sure you get this behavior:

2025-06-17 1:00:48 PM : Mission: 1 VTOLTakeoff
2025-06-17 1:01:21 PM : Mission: 2 WP
2025-06-17 1:01:43 PM : Mission: 3 WP
2025-06-17 1:01:54 PM : Mission: 4 AuxFunction
2025-06-17 1:01:54 PM : Mission: 5 Jump 1/2
2025-06-17 1:01:54 PM : Mission: 2 WP
2025-06-17 1:02:12 PM : Mission: 3 WP
2025-06-17 1:02:27 PM : Mission: 4 AuxFunction
2025-06-17 1:02:27 PM : Mission: 5 Jump 2/2
2025-06-17 1:02:27 PM : Mission: 2 WP
2025-06-17 1:02:27 PM : Mission: 6 AuxFunction    <- both here
2025-06-17 1:02:43 PM : Mission: 3 WP
2025-06-17 1:02:58 PM : Mission: 4 AuxFunction
2025-06-17 1:02:27 PM : Mission: 6 AuxFunction    <- and here
2025-06-17 1:02:58 PM : Mission: 7 LoitTurns
2025-06-17 1:03:31 PM : Mission: 8 LoitAltitude
2025-06-17 1:04:20 PM : Mission: 9 LoitTurns
2025-06-17 1:04:36 PM : Mission: 10 VTOLLand

I'll test later to confirm.

That PR basically thwarted one of my "easy fixes" that I'm sure had like 3 unintended consequences anyway.

robertlong13 avatar Jun 17 '25 05:06 robertlong13

It gets a little weirder. If you have commands loaded as part of the mission then it won't even execute the command after the DO_JUMP. PR for test here: https://github.com/ArduPilot/ardupilot/pull/30422

peterbarker avatar Jun 21 '25 10:06 peterbarker