AP_GPS: reduce POS param range to 5m and add increment

This commit is contained in:
Randy Mackay 2020-01-30 13:30:35 +09:00
parent 8b2629bfc1
commit a19634b9d2

View File

@ -205,44 +205,50 @@ 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
// @Range: -5 5
// @Increment: 0.01
// @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
// @Range: -5 5
// @Increment: 0.01
// @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
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced
AP_GROUPINFO("POS1", 16, AP_GPS, _antenna_offset[0], 0.0f),
#if GPS_MAX_RECEIVERS > 1
// @Param: POS2_X
// @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
// @Range: -5 5
// @Increment: 0.01
// @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
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced
#if GPS_MAX_RECEIVERS > 1
// @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
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced
AP_GROUPINFO("POS2", 17, AP_GPS, _antenna_offset[1], 0.0f),
#endif