mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 02:48:28 -04:00
Plane: adjust target vector for wind in overshoot
at low speeds we want to keep the nose pointed into the wind on landings
This commit is contained in:
parent
473804f11c
commit
b2f17e7553
@ -2520,6 +2520,12 @@ void QuadPlane::vtol_position_controller(void)
|
||||
target_accel_cms.zero();
|
||||
target_speed_xy_cms = diff_wp_norm * position2_target_speed * 100;
|
||||
have_target_yaw = true;
|
||||
|
||||
// adjust target yaw angle for wind
|
||||
const Vector2f wind = plane.ahrs.wind_estimate().xy();
|
||||
const float gnd_speed = plane.ahrs.groundspeed();
|
||||
Vector2f target_speed_xy = diff_wp_norm * gnd_speed - wind;
|
||||
target_yaw_deg = degrees(target_speed_xy.angle());
|
||||
}
|
||||
}
|
||||
const float target_speed_ms = target_speed_xy_cms.length() * 0.01;
|
||||
|
Loading…
Reference in New Issue
Block a user