mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RangeFinder: add range to POS param description
This commit is contained in:
parent
760989d786
commit
fbf072d84b
@ -146,18 +146,21 @@ const AP_Param::GroupInfo RangeFinder::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: -10 10
|
||||
// @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: -10 10
|
||||
// @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: -10 10
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_POS", 49, RangeFinder, state[0].pos_offset, 0.0f),
|
||||
|
||||
@ -269,18 +272,21 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
||||
// @DisplayName: X position offset
|
||||
// @Description: X position of the second rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: 2_POS_Y
|
||||
// @DisplayName: Y position offset
|
||||
// @Description: Y position of the second rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: 2_POS_Z
|
||||
// @DisplayName: Z position offset
|
||||
// @Description: Z position of the second rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("2_POS", 50, RangeFinder, state[1].pos_offset, 0.0f),
|
||||
|
||||
@ -394,18 +400,21 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
||||
// @DisplayName: X position offset
|
||||
// @Description: X position of the third rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: 3_POS_Y
|
||||
// @DisplayName: Y position offset
|
||||
// @Description: Y position of the third rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: 3_POS_Z
|
||||
// @DisplayName: Z position offset
|
||||
// @Description: Z position of the third rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("3_POS", 51, RangeFinder, state[2].pos_offset, 0.0f),
|
||||
|
||||
@ -519,18 +528,21 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
||||
// @DisplayName: X position offset
|
||||
// @Description: X position of the fourth rangefinder in body frame. Use the zero range datum point if supplied.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: 4_POS_Y
|
||||
// @DisplayName: Y position offset
|
||||
// @Description: Y position of the fourth rangefinder in body frame. Use the zero range datum point if supplied.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: 4_POS_Z
|
||||
// @DisplayName: Z position offset
|
||||
// @Description: Z position of the fourth rangefinder in body frame. Use the zero range datum point if supplied.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("4_POS", 52, RangeFinder, state[3].pos_offset, 0.0f),
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user