MAVLINKHUD

Overview

The WNDVN parameter group configures the Wind Vane (Anemometer) sensor. This is required for Autonomous Sailing and provides high-accuracy wind data for landing and takeoff on all vehicles.

Key Concepts

1. Sensor Types (WNDVN_TYPE)

Defines the hardware protocol.

  • 1 (Analog): Potentiometer-based vane (reads voltage).
  • 2 (I2C): Digital I2C sensor (e.g., AS5600).
  • 3 (NMEA): Standard marine NMEA 0183 wind sensor.
  • 4 (DroneCAN): CAN-based sensors.

2. Calibration (WNDVN_DIR_OFS)

Aligns the sensor's "zero" position with the vehicle's "Forward" axis.

Parameter Breakdown

  • WNDVN_SPEED_TYPE: Selection of speed sensor (e.g., cup anemometer vs ultrasonic).
  • WNDVN_DIR_PIN: (Analog) ADC pin number.

Integration Guide

  1. Hardware: Mount the vane at the highest point of the vehicle, clear of air turbulence.
  2. Config: Set WNDVN_TYPE.
  3. Calibrate: Point the vane exactly forward and use WNDVN_DIR_OFS to zero the reading in the GCS.

Developer Notes

  • Library: libraries/AP_WindVane.

WNDVN_CAL

Default 0
Range 0 2

Wind Vane Calibration Trigger (WNDVN_CAL)

Description

WNDVN_CAL initiates a specialized routine to find the voltage limits of your analog wind vane.

Instead of manually typing in the V_MIN and V_MAX voltages, you can use this trigger to let the autopilot learn them.

  • 1: Start Calibration. The autopilot begins recording the highest and lowest voltages it sees.
  • 2: Finish and Save. Saves the learned values to the V_MIN/V_MAX parameters and resets this trigger to 0.

Tuning & Behavior

  • Default: 0.
  • Procedure:
    1. Set WNDVN_CAL to 1.
    2. Manually rotate your wind vane through several full 360-degree circles.
    3. Set WNDVN_CAL to 2 to lock in the results.

WNDVN_DIR_DZ

deg
Default 0
Range 0 360

Wind Vane Analog Deadzone (WNDVN_DIR_DZ)

Description

WNDVN_DIR_DZ compensates for the "Mechanical Gap" found in many analog wind vanes.

Most analog vanes use a simple potentiometer to measure direction. In a full 360-degree rotation, there is usually a tiny physical area where the metal "wiper" inside the sensor isn't touching the resistive track. In this gap, the sensor may output a random or incorrect voltage. This parameter tells the autopilot how many degrees wide that gap is, so it can ignore the data and "Hold" the last known good heading while the vane passes through that sector.

Tuning & Behavior

  • Default: 0.
  • Calibration: Rotate the vane slowly. If you see the direction "Jump" wildly at one specific point in the circle, measure the width of that jump in degrees and enter it here.
  • Note: Only applicable for Analog wind vanes.

WNDVN_DIR_FILT

Hz
Default 0.5
Range -1.0 10.0

Wind Vane Direction Filter (WNDVN_DIR_FILT)

Description

WNDVN_DIR_FILT smooths the raw data coming from the wind vane.

Wind is naturally turbulent, and physical vanes tend to "jitter" or bounce rapidly. This filter removes that high-frequency noise, providing a stable "Apparent Wind" direction for the autopilot to use for sail trimming.

  • Higher Frequency (e.g. 2.0 Hz): More responsive to quick wind shifts, but "nervous" sails.
  • Lower Frequency (e.g. 0.1 Hz): Very smooth sail movement, but may be too slow to react to real gusts.
  • -1: Disables the filter (Not recommended).

Tuning & Behavior

  • Default: 0.5 Hz.
  • Recommendation: Leave at 0.5 Hz. If your sail servos are constantly twitching, reduce this value to 0.2 Hz.

WNDVN_DIR_OFS

deg
Default 0
Range 0 360

Wind Vane Direction Offset (WNDVN_DIR_OFS)

Description

WNDVN_DIR_OFS allows you to calibrate your wind vane without having to physically remount it. It defines the angle the sensor reports when the wind is coming directly from the front of the vehicle.

  • Units: Degrees.
  • Calibration: Point the vehicle directly into the wind and hold the wind vane at its "neutral" position. If the HUD reports 10 degrees, set the offset to -10 (or 350).

Tuning & Behavior

  • Default: 0.
  • Usage: Use this to align the digital "Front" of the sensor with the physical "Front" of your vehicle.

