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

Fixed-wing takeoff and landing revisions #20537

Merged
merged 22 commits into from
Nov 22, 2022

Conversation

sfuhrer
Copy link
Contributor

@sfuhrer sfuhrer commented Nov 2, 2022

General improvements to the fixed-wing auto takeoff/landing logic and controller done by @tstastny and me in the last weeks.

New things (more info contained in the commit messages)

Runway takeoff

Procedure:

  • ramp in throttle
  • hold throttle and clamp to runway until reaching rotation speed
  • rotate (ramp in relaxed pitch and throttle constraints, TECS controls, takeoff airspeed setpoint)
  • control aircraft to max climb and prescribed takeoff airspeed until reaching clearance altitude

Details:

  • explicit runway takeoff rotation and climbout airspeed setpoints (new params FW_TKO_AIRSPD and RWTO_ROT_AIRSPD, deleted param RWTO_AIRSPD_SCL)
  • don't use climbout mode for runway takeoff climbout
  • ramping in of constraints and setpoints on all transitions (avoid jumps) --> remove param RWTO_MAX_PITCH, introduce RWTO_ROT_TIME

Landing flare

Procedure:

  • once range finder detects imminent impact (see FW_LND_FL_TIME), start flare
  • TECS is switched to height rate control at FW_LND_FL_SINK m/s
  • pitch min/max constraints, throttle max constraint, and height rate setpoint are ramped in using a square root function of the time since flare start (over FW_LND_FL_TIME) - square root to be more aggressive in the flaring action for these states
  • throttle setpoint and L1/NPFG periods for ground roll are ramped in linearly
  • if enabled, FW_LND_TD_TIME determines the time after flare start that touchdown is expected. after this time, touchdown clamping (for runway ground roll out) will be ramped in over a hardcoded 0.5 seconds. I.e. pitch constraint for runway. if disabled - the flare constraints will be held throughout until land is detected.

More details:

  • use path following throughout flare (instead of changing to heading hold mode)

Landing abort

  • don't allow automatic landing aborts after flare has started (manual aborts are still always possible)
  • disable early landing config during a landing abort
  • rename MIS_LTRMIN_ALT param to NAV_MIN_LTR_ALT and only consider on loiters which are *not part of a mission
  • use new specific param MIS_LND_ABRT_ALT for landing abort altitude
  • remove param FW_CLMBOUT_DIFF

General changes

  • explicit landing airspeed (new param FW_LND_AIRSPD, replaced param FW_LND_AIRSPD_SC)
  • vehicle_attitude_setpoint: rename fw_control_yaw to fw_control_yaw_wheel to make more explicit
  • splitting wheel and yaw control and enable steering wheel in control allocation (allows wheel control in stabilized via yaw stick independent of attitude controller)

Test data / coverage

Most of it has been test-flown on both hand-launched and runway-takeoff vehicles.

Auto take-off:
https://user-images.githubusercontent.com/8026163/201090349-9300a150-b1d3-4794-aa49-d9e279bf641b.mp4

Auto land. Note in this video, just before reaching the ground, you can see the flare start, and the touchdown time initiated nose down action.
https://user-images.githubusercontent.com/8026163/201090378-8dded870-6082-45c4-ac2c-c699bbe7eeaf.mp4

TODO:

  • provide videos
  • param translation
  • in follow up doc pr ... update documentation!

@ryanjAA
Copy link
Contributor

ryanjAA commented Nov 10, 2022

I don’t think MIS_LTRMIN_ALT should be deleted.

If you are flying level at 30m alt and have MIS_LTRMIN_ALT set to 50 and hit the hold/loiter switch, it climbs. From my understanding, this removes that.

On a landing abort, the new setup works with landing abort min alt param (above) but if I don’t abort, just hit hold, the ability to climb is gone and if I hit it any other time, I can’t guarantee a min alt.

@sfuhrer
Copy link
Contributor Author

sfuhrer commented Nov 10, 2022

If you are flying level at 30m alt and have MIS_LTRMIN_ALT set to 50 and hit the hold/loiter switch, it climbs. From my understanding, this removes that.

