From 9f3154372d3029a1b75c2f698737a93c6165359b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 30 Jan 2020 13:32:23 +0900 Subject: [PATCH] AP_RangeFinder: POS param range of 5m and 1cm increment --- libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp index a11cd18b06..61c9033097 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp @@ -101,18 +101,24 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = { // @DisplayName: X position offset // @Description: X position of the first rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied. // @Units: m + // @Range: -5 5 + // @Increment: 0.01 // @User: Advanced // @Param: POS_Y // @DisplayName: Y position offset // @Description: Y position of the first rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied. // @Units: m + // @Range: -5 5 + // @Increment: 0.01 // @User: Advanced // @Param: POS_Z // @DisplayName: Z position offset // @Description: Z position of the first rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied. // @Units: m + // @Range: -5 5 + // @Increment: 0.01 // @User: Advanced AP_GROUPINFO("POS", 49, AP_RangeFinder_Params, pos_offset, 0.0f),