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

Various RTL improvements (mainly VTOL specific) #16377

Merged
merged 18 commits into from
Jan 4, 2021
Merged

Conversation

sfuhrer
Copy link
Contributor

@sfuhrer sfuhrer commented Dec 11, 2020

Replaces #14728.

Describe problem solved by this pull request

Describe your solution
RTL logic with this PR, changes to current logic in bold
(assuming RTL_TYPE is set to 1 (VTOL and FW default, using mission landing if available))

  • if close to RTL landing position and in hover, use cone RTL logic (if mission landing is planned that one is used)
  • if VTOL and in hover mode, use normal MC RTL strategy (climb to RTL_RETURN_ALT, come back and land at RTL landing position)
  • if DO_LAND_START is set (landing using mission landing):
    • if in FW mode, go to DO_LAND_START marker in FW mode and from there on follow mission landing
    • if in MC mode, go to the Land position and land there (don't follow landing pattern as in FW mode)
  • if DO_LAND_START is not set
    • if VTOL and in FW mode, climb to RTL_RETURN_ALT, fly to home, loiter down until RTL_DESCEND_ALT in FW mode, transition to hover and land

Test data / coverage
SITL tested with Standard VTOL and multicopter.

Additional context
For VTOL, it is recommended to always fly with a mission landing planned, such that this one can be used during the RTL. Landing approaches using mission landing can be optimized for current wind direction (transition into the wind), and result in less hover time (vehicle transitions over hover, instead of while loitering around home)

@sfuhrer sfuhrer requested review from dagar and RomanBapst December 11, 2020 15:23
@sfuhrer sfuhrer added the Hybrid VTOL 🛩️🚁 Multirotor + Fixedwing! label Dec 11, 2020
@sfuhrer sfuhrer force-pushed the pr-vtol-rtl-fixes branch 4 times, most recently from 7061aff to 0ef2f6e Compare December 11, 2020 20:52
@Antiheavy
Copy link
Contributor

Antiheavy commented Dec 11, 2020

is this:

For VTOL, it is recommended to always fly with a mission landing planned, such that this one can be used during the RTL. Landing approaches using mission landing can be optimized for current wind direction (transition into the wind), and result in less hover time (vehicle transitions over hover, instead of while loitering around home)

consistent with this?:

  • if close to home position and in hover, use cone RTL logic

  • if VTOL and in hover mode, use normal MC RTL strategy (climb to RTL_RETURN_ALT, come back and land)

Have you considered if there should be a parameter that allows/avoids RTL at the Home location if in MC mode? I wonder how many VTOL people would always want to use the mission landing if at all possible? The "return to home" fall-back in the RTL_TYPE=1 logic was originally designed for the case when the mission landing accidentally gets deleted or gets overwritten with an infeasible landing pattern (which unfortunately is something that can easily happen).

From the way this PR is currently written you intend the VTOL vehicle will perform different Return mode behaviors depending on the context. I wonder if that is how 100% of VTOL users will want it to work. I'm not a VTOL expert so I'm not advocating one way or another, just curious.

@sfuhrer
Copy link
Contributor Author

sfuhrer commented Dec 15, 2020

Have you considered if there should be a parameter that allows/avoids RTL at the Home location if in MC mode?

Thanks for pointing this out. I actually wrote it down wrongly in the description. It will always use the mission landing for RTL if RTL_TYPE is 1. What changes is that it now won't follow the landing pattern (all that is after the DO_LAND_START) in hover, but directly go to Land and descend there.

@@ -73,6 +76,12 @@ Mission::on_inactive()
* is used for missions such as RTL. */
_navigator->set_cruising_speed();

// if we were executing an landing but have been inactive for 2 seconds, then make the landing invalid
// this prevents RTL to just continue at the current mission index
if (_navigator->getMissionLandingInProgress() && (hrt_absolute_time() - _time_mission_deactivated) > 2_s) {
Copy link
Member

Choose a reason for hiding this comment

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

I'm not sure I follow, how would this fail if the mission landing progress was set to false immediately on first inactivation?

Copy link
Contributor

Choose a reason for hiding this comment

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

@dagar This prevents the situation where e.g. you are on a mission landing and then RTL kicks in. You don't want to start from the beginning but continue the mission. However, if e.g. the user takes over in manual during a mission landing and then switches back, you probably want to start he mission landing from scratch, as you have no clue where exactly you are and if you are still aligned with the path.

Copy link
Member

Choose a reason for hiding this comment

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

I should have been more specific, the part I don't follow is the magic 2 seconds.

Copy link
Contributor

Choose a reason for hiding this comment

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

@dagar A long study over many years has calculated this number to be the one and only reasonable value. It's almost like pi....

Copy link
Member

Choose a reason for hiding this comment

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

Why not do it immediately on the actual mission deactivation?

Copy link
Member

Choose a reason for hiding this comment

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

Let's track this in a separate issue - we shouldn't be blocking an incremental move towards a much better behavior.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Issue to track that: #16488

Copy link
Contributor

Choose a reason for hiding this comment

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

@dagar I think I might need to explain this a bit better:
When you are executing a mission landing and RTL kicks in due to low battery, then the mode switches from mission to RTL and back to mission (assuming you are executing a mission landing, which is the preferred choice almost always).
Two the second delay (it actually needs way less) allows the mission to just continue the landing rather than restarting the landing pattern.

Copy link
Contributor

Choose a reason for hiding this comment

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

@dagar Sorry, I noticed I told you this before. What is the issue here?

Copy link
Member

Choose a reason for hiding this comment

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

@dagar Sorry, I noticed I told you this before. What is the issue here?

Nothing necessarily, I just wanted to make sure there wasn't a potential hole for a hard to reproduce bug down the round. Eg dataman chokes reading the sdcard and there's a one off delay that's much longer than expected.

RomanBapst
RomanBapst previously approved these changes Dec 18, 2020
@moreba1
Copy link
Contributor

moreba1 commented Dec 29, 2020

in the master version, VTOL has a dangerous behavior when it reaches VTOL Land.
@sfuhrer
https://logs.px4.io/plot_app?log=9df156fc-233e-4b54-ad23-e82017ff47f4

desirable behavior is that VTOL transition location be near to land location to minimize power consumption, and the drone doesn't have that much tilt angle and oscillation in MC mode.

…CEND_ALT

before reaching home

Signed-off-by: RomanBapst <[email protected]>
NAV_CMD_LOITER_TO_ALT

- this allows vtol to track the loiter circle during the transition instead
of trying to fly to the landing position

Signed-off-by: RomanBapst <[email protected]>
- descend to RTL descend altitude
- transition
- move to land waypoint
- loiter and then land

Signed-off-by: RomanBapst <[email protected]>
…nding

- previously the decision of being on a landing pattern was taken by just
looking at the current mission index. However, even if the current mission
index indicates a landing pattern the vehicle could be at an arbitrary location, far
from being established on the pattern.

Signed-off-by: RomanBapst <[email protected]>
…item

instead of using the previous waypoint as landing target
- the previous waypoint could be miles away

Signed-off-by: RomanBapst <[email protected]>
Signed-off-by: RomanBapst <[email protected]>
- this fixes a race condition which happens when an RTL is triggered
during the final approach of a mission landing. In that case the mission inactive
method is never called.

Signed-off-by: RomanBapst <[email protected]>
RomanBapst and others added 5 commits December 29, 2020 12:13
- if vtol and in rotary wing mode then don't execute the mission landing
because it's designed to be flow as a fixed wing
- if vtol and in rotary wing mode and mission land is available then fly directly
to landing point and don't go home!

Signed-off-by: RomanBapst <[email protected]>
… landing

- especially when there are strong winds it's better to just go straight
to the landing point instead of trying to follow the planned path

Signed-off-by: RomanBapst <[email protected]>
…TO_ALT for FW

Do not use LOITER_TO_ALT for rotary wing mode as it would then always climb to
at least MIS_LTRMIN_ALT, even if current clib altitude is below
(e.g. RTL immediately after take off)

Signed-off-by: Silvan Fuhrer <[email protected]>
@dagar
Copy link
Member

dagar commented Dec 29, 2020

Rebased on master.

@dagar dagar force-pushed the pr-vtol-rtl-fixes branch from 14735ee to 0bc54f2 Compare December 29, 2020 17:13
@ghost
Copy link

ghost commented Dec 31, 2020

I also noticed that the standard_vtol back transition is behaving dangerously. it's on master and also in this pr,
I noticed this on my flight on the real hardware as well.
just after the back-transition it tries to do a roll maneuver in most of the times,
But every once in a while, it does a ok back-transition, without trying to roll .

same mission, two instances, same-pr (firmware), back-transition behavior is different.
https://review.px4.io/plot_app?log=1e1bb5d2-5260-40da-bd7e-46fadf55fc6c ---> rolling
https://review.px4.io/plot_app?log=12468162-8610-4965-831c-dd25c8edfeda ---> without roll

dangerous.back-transition.mp4

@LorenzMeier
Copy link
Member

Thanks for reporting - @RomanBapst @sfuhrer could you please follow up?

@LorenzMeier
Copy link
Member

@yuthikasagarage Have you reviewed your flights? It looks like the vehicle is overshooting the transition waypoint (so your plan is "not doable") and hence correcting. There is nothing wrong about the control performance, this seems to be more a planning UX / tuning issue than anything else. That still needs to be solved, but not necessarily in the VTOL controller.

@ghost
Copy link

ghost commented Jan 4, 2021

i will look into the flights again, and will try to tune the back transition and check whether the issue persists.
however, with a bad planning let's say it does a back-transition in some case, i think all the back-transitions need to be on level flight even if it overshoots, just my two cents.

Copy link
Member

@LorenzMeier LorenzMeier left a comment

Choose a reason for hiding this comment

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

Reviewed, approving after intense flight testing.

@LorenzMeier LorenzMeier merged commit 92634e7 into master Jan 4, 2021
@LorenzMeier LorenzMeier deleted the pr-vtol-rtl-fixes branch January 4, 2021 10:58
@sfuhrer
Copy link
Contributor Author

sfuhrer commented Jan 4, 2021

@moreba1

in the master version, VTOL has a dangerous behavior when it reaches VTOL Land.

This should be fixed with this PR, please re-test.

desirable behavior is that VTOL transition location be near to land location to minimize power consumption, and the drone doesn't have that much tilt angle and oscillation in MC mode.

With the code from this PR in, it will transition at a distance of the loiter radius from home if no mission landing is planned and the waypoint before the landing waypoint isn't at the transition altitude (RTL_DESCEND_ALT). I'm aware that this isn't optimal for minimized hover time, but at least it should be an improvement to before where it could transition 100m above home and then descend in hover.

@moreba1
Copy link
Contributor

moreba1 commented Jan 28, 2021

* if in FW mode, go to DO_LAND_START marker in FW mode and from there on follow mission landing

Is it possible that VTOL first climbs to RTL_RETURN_ALT and keep this attitude until it reaches to landing pattern?

@sfuhrer
Copy link
Contributor Author

sfuhrer commented Jan 28, 2021

Is it possible that VTOL first climbs to RTL_RETURN_ALT and keep this attitude until it reaches to landing pattern?

That should be the desired behavior. If you noticed something else then let me know, that would indicate a bug.

@VTOLDavid
Copy link
Contributor

i will look into the flights again, and will try to tune the back transition and check whether the issue persists.
however, with a bad planning let's say it does a back-transition in some case, i think all the back-transitions need to be on level flight even if it overshoots, just my two cents.

I having this problem with a tailsitter with very dangerous turns during transition. Is it possible to disable the navigation during transition? The sugested solution is to give more time to the backtransition?

@sfuhrer
Copy link
Contributor Author

sfuhrer commented Feb 11, 2021

I having this problem with a tailsitter with very dangerous turns during transition. Is it possible to disable the navigation during transition? The sugested solution is to give more time to the backtransition?

I don't think this is directly related to this specific PR - would you mind creating a new issue, and include some flight logs in the description? Thanks!

@hamishwillee
Copy link
Contributor

@sfuhrer @Antiheavy Are there any docs changes related to this for PX4v1.12? My guess is yes, though it is unclear with the long thread, what delivered/what the landing behaviour is (?).

Looking at the initial post, it is mostly about what should happen if RTL_TYPE is set to use a mission landing (RTL_TYPE=1) and there was no mission landing pattern defined - in which case it should fly down in FW mode to the descent altitude and then switch to MC and descend "as per usual".

The description is a little flawed because it does not cater for the behaviour with rally points.

Docs for vtol are here:
https://docs.px4.io/master/en/flight_modes/return.html#vtol
https://docs.px4.io/master/en/flight_modes/return.html#mission-landing-rally-point-return-type-rtl-type-1

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.

9 participants