It does. it's simply a question if it's really required, most of all as now the landing abort altitude has its own new parameter.
Can you explain how you use it? You set e.g. to 50m, do a manual takeoff and then instead of climbing in a manual mode, you flip the Loiter switch on the RC to make it climb autonomously to a safe altitude?

@tstastny
Copy link

tstastny commented Nov 10, 2022

If you are flying level at 30m alt and have MIS_LTRMIN_ALT set to 50 and hit the hold/loiter switch, it climbs.

I'm not a big fan of implicit uses of mode switches / parameters (e.g. in this case with the purpose of making it climb). Hold as I understood it just tells it to loiter where it currently is. I would think this should be the operator's responsibility to know they are at a safe altitude when commanding the hold. -- I see the documentation does specify these minimum altitude constraints, however. https://docs.px4.io/main/en/flight_modes/hold.html#hold-mode

If the intent is to hold at a higher altitude - one can use position mode to first climb, and then hold. Or set an Orbit at a specific altitude (orbit has altitude in its definition) to do so fully automatically. In these two examples, the intention is clear.

If the minimum constraint on hold altitude is a widely used and desired feature - maybe we should explicitly define it - e.g. NAV_MIN_HOLD_ALT (default = 0). to be precise in intentions. As it's not really a "mission" parameter. Hold is not a mission item.

Regardless - still should be a separate param for landing abort IMHO.

@ryanjAA
Copy link
Contributor

ryanjAA commented Nov 10, 2022

If you are flying level at 30m alt and have MIS_LTRMIN_ALT set to 50 and hit the hold/loiter switch, it climbs. From my understanding, this removes that.

It does. it's simply a question if it's really required, most of all as now the landing abort altitude has its own new parameter. Can you explain how you use it? You set e.g. to 50m, do a manual takeoff and then instead of climbing in a manual mode, you flip the Loiter switch on the RC to make it climb autonomously to a safe altitude?

I would say it is required. And if you don't want to use it, set to -1 for disable. It's used a lot when not on landing too. Exactly how you wrote it but I've seen it in practice quite very frequently from multiple user types - also from a safety case where having it disables the ability to loiter by accident at 1m altitude (i've see that occur when it was set to 0). See my further explanation in bellow message but I would say this is only a benefit to have and if people don't want to use it, -1 to disable.

@ryanjAA
Copy link
Contributor

ryanjAA commented Nov 10, 2022

If you are flying level at 30m alt and have MIS_LTRMIN_ALT set to 50 and hit the hold/loiter switch, it climbs.

I'm not a big fan of implicit uses of mode switches / parameters (e.g. in this case with the purpose of making it climb). Hold as I understood it just tells it to loiter where it currently is. I would think this should be the operator's responsibility to know they are at a safe altitude when commanding the hold. -- I see the documentation does specify these minimum altitude constraints, however. https://docs.px4.io/main/en/flight_modes/hold.html#hold-mode

If the intent is to hold at a higher altitude - one can use position mode to first climb, and then hold. Or set an Orbit at a specific altitude (orbit has altitude in its definition) to do so fully automatically. In these two examples, the intention is clear.

If the minimum constraint on hold altitude is a widely used and desired feature - maybe we should explicitly define it - e.g. NAV_MIN_HOLD_ALT (default = 0). to be precise in intentions. As it's not really a "mission" parameter. Hold is not a mission item.

Regardless - still should be a separate param for landing abort IMHO.

I'm not a fan of implicit mode switches either and you're totally correct, hold should be hold and it is the PICs responsibilty but here's the practical side, if you run into a problem, hit loiter and it goes up and circles. One and done. No thought.

On the safety side if you are at 10m alt, i cant see a benefit to being able to loiter at 10m so climb and then loiter (for sure someone may want to though with a small aircraft).

Hit loiter by accident while at 3m, you wont crash but instead climb then circle.

Flying without an RC and hit loiter, you climb (position mode wont be possible with ease).

