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 param LAND_RNGFND_HLD to hold-off lidar during landing #25549

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

Conversation

magicrub
Copy link
Contributor

@magicrub magicrub commented Nov 15, 2023

Add param LAND_RNGFND_HLD to holdd-off lidar during landing

// @Description: Rangefinder hold-off distance from land point. Hold off using the rangefinder's altitude correction until you're this close to the NAV_LAND point. Requires RNGFND_LANDING = 1. This is useful to avoid the rangefinder reacting to objects/trees, or pits, before the level-ish runway starts. Set to zero to disable the hold-off (don't inhibit the rangefinder). Using this feature will cause the rangefinder to correct the baro offset later in the landing which will lead to a larger slope correction. It is suggested to use LAND_ABORT_DEG with this feature so that unacheivable slopes will cause automatic go-arounds while retaining the rangefinder correction in the baro for a smoother landing on the next attempt.

Inspired by Ryan Johnston (@ryanjAA) at Applied Aeronautics

An even better solution would be to add it to the NAV_LAND point but it's pretty maxed out for us :(

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Nov 15, 2023
@magicrub magicrub changed the title Plane: add param LAND_RNGFND_HLD to holdd-off lidar during landing Plane: add param LAND_RNGFND_HLD to hold-off lidar during landing Nov 15, 2023
@magicrub magicrub force-pushed the pr/land_reduced_lidar branch from 2d02948 to e8be476 Compare November 15, 2023 20:51
@@ -163,6 +163,15 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
// @User: Advanced
AP_GROUPINFO("WIND_COMP", 18, AP_Landing, wind_comp, 50),

// @Param: RNGFND_HLD
// @DisplayName: Rangefinder hold-off
// @Description: Rangefinder hold-off distance from land point. Hold off using the rangefinder's altitude correction until you're this close to the NAV_LAND point. Requires RNGFND_LANDING = 1. This is useful to avoid the rangefinder reacting to objects/trees, or pits, before the level-ish runway starts. Set to zero to disable the hold-off (don't inhibit the rangefinder). Using this feature will cause the rangefinder to correct the baro offset later in the landing which will lead to a larger slope correction. It is suggested to use LAND_ABORT_DEG with this feature so that unacheivable slopes will cause automatic go-arounds while retaining the rangefinder correction in the baro for a smoother landing on the next attempt.
Copy link
Contributor

Choose a reason for hiding this comment

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

maybe say "this close horizontally" to the land point (not clear on first read it is horizontal)

Copy link
Contributor Author

Choose a reason for hiding this comment

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

added!

if (landing.get_rangefinder_holdoff_distance() <= 0 || // rangefinder holdoff is disabled (never hold off, always use rtanegfinder)
auto_state.wp_proportion >= 1 || // or we have reached the land waypoint
landing.is_flaring() || // or we are flaring
current_loc.get_distance(next_WP_loc) >= landing.get_rangefinder_holdoff_distance()) // or we've reached the holdoff distance
Copy link
Contributor

Choose a reason for hiding this comment

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

shouldn't that be <= not >= ?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

whoops, fixed! I went back and forth about it being a bunch of not ANDs instead of positive ORs.. guess I missed this one

@magicrub magicrub force-pushed the pr/land_reduced_lidar branch from e8be476 to 58c6dc8 Compare November 16, 2023 06:01
// use rangefinder to correct if possible
float height = height_above_target() - rangefinder_correction();
if (landing.get_rangefinder_holdoff_distance() <= 0 || // rangefinder holdoff is disabled (never hold off, always use rtanegfinder)
Copy link
Member

@IamPete1 IamPete1 Nov 20, 2023

Choose a reason for hiding this comment

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

Suggested change
if (landing.get_rangefinder_holdoff_distance() <= 0 || // rangefinder holdoff is disabled (never hold off, always use rtanegfinder)
if (landing.get_rangefinder_holdoff_distance() <= 0 || // rangefinder holdoff is disabled (never hold off, always use rangefinder)

float height = height_above_target() - rangefinder_correction();
if (landing.get_rangefinder_holdoff_distance() <= 0 || // rangefinder holdoff is disabled (never hold off, always use rtanegfinder)
auto_state.wp_proportion >= 1 || // or we have reached the land waypoint
landing.is_flaring() || // or we are flaring
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 its a good idea to change the altitude once the flare has started. I don't think it will do anything in anycase.

Copy link

Choose a reason for hiding this comment

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

Why not?

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?

What are you expecting to happen once the flare has already started? Suddenly the correction means were now above flare height and we stop flaring? (which of course means we won't do this correction next loop... )

I just think if your already in the flair its too late to start moving the target altitude about, trying to do it might cause unexpected behavior.

@IamPete1
Copy link
Member

Why not pass the rangefinder correction in to AP landing and let it decide?

@ryanjAA
Copy link

ryanjAA commented Nov 20, 2023

Why not pass the rangefinder correction in to AP landing and let it decide?

I think the idea is to ensure that in tricky landing scenarios (carrier style which is extremely common with uneven terrain), you want it to do less deciding if you have planned accordingly.

@IamPete1
Copy link
Member

I think the idea is to ensure that in tricky landing scenarios (carrier style which is extremely common with uneven terrain), you want it to do less deciding if you have planned accordingly.

I'm not saying the logic should be any different, I just think its in the wrong place. This new logic is calling AP_Landing for three times and calculating things that are already done in the verify_land method (distance to target). Apart from that code neatness argument keeping all the landing code in AP_Landing makes it easier to understand and review since all the logic is in one place.

@magicrub
Copy link
Contributor Author

devcall result: refactor to AP_Landing and then lets discuss again

@magicrub
Copy link
Contributor Author

I think the param name is misleading. Even though it technically IS holding off, what we're really trying to say is only engage the rangefinder within X many meters from NAV_LAND. The length of the landing glide slope is not considered, only distance to the point. I was talking to someone about this and they interpreted the name (not the desc) as X many meters to NOT use the lidar before engaging it. With that interpretation your landing start makes a huge difference and is harder to mission plan

@ryanjAA
Copy link

ryanjAA commented Nov 22, 2023

Will be good to run this through some varying terrain based SITL tests (is that possible, I will need to learn to help) and see if we can induce some errors and what it takes to create the errors so we can identify the limits of the current implementation. Then we can give it some real-world tests and put/plan objects in our final path to reproduce. Maybe move one of the shipping containers to just before the runway (and also try and not hit is too...).

@LupusTheCanine
Copy link

IMHO it would be good to have a dedicated waypoint for barometer alignment this would allow for baro alignment near the center of the runway instead of the threshold just before touchdown.

This would prevent situation where plane flies into the terrain before entering rangefinding zone due to altitude error.

@magicrub
Copy link
Contributor Author

@magicrub
Copy link
Contributor Author

@ryanjAA How's the testing going? Need a rebase?

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

Successfully merging this pull request may close these issues.

7 participants