mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: added RM3100 in f303-GPS
This commit is contained in:
parent
207dffba88
commit
22f0e8a065
|
@ -5,6 +5,13 @@ define HAL_CAN_DEFAULT_NODE_ID 117
|
|||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps"
|
||||
|
||||
# added rm3100 mag on SPI
|
||||
SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
|
||||
COMPASS RM3100 SPI:rm3100 false ROTATION_NONE
|
||||
|
||||
# and support all external compass types
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
|
||||
# GPS+MAG
|
||||
define HAL_PERIPH_ENABLE_GPS
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
|
|
|
@ -57,8 +57,6 @@ PA5 SPI1_SCK SPI1
|
|||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
|
||||
SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
|
||||
|
||||
# analog input
|
||||
# PA5 VIN5 ADC1
|
||||
define HAL_USE_ADC FALSE
|
||||
|
@ -117,15 +115,12 @@ define HAL_BUILD_AP_PERIPH
|
|||
# only one I2C bus
|
||||
I2C_ORDER I2C1
|
||||
|
||||
COMPASS RM3100 SPI:rm3100 false ROTATION_NONE
|
||||
|
||||
define HAL_I2C_CLEAR_ON_TIMEOUT 0
|
||||
|
||||
define HAL_DEVICE_THREAD_STACK 256
|
||||
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
||||
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define HAL_I2C_INTERNAL_MASK 0
|
||||
|
||||
# disable dual GPS and GPS blending to save flash space
|
||||
|
|
Loading…
Reference in New Issue