Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: add Autoland mode #28771

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open

Conversation

Hwurzburg
Copy link
Collaborator

Upon entry creates a final approach waypoint at parameterized distance and alt from home in the opposite direction of takeoff direction, flies to to it and does a land like NAV_LAND.
If a DO_LAND_START sequence(s) exist, will jump to them instead

Needs an autotest, which is beyond me to write

Copy link
Contributor

@timtuxworth timtuxworth left a comment

Choose a reason for hiding this comment

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

Love this idea - some suggestions.

plane.next_WP_loc = home;
uint16_t bearing_cd = wrap_360((plane.takeoff_state.takeoff_initial_direction + 180));
plane.next_WP_loc.offset_bearing(bearing_cd, final_wp_dist);
plane.next_WP_loc.alt = home.alt + final_wp_alt*100;
Copy link
Contributor

@timtuxworth timtuxworth Nov 29, 2024

Choose a reason for hiding this comment

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

Could you use set_alt_cm()? We are trying to move away from using alt directly. You could provide ABOVE_HOME as the frame.

ArduPlane/mode_autoland.cpp Outdated Show resolved Hide resolved
ArduPlane/mode_autoland.cpp Show resolved Hide resolved
@robustini
Copy link
Contributor

robustini commented Nov 29, 2024

Very interesting, I would instead have a suggestion for a much more solid approach in my opinion, since yours is great for taxiing takeoffs but not for hand launches, which is often not necessarily the direction of the runway.
The automatism I propose requires a very trivial thing in Mission Planner, then Ardupilot on that can do all the reasoning for a land without doing complex missions.
This a simple emergency LAND mission that I often use with some of my fpv planes.
The operation is simple, the automatic manual launch that gives me time to switch to Loiter or force an RTL once the takeoff has happened correctly (so during the LOITER_TIME), gives me time to put on goggles and then switch to other flight modes and proceed.
I also set an alternate home a short distance away because I don't want it to loiter over our heads in an emergency.
In case of failsafe AUTO intervenes, then the plane goes back to the LOITER_TIME event that I had not let it finish and shortly thereafter executes the circuit for LAND.
During that LOITER_TIME if I have the tx out I have time to decide whether to have it continue or maybe intervene in telemetry in some other way, a system that has been tried hundreds of times before.

immagine

Instead, here is what I propose, in my opinion the most logical and hyper simple: if there was the possibility in Ardupilot to fix two points on the runway, to indicate LR of the correct axis would be more than enough to tell Ardupilot to use that line to perform any kind of LAND, so something like this.

immagine

In this very simple approach Ardupilot knows of the runway the direction, the center and the correct length, so he knows that that is the runway in all its useful aspects.
Then 2 coordinates (latitude and longitude for each of the two points) that can be entered perhaps from mission planning or with parameters would suffice.
This simple line would be enough to then do any kind of automated LAND developed for this approach, without perhaps having to resort to complex planning on Mission Planner.
This is an aviation approach already known for planes performing ILS or any other instrumental approaches to the runway, and has been using Micropilot for at least a decade.
These two points are enough to allow AUTOLAND to make no mistake.
Certainly your PR is more immediate but in my opinion less secure in many contexts, of course definitely better that than nothing but supplementing it with this would make it infallible imho.

@Hwurzburg
Copy link
Collaborator Author

Hwurzburg commented Nov 29, 2024

@robustini many people never use MP after initial setup and arent comfortable with mission planning....I never use missions other than autotakeoff/do-land-start/landing sequence with my mission selector app to select land direction for my field based on wind direction....or my UniversalAutoLand lua when travelling to other locations

this is the C++ implementation of my UniversalAutoLand lua script which I use when traveling and just stop at a location and fly...no laptop used..

@Hwurzburg Hwurzburg force-pushed the autoland branch 2 times, most recently from fcf710d to a1b1b13 Compare November 29, 2024 13:38
@timtuxworth
Copy link
Contributor

Should this be disabling fences (autoenabled, and floor) when doing a landing?

@Hwurzburg
Copy link
Collaborator Author

It does a NAV_LAND....so whatever it does or does not

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants