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

FlightTasks: add Descend task to land without GPS #13143

Merged
merged 3 commits into from
Oct 18, 2019

Conversation

julianoes
Copy link
Contributor

@julianoes julianoes commented Oct 9, 2019

This adds a flight task to catch the case where we want to do an emergency descent without GPS but only a baro.

Previously, this would lead to the navigator land class being called without position estimates which then made the flight tasks fail and react with a flight task failsafe. This however meant that landed was never detected and a couple of confusing error messages.

This applies if NAV_RCL_ACT is set to 3 "land".

Fixes #11468.

Tested in SITL with iris, plane, and standard_vtol.

@julianoes
Copy link
Contributor Author

I tried this with and without GPS withvtol_standard and in both cases it transitioned to multicopter flight and then descended. I think that's correct but I don't exactly understand why/how the backtransition is triggered.

@ThomasRigi
Copy link
Member

I tried this with and without GPS withvtol_standard and in both cases it transitioned to multicopter flight and then descended. I think that's correct but I don't exactly understand why/how the backtransition is triggered.

@julianoes I think this is due to NAV_FORCE_VT parameter. Not sure about the exact implementation though. If NAV_FORCE_VT is true then the vehicle will / should always land (and takeoff) in MC mode. Meaning that if you deactivate it it should stay in FW for landing

@mhkabir
Copy link
Member

mhkabir commented Oct 10, 2019

How is this different from the Failsafe flight task?

@bresch
Copy link
Member

bresch commented Oct 11, 2019

I also don't really see the advantage over the failsafe flight task. Also, no GPS doesn't mean no position/velocity estimate, the drone can still have an optical flow sensor and brake horizontal speed.

@julianoes
Copy link
Contributor Author

The failsafe task will actually stay at the same position because we have a valid z-position, however, we should descend.

@julianoes
Copy link
Contributor Author

@MaEtUgR please review.

@julianoes
Copy link
Contributor Author

julianoes commented Oct 14, 2019

@Tony3dr I would appreciate if you could test this pull request carefully on the cheapest multicopter 😄:

Test instructions
Before the tests:

  1. Set RC failsafe to Land (NAV_RCL_ACT = 3)

  2. Make sure RC failsafe is correctly detected (on ground)

  3. Test:
    Hover in POSCTL, then switch off RC -> it should land nicely

  4. Test:
    Fly without GPS, so after powering on PX4, open mavlink shell and do gps stop.
    Hover in ALTCTL (maybe around 1-2 meters), then switch off RC -> it should descend/land but it will drift with wind, so you need to make sure you have enough space and no wind!

Nevermind please wait with this test.

bool ret = FlightTask::activate(last_setpoint);
_position_setpoint = {NAN, NAN, NAN};
_velocity_setpoint = {NAN, NAN, NAN};
_thrust_setpoint = matrix::Vector3f(0.0f, 0.0f, -_param_mpc_thr_hover.get() * 0.6f);
Copy link
Member

@MaEtUgR MaEtUgR Oct 14, 2019

Choose a reason for hiding this comment

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

Note to myself: This conflicts with #12072 and will only show up as a compile error.

@@ -620,6 +615,7 @@ Navigator::run()
case vehicle_status_s::NAVIGATION_STATE_ACRO:
case vehicle_status_s::NAVIGATION_STATE_ALTCTL:
case vehicle_status_s::NAVIGATION_STATE_POSCTL:
case vehicle_status_s::NAVIGATION_STATE_DESCEND:
Copy link
Member

Choose a reason for hiding this comment

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

It would anyways run into default.

src/lib/FlightTasks/tasks/Descend/FlightTaskDescend.cpp Outdated Show resolved Hide resolved
src/lib/FlightTasks/tasks/Descend/FlightTaskDescend.cpp Outdated Show resolved Hide resolved
src/lib/FlightTasks/tasks/Descend/FlightTaskDescend.cpp Outdated Show resolved Hide resolved
@julianoes
Copy link
Contributor Author

@Tony3dr sorry, don't test just yet. We need to change something first.

@Tony3dr
Copy link

Tony3dr commented Oct 14, 2019

@Tony3dr sorry, don't test just yet. We need to change something first.

Sounds good let us know when it's ready.

@MaEtUgR MaEtUgR force-pushed the pr-fix-emergency-descend branch from b1b1e83 to e67b5db Compare October 15, 2019 11:59
@MaEtUgR
Copy link
Member

MaEtUgR commented Oct 15, 2019

@julianoes I pushed on your pr, I hope that's ok.

  • The first commit I squeezed in is fixing the failsafe handling if erroneous non-executable setpoints get into the position controller which was the case before. It then still does an emergency descend but spitting warnings this time.
  • The second commit is yours unchanged
  • The third commit contains my suggestions to use the flight task interface for that case.

I tested before and after the descend introduction and it does the right thing in the case you described (default configuration NAV_RCL_ACT = 3 suffered the same problem). The case where you lose the altitude estimate is hard to test currently... not sure if that's supported at the moment.

@julianoes
Copy link
Contributor Author

@MaEtUgR I've tested these cases:

  1. NAV_RCL_ACT=3 -> GPS ok and RC lost -> switches from POSCTL to LAND and lands ✔️
  2. NAV_RCL_ACT=3 -> no GPS and RC lost -> switches from POSCTL to LAND and descends ✔️
  3. NAV_RCL_ACT=0 -> GPS ok and RC lost -> stays still in POSCTL and stays still ✔️
  4. NAV_RCL_ACT=0 -> no GPS and RC lost -> stays in ALTCTL but descends ✖️

