AP_RangeFinder: Improve consistency of parameter naming

This commit is contained in:
priseborough 2016-10-15 09:22:08 +11:00 committed by Andrew Tridgell
parent c93c3d54f3
commit 3ca6c12344

View File

@ -130,24 +130,24 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
// @User: Standard // @User: Standard
AP_GROUPINFO("_ADDR", 23, RangeFinder, _address[0], 0), AP_GROUPINFO("_ADDR", 23, RangeFinder, _address[0], 0),
// @Param: 1_POS_X // @Param: _POS_X
// @DisplayName: X position offset // @DisplayName: X position offset
// @Description: X position of the first rangefinder in body frame. Use the zero range datum point if supplied. // @Description: X position of the first rangefinder in body frame. Use the zero range datum point if supplied.
// @Units: m // @Units: m
// @User: Advanced // @User: Advanced
// @Param: 1_POS_Y // @Param: _POS_Y
// @DisplayName: Y position offset // @DisplayName: Y position offset
// @Description: Y position of the first rangefinder in body frame. Use the zero range datum point if supplied. // @Description: Y position of the first rangefinder in body frame. Use the zero range datum point if supplied.
// @Units: m // @Units: m
// @User: Advanced // @User: Advanced
// @Param: 1_POS_Z // @Param: _POS_Z
// @DisplayName: Z position offset // @DisplayName: Z position offset
// @Description: Z position of the first rangefinder in body frame. Use the zero range datum point if supplied. // @Description: Z position of the first rangefinder in body frame. Use the zero range datum point if supplied.
// @Units: m // @Units: m
// @User: Advanced // @User: Advanced
AP_GROUPINFO("1_POS", 49, RangeFinder, _pos_offset[0], 0.0f), AP_GROUPINFO("_POS", 49, RangeFinder, _pos_offset[0], 0.0f),
#if RANGEFINDER_MAX_INSTANCES > 1 #if RANGEFINDER_MAX_INSTANCES > 1
// @Param: 2_TYPE // @Param: 2_TYPE