Browse Source

HAL_ChibiOS: hwdef: modify to use HAL CAN driver instead of ChibiOS's

zr-v5.1
Siddharth Purohit 5 years ago committed by Peter Barker
parent
commit
62df67a4b8
  1. 4
      libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat
  2. 7
      libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat
  3. 7
      libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat
  4. 2
      libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat
  5. 7
      libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat
  6. 7
      libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat
  7. 2
      libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py

4
libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat

@ -125,8 +125,8 @@ define HAL_DISABLE_LOOP_DELAY @@ -125,8 +125,8 @@ define HAL_DISABLE_LOOP_DELAY
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0

7
libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat

@ -60,8 +60,8 @@ define HAL_UART_NODMA @@ -60,8 +60,8 @@ define HAL_UART_NODMA
# enable CAN support
PA11 CAN_RX CAN
PB9 CAN_TX CAN
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
# no I2C buses
# I2C_ORDER
@ -127,3 +127,6 @@ define HAL_STORAGE_SIZE 800 @@ -127,3 +127,6 @@ define HAL_STORAGE_SIZE 800
# Add CS pins to ensure they are high in bootloader
PA15 BARO_CS CS
PD2 MAG_CS CS
# reduce the number of CAN RX Buffer
define HAL_CAN_RX_QUEUE_SIZE 32

7
libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat

@ -78,8 +78,8 @@ define HAL_WATCHDOG_ENABLED_DEFAULT true @@ -78,8 +78,8 @@ define HAL_WATCHDOG_ENABLED_DEFAULT true
# enable CAN support
PA11 CAN_RX CAN
PB9 CAN_TX CAN
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
# no I2C buses
# I2C_ORDER
@ -162,3 +162,6 @@ define HAL_NO_MONITOR_THREAD @@ -162,3 +162,6 @@ define HAL_NO_MONITOR_THREAD
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
# reduce the number of CAN RX Buffer
define HAL_CAN_RX_QUEUE_SIZE 32

2
libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat

@ -11,6 +11,8 @@ COMPASS RM3100 SPI:rm3100 false ROTATION_NONE @@ -11,6 +11,8 @@ COMPASS RM3100 SPI:rm3100 false ROTATION_NONE
# and support all external compass types
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_DISABLE_I2C_MAGS_BY_DEFAULT
define HAL_USE_I2C_MAG_HMC5843
# increase TX size for RTCM
undef HAL_UART_MIN_TX_SIZE

7
libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat

@ -92,8 +92,8 @@ define HAL_DISABLE_LOOP_DELAY @@ -92,8 +92,8 @@ define HAL_DISABLE_LOOP_DELAY
# enable CAN support
PA11 CAN_RX CAN
PA12 CAN_TX CAN
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
# reduce memory overheads
define HAL_CAN_POOL_SIZE 2500
@ -142,3 +142,6 @@ RAM_RESERVE_START 256 @@ -142,3 +142,6 @@ RAM_RESERVE_START 256
# keep ROMFS uncompressed as we don't have enough RAM
# to uncompress the bootloader at runtime
env ROMFS_UNCOMPRESSED True
# reduce the number of CAN RX Buffer
define HAL_CAN_RX_QUEUE_SIZE 32

7
libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat

@ -87,8 +87,8 @@ define HAL_DISABLE_LOOP_DELAY @@ -87,8 +87,8 @@ define HAL_DISABLE_LOOP_DELAY
# enable CAN support
PA11 CAN_RX CAN
PA12 CAN_TX CAN
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
# debugger support
PA13 JTMS-SWDIO SWD
@ -138,3 +138,6 @@ RAM_RESERVE_START 256 @@ -138,3 +138,6 @@ RAM_RESERVE_START 256
# keep ROMFS uncompressed as we don't have enough RAM
# to uncompress the bootloader at runtime
env ROMFS_UNCOMPRESSED True
# reduce the number of CAN RX Buffer
define HAL_CAN_RX_QUEUE_SIZE 32

2
libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py

@ -645,7 +645,7 @@ def write_mcu_config(f): @@ -645,7 +645,7 @@ def write_mcu_config(f):
f.write('#define HAL_USE_SERIAL_USB TRUE\n')
if 'OTG2' in bytype:
f.write('#define STM32_USB_USE_OTG2 TRUE\n')
if have_type_prefix('CAN') and 'AP_PERIPH' not in env_vars:
if have_type_prefix('CAN') and not args.bootloader:
if 'CAN1' in bytype and 'CAN2' in bytype:
enable_can(f, 2)
else:

Loading…
Cancel
Save