AP_GPS: move underscore one layer down for GPS
This commit is contained in:
parent
5657dad3e6
commit
edceb4e3a4
@ -78,138 +78,138 @@ AP_GPS *AP_GPS::_singleton;
|
||||
|
||||
// table of user settable parameters
|
||||
const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @Param: TYPE
|
||||
// @Param: _TYPE
|
||||
// @DisplayName: GPS type
|
||||
// @Description: GPS type
|
||||
// @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:UAVCAN,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
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TYPE", 0, AP_GPS, _type[0], HAL_GPS_TYPE_DEFAULT),
|
||||
AP_GROUPINFO("_TYPE", 0, AP_GPS, _type[0], HAL_GPS_TYPE_DEFAULT),
|
||||
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
// @Param: TYPE2
|
||||
// @Param: _TYPE2
|
||||
// @DisplayName: 2nd GPS type
|
||||
// @Description: GPS type of 2nd GPS
|
||||
// @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:UAVCAN,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
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TYPE2", 1, AP_GPS, _type[1], 0),
|
||||
AP_GROUPINFO("_TYPE2", 1, AP_GPS, _type[1], 0),
|
||||
#endif
|
||||
|
||||
// @Param: NAVFILTER
|
||||
// @Param: _NAVFILTER
|
||||
// @DisplayName: Navigation filter setting
|
||||
// @Description: Navigation filter engine setting
|
||||
// @Values: 0:Portable,2:Stationary,3:Pedestrian,4:Automotive,5:Sea,6:Airborne1G,7:Airborne2G,8:Airborne4G
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("NAVFILTER", 2, AP_GPS, _navfilter, GPS_ENGINE_AIRBORNE_4G),
|
||||
AP_GROUPINFO("_NAVFILTER", 2, AP_GPS, _navfilter, GPS_ENGINE_AIRBORNE_4G),
|
||||
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
// @Param: AUTO_SWITCH
|
||||
// @Param: _AUTO_SWITCH
|
||||
// @DisplayName: Automatic Switchover Setting
|
||||
// @Description: Automatic switchover to GPS reporting best lock, 1:UseBest selects the GPS with highest status, if both are equal the GPS with highest satellite count is used 4:Use primary if 3D fix or better, will revert over 'UseBest' behaviour if 3D fix is lost on primary
|
||||
// @Values: 0:Use primary, 1:UseBest, 2:Blend, 4:Use primary if 3D fix or better
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("AUTO_SWITCH", 3, AP_GPS, _auto_switch, (int8_t)GPSAutoSwitch::USE_BEST),
|
||||
AP_GROUPINFO("_AUTO_SWITCH", 3, AP_GPS, _auto_switch, (int8_t)GPSAutoSwitch::USE_BEST),
|
||||
#endif
|
||||
|
||||
// @Param: MIN_DGPS
|
||||
// @Param: _MIN_DGPS
|
||||
// @DisplayName: Minimum Lock Type Accepted for DGPS
|
||||
// @Description: Sets the minimum type of differential GPS corrections required before allowing to switch into DGPS mode.
|
||||
// @Values: 0:Any,50:FloatRTK,100:IntegerRTK
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("MIN_DGPS", 4, AP_GPS, _min_dgps, 100),
|
||||
AP_GROUPINFO("_MIN_DGPS", 4, AP_GPS, _min_dgps, 100),
|
||||
|
||||
// @Param: SBAS_MODE
|
||||
// @Param: _SBAS_MODE
|
||||
// @DisplayName: SBAS Mode
|
||||
// @Description: This sets the SBAS (satellite based augmentation system) mode if available on this GPS. If set to 2 then the SBAS mode is not changed in the GPS. Otherwise the GPS will be reconfigured to enable/disable SBAS. Disabling SBAS may be worthwhile in some parts of the world where an SBAS signal is available but the baseline is too long to be useful.
|
||||
// @Values: 0:Disabled,1:Enabled,2:NoChange
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SBAS_MODE", 5, AP_GPS, _sbas_mode, 2),
|
||||
AP_GROUPINFO("_SBAS_MODE", 5, AP_GPS, _sbas_mode, 2),
|
||||
|
||||
// @Param: MIN_ELEV
|
||||
// @Param: _MIN_ELEV
|
||||
// @DisplayName: Minimum elevation
|
||||
// @Description: This sets the minimum elevation of satellites above the horizon for them to be used for navigation. Setting this to -100 leaves the minimum elevation set to the GPS modules default.
|
||||
// @Range: -100 90
|
||||
// @Units: deg
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MIN_ELEV", 6, AP_GPS, _min_elevation, -100),
|
||||
AP_GROUPINFO("_MIN_ELEV", 6, AP_GPS, _min_elevation, -100),
|
||||
|
||||
// @Param: INJECT_TO
|
||||
// @Param: _INJECT_TO
|
||||
// @DisplayName: Destination for GPS_INJECT_DATA MAVLink packets
|
||||
// @Description: The GGS can send raw serial packets to inject data to multiple GPSes.
|
||||
// @Values: 0:send to first GPS,1:send to 2nd GPS,127:send to all
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("INJECT_TO", 7, AP_GPS, _inject_to, GPS_RTK_INJECT_TO_ALL),
|
||||
AP_GROUPINFO("_INJECT_TO", 7, AP_GPS, _inject_to, GPS_RTK_INJECT_TO_ALL),
|
||||
|
||||
// @Param: SBP_LOGMASK
|
||||
// @Param: _SBP_LOGMASK
|
||||
// @DisplayName: Swift Binary Protocol Logging Mask
|
||||
// @Description: Masked with the SBP msg_type field to determine whether SBR1/SBR2 data is logged
|
||||
// @Values: 0:None (0x0000),-1:All (0xFFFF),-256:External only (0xFF00)
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SBP_LOGMASK", 8, AP_GPS, _sbp_logmask, -256),
|
||||
AP_GROUPINFO("_SBP_LOGMASK", 8, AP_GPS, _sbp_logmask, -256),
|
||||
|
||||
// @Param: RAW_DATA
|
||||
// @Param: _RAW_DATA
|
||||
// @DisplayName: Raw data logging
|
||||
// @Description: Handles logging raw data; on uBlox chips that support raw data this will log RXM messages into logger; on Septentrio this will log on the equipment's SD card and when set to 2, the autopilot will try to stop logging after disarming and restart after arming
|
||||
// @Values: 0:Ignore,1:Always log,2:Stop logging when disarmed (SBF only),5:Only log every five samples (uBlox only)
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RAW_DATA", 9, AP_GPS, _raw_data, 0),
|
||||
AP_GROUPINFO("_RAW_DATA", 9, AP_GPS, _raw_data, 0),
|
||||
|
||||
// @Param: GNSS_MODE
|
||||
// @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)
|
||||
// @Values: 0:Leave as currently configured, 1:GPS-NoSBAS, 3:GPS+SBAS, 4:Galileo-NoSBAS, 6:Galileo+SBAS, 8:Beidou, 51:GPS+IMES+QZSS+SBAS (Japan Only), 64:GLONASS, 66:GLONASS+SBAS, 67:GPS+GLONASS+SBAS
|
||||
// @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("GNSS_MODE", 10, AP_GPS, _gnss_mode[0], 0),
|
||||
AP_GROUPINFO("_GNSS_MODE", 10, AP_GPS, _gnss_mode[0], 0),
|
||||
|
||||
// @Param: SAVE_CFG
|
||||
// @Param: _SAVE_CFG
|
||||
// @DisplayName: Save GPS configuration
|
||||
// @Description: Determines whether the configuration for this GPS should be written to non-volatile memory on the GPS. Currently working for UBlox 6 series and above.
|
||||
// @Values: 0:Do not save config,1:Save config,2:Save only when needed
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SAVE_CFG", 11, AP_GPS, _save_config, 2),
|
||||
AP_GROUPINFO("_SAVE_CFG", 11, AP_GPS, _save_config, 2),
|
||||
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
// @Param: GNSS_MODE2
|
||||
// @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)
|
||||
// @Values: 0:Leave as currently configured, 1:GPS-NoSBAS, 3:GPS+SBAS, 4:Galileo-NoSBAS, 6:Galileo+SBAS, 8:Beidou, 51:GPS+IMES+QZSS+SBAS (Japan Only), 64:GLONASS, 66:GLONASS+SBAS, 67:GPS+GLONASS+SBAS
|
||||
// @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("GNSS_MODE2", 12, AP_GPS, _gnss_mode[1], 0),
|
||||
AP_GROUPINFO("_GNSS_MODE2", 12, AP_GPS, _gnss_mode[1], 0),
|
||||
#endif
|
||||
|
||||
// @Param: AUTO_CONFIG
|
||||
// @Param: _AUTO_CONFIG
|
||||
// @DisplayName: Automatic GPS configuration
|
||||
// @Description: Controls if the autopilot should automatically configure the GPS based on the parameters and default settings
|
||||
// @Values: 0:Disables automatic configuration,1:Enable automatic configuration
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("AUTO_CONFIG", 13, AP_GPS, _auto_config, 1),
|
||||
AP_GROUPINFO("_AUTO_CONFIG", 13, AP_GPS, _auto_config, 1),
|
||||
|
||||
// @Param: RATE_MS
|
||||
// @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.
|
||||
// @Units: ms
|
||||
// @Values: 100:10Hz,125:8Hz,200:5Hz
|
||||
// @Range: 50 200
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RATE_MS", 14, AP_GPS, _rate_ms[0], 200),
|
||||
AP_GROUPINFO("_RATE_MS", 14, AP_GPS, _rate_ms[0], 200),
|
||||
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
// @Param: RATE_MS2
|
||||
// @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.
|
||||
// @Units: ms
|
||||
// @Values: 100:10Hz,125:8Hz,200:5Hz
|
||||
// @Range: 50 200
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RATE_MS2", 15, AP_GPS, _rate_ms[1], 200),
|
||||
AP_GROUPINFO("_RATE_MS2", 15, AP_GPS, _rate_ms[1], 200),
|
||||
#endif
|
||||
|
||||
// @Param: POS1_X
|
||||
// @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.
|
||||
// @Units: m
|
||||
@ -217,7 +217,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @Increment: 0.01
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POS1_Y
|
||||
// @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
|
||||
@ -225,17 +225,17 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @Increment: 0.01
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POS1_Z
|
||||
// @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: -5 5
|
||||
// @Increment: 0.01
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("POS1", 16, AP_GPS, _antenna_offset[0], 0.0f),
|
||||
AP_GROUPINFO("_POS1", 16, AP_GPS, _antenna_offset[0], 0.0f),
|
||||
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
// @Param: POS2_X
|
||||
// @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
|
||||
@ -243,7 +243,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @Increment: 0.01
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POS2_Y
|
||||
// @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
|
||||
@ -251,104 +251,104 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @Increment: 0.01
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POS2_Z
|
||||
// @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: -5 5
|
||||
// @Increment: 0.01
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("POS2", 17, AP_GPS, _antenna_offset[1], 0.0f),
|
||||
AP_GROUPINFO("_POS2", 17, AP_GPS, _antenna_offset[1], 0.0f),
|
||||
#endif
|
||||
|
||||
// @Param: DELAY_MS
|
||||
// @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.
|
||||
// @Units: ms
|
||||
// @Range: 0 250
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("DELAY_MS", 18, AP_GPS, _delay_ms[0], 0),
|
||||
AP_GROUPINFO("_DELAY_MS", 18, AP_GPS, _delay_ms[0], 0),
|
||||
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
// @Param: DELAY_MS2
|
||||
// @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.
|
||||
// @Units: ms
|
||||
// @Range: 0 250
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("DELAY_MS2", 19, AP_GPS, _delay_ms[1], 0),
|
||||
AP_GROUPINFO("_DELAY_MS2", 19, AP_GPS, _delay_ms[1], 0),
|
||||
#endif
|
||||
|
||||
#if defined(GPS_BLENDED_INSTANCE)
|
||||
// @Param: BLEND_MASK
|
||||
// @Param: _BLEND_MASK
|
||||
// @DisplayName: Multi GPS Blending Mask
|
||||
// @Description: Determines which of the accuracy measures Horizontal position, Vertical Position and Speed are used to calculate the weighting on each GPS receiver when soft switching has been selected by setting GPS_AUTO_SWITCH to 2(Blend)
|
||||
// @Bitmask: 0:Horiz Pos,1:Vert Pos,2:Speed
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("BLEND_MASK", 20, AP_GPS, _blend_mask, 5),
|
||||
AP_GROUPINFO("_BLEND_MASK", 20, AP_GPS, _blend_mask, 5),
|
||||
|
||||
// @Param: BLEND_TC
|
||||
// @Param: _BLEND_TC
|
||||
// @DisplayName: Blending time constant
|
||||
// @Description: Controls the slowest time constant applied to the calculation of GPS position and height offsets used to adjust different GPS receivers for steady state position differences.
|
||||
// @Units: s
|
||||
// @Range: 5.0 30.0
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("BLEND_TC", 21, AP_GPS, _blend_tc, 10.0f),
|
||||
AP_GROUPINFO("_BLEND_TC", 21, AP_GPS, _blend_tc, 10.0f),
|
||||
#endif
|
||||
|
||||
#if GPS_MOVING_BASELINE
|
||||
// @Param: DRV_OPTIONS
|
||||
// @Param: _DRV_OPTIONS
|
||||
// @DisplayName: driver options
|
||||
// @Description: Additional backend specific options
|
||||
// @Bitmask: 0:Use UART2 for moving baseline on ublox,1:Use base station for GPS yaw on SBF
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("DRV_OPTIONS", 22, AP_GPS, _driver_options, 0),
|
||||
AP_GROUPINFO("_DRV_OPTIONS", 22, AP_GPS, _driver_options, 0),
|
||||
#endif
|
||||
|
||||
// @Param: COM_PORT
|
||||
// @Param: _COM_PORT
|
||||
// @DisplayName: GPS physical COM port
|
||||
// @Description: The physical COM port on the connected device, currently only applies to SBF GPS
|
||||
// @Range: 0 10
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("COM_PORT", 23, AP_GPS, _com_port[0], HAL_GPS_COM_PORT_DEFAULT),
|
||||
AP_GROUPINFO("_COM_PORT", 23, AP_GPS, _com_port[0], HAL_GPS_COM_PORT_DEFAULT),
|
||||
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
// @Param: COM_PORT2
|
||||
// @Param: _COM_PORT2
|
||||
// @DisplayName: GPS physical COM port
|
||||
// @Description: The physical COM port on the connected device, currently only applies to SBF GPS
|
||||
// @Range: 0 10
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("COM_PORT2", 24, AP_GPS, _com_port[1], HAL_GPS_COM_PORT_DEFAULT),
|
||||
AP_GROUPINFO("_COM_PORT2", 24, AP_GPS, _com_port[1], HAL_GPS_COM_PORT_DEFAULT),
|
||||
#endif
|
||||
|
||||
#if GPS_MOVING_BASELINE
|
||||
|
||||
// @Group: MB1_
|
||||
// @Group: _MB1_
|
||||
// @Path: MovingBase.cpp
|
||||
AP_SUBGROUPINFO(mb_params[0], "MB1_", 25, AP_GPS, MovingBase),
|
||||
AP_SUBGROUPINFO(mb_params[0], "_MB1_", 25, AP_GPS, MovingBase),
|
||||
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
// @Group: MB2_
|
||||
// @Group: _MB2_
|
||||
// @Path: MovingBase.cpp
|
||||
AP_SUBGROUPINFO(mb_params[1], "MB2_", 26, AP_GPS, MovingBase),
|
||||
AP_SUBGROUPINFO(mb_params[1], "_MB2_", 26, AP_GPS, MovingBase),
|
||||
#endif // GPS_MAX_RECEIVERS > 1
|
||||
|
||||
#endif // GPS_MOVING_BASELINE
|
||||
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
// @Param: PRIMARY
|
||||
// @Param: _PRIMARY
|
||||
// @DisplayName: Primary GPS
|
||||
// @Description: This GPS will be used when GPS_AUTO_SWITCH is 0 and used preferentially with GPS_AUTO_SWITCH = 4.
|
||||
// @Increment: 1
|
||||
// @Values: 0:FirstGPS, 1:SecondGPS
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("PRIMARY", 27, AP_GPS, _primary, 0),
|
||||
AP_GROUPINFO("_PRIMARY", 27, AP_GPS, _primary, 0),
|
||||
#endif
|
||||
|
||||
#if GPS_MAX_RECEIVERS > 1 && HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
|
Loading…
Reference in New Issue
Block a user