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: added Q_APPROACH_DIST #28072

Merged
merged 1 commit into from
Sep 12, 2024
Merged
Show file tree
Hide file tree
Changes from all 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
12 changes: 11 additions & 1 deletion ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -538,6 +538,15 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = {
// @User: Standard
AP_GROUPINFO("BCK_PIT_LIM", 38, QuadPlane, q_bck_pitch_lim, 10.0f),

// @Param: APPROACH_DIST
// @DisplayName: Q mode approach distance
// @Description: The minimum distance from the destination to use the fixed wing airbrake and approach code for landing approach. This is useful if you don't want the fixed wing approach logic to be used when you are close to the destination. Set to zero to always use fixed wing approach.
// @Units: m
// @Range: 0.0 1000
// @Increment: 1
// @User: Standard
AP_GROUPINFO("APPROACH_DIST", 39, QuadPlane, approach_distance, 0),
Copy link
Contributor

Choose a reason for hiding this comment

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

Although it's a bit of a mouthful, we already have Q_FW_LND_APR_RAD - so for consistency, it might make sense to call this Q_FW_LND_APR_DST.

Copy link
Member

Choose a reason for hiding this comment

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

Q_FW_LND_APR_RAD is related to the circle before transition into the wind stuff. Its not the same thing.


AP_GROUPEND
};

Expand Down Expand Up @@ -2160,7 +2169,8 @@ void QuadPlane::run_xy_controller(float accel_limit)
void QuadPlane::poscontrol_init_approach(void)
{
const float dist = plane.current_loc.get_distance(plane.next_WP_loc);
if (option_is_set(QuadPlane::OPTION::DISABLE_APPROACH)) {
if (option_is_set(QuadPlane::OPTION::DISABLE_APPROACH) ||
(is_positive(approach_distance) && dist < approach_distance)) {
// go straight to QPOS_POSITION1
poscontrol.set_state(QPOS_POSITION1);
gcs().send_text(MAV_SEVERITY_INFO,"VTOL Position1 d=%.1f", dist);
Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -609,6 +609,9 @@ class QuadPlane
return (options.get() & int32_t(option)) != 0;
}

// minimum distance to be from destination to use approach logic
AP_Float approach_distance;

AP_Float takeoff_failure_scalar;
AP_Float maximum_takeoff_airspeed;
uint32_t takeoff_start_time_ms;
Expand Down
Loading