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

navigator: check distances between waypoints #8146

Merged
merged 1 commit into from
Oct 18, 2017

Conversation

julianoes
Copy link
Contributor

Instead of just checking whether the first waypoint is too far away from home it makes sense to also check between waypoints.

This can prevent

  • flyaways due to user errors, or
  • catch the corner case where a takeoff waypoint is added to a mission
    and therefore the first waypoint is not too far away, however, the
    subsequent waypoints are still too far away.

Tested in SITL using DroneCore.

Instead of just checking whether the first waypoint is too far away from
home it makes sense to also check between waypoints.
This can prevent
- flyaways due to user errors, or
- catch the corner case where a takeoff waypoint is added to a mission
  and therefore the first waypoint is not too far away, however, the
  subsequent waypoints are still too far away.
@julianoes julianoes requested a review from dagar October 17, 2017 18:16
@dagar
Copy link
Member

dagar commented Oct 17, 2017

Sounds like a good addition. While we're on the subject, what do you think of the distance to first waypoint check?

The majority of our existing feasibility checks could happen even before you have GPS or a valid home. So if we handle the distance to first waypoint check at a different level we could be a lot more restrictive and prevent navigator from taking the mission at all if it's not feasible.

The current situation where navigator has the updated mission even if it's not feasible can be dangerous.

@julianoes
Copy link
Contributor Author

The current situation where navigator has the updated mission even if it's not feasible can be dangerous.

But it is still safe because it won't do the mission later even if you can upload it.

I think the advantage of the current flow is that you can load the mission before going to the field.

@dagar
Copy link
Member

dagar commented Oct 17, 2017

I want both the ability to plan the mission before going to the field (when possible), and the separation of navigator mission not even able to touch an infeasible mission.

By not safe I mean for a plane that needs a planned mission landing to not hit trees or a building.

@LorenzMeier LorenzMeier merged commit 787931f into master Oct 18, 2017
@LorenzMeier LorenzMeier deleted the check-distances-between-waypoints branch October 18, 2017 06:42
@julianoes
Copy link
Contributor Author

I want both the ability to plan the mission before going to the field (when possible), and the separation of navigator mission not even able to touch an infeasible mission.

I see. So we need library calls for the mission checks that we can use in e.g. mavlink where the mission arrives but also later in navigator.

@sanderux
Copy link
Member

sanderux commented Nov 21, 2017

@julianoes this might make sense for multirotors but for FW it is way too narrow a default.
To allow use of the full range of the DeltaQuad you would need to set 200 waypoints this way.

Any ideas on how to solve this? Maybe disable by default and set it separately in MC FW and VTOL rc defaults script?

@julianoes
Copy link
Contributor Author

@sanderux I didn't think of that. I was assuming most people can only fly line of sight, so a radius of 500m anyway 😄.

I think it makes sense to change the param once you are actually doing a longer mission (and really know what you're doing), or change the param for the vehicle, so you could add it into the DeltaQuad startup script.

@sanderux
Copy link
Member

It is making it hard for me to manage vehicles already in service when they upgrade.
but if it is what it is i suppose i will have to instruct all of them to disable this param or set it to something sensible.

@julianoes
Copy link
Contributor Author

julianoes commented Nov 22, 2017

I guess so. Otherwise you can hard-code it for DeltaQuad in:
https://github.com/PX4/Firmware/blob/master/ROMFS/px4fmu_common/init.d/13013_deltaquad#L110

if param compare MIS_DIST_WPS 900
then
    param set MIS_DIST_WPS <new value>
fi

Or if you only want it to be changed on auto-config, then add it in there.

@sanderux
Copy link
Member

For the DeltaQuad i can fix it (its still manageable now) but im also concerned for other vtol/fw users

@julianoes
Copy link
Contributor Author

I still think the default values make sense for the general case because I think we should err on the side of caution and trying to prevent fly-aways.

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.

4 participants