Skip to content

Conversation

@msberk
Copy link
Contributor

@msberk msberk commented Sep 22, 2025

Solved Problem

Currently, when proceeding to the landing point the previous setpoint is not updated, which results in an unexpected and off course landing pattern in fixed wing.

Fixes #25436

Solution

Move position setpoint logic outside of conditional so it is applied even when it is a landing waypoint

Changelog Entry

For release notes:

Bugfix: Fix RTL logic in fixed wing RTL Mission mode that caused landing patterns to veer off of expected course

Test coverage

Context

#25436

@msberk
Copy link
Contributor Author

msberk commented Sep 22, 2025

@sfuhrer Saw you reviewed the PR which likely introduced this behavior, if you want to see this proposed fix.

@KonradRudin interested in your feedback too

@DronecodeBot
Copy link

This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/px4-dev-call-sep-24-2025-team-sync-and-community-q-a/47494/1

@dagar dagar requested a review from sfuhrer September 24, 2025 15:28
@msberk
Copy link
Contributor Author

msberk commented Sep 24, 2025

New log for change to match mission.cpp logic is here: https://review.px4.io/plot_app?log=a8191432-e1bc-495d-8b38-1996cfa02cd7

@msberk
Copy link
Contributor Author

msberk commented Oct 1, 2025

@sfuhrer @dagar Wasn't able to make the dev call today, but wondering if there's any other comment on this. As far as I can tell this synchronizes the waypoint update logic from plain mission.cpp and fixes the bug. If this gets merged I'll make a backport PR to 1.16, as well.

@dakejahl dakejahl self-assigned this Oct 10, 2025
@DronecodeBot
Copy link

This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/px4-dev-call-oct-15-2025-team-sync-and-community-q-a/47650/1

@DronecodeBot
Copy link

This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/px4-dev-call-oct-22-2025-team-sync-and-community-q-a/47712/2

@farhangnaderi farhangnaderi requested a review from dagar October 22, 2025 15:20
@dakejahl
Copy link
Contributor

dakejahl commented Nov 1, 2025

@msberk we discussed this on the dev call last week. I wasn't able to reproduce in sim. If you can provide a plan file and steps to reproduce so that I can verify I will be happy to merge the bug fix.

@sfuhrer
Copy link
Contributor

sfuhrer commented Nov 3, 2025

Thanks a lot for handling that fix @msberk. I agree with your solution. Can you please include that commit in this PR? It's for fixing it also for RTL_TYPE=2. Then we can get it in.

@msberk
Copy link
Contributor Author

msberk commented Nov 3, 2025

@sfuhrer done

@dakejahl I was just getting this back up and running to make a plan when I saw Silvan's message - any need still for this? Plan which reproduces in following steps on main (specifically f3ee45b175) and QGC 5.0.8 with plan below.

  1. make px4_sitl gz_advanced_plane (default parameters)
  2. Start QGC
  3. Load plan below, then upload
  4. Takeoff and start mission from QGC
  5. The aircraft will enter indefinite loiter. Click "Return" in QGC
  6. Observe that landing approach goes from RTL start point to landing point, and not from end of landing loiter descent tangent
{
    "fileType": "Plan",
    "geoFence": {
        "circles": [
        ],
        "polygons": [
        ],
        "version": 2
    },
    "groundStation": "QGroundControl",
    "mission": {
        "cruiseSpeed": 15,
        "firmwareType": 12,
        "globalPlanAltitudeMode": 0,
        "hoverSpeed": 5,
        "items": [
            {
                "AMSLAltAboveTerrain": null,
                "Altitude": 50,
                "AltitudeMode": 1,
                "autoContinue": true,
                "command": 22,
                "doJumpId": 1,
                "frame": 3,
                "params": [
                    15,
                    0,
                    0,
                    0,
                    47.397927759117486,
                    8.549262865676198,
                    50
                ],
                "type": "SimpleItem"
            },
            {
                "AMSLAltAboveTerrain": null,
                "Altitude": 50,
                "AltitudeMode": 1,
                "autoContinue": true,
                "command": 17,
                "doJumpId": 2,
                "frame": 3,
                "params": [
                    0,
                    0,
                    49.999999999864215,
                    null,
                    47.39786884948544,
                    8.553402834925613,
                    50
                ],
                "type": "SimpleItem"
            },
            {
                "altitudesAreRelative": true,
                "complexItemType": "fwLandingPattern",
                "finalApproachSpeed": 9,
                "landCoordinate": [
                    47.393168234460475,
                    8.546233581644538,
                    0
                ],
                "landingApproachCoordinate": [
                    47.39659085928292,
                    8.54523717043706,
                    40
                ],
                "loiterClockwise": true,
                "loiterRadius": 75,
                "stopTakingPhotos": true,
                "stopVideoPhotos": true,
                "type": "ComplexItem",
                "useDoChangeSpeed": false,
                "useLoiterToAlt": true,
                "valueSetIsDistance": false,
                "version": 2
            }
        ],
        "plannedHomePosition": [
            47.3979709,
            8.5461637,
            491
        ],
        "vehicleType": 1,
        "version": 2
    },
    "rallyPoints": {
        "points": [
        ],
        "version": 2
    },
    "version": 1
}

Copy link
Contributor

@sfuhrer sfuhrer left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This aligns setActiveMissionItems() in rtl_direct_mission_land.cpp and in rtl_mission_fast.cpp with what was already in mission.cpp. It probably was on oversight when the RTL restructure happened. The FW landing requires the previous waypoint to be correctly set, that's why it was only noticeable there.
I've tested with RTL_TYPE 1 and 2 for FW, VTOL and MC, all looked correct now that fix.

msberk and others added 4 commits November 3, 2025 16:34
Currently, when proceeding to the landing point the previous setpoint is not updated, which results in an unexpected and off course landing pattern in fixed wing. (see PX4#25436)
@sfuhrer sfuhrer merged commit 9702a2a into PX4:main Nov 3, 2025
65 of 67 checks passed
@sfuhrer
Copy link
Contributor

sfuhrer commented Nov 3, 2025

@msberk can you port it to release/1.16 as well?

@msberk msberk deleted the fix_rtl_sp_logic branch November 3, 2025 19:07
mrpollo pushed a commit that referenced this pull request Nov 24, 2025
…t correctly (#25600)

This aligns setActiveMissionItems() in rtl_direct_mission_land.cpp and in rtl_mission_fast.cpp with what was already in mission.cpp. It probably was on oversight when the RTL restructure happened. The FW landing requires the previous waypoint to be correctly set, that's why it was only noticeable there.

* Fix position setpoint update logic in Mission RTL

Currently, when proceeding to the landing point the previous setpoint is not updated, which results in an unexpected and off course landing pattern in fixed wing. (see #25436)

* Change to work more like `mission.cpp`

* Fix rtl_direct_misssion_land formatting for style guide

* rtl_mission_fast: fix FW landing by setting previous wp in landing

Signed-off-by: Silvan <[email protected]>

---------

Signed-off-by: Silvan <[email protected]>
Co-authored-by: Silvan <[email protected]>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

[Bug] Fixed-wing Mission landing veers off-course in Return *Personnel Safety Risk!*

5 participants