mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 14:48:28 -04:00
AP_WindVane: report apparent wind with named float
This commit is contained in:
parent
84f3e70b10
commit
608e1dcdc4
@ -331,6 +331,12 @@ void AP_WindVane::send_wind(mavlink_channel_t chan)
|
|||||||
wrap_360(degrees(get_true_wind_direction_rad())),
|
wrap_360(degrees(get_true_wind_direction_rad())),
|
||||||
get_true_wind_speed(),
|
get_true_wind_speed(),
|
||||||
0);
|
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
|
// calculate true wind speed and direction from apparent wind
|
||||||
|
Loading…
Reference in New Issue
Block a user