From 18b54467657241669c05052af4e454419ac6c1f4 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 13 Feb 2017 11:34:39 -0700 Subject: [PATCH] Camera: Fix an incorrect label on CAM_DURATION --- libraries/AP_Camera/AP_Camera.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 30b7226021..f18ae67fde 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -26,7 +26,7 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = { // @Param: DURATION // @DisplayName: Duration that shutter is held open // @Description: How long the shutter will be held open in 10ths of a second (i.e. enter 10 for 1second, 50 for 5seconds) - // @Units: seconds + // @Units: deciseconds // @Range: 0 50 // @User: Standard AP_GROUPINFO("DURATION", 1, AP_Camera, _trigger_duration, AP_CAMERA_TRIGGER_DEFAULT_DURATION),