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

RTL: do not RTL if RTL alt is above max HAGL #23501

Merged
merged 4 commits into from
Aug 14, 2024
Merged

RTL: do not RTL if RTL alt is above max HAGL #23501

merged 4 commits into from
Aug 14, 2024

Conversation

bresch
Copy link
Member

@bresch bresch commented Aug 6, 2024

Solved Problem

When using a downward looking sensor for navigation (e.g.: optical flow), the EKF sends a height above ground limit that the vehicle shouldn't exceed to avoid a loss of navigation. Currently, commander/navigator are unaware of this and are allowed to trigger RTL with an altitude higher than the maximum value, leading to a descend. When below the max HAGL, the navigation re-starts and commander tries to RTL again. The vehicle is then stuck in a loop.

Solution

RTL shouldn't send the vehicle to an altitude above the mag HAGL. Sending the drone to the max HAGL and then to home is dangerous too, so the best option is to land instead.

New uORB topic: navigator_status is used to report when a navigator mode fails to execute.
Commander monitors this field and triggers a failsafe if the current navigator mode fails.

Changelog Entry

For release notes:

-
New parameter: -
Documentation: -

Test coverage

sitl with optical flow

@bresch bresch requested a review from KonradRudin August 6, 2024 11:41
@bresch bresch self-assigned this Aug 6, 2024
Copy link
Contributor

@KonradRudin KonradRudin left a comment

Choose a reason for hiding this comment

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

For the case when we trigger an RTL where at the beginning the hagl condition (_rtl_alt - terrain > hagl_max) is not true, we would make a normal RTL. When then the terrain changes and the hagl altitude is exceeded, then it would also go into failsafe descend first and then into RTL again, correct? Is there a way to avoid that? Or flying in this situation should always trigger land instead of RTL? An alternative approach would be to enforce that in navigator rather than in the RTL.

src/modules/navigator/rtl_direct.cpp Outdated Show resolved Hide resolved
@bresch bresch marked this pull request as draft August 7, 2024 14:07
@bresch
Copy link
Member Author

bresch commented Aug 7, 2024

I will in fact try to do something similar to geofence:

  1. Navigator sends a uorb topic with the "breached" flag
  2. commander/HealthAndArmingChecks subs to that topic and sets a failsafe flag
  3. failsafe.cpp gets that flag and switches to land

@bresch bresch force-pushed the pr-rtl-max-hagl branch 2 times, most recently from 9ba0fc4 to a3d69cd Compare August 9, 2024 12:20
@bresch bresch marked this pull request as ready for review August 9, 2024 12:21
src/modules/navigator/navigator_main.cpp Show resolved Hide resolved
src/modules/commander/failsafe/failsafe.cpp Outdated Show resolved Hide resolved
msg/CMakeLists.txt Show resolved Hide resolved
KonradRudin
KonradRudin previously approved these changes Aug 12, 2024
@bresch bresch merged commit 4ed3e9e into main Aug 14, 2024
95 checks passed
@bresch bresch deleted the pr-rtl-max-hagl branch August 14, 2024 09:08
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.

2 participants