mirror of https://github.com/ArduPilot/ardupilot
Plane: limit target accel in POSITION1
don't ask for more than 2* transition limit, and reset when we enter overshoot case
This commit is contained in:
parent
b2f17e7553
commit
29ccd0e106
|
@ -2498,7 +2498,7 @@ void QuadPlane::vtol_position_controller(void)
|
||||||
Vector2f target_accel_cms;
|
Vector2f target_accel_cms;
|
||||||
bool have_target_yaw = false;
|
bool have_target_yaw = false;
|
||||||
float target_yaw_deg;
|
float target_yaw_deg;
|
||||||
const float target_accel = accel_needed(distance, sq(closing_groundspeed));
|
const float target_accel = MIN(accel_needed(distance, sq(closing_groundspeed)), transition_decel*2);
|
||||||
if (distance > 0.1) {
|
if (distance > 0.1) {
|
||||||
Vector2f diff_wp_norm = diff_wp.normalized();
|
Vector2f diff_wp_norm = diff_wp.normalized();
|
||||||
target_speed_xy_cms = diff_wp_norm * target_speed * 100;
|
target_speed_xy_cms = diff_wp_norm * target_speed * 100;
|
||||||
|
@ -2510,6 +2510,7 @@ void QuadPlane::vtol_position_controller(void)
|
||||||
gcs().send_text(MAV_SEVERITY_INFO,"VTOL Overshoot d=%.1f cs=%.1f yerr=%.1f",
|
gcs().send_text(MAV_SEVERITY_INFO,"VTOL Overshoot d=%.1f cs=%.1f yerr=%.1f",
|
||||||
distance, closing_groundspeed, yaw_err_deg);
|
distance, closing_groundspeed, yaw_err_deg);
|
||||||
poscontrol.overshoot = true;
|
poscontrol.overshoot = true;
|
||||||
|
pos_control->set_accel_desired_xy_cmss(Vector2f());
|
||||||
}
|
}
|
||||||
if (poscontrol.overshoot) {
|
if (poscontrol.overshoot) {
|
||||||
/* we have overshot the landing point or our nose is
|
/* we have overshot the landing point or our nose is
|
||||||
|
|
Loading…
Reference in New Issue