For 4. the output is:

WARN  [commander] Manual control lost
WARN  [mc_pos_control] Position-Control Setpoint-Update failed
WARN  [mc_pos_control] Failsafe: blind hover

@MaEtUgR
Copy link
Member

MaEtUgR commented Oct 15, 2019

I wonder why it would use so much more flash...

@julianoes

  1. "stays in ALTCTL but descends" that's what I implemented because:
    • you are in altitude mode relying on RC
    • you loose RC but have no reaction so you stay relying on it
    • the consumer trying to use RC is failing so you go into last resort handling
    • there's no GPS to just stop and wait so it stays level and will start drifting
    • because drifting without RC is not a sustainable state it's descending
      I consider this much safer than any other solution like staying on altitude drifting away which is a flyaway or terminating which is probably unexpected and is likely causing more damage.
  2. You must be running a different/old branch since I replaced the posted message

    Failsafe: blind hover

Can you check again?

@julianoes
Copy link
Contributor Author

julianoes commented Oct 16, 2019

@MaEtUgR I checked 4. again and you're right. It's now correct. And I agree with your reasoning of switching to descend for this case.

WARN  [commander] Manual control lost
WARN  [mc_pos_control] Position-Control Setpoint-Update failed
WARN  [mc_pos_control] Failsafe: blind land

@julianoes
Copy link
Contributor Author

So now the only thing is to figure out how this fits into fmu-v2.

@julianoes
Copy link
Contributor Author

julianoes commented Oct 16, 2019

@Tony3dr ok I think you can go ahead and test this now:

Test instructions
Before the tests:

  1. Set RC failsafe to Land (NAV_RCL_ACT = 3)

  2. Make sure RC failsafe is correctly detected (on ground)

  3. Test:
    Hover in POSCTL, then switch off RC -> it should land (not RTL) nicely

  4. Test:
    Fly without GPS, so after powering on PX4, open mavlink shell and do gps stop. Don't disconnect the GPS, otherwise you don't have the external mag.
    Hover in ALTCTL (maybe around 1-2 meters), then switch off RC -> it should descend/land but it will drift with wind, so you need to make sure you have enough space and no wind!

@dagar dagar self-requested a review October 16, 2019 16:27
@dannyfpv
Copy link

dannyfpv commented Oct 17, 2019

Tested on Pixhawk 4 v5 f-450

NAV_RCL_ACT = land mode

1 log switch off RC with GPS: no issues
https://review.px4.io/plot_app?log=2ea6423f-b232-45c9-8c40-32e775118359

2 log switch off RC without GPS: no issues drift with wind 30 meters
https://review.px4.io/plot_app?log=3104d449-dd29-473f-9055-354984ff8afa

@LorenzMeier
Copy link
Member

I've updated the branch - let's see if it passes now.

MaEtUgR and others added 3 commits October 18, 2019 11:56
This adds a flight task to catch the case where we want to do an
emergency descent without GPS but only a baro.

Previously, this would lead to the navigator land class being called
without position estimates which then made the flight tasks fail and
react with a flight task failsafe. This however meant that landed was
never detected and a couple of confusing error messages.

This applies if NAV_RCL_ACT is set to 3 "land".
@julianoes julianoes force-pushed the pr-fix-emergency-descend branch from bb2a0ea to 935897a Compare October 18, 2019 09:57
@julianoes
Copy link
Contributor Author

julianoes commented Oct 18, 2019

@dannyfpv thanks a lot for testing and adding the logs, that's very helpful!

@MaEtUgR we need to check the descend case, something is odd with thrust:

bokeh_plot

@julianoes
Copy link
Contributor Author

julianoes commented Oct 18, 2019

@MaEtUgR it looks like ground_contact triggers but always after throttle is set to 0, somehow.

ground_contact

And I can't reproduce it in SITL.

@julianoes
Copy link
Contributor Author

Looking at the vertical position z estimate it looks like not enough vertical movement which triggered the ground contact.

no-vertical-movement

@julianoes
Copy link
Contributor Author

@bresch and I found that the land detector determined:

  1. vertical_movement to be false: https://github.com/PX4/Firmware/blob/95dc522b99688a08402ac6462ad28f5dfd338eda/src/modules/land_detector/MulticopterLandDetector.cpp#L154
  2. hit_ground to be true: https://github.com/PX4/Firmware/blob/95dc522b99688a08402ac6462ad28f5dfd338eda/src/modules/land_detector/MulticopterLandDetector.cpp#L165

This happens because the z controller only reacts slowly to the new setpoint so the z velocity down is much less than the z velocity setpoint here:
https://github.com/PX4/Firmware/blob/95dc522b99688a08402ac6462ad28f5dfd338eda/src/modules/land_detector/MulticopterLandDetector.cpp#L151-L154

It looks to us that we should check the land detector for this edge cases in a future pull request. The issue is general and not specific to this change. Therefore we can merge this PR already.

@julianoes julianoes requested a review from bresch October 18, 2019 14:15
Copy link
Member

@bresch bresch left a comment

Choose a reason for hiding this comment

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

Let's merge that and address the land detector in a separate PR.

@julianoes julianoes merged commit 22c4bb4 into master Oct 18, 2019
@julianoes julianoes deleted the pr-fix-emergency-descend branch October 18, 2019 14:18
@RomanBapst RomanBapst restored the pr-fix-emergency-descend branch May 15, 2020 12:07
@MaEtUgR MaEtUgR deleted the pr-fix-emergency-descend branch July 26, 2020 15:35
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.

Land failsafe broken without GPS
8 participants