Skip to content

Commit

Permalink
AP_GPS:add note to old param names to avoid confusion
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Aug 26, 2024
1 parent a65cd27 commit 2658b30
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 24 deletions.
40 changes: 20 additions & 20 deletions libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1999,111 +1999,111 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg,

// @Param: _TYPE
// @DisplayName: 1st GPS type
// @Description: GPS type of 1st GPS
// @Description: GPS type of 1st GPS.Renamed in 4.6 and later to GPS1_TYPE
// @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:DroneCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:DroneCAN-MovingBaseline-Base,23:DroneCAN-MovingBaseline-Rover,24:UnicoreNMEA,25:UnicoreMovingBaselineNMEA,26:SBF-DualAntenna
// @RebootRequired: True
// @User: Advanced

// @Param: _TYPE2
// @CopyFieldsFrom: GPS_TYPE
// @DisplayName: 2nd GPS type
// @DisplayName: 2nd GPS type.Renamed in 4.6 to GPS2_TYPE
// @Description: GPS type of 2nd GPS

// @Param: _GNSS_MODE
// @DisplayName: GNSS system configuration
// @Description: Bitmask for what GNSS system to use on the first GPS (all unchecked or zero to leave GPS as configured)
// @Description: Bitmask for what GNSS system to use on the first GPS (all unchecked or zero to leave GPS as configured).Renamed in 4.6 and later to GPS1_GNSS_MODE.
// @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLONASS
// @User: Advanced

// @Param: _GNSS_MODE2
// @DisplayName: GNSS system configuration
// @Description: Bitmask for what GNSS system to use on the second GPS (all unchecked or zero to leave GPS as configured)
// @DisplayName: GNSS system configuration.
// @Description: Bitmask for what GNSS system to use on the second GPS (all unchecked or zero to leave GPS as configured). Renamed in 4.6 and later to GPS2_GNSS_MODE
// @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLONASS
// @User: Advanced

// @Param: _RATE_MS
// @DisplayName: GPS update rate in milliseconds
// @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance.
// @DisplayName: GPS update rate in milliseconds. Renamed in 4.6 to GPS1_RAATE_MS
// @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance.Renamed in 4.6 and later to GPS1_RATE_MS
// @Units: ms
// @Values: 100:10Hz,125:8Hz,200:5Hz
// @Range: 50 200
// @User: Advanced

// @Param: _RATE_MS2
// @DisplayName: GPS 2 update rate in milliseconds
// @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance.
// @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance.Renamed in 4.6 and later to GPS2_RATE_MS
// @Units: ms
// @Values: 100:10Hz,125:8Hz,200:5Hz
// @Range: 50 200
// @User: Advanced

// @Param: _POS1_X
// @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.
// @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.Renamed in 4.6 and later to GPS1_POS_X.
// @Units: m
// @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.
// @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.Renamed in 4.6 and later to GPS1_POS_Y.
// @Units: m
// @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.
// @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.Renamed in 4.6 and later to GPS1_POS_Z.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced

// @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.
// @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.Renamed in 4.6 and later to GPS2_POS_X.
// @Units: m
// @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.
// @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.Renamed in 4.6 and later to GPS2_POS_Y.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @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.
// @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.Renamed in 4.6 and later to GPS2_POS_Z.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced

// @Param: _DELAY_MS
// @DisplayName: GPS delay in milliseconds
// @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.
// @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.Renamed in 4.6 and later to GPS1_DELAY_MS.
// @Units: ms
// @Range: 0 250
// @User: Advanced
// @RebootRequired: True

// @Param: _DELAY_MS2
// @DisplayName: GPS 2 delay in milliseconds
// @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.
// @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.Renamed in 4.6 and later to GPS2_DELAY_MS.
// @Units: ms
// @Range: 0 250
// @User: Advanced
// @RebootRequired: True

// @Param: _COM_PORT
// @DisplayName: GPS physical COM port
// @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS
// @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS,Renamed in 4.6 and later to GPS1_COM_PORT.
// @Range: 0 10
// @Increment: 1
// @User: Advanced
Expand All @@ -2112,7 +2112,7 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg,

// @Param: _COM_PORT2
// @DisplayName: GPS physical COM port
// @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS
// @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS.Renamed in 4.6 and later to GPS1_COM_PORT.
// @Range: 0 10
// @Increment: 1
// @User: Advanced
Expand All @@ -2126,13 +2126,13 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg,

// @Param: _CAN_NODEID1
// @DisplayName: GPS Node ID 1
// @Description: GPS Node id for first-discovered GPS.
// @Description: GPS Node id for first-discovered GPS.Renamed in 4.6 and later to GPS1_CAN_NODEID.
// @ReadOnly: True
// @User: Advanced

// @Param: _CAN_NODEID2
// @DisplayName: GPS Node ID 2
// @Description: GPS Node id for second-discovered GPS.
// @Description: GPS Node id for second-discovered GPS.Renamed in 4.6 and later to GPS2_CAN_NODEID.
// @ReadOnly: True
// @User: Advanced

Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_GPS/MovingBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,31 +3,31 @@
const AP_Param::GroupInfo MovingBase::var_info[] = {
// @Param: TYPE
// @DisplayName: Moving base type
// @Description: Controls the type of moving base used if using moving base.
// @Description: Controls the type of moving base used if using moving base.This is renamed in 4.6 and later to GPSx_MB_TYPE.
// @Values: 0:Relative to alternate GPS instance,1:RelativeToCustomBase
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO_FLAGS("TYPE", 1, MovingBase, type, int8_t(Type::RelativeToAlternateInstance), AP_PARAM_FLAG_ENABLE),

// @Param: OFS_X
// @DisplayName: Base antenna X position offset
// @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.
// @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.This is renamed in 4.6 and later to GPSx_MB_OFS_X.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced

// @Param: OFS_Y
// @DisplayName: Base antenna Y position offset
// @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.
// @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.This is renamed in 4.6 and later to GPSx_MB_OFS_Y.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced

// @Param: OFS_Z
// @DisplayName: Base antenna Z position offset
// @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.
// @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.This is renamed in 4.6 and later to GPSx_MB_OFS_Z.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
Expand Down

0 comments on commit 2658b30

Please sign in to comment.