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

updated rtl parameter descriptions. #12470

Merged
merged 3 commits into from
Oct 21, 2019
Merged
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
25 changes: 13 additions & 12 deletions src/modules/navigator/rtl_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -34,19 +34,20 @@
/**
* @file rtl_params.c
*
* Parameters for RTL
* Parameters for return to home mode.
hamishwillee marked this conversation as resolved.
Show resolved Hide resolved
*
* @author Julian Oes <[email protected]>
*/

/*
* RTL parameters, accessible via MAVLink
* Return to home parameters, accessible via MAVLink
*/

/**
* RTL altitude
* Return to home relative altitude.
*
* Altitude to fly back in RTL in meters
* Default minimum altitude above home for return flight in return mode.
* This is affected by RTL_MIN_DIST and RTL_CONE_ANG.
*
* @unit m
* @min 0
Expand All @@ -59,9 +60,9 @@ PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 60);


/**
* Return mode loiter altitude
* Return mode loiter altitude (relative to home).
*
* Stay at this altitude above home position after RTL descending.
* Stay at this altitude above home position after return to home mode descending.
hamishwillee marked this conversation as resolved.
Show resolved Hide resolved
* Land (i.e. slowly descend) from this altitude if autolanding allowed.
*
* @unit m
Expand Down Expand Up @@ -89,11 +90,10 @@ PARAM_DEFINE_FLOAT(RTL_DESCEND_ALT, 30);
PARAM_DEFINE_FLOAT(RTL_LAND_DELAY, -1.0f);

/**
* Minimum distance to trigger rising to a safe altitude
* Maximum horizontal distance from home, below which RTL_DESCEND_ALT is used as return altitude.
*
* If the system is horizontally closer than this distance to home
* it will land straight on home instead of raising to the return
* altitude first.
* If the vehicle is less than this horizontal distance from home when return mode is activated it will ascend
* to RTL_DESCEND_ALT for the return journey (rather than the altitude set by RTL_RETURN_ALT and RTL_CONE_ANG).
*
* @unit m
* @min 0.5
Expand All @@ -118,9 +118,10 @@ PARAM_DEFINE_FLOAT(RTL_MIN_DIST, 5.0f);
PARAM_DEFINE_INT32(RTL_TYPE, 0);

/**
* Half-angle of the RTL cone.
* Half-angle of the return to home cone.
hamishwillee marked this conversation as resolved.
Show resolved Hide resolved
*
* Defines the half-angle of the cone which defines the vehicle RTL behavior.
* Defines the half-angle of a cone centered around the home position that
* affects the altitude at which the vehicle returns during return to home.
hamishwillee marked this conversation as resolved.
Show resolved Hide resolved
*
* @unit degrees
* @min 0
Expand Down