WNDVN_DIR_PIN

Default -1
Range -1 103

Wind Vane Direction Pin (WNDVN_DIR_PIN)

Description

WNDVN_DIR_PIN sets the physical analog pin on the flight controller where the wind vane's direction signal is connected.

This parameter is only used if WNDVN_TYPE is set to 3 (Analog).

  • -1: Not used.
  • 0-9: Analog Pin Number. (e.g., 0 for A0).
  • 50-55: AUX Out Pins. (When configured as analog inputs).
  • 103: RSSI/SBUS pin. (On some hardware).

Tuning & Behavior

  • Default: -1.
  • Selection: Consult your flight controller's hardware documentation (GPIO/Analog Pin mapping) to find the correct number for the pin you have used.

WNDVN_DIR_V_MAX

V
Default 3.3
Range 0 5.0

Wind Vane Max Voltage (WNDVN_DIR_V_MAX)

Description

WNDVN_DIR_V_MAX calibrates the "End" of the rotation for an Analog wind vane.

It defines the voltage that the autopilot should interpret as a full 360-degree rotation. Together with V_MIN, it establishes the scaling for the entire rotation circle.

Tuning & Behavior

  • Default: 3.3V.
  • Calibration: Rotate the wind vane manually to its mechanical end point and observe the voltage in your GCS. Enter that value here.
  • Important: Most analog vanes have a small "Dead Zone" between 359° and 0° where the wiper doesn't touch the resistive track. See WNDVN_DIR_DZ to handle this gap.

WNDVN_DIR_V_MIN

V
Default 0
Range 0 5.0

Wind Vane Min Voltage (WNDVN_DIR_V_MIN)

Description

WNDVN_DIR_V_MIN calibrates the "Start" of the rotation for an Analog wind vane.

Most analog wind vanes use a potentiometer that maps 0-360 degrees of rotation to a voltage range (e.g. 0.0V to 3.3V). This parameter defines the voltage that the autopilot should interpret as the very beginning of that rotation.

Tuning & Behavior

  • Default: 0V.
  • Calibration: Rotate the wind vane manually to its mechanical start point (often marked on the sensor) and observe the voltage in your GCS. Enter that value here.
  • Constraint: On most modern flight controllers, the maximum readable voltage is 3.3V.

WNDVN_SPEED_FILT

Hz
Default 0.5
Range 0 20

Wind Speed Low-Pass Filter (WNDVN_SPEED_FILT)

Description

WNDVN_SPEED_FILT smooths out the "gusty" or noisy data from your anemometer (wind speed sensor).

Wind speed is naturally turbulent, especially near the surface. Without a filter, the reported wind speed would jump around rapidly, which can make the sail trimming or mission logic twitchy. This parameter sets the cutoff frequency for a low-pass filter to provide a stable "Apparent Wind" speed.

  • Higher Frequency (e.g. 2.0 Hz): More responsive to quick wind shifts, but more noise.
  • Lower Frequency (e.g. 0.1 Hz): Very smooth data, but slow to react to real gusts.

Tuning & Behavior

  • Default: 0.5 Hz.
  • Recommendation: Leave at 0.5 Hz. If your telemetry shows very jumpy wind speeds even in steady air, reduce this value to 0.2 Hz.

WNDVN_SPEED_MIN

m/s
Default 0
Range 0 5

Wind Vane Cut-off Speed (WNDVN_SPEED_MIN)

Description

WNDVN_SPEED_MIN prevents the autopilot from reacting to "Flutter" or "Dithering" when there is no wind.

Physical wind vanes require a certain amount of airflow to overcome friction and point accurately. In very light winds, a vane might just flop around or stay stuck in an old position. This parameter tells the autopilot to ignore the wind direction data unless the measured wind speed is above this threshold.

Tuning & Behavior

  • Default: 0.
  • Recommendation: Set to 0.5 m/s to 1.0 m/s depending on how free-moving your physical wind vane is.
  • Dependencies: Requires a functional wind speed sensor (WNDVN_SPEED_TYPE).

WNDVN_SPEED_OFS

V
Default 0
Range 0 3.3

Wind Speed Voltage Offset (WNDVN_SPEED_OFS)

Description

WNDVN_SPEED_OFS calibrates the "Zero Point" for Analog wind speed sensors.

Many analog anemometers (like the Modern Devices sensor) output a small baseline voltage even when there is no wind. This parameter tells the autopilot to treat that specific voltage as "0.0 m/s," ensuring that subsequent speed readings are accurate.

