From b290148ed028374631e6e15f6a446ad4a5a5bc4c Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Thu, 21 Feb 2019 23:04:35 -0700 Subject: [PATCH] Plane: Don't overwrite the quadplane loiter relax --- ArduPlane/quadplane.cpp | 16 ++++++++-------- ArduPlane/quadplane.h | 2 +- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 7ce40661f5..7f9c6b1a3b 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -895,7 +895,7 @@ void QuadPlane::init_loiter(void) last_loiter_ms = AP_HAL::millis(); } -void QuadPlane::init_land(void) +void QuadPlane::init_qland(void) { init_loiter(); throttle_wait = false; @@ -1750,7 +1750,7 @@ bool QuadPlane::init_mode(void) init_loiter(); break; case QLAND: - init_land(); + init_qland(); break; case QRTL: init_qrtl(); @@ -1877,7 +1877,7 @@ void QuadPlane::vtol_position_controller(void) case QPOS_POSITION1: { Vector2f diff_wp = location_diff(plane.current_loc, loc); - float distance = diff_wp.length(); + const float distance = diff_wp.length(); if (poscontrol.speed_scale <= 0) { // initialise scaling so we start off targeting our @@ -1986,7 +1986,11 @@ void QuadPlane::vtol_position_controller(void) pos_control->set_desired_accel_xy(0.0f,0.0f); // set position control target and update - pos_control->set_xy_target(poscontrol.target.x, poscontrol.target.y); + if (should_relax()) { + loiter_nav->soften_for_landing(); + } else { + pos_control->set_xy_target(poscontrol.target.x, poscontrol.target.y); + } pos_control->update_xy_controller(); // nav roll and pitch are controller by position controller @@ -2369,10 +2373,6 @@ bool QuadPlane::verify_vtol_land(void) plane.set_next_WP(plane.next_WP_loc); } - if (should_relax()) { - loiter_nav->soften_for_landing(); - } - // at land_final_alt begin final landing float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing); if (poscontrol.state == QPOS_LAND_DESCEND && height_above_ground < land_final_alt) { diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 8b2e9ba8ea..0e6464e809 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -200,7 +200,7 @@ private: void control_hover(void); void init_loiter(void); - void init_land(void); + void init_qland(void); void control_loiter(void); void check_land_complete(void);