// @Description: Enable weather vaning. When active, the aircraft will automatically yaw into wind when in a VTOL position controlled mode. Pilot yaw commands overide the weathervaning action.
// @Values: 0:Disabled,1:Nose into wind,2:Nose or tail into wind,3:Side into wind,4:tail into wind
// @Description: This converts the target roll/pitch angle of the aircraft into the correcting (into wind) yaw rate. e.g. Gain = 2, roll = 30 deg, pitch = 0 deg, yaw rate = 60 deg/s.
// @Range: 0.5 4
// @Increment: 0.1
// @User: Standard
AP_GROUPINFO("GAIN",2,AC_WeatherVane,_gain,1.0),
// @Param: ANG_MIN
// @DisplayName: Weathervaning min angle
// @Description: The minimum target roll/pitch angle before active weathervaning will start. This provides a dead zone that is particularly useful for poorly trimmed quadplanes.
// @Description{Copter}: Above this height weathervaning is permitted. If a range finder is fitted or if terrain is enabled, this parameter sets height AGL. Otherwise, this parameter sets height above home. Set zero to ignore minimum height requirement to activate weathervaning.
// @Description{Plane}: Above this height weathervaning is permitted. If RNGFND_LANDING is enabled or terrain is enabled then this parameter sets height AGL. Otherwise this parameter sets height above home. Set zero to ignore minimum height requirement to activate weathervaning
// @Description: The maximum climb or descent speed that the vehicle will still attempt to weathervane. Set to 0 to ignore this condition to get the aircraft to weathervane at any climb/descent rate. This is particularly useful for aircraft with low disc loading that struggle with yaw control in decent.