mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: make GPS_MB parameters clearer
offsets are from the 2nd antenna to the base (primary) antenna
This commit is contained in:
parent
366a325fc0
commit
b9642b549b
@ -11,7 +11,7 @@ const AP_Param::GroupInfo MovingBase::var_info[] = {
|
||||
|
||||
// @Param: OFS_X
|
||||
// @DisplayName: Base antenna X position offset
|
||||
// @Description: X position of the base GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
|
||||
// @Description: X position of the base (primary) GPS antenna in body frame from the position of the 2nd antenna. Positive X is forward of the 2nd antenna. Use antenna phase centroid location if provided by the manufacturer.
|
||||
// @Units: m
|
||||
// @Range: -5 5
|
||||
// @Increment: 0.01
|
||||
@ -19,7 +19,7 @@ const AP_Param::GroupInfo MovingBase::var_info[] = {
|
||||
|
||||
// @Param: OFS_Y
|
||||
// @DisplayName: Base antenna Y position offset
|
||||
// @Description: Y position of the base GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
|
||||
// @Description: Y position of the base (primary) GPS antenna in body frame from the position of the 2nd antenna. Positive Y is to the right of the 2nd antenna. Use antenna phase centroid location if provided by the manufacturer.
|
||||
// @Units: m
|
||||
// @Range: -5 5
|
||||
// @Increment: 0.01
|
||||
@ -27,7 +27,7 @@ const AP_Param::GroupInfo MovingBase::var_info[] = {
|
||||
|
||||
// @Param: OFS_Z
|
||||
// @DisplayName: Base antenna Z position offset
|
||||
// @Description: Z position of the base GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
|
||||
// @Description: Z position of the base (primary) GPS antenna in body frame from the position of the 2nd antenna. Positive Z is down from the 2nd antenna. Use antenna phase centroid location if provided by the manufacturer.
|
||||
// @Units: m
|
||||
// @Range: -5 5
|
||||
// @Increment: 0.01
|
||||
|
Loading…
Reference in New Issue
Block a user