From a016f74188505567635411e4fbde6effba9e2f8b Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Wed, 26 Jun 2024 00:56:41 +0200 Subject: [PATCH] Added MAV_CMD_EXTERNAL_WIND_ESTIMATE to development (#2122) --- message_definitions/v1.0/development.xml | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index 36deb98fc7..37e1fd242d 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -35,6 +35,18 @@ Reboot components after ID change. Any non-zero value triggers the reboot. + + Set an external estimate of wind direction and speed. + This might be used to provide an initial wind estimate to the estimator (EKF) in the case where the vehicle is wind dead-reckoning, extending the time when operating without GPS before before position drift builds to an unsafe level. For this use case the command might reasonably be sent every few minutes when operating at altitude, and the value is cleared if the estimator resets itself. + + Horizontal wind speed. + Estimated 1 sigma accuracy of wind speed. Set to NaN if unknown. + Azimuth (relative to true north) from where the wind is blowing. + Estimated 1 sigma accuracy of wind direction. Set to NaN if unknown. + Empty + Empty + Empty +