Rather than delete the param, just set to -1 for disable. >0 for use and keep at -1 by default but that at least captures both perspectives and keeps the safety elemement there - Anything we can do to increase safety is a good thing.

Also, yes definitely a separate param for landing abort.

@tstastny
Copy link

@ryanjAA fair enough! I discussed briefly with @sfuhrer -- how about we keep the hold alt min param, but rename to specifically define it for hold? (and thus discourage cross use in other portions of the code base). I'll add to param translation of course as well.

@ryanjAA
Copy link
Contributor

ryanjAA commented Nov 11, 2022

👍👍👍👍👍
(Ya shouldn’t have really been called mis_xxx since you can do it anytime. Hold makes much sense since you can do it in mission or not mission, etc)

@sfuhrer
Copy link
Contributor Author

sfuhrer commented Nov 14, 2022

@ryanjAA @tstastny I've pushed a commit which bring back the minimum loiter altitude.
7765f97
It's now implemented as followed: New parameter NAV_MIN_LTR_ALT, that is set to -1 by default, and if set to >0 then will be used to enforce a loiter altitude of that amount above Home, if there is no explicitly specified loiter altitude setpoint (through a Reposition command). It's applied when Loiter mode is entered e.g. through a RC switch or because the previous mode is done (Takeoff, VTOL Takeoff, Mission).

BTW it was broken on current main: On current main MIS_LTRMIN_ALT is only listened to for landing aborts and within LOITER_TO_ALTITUDE commands, but not at all accordingly to the docs ("always in Hold mode"). bf6a47b broke it.

@ryanjAA
Copy link
Contributor

ryanjAA commented Nov 14, 2022

Thanks - it will be good to note in the docs that it is relative alt (relative to home). That is pretty much assumed but good to tell people explicitly.

Thanks for putting this back in - Should be able to have it tested on Friday.

@tstastny
Copy link

Thanks @sfuhrer !

Alright - I think this is all ready to go now. I also updated the PR description to give a bit more specifics on the new logic. I still need to make some proper diagrams etc and update the webpage documentation - but I wont have time to do this until a bit later this week.

@dagar since @sfuhrer and I both contributed to this PR - it would be a bit incestuous if either of us approved and merged - can you give this one last set of eyes?

@ryanjAA I would say this is good for testing on your end if you're ready! just let me know if we should sync offline (e.g. discord / google meet) for any details on the new logic / params.

@ryanjAA
Copy link
Contributor

ryanjAA commented Nov 16, 2022

Epic! Thanks for all the hard work! Will get it in the air Friday. Will sync offline as needed after a quick pass over again. Thanks again!

@tstastny tstastny requested a review from dagar November 16, 2022 13:45
@ryanjAA
Copy link
Contributor

ryanjAA commented Nov 21, 2022

@ryanjAA @tstastny I've pushed a commit which bring back the minimum loiter altitude. 7765f97 It's now implemented as followed: New parameter NAV_MIN_LTR_ALT, that is set to -1 by default, and if set to >0 then will be used to enforce a loiter altitude of that amount above Home, if there is no explicitly specified loiter altitude setpoint (through a Reposition command). It's applied when Loiter mode is entered e.g. through a RC switch or because the previous mode is done (Takeoff, VTOL Takeoff, Mission).

BTW it was broken on current main: On current main MIS_LTRMIN_ALT is only listened to for landing aborts and within LOITER_TO_ALTITUDE commands, but not at all accordingly to the docs ("always in Hold mode"). bf6a47b broke it.

Tested this (NAV_MIN_LTR_ALT) in SITL just now. Works as intended except in one scenario. If you enter into Hold when in mission mode and the selected WP is the loiter/land waypoint, it doesn't listen to the WP altitude (see attached log). It will still loiter at whatever altitude you are at.

https://review.px4.io/plot_app?log=d19aa4de-0c28-46ca-9a82-35d283af61e4

Thomas Stastny added 9 commits November 21, 2022 12:02
previously a scale factor param on min airspeed was used to define the climbout airspeed for runway takeoff
additionally, the rotation speed was defined by another hardcoded scale on top of the previously scaled min airspeed
this commit explicitly defines a takeoff speed and rotation speed for runway takeoff in params, with option to disable
… max climb rate

