From 176e8b886115897c79cb18a89a151c6fa0448b41 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 3 Feb 2020 13:39:40 +0900 Subject: [PATCH] AP_OpticalFlow: add orient-yaw parameter units --- libraries/AP_OpticalFlow/OpticalFlow.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_OpticalFlow/OpticalFlow.cpp b/libraries/AP_OpticalFlow/OpticalFlow.cpp index bc460df58a..018eacbd39 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow.cpp @@ -49,6 +49,7 @@ const AP_Param::GroupInfo OpticalFlow::var_info[] = { // @Param: _ORIENT_YAW // @DisplayName: Flow sensor yaw alignment // @Description: Specifies the number of centi-degrees that the flow sensor is yawed relative to the vehicle. A sensor with its X-axis pointing to the right of the vehicle X axis has a positive yaw angle. + // @Units: cdeg // @Range: -18000 +18000 // @Increment: 1 // @User: Standard