diff --git a/libraries/AP_WindVane/AP_WindVane.cpp b/libraries/AP_WindVane/AP_WindVane.cpp index e6d4f0ff2e..54eceab80a 100644 --- a/libraries/AP_WindVane/AP_WindVane.cpp +++ b/libraries/AP_WindVane/AP_WindVane.cpp @@ -331,6 +331,12 @@ void AP_WindVane::send_wind(mavlink_channel_t chan) wrap_360(degrees(get_true_wind_direction_rad())), get_true_wind_speed(), 0); + + // send apparent wind using named floats + // TODO: create a dedicated MAVLink message + gcs().send_named_float("AppWndSpd", get_apparent_wind_speed()); + gcs().send_named_float("AppWndDir", degrees(get_apparent_wind_direction_rad())); + } // calculate true wind speed and direction from apparent wind