mirror of https://github.com/ArduPilot/ardupilot
hwdef: enable GPS_MOVING_BASELINE on FreeflyRTK and f303-GPS
this allows for F9P based dual-GPS yaw on DroneCAN peripherals with auto-config
This commit is contained in:
parent
83404f7537
commit
0df1dd6999
|
@ -130,6 +130,7 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
|||
# disable dual GPS and GPS blending to save flash space
|
||||
define GPS_MAX_RECEIVERS 1
|
||||
define GPS_MAX_INSTANCES 1
|
||||
define GPS_MOVING_BASELINE 1
|
||||
define HAL_COMPASS_MAX_SENSORS 1
|
||||
|
||||
# GPS+MAG+BARO+Buzzer+NeoPixels
|
||||
|
|
|
@ -14,3 +14,6 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
|||
define HAL_PERIPH_ENABLE_GPS
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY
|
||||
|
||||
# allow for F9P GPS modules with moving baseline
|
||||
define GPS_MOVING_BASELINE 1
|
||||
|
|
|
@ -16,6 +16,9 @@ define HAL_PERIPH_ENABLE_ADSB
|
|||
define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY
|
||||
define HAL_PERIPH_ENABLE_RANGEFINDER
|
||||
|
||||
# allow for F9P GPS modules with moving baseline
|
||||
define GPS_MOVING_BASELINE 1
|
||||
|
||||
define HAL_PERIPH_ADSB_PORT_DEFAULT 3
|
||||
|
||||
define HAL_AIRSPEED_BUS_DEFAULT 0
|
||||
|
|
Loading…
Reference in New Issue