Tuning & Behavior

  • Default: 0.
  • Calibration: Power on the vehicle in a room with perfectly still air. Observe the raw voltage from the sensor in the GCS status tab (or via logs) and enter that value here.
  • Effect: If this value is too high, the drone will under-report wind speed. If too low, it will report a phantom wind even when stationary.

WNDVN_SPEED_PIN

Default -1
Range -1 103

Wind Speed Pin (WNDVN_SPEED_PIN)

Description

WNDVN_SPEED_PIN sets the physical analog pin on the flight controller where the wind speed sensor's signal is connected.

This parameter is only used if WNDVN_SPEED_TYPE is set to 2 (Modern Devices Analog).

  • -1: Not used.
  • 0-9: Analog Pin Number. (e.g., 0 for A0).
  • 50-55: AUX Out Pins. (When configured as analog inputs).
  • 103: RSSI/SBUS pin.

Tuning & Behavior

  • Default: -1.
  • Configuration: You must also set WNDVN_SPEED_OFS to calibrate the voltage at zero wind speed.

WNDVN_SPEED_TYPE

Default 0
Range 0 11

Wind Speed Sensor Type (WNDVN_SPEED_TYPE)

Description

WNDVN_SPEED_TYPE enables the measurement of wind speed (Anemometer).

This is critical for sailboats to calculate "True Wind" and for any vehicle that needs to record local weather conditions. If enabled, the autopilot will use this data to improve navigation and sail control.

  • 0: None. No wind speed sensor.
  • 1: Airspeed Library. Uses the drone's existing pitot tube.
  • 2: Modern Devices. (Analog).
  • 3: RPM Library. Calculates wind speed based on the rotation rate of a cup-style anemometer.
  • 4: NMEA.

Tuning & Behavior

  • Reboot Required: Yes.
  • Integration: If using an analog sensor, you must also set WNDVN_SPEED_PIN.

WNDVN_TEMP_PIN

Default -1
Range -1 100

Wind vane speed sensor analog temp pin (WNDVN_TEMP_PIN)

Description

This parameter specifies the microcontroller pin connected to the temperature output of the wind speed sensor (specifically designed for the Modern Devices Wind Sensor Rev. P). This analog temperature reading is critical for compensating the hot-wire anemometer data, ensuring accurate wind speed measurements across varying ambient temperatures.

The Mathematics

$$ V\_{\text{wind\_comp}} = f(V\_{\text{raw}}, V\_{\text{temp}}) $$

The Engineer's View

Defined in libraries/AP_WindVane/AP_WindVane.cpp.

  • -1: Disabled.
  • Pin Number: The ADC pin ID (e.g., 14 or 15).

Tuning & Behavior

  • Default Value: -1 (Disabled)
  • Usage: Only relevant for analog hot-wire sensors. Mechanical cups/vanes do not use this.

WNDVN_TRUE_FILT

Hz
Default 0.05
Range 0 10

True Wind Data Low-Pass Filter (WNDVN_TRUE_FILT)

Description

WNDVN_TRUE_FILT smooths the "Global" wind estimate.

Unlike apparent wind (what the drone feels while moving), True Wind is the actual wind speed and direction relative to the ground. It is calculated by combining apparent wind data with the drone's own velocity and heading. This calculation is prone to errors during turns. This very slow filter (default 0.05 Hz) ensures that the drone builds a stable long-term estimate of the real wind conditions.

Tuning & Behavior

  • Default: 0.05 Hz (Very Slow).
  • Significance: It takes about 20 seconds for a change in the real wind to be fully reflected in the "True Wind" estimate. This prevent's the drone's own movements from "polluting" the wind estimate.

WNDVN_TYPE

Default 0
Range 0 11

Wind Vane Type (WNDVN_TYPE)

Description

WNDVN_TYPE enables support for measuring the wind direction relative to the vehicle. This is primarily used by Sailboats to trim their sails and by some autonomous vehicles for advanced weather logging or drift compensation.

  • 0: None. Wind vane support is disabled.
  • 1: Heading when armed. Assumes the wind is coming from the direction the vehicle is pointing when it arms.
  • 3: Analog. For physical wind vanes that output a voltage proportional to the angle.
  • 4: NMEA. For digital wind sensors (Anemometers) that output MAVLink or NMEA data strings.
  • 10-11: SITL. For simulation testing.

Tuning & Behavior

  • Reboot Required: Yes.
  • Setup: Once enabled, you must configure the input pin (WNDVN_DIR_PIN) if using an Analog type.