mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Plane: Don't overwrite the quadplane loiter relax
This commit is contained in:
parent
51acb72152
commit
7a33d949ca
@ -874,7 +874,7 @@ void QuadPlane::init_loiter(void)
|
|||||||
last_loiter_ms = AP_HAL::millis();
|
last_loiter_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
void QuadPlane::init_land(void)
|
void QuadPlane::init_qland(void)
|
||||||
{
|
{
|
||||||
init_loiter();
|
init_loiter();
|
||||||
throttle_wait = false;
|
throttle_wait = false;
|
||||||
@ -1653,7 +1653,7 @@ bool QuadPlane::init_mode(void)
|
|||||||
init_loiter();
|
init_loiter();
|
||||||
break;
|
break;
|
||||||
case QLAND:
|
case QLAND:
|
||||||
init_land();
|
init_qland();
|
||||||
break;
|
break;
|
||||||
case QRTL:
|
case QRTL:
|
||||||
init_qrtl();
|
init_qrtl();
|
||||||
@ -1777,7 +1777,7 @@ void QuadPlane::vtol_position_controller(void)
|
|||||||
|
|
||||||
case QPOS_POSITION1: {
|
case QPOS_POSITION1: {
|
||||||
Vector2f diff_wp = location_diff(plane.current_loc, loc);
|
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) {
|
if (poscontrol.speed_scale <= 0) {
|
||||||
// initialise scaling so we start off targeting our
|
// initialise scaling so we start off targeting our
|
||||||
@ -1886,7 +1886,11 @@ void QuadPlane::vtol_position_controller(void)
|
|||||||
pos_control->set_desired_accel_xy(0.0f,0.0f);
|
pos_control->set_desired_accel_xy(0.0f,0.0f);
|
||||||
|
|
||||||
// set position control target and update
|
// 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(ekfNavVelGainScaler);
|
pos_control->update_xy_controller(ekfNavVelGainScaler);
|
||||||
|
|
||||||
// nav roll and pitch are controller by position controller
|
// nav roll and pitch are controller by position controller
|
||||||
@ -2291,10 +2295,6 @@ bool QuadPlane::verify_vtol_land(void)
|
|||||||
plane.set_next_WP(plane.next_WP_loc);
|
plane.set_next_WP(plane.next_WP_loc);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (should_relax()) {
|
|
||||||
loiter_nav->soften_for_landing();
|
|
||||||
}
|
|
||||||
|
|
||||||
// at land_final_alt begin final landing
|
// at land_final_alt begin final landing
|
||||||
if (poscontrol.state == QPOS_LAND_DESCEND && check_land_final()) {
|
if (poscontrol.state == QPOS_LAND_DESCEND && check_land_final()) {
|
||||||
poscontrol.state = QPOS_LAND_FINAL;
|
poscontrol.state = QPOS_LAND_FINAL;
|
||||||
|
@ -189,7 +189,7 @@ private:
|
|||||||
void run_rate_controller(void);
|
void run_rate_controller(void);
|
||||||
|
|
||||||
void init_loiter(void);
|
void init_loiter(void);
|
||||||
void init_land(void);
|
void init_qland(void);
|
||||||
void control_loiter(void);
|
void control_loiter(void);
|
||||||
void check_land_complete(void);
|
void check_land_complete(void);
|
||||||
bool land_detector(uint32_t timeout_ms);
|
bool land_detector(uint32_t timeout_ms);
|
||||||
|
Loading…
Reference in New Issue
Block a user