TECS climbout mode was used for takeoff climbout, which puts throttle to full and does not regulate a specific airspeed.
This commit sets the desired takeoff airspeed explicitly and allows max climb rate to track the ascent.
…point on takeoff rotation

- consolidate takeoff rotation transition times for pitch constraints and throttle setpoint with a single param
- consolidate pitch takeoff constraint parameters (remove rwto_max_pitch, use nominal max)
- input correct units to rwto pitch constraint getters
- encapsulate absolute time interpolator method for transitions
- start runway ops from idle throttle
abruptly changing to a heading setpoint on flare can cause the aircraft to roll and deviate from the runway, this commit
- maintains path following control during the flare not to disrupt the tracking just before touchdown
- (unfortunately for crosswind landing) removes the body axis alignment for runway bearing - this is a compromise

to achieve both runway bearing body axis alignment AND a specific touchdown point, either
1. the wind would need to be considered, and an appropriate diagonal approach (obstructions allowing)  defined to the runway
2. slip control added, keeping path following outputs only commanding roll (controlling airspeed vector) and using yaw-rate command (only actuated by e.g. rudder) to align body axis with the runway
…ttle state to keep control continuity

- also put flaring internal states into a struct to organize a bit
- one concern with blending the throttle setpoint like this with the flare time param is that folding prop belly landing airframes may want to have a separate param for shorter throttle kill and still use the flare time ramps for everything else
…ramps to sqrt function to make more aggressive
…rwto pitch setpoint after the flare to keep wheels on ground
Thomas Stastny and others added 13 commits November 21, 2022 12:02
…l to make usage clearer

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
… LandingGearWheel

Completely detach the steering wheel logic from the yaw controller (beside using the
same manual stick input in a manual flight mode).

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
…ications

- explicitly defined takeoff airspeed setpoint
- dont use climbout mode
- allow max climb on takeoff
- dont handle post clearance altitude case (navigator will switch anyway)
…ng abort

previously, the next position setpoint in the triplet was left unchanged during an abort, which meant that the abort loiter current point combined with land next point triggered the early landing config logic. this commit is only a hack to make things work temporarily.. this needs to be handled better.
…T_ALT for landing abort

MIS_LTRMIN_ALt was used to limit the go-to altitude of a LOITER_TO_ALT (not the exit altitude,
but the altitude that the vehicle went to to fly to WP), and during landing abort to climb to
at least this altitude. The min entry altitude of LOITER_TO_ALT I remove with this commit, while
for the min alt during abort I added the new parameter MIS_LND_ABRT_ALT.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
…dcoded 10m for clearing aborted flag

Use kClearanceAltitudeBuffer for it, which is also used to ensure that during takeoff an
altitude setpoint above the clearance altitdue is set.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
…, but allow manual aborts

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
landing airspeed was previously defined by a scale factor multiplied by minimum airspeed. this commit changes this parameter to an explicit speed, and when unspecified, defaults to the minimum airspeed
… w/o a specified altitude setpoint

Also applies to Loiters that are started due to the previous mode being over (Takeoff,
VTOL_Takeoff, Mission).

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
@sfuhrer
Copy link
Contributor Author

sfuhrer commented Nov 21, 2022

If you enter into Hold when in mission mode and the selected WP is the loiter/land waypoint, it doesn't listen to the WP altitude (see attached log). It will still loiter at whatever altitude you are at.

But that's what's expected no? Switching into Hold will make it hold at the current altitude, unless that one is below the one set in NAV_MIN_LTR_ALT or we're already in a loiter (in the Mission), in which case it will also stay on the current altitude.

I've rebased on current main and force pushed.

@sfuhrer sfuhrer force-pushed the more-fixed-wing-takeoff-and-landing-revisions branch from 7765f97 to b50de6d Compare November 21, 2022 12:57
@dagar
Copy link
Member

dagar commented Nov 22, 2022

Seems fine, but I'll give it another pass tomorrow.

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.

5 participants