mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_GPS: add range to POS param description
This commit is contained in:
parent
bbf1c434c6
commit
c7287bb98f
@ -191,18 +191,21 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @DisplayName: Antenna X position offset
|
||||
// @Description: X position of the first GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POS1_Y
|
||||
// @DisplayName: Antenna Y position offset
|
||||
// @Description: Y position of the first GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POS1_Z
|
||||
// @DisplayName: Antenna Z position offset
|
||||
// @Description: Z position of the first GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("POS1", 16, AP_GPS, _antenna_offset[0], 0.0f),
|
||||
|
||||
@ -210,18 +213,21 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @DisplayName: Antenna X position offset
|
||||
// @Description: X position of the second GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POS2_Y
|
||||
// @DisplayName: Antenna Y position offset
|
||||
// @Description: Y position of the second GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POS2_Z
|
||||
// @DisplayName: Antenna Z position offset
|
||||
// @Description: Z position of the second GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
|
||||
// @Units: m
|
||||
// @Range: -10 10
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("POS2", 17, AP_GPS, _antenna_offset[1], 0.0f),
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user