mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: add param defaults for EMLID_EDGE for GPS_TYPE=9
This commit is contained in:
parent
3105fd56bc
commit
793f50808d
@ -71,7 +71,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @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,12:QURT,13:ERB,14:MAV,15:NOVA
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TYPE", 0, AP_GPS, _type[0], 1),
|
||||
AP_GROUPINFO("TYPE", 0, AP_GPS, _type[0], HAL_GPS_TYPE_DEFAULT),
|
||||
|
||||
// @Param: TYPE2
|
||||
// @DisplayName: 2nd GPS type
|
||||
|
Loading…
Reference in New Issue
Block a user