mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
HAL_ChibiOS: CS pins don't need to be a single SPI BUS
its possible to use a CS pin on different buses, so they should not have a particular bus tag
This commit is contained in:
parent
a554215576
commit
48d2704cf4
@ -53,7 +53,7 @@ PA14 JTCK-SWCLK SWD
|
|||||||
# PA15 ALARM
|
# PA15 ALARM
|
||||||
|
|
||||||
PB0 EXTERN_DRDY INPUT
|
PB0 EXTERN_DRDY INPUT
|
||||||
PB1 EXTERN_CS INPUT
|
PB1 EXTERN_GPIO INPUT
|
||||||
PB2 BOOT1 INPUT
|
PB2 BOOT1 INPUT
|
||||||
PB3 FMU_SW0 INPUT
|
PB3 FMU_SW0 INPUT
|
||||||
PB8 I2C1_SCL I2C1
|
PB8 I2C1_SCL I2C1
|
||||||
@ -65,8 +65,8 @@ PB14 SPI2_MISO SPI2
|
|||||||
PB15 SPI2_MOSI SPI2
|
PB15 SPI2_MOSI SPI2
|
||||||
|
|
||||||
PC0 VBUS_VALID INPUT
|
PC0 VBUS_VALID INPUT
|
||||||
PC1 MAG_CS SPI1 CS
|
PC1 MAG_CS CS
|
||||||
PC2 MPU_CS SPI1 CS
|
PC2 MPU_CS CS
|
||||||
PC3 AUX_POWER ADC1
|
PC3 AUX_POWER ADC1
|
||||||
PC4 AUX_ADC2 ADC1
|
PC4 AUX_ADC2 ADC1
|
||||||
PC5 PRESSURE_SENS ADC1
|
PC5 PRESSURE_SENS ADC1
|
||||||
|
@ -76,7 +76,7 @@ PB15 SPI2_MOSI SPI2
|
|||||||
|
|
||||||
PC0 VBUS_VALID INPUT
|
PC0 VBUS_VALID INPUT
|
||||||
PC1 RSSI_IN ADC1
|
PC1 RSSI_IN ADC1
|
||||||
PC2 MPU9250_CS SPI1 CS
|
PC2 MPU9250_CS CS
|
||||||
PC3 LED_SAFETY OUTPUT
|
PC3 LED_SAFETY OUTPUT
|
||||||
PC4 SAFETY_IN INPUT
|
PC4 SAFETY_IN INPUT
|
||||||
PC5 VDD_PERIPH_EN OUTPUT HIGH
|
PC5 VDD_PERIPH_EN OUTPUT HIGH
|
||||||
@ -90,7 +90,7 @@ PC12 SDIO_CK SDIO
|
|||||||
|
|
||||||
PC13 SBUS_INV OUTPUT
|
PC13 SBUS_INV OUTPUT
|
||||||
PC14 20608_DRDY INPUT
|
PC14 20608_DRDY INPUT
|
||||||
PC15 20608_CS SPI1 CS
|
PC15 20608_CS CS
|
||||||
|
|
||||||
PD0 CAN1_RX CAN1
|
PD0 CAN1_RX CAN1
|
||||||
PD1 CAN1_TX CAN1
|
PD1 CAN1_TX CAN1
|
||||||
@ -102,12 +102,12 @@ PD4 USART2_RTS USART2
|
|||||||
PD5 USART2_TX USART2
|
PD5 USART2_TX USART2
|
||||||
PD6 USART2_RX USART2
|
PD6 USART2_RX USART2
|
||||||
|
|
||||||
PD7 BARO_CS SPI2 CS
|
PD7 BARO_CS CS
|
||||||
|
|
||||||
# USART3 serial3 telem2
|
# USART3 serial3 telem2
|
||||||
PD8 USART3_TX USART3
|
PD8 USART3_TX USART3
|
||||||
PD9 USART3_RX USART3
|
PD9 USART3_RX USART3
|
||||||
PD10 FRAM_CS SPI2 CS
|
PD10 FRAM_CS CS
|
||||||
PD11 USART3_CTS USART3
|
PD11 USART3_CTS USART3
|
||||||
PD12 USART3_RTS USART3
|
PD12 USART3_RTS USART3
|
||||||
|
|
||||||
@ -134,7 +134,7 @@ PE11 TIM1_CH2 TIM1 # FMU_CH3
|
|||||||
PE12 MAG_DRDY INPUT
|
PE12 MAG_DRDY INPUT
|
||||||
PE13 TIM1_CH3 TIM1 # FMU_CH2
|
PE13 TIM1_CH3 TIM1 # FMU_CH2
|
||||||
PE14 TIM1_CH4 TIM1 # FMU_CH1
|
PE14 TIM1_CH4 TIM1 # FMU_CH1
|
||||||
PE15 MAG_CS SPI1 CS
|
PE15 MAG_CS CS
|
||||||
|
|
||||||
# SPI device table. The DEVID values are chosen to match the PX4 port
|
# SPI device table. The DEVID values are chosen to match the PX4 port
|
||||||
# of ArduPilot so users don't need to re-do their accel and compass calibrations
|
# of ArduPilot so users don't need to re-do their accel and compass calibrations
|
||||||
|
@ -56,7 +56,7 @@ PA15 TIM2_CH1 TIM2 # PWM_OUT5
|
|||||||
|
|
||||||
PB0 TIM3_CH3 TIM3 # PWM_OUT3
|
PB0 TIM3_CH3 TIM3 # PWM_OUT3
|
||||||
PB1 TIM3_CH4 TIM3 # PWM_OUT4
|
PB1 TIM3_CH4 TIM3 # PWM_OUT4
|
||||||
PB2 GYRO_CS SPI4 CS
|
PB2 GYRO_CS CS
|
||||||
PB3 TIM2_CH2 TIM2 # PWM_OUT6
|
PB3 TIM2_CH2 TIM2 # PWM_OUT6
|
||||||
PB4 TIM3_CH1 TIM3 # PWM_OUT1
|
PB4 TIM3_CH1 TIM3 # PWM_OUT1
|
||||||
PB5 SPI1_MOSI SPI1
|
PB5 SPI1_MOSI SPI1
|
||||||
@ -97,7 +97,7 @@ PC12 SDIO_CK SDIO
|
|||||||
|
|
||||||
PC13 ACCEL_DRDY INPUT
|
PC13 ACCEL_DRDY INPUT
|
||||||
PC14 MAG_DRDY INPUT
|
PC14 MAG_DRDY INPUT
|
||||||
PC15 BARO_CS SPI4 CS
|
PC15 BARO_CS CS
|
||||||
|
|
||||||
PD0 CAN1_RX CAN1
|
PD0 CAN1_RX CAN1
|
||||||
PD1 CAN1_TX CAN1
|
PD1 CAN1_TX CAN1
|
||||||
@ -114,7 +114,7 @@ PD7 NRF_CSN INPUT
|
|||||||
PD8 USART3_TX USART3
|
PD8 USART3_TX USART3
|
||||||
PD9 USART3_RX USART3
|
PD9 USART3_RX USART3
|
||||||
PD10 NRF_INT INPUT
|
PD10 NRF_INT INPUT
|
||||||
PD11 ACCEL_MAG_CS SPI4 CS
|
PD11 ACCEL_MAG_CS CS
|
||||||
|
|
||||||
PD12 TIM4_CH1 TIM4 # FMU_CH5
|
PD12 TIM4_CH1 TIM4 # FMU_CH5
|
||||||
PD13 TIM4_CH2 TIM4 # FMU_CH6
|
PD13 TIM4_CH2 TIM4 # FMU_CH6
|
||||||
@ -127,7 +127,7 @@ PE1 UART8_TX UART8
|
|||||||
|
|
||||||
# SPI4 is M_SPI (main sensors)
|
# SPI4 is M_SPI (main sensors)
|
||||||
PE2 SPI4_SCK SPI4
|
PE2 SPI4_SCK SPI4
|
||||||
PE3 MPU_CS SPI4 CS
|
PE3 MPU_CS CS
|
||||||
PE4 GYRO_DRDY INPUT
|
PE4 GYRO_DRDY INPUT
|
||||||
PE5 SPI4_MISO SPI4
|
PE5 SPI4_MISO SPI4
|
||||||
PE6 SPI4_MOSI SPI4
|
PE6 SPI4_MOSI SPI4
|
||||||
@ -139,10 +139,10 @@ PE8 UART7_TX UART7
|
|||||||
PE9 TIM1_CH1 TIM1 # FMU_CH1
|
PE9 TIM1_CH1 TIM1 # FMU_CH1
|
||||||
PE10 MPU_DRDY INPUT
|
PE10 MPU_DRDY INPUT
|
||||||
PE11 TIM1_CH2 TIM1 # FMU_CH2
|
PE11 TIM1_CH2 TIM1 # FMU_CH2
|
||||||
PE12 FRAM_CS SPI1 CS
|
PE12 FRAM_CS CS
|
||||||
PE13 TIM1_CH3 TIM1 # FMU_CH3
|
PE13 TIM1_CH3 TIM1 # FMU_CH3
|
||||||
PE14 TIM1_CH4 TIM1 # FMU_CH4
|
PE14 TIM1_CH4 TIM1 # FMU_CH4
|
||||||
PE15 NRF_CS SPI2 CS
|
PE15 NRF_CS CS
|
||||||
|
|
||||||
# SPI device table
|
# SPI device table
|
||||||
SPIDEV ms5611 SPI4 DEVID1 BARO_CS MODE3 2*MHZ 2*MHZ
|
SPIDEV ms5611 SPI4 DEVID1 BARO_CS MODE3 2*MHZ 2*MHZ
|
||||||
|
@ -109,6 +109,10 @@ class generic_pin(object):
|
|||||||
return True
|
return True
|
||||||
return False
|
return False
|
||||||
|
|
||||||
|
def is_CS(self):
|
||||||
|
'''return true if this is a CS pin'''
|
||||||
|
return self.has_extra("CS") or self.type == "CS"
|
||||||
|
|
||||||
def get_MODER(self):
|
def get_MODER(self):
|
||||||
'''return one of ALTERNATE, OUTPUT, ANALOG, INPUT'''
|
'''return one of ALTERNATE, OUTPUT, ANALOG, INPUT'''
|
||||||
if self.af is not None:
|
if self.af is not None:
|
||||||
@ -117,7 +121,7 @@ class generic_pin(object):
|
|||||||
v = "OUTPUT"
|
v = "OUTPUT"
|
||||||
elif self.type.startswith('ADC'):
|
elif self.type.startswith('ADC'):
|
||||||
v = "ANALOG"
|
v = "ANALOG"
|
||||||
elif self.has_extra("CS"):
|
elif self.is_CS():
|
||||||
v = "OUTPUT"
|
v = "OUTPUT"
|
||||||
elif self.is_RTS():
|
elif self.is_RTS():
|
||||||
v = "OUTPUT"
|
v = "OUTPUT"
|
||||||
@ -141,7 +145,7 @@ class generic_pin(object):
|
|||||||
'''return one of SPEED_VERYLOW, SPEED_LOW, SPEED_MEDIUM, SPEED_HIGH'''
|
'''return one of SPEED_VERYLOW, SPEED_LOW, SPEED_MEDIUM, SPEED_HIGH'''
|
||||||
values = ['SPEED_VERYLOW', 'SPEED_LOW', 'SPEED_MEDIUM', 'SPEED_HIGH']
|
values = ['SPEED_VERYLOW', 'SPEED_LOW', 'SPEED_MEDIUM', 'SPEED_HIGH']
|
||||||
v = 'SPEED_HIGH'
|
v = 'SPEED_HIGH'
|
||||||
if self.has_extra("CS"):
|
if self.is_CS():
|
||||||
v = "SPEED_MEDIUM"
|
v = "SPEED_MEDIUM"
|
||||||
if self.type.startswith("I2C"):
|
if self.type.startswith("I2C"):
|
||||||
v = "SPEED_MEDIUM"
|
v = "SPEED_MEDIUM"
|
||||||
@ -154,7 +158,7 @@ class generic_pin(object):
|
|||||||
'''return one of FLOATING, PULLUP, PULLDOWN'''
|
'''return one of FLOATING, PULLUP, PULLDOWN'''
|
||||||
values = ['FLOATING', 'PULLUP', 'PULLDOWN']
|
values = ['FLOATING', 'PULLUP', 'PULLDOWN']
|
||||||
v = 'FLOATING'
|
v = 'FLOATING'
|
||||||
if self.has_extra("CS"):
|
if self.is_CS():
|
||||||
v = "PULLUP"
|
v = "PULLUP"
|
||||||
for e in self.extra:
|
for e in self.extra:
|
||||||
if e in values:
|
if e in values:
|
||||||
@ -297,7 +301,7 @@ def write_SPI_table(f):
|
|||||||
error("Bad SPI bus in SPIDEV line %s" % dev)
|
error("Bad SPI bus in SPIDEV line %s" % dev)
|
||||||
if not devid.startswith('DEVID') or not is_int(devid[5:]):
|
if not devid.startswith('DEVID') or not is_int(devid[5:]):
|
||||||
error("Bad DEVID in SPIDEV line %s" % dev)
|
error("Bad DEVID in SPIDEV line %s" % dev)
|
||||||
if not cs in bylabel:
|
if not cs in bylabel or not bylabel[cs].is_CS():
|
||||||
error("Bad CS pin in SPIDEV line %s" % dev)
|
error("Bad CS pin in SPIDEV line %s" % dev)
|
||||||
if not mode in ['MODE0', 'MODE1', 'MODE2', 'MODE3']:
|
if not mode in ['MODE0', 'MODE1', 'MODE2', 'MODE3']:
|
||||||
error("Bad MODE in SPIDEV line %s" % dev)
|
error("Bad MODE in SPIDEV line %s" % dev)
|
||||||
|
@ -33,7 +33,7 @@ PA2 USART2_TX USART2
|
|||||||
PA3 USART2_RX USART2
|
PA3 USART2_RX USART2
|
||||||
|
|
||||||
# SPI1 is radio
|
# SPI1 is radio
|
||||||
PA4 RADIO_CS SPI1 CS
|
PA4 RADIO_CS CS
|
||||||
PA5 SPI1_SCK SPI1
|
PA5 SPI1_SCK SPI1
|
||||||
PA6 SPI1_MISO SPI1
|
PA6 SPI1_MISO SPI1
|
||||||
PA7 SPI1_MOSI SPI1
|
PA7 SPI1_MOSI SPI1
|
||||||
@ -70,7 +70,7 @@ PC6 TIM3_CH1 TIM3
|
|||||||
PB15 SPI2_MOSI SPI2
|
PB15 SPI2_MOSI SPI2
|
||||||
PB14 SPI2_MISO SPI2
|
PB14 SPI2_MISO SPI2
|
||||||
PB13 SPI2_SCK SPI2
|
PB13 SPI2_SCK SPI2
|
||||||
PB12 FLOW_CS SPI2 CS
|
PB12 FLOW_CS CS
|
||||||
|
|
||||||
# SPI Device table
|
# SPI Device table
|
||||||
SPIDEV cypress SPI1 DEVID1 RADIO_CS MODE0 2*MHZ 2*MHZ
|
SPIDEV cypress SPI1 DEVID1 RADIO_CS MODE0 2*MHZ 2*MHZ
|
||||||
|
Loading…
Reference in New Issue
Block a user