HAL_Chibios: moved SPI device tables to hwdef.dat
This commit is contained in:
parent
d1f93cd66c
commit
58796ff435
@ -24,91 +24,6 @@
|
||||
using namespace ChibiOS;
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
|
||||
#define SPI_BUS_FLOW 1
|
||||
#define SPI_BUS_RADIO 0
|
||||
|
||||
#define SPIDEV_CS_FLOW GPIOB, 12
|
||||
#define SPIDEV_CS_RADIO GPIOA, 4
|
||||
|
||||
#define SPIDEV_RADIO 1
|
||||
#define SPIDEV_FLOW 2
|
||||
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV3
|
||||
#define SPI_BUS_SENSORS 0
|
||||
#define SPI_BUS_RAMTRON 1
|
||||
#define SPI_BUS_RADIO 1
|
||||
#define SPI_BUS_EXT 2
|
||||
|
||||
#define SPIDEV_CS_MS5611 GPIOD, 7
|
||||
#define SPIDEV_CS_EXT_MS5611 GPIOC, 14
|
||||
#define SPIDEV_CS_MPU GPIOC, 2
|
||||
#define SPIDEV_CS_HMC GPIOC, 1
|
||||
#define SPIDEV_CS_EXT_MPU GPIOE, 4
|
||||
#define SPIDEV_CS_LSM9DS0_G GPIOC, 13 // same cs for both internal and external
|
||||
#define SPIDEV_CS_LSM9DS0_AM GPIOC, 15 // same cs for both internal and external
|
||||
#define SPIDEV_CS_RAMTRON GPIOD, 10
|
||||
#define SPIDEV_CS_RADIO GPIOD, 10
|
||||
#define SPIDEV_CS_FLOW GPIOE, 4
|
||||
#define SPIDEV_CS_EXT0 GPIOE, 4
|
||||
|
||||
// these device numbers are chosen to match those used when running NuttX. That prevent
|
||||
// users having to recal when updating to ChibiOS
|
||||
#define SPIDEV_LSM9DS0_G 1
|
||||
#define SPIDEV_LSM9DS0_AM 2
|
||||
#define SPIDEV_BARO 3
|
||||
#define SPIDEV_MPU 4
|
||||
#define SPIDEV_HMC 5
|
||||
#define SPIDEV_EXT_MPU 1
|
||||
#define SPIDEV_EXT_BARO 2
|
||||
#define SPIDEV_EXT_LSM9DS0_AM 3
|
||||
#define SPIDEV_EXT_LSM9DS0_G 4
|
||||
#define SPIDEV_EXT0 5
|
||||
|
||||
#define SPIDEV_RAMTROM 10
|
||||
#define SPIDEV_CYRF 11
|
||||
|
||||
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV4
|
||||
#define SPI_BUS_SENSORS 0
|
||||
#define SPI_BUS_RAMTRON 1
|
||||
#define SPI_BUS_BARO 1
|
||||
|
||||
#define SPIDEV_CS_MPU GPIOC, 2
|
||||
#define SPIDEV_CS_ICM GPIOC, 15
|
||||
#define SPIDEV_CS_BARO GPIOD, 7
|
||||
#define SPIDEV_CS_RAMTRON GPIOD, 10
|
||||
#define SPIDEV_CS_MAG GPIOE, 15
|
||||
|
||||
// these device numbers are chosen to match those used when running NuttX. That prevent
|
||||
// users having to recal when updating to ChibiOS
|
||||
#define SPIDEV_BARO 3
|
||||
#define SPIDEV_MPU 4
|
||||
#define SPIDEV_MAG 5
|
||||
#define SPIDEV_ICM 6
|
||||
#define SPIDEV_RAMTROM 10
|
||||
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2
|
||||
#define SPI_BUS_SENSORS 2
|
||||
#define SPI_BUS_EXT 1
|
||||
#define SPI_BUS_RAMTRON 0
|
||||
|
||||
#define SPIDEV_CS_GYRO GPIOB, 2
|
||||
#define SPIDEV_CS_BARO GPIOC, 15
|
||||
#define SPIDEV_CS_AM GPIOD, 11
|
||||
#define SPIDEV_CS_MPU GPIOE, 3
|
||||
#define SPIDEV_CS_RAMTRON GPIOE, 12
|
||||
#define SPIDEV_CS_RADIO GPIOE, 15
|
||||
|
||||
#define SPIDEV_BARO 1
|
||||
#define SPIDEV_MPU 2
|
||||
#define SPIDEV_GYRO 3
|
||||
#define SPIDEV_AM 4
|
||||
#define SPIDEV_RADIO 5
|
||||
#define SPIDEV_RAMTROM 6
|
||||
|
||||
#endif // CONFIG_HAL_BOARD_SUBTYPE
|
||||
|
||||
// SPI mode numbers
|
||||
#define SPIDEV_MODE0 0
|
||||
#define SPIDEV_MODE1 SPI_CR1_CPHA
|
||||
@ -125,49 +40,12 @@ static const struct SPIDriverInfo {
|
||||
uint8_t busid; // used for device IDs in parameters
|
||||
uint8_t dma_channel_rx;
|
||||
uint8_t dma_channel_tx;
|
||||
} spi_devices[] = { HAL_SPI_DEVICE_LIST };
|
||||
} spi_devices[] = { HAL_SPI_BUS_LIST };
|
||||
|
||||
#define MHZ (1000U*1000U)
|
||||
#define KHZ (1000U)
|
||||
SPIDesc SPIDeviceManager::device_table[] = {
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
|
||||
SPIDesc("cypress", SPI_BUS_RADIO, SPIDEV_RADIO, SPIDEV_CS_RADIO, SPIDEV_MODE0, 2*MHZ, 2*MHZ),
|
||||
SPIDesc("pixartflow", SPI_BUS_FLOW, SPIDEV_FLOW, SPIDEV_CS_FLOW, SPIDEV_MODE3, 2*MHZ, 2*MHZ),
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV3
|
||||
SPIDesc("ms5611", SPI_BUS_SENSORS, SPIDEV_BARO, SPIDEV_CS_MS5611, SPIDEV_MODE3, 20*MHZ, 20*MHZ),
|
||||
SPIDesc("ms5611_ext", SPI_BUS_EXT, SPIDEV_EXT_BARO, SPIDEV_CS_EXT_MS5611, SPIDEV_MODE3, 20*MHZ, 20*MHZ),
|
||||
SPIDesc("mpu6000", SPI_BUS_SENSORS, SPIDEV_MPU, SPIDEV_CS_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ ),
|
||||
SPIDesc("mpu9250", SPI_BUS_SENSORS, SPIDEV_MPU, SPIDEV_CS_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ ),
|
||||
SPIDesc("mpu9250_ext", SPI_BUS_EXT, SPIDEV_EXT_MPU, SPIDEV_CS_EXT_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ ),
|
||||
SPIDesc("hmc5843", SPI_BUS_SENSORS, SPIDEV_HMC, SPIDEV_CS_HMC, SPIDEV_MODE3, 11*MHZ, 11*MHZ ),
|
||||
SPIDesc("lsm9ds0_g", SPI_BUS_SENSORS, SPIDEV_LSM9DS0_G, SPIDEV_CS_LSM9DS0_G, SPIDEV_MODE3, 11*MHZ, 11*MHZ ),
|
||||
SPIDesc("lsm9ds0_am", SPI_BUS_SENSORS, SPIDEV_LSM9DS0_AM, SPIDEV_CS_LSM9DS0_AM, SPIDEV_MODE3, 11*MHZ, 11*MHZ ),
|
||||
SPIDesc("lsm9ds0_ext_g", SPI_BUS_EXT, SPIDEV_EXT_LSM9DS0_G, SPIDEV_CS_LSM9DS0_G, SPIDEV_MODE3, 11*MHZ, 11*MHZ ),
|
||||
SPIDesc("lsm9ds0_ext_am", SPI_BUS_EXT, SPIDEV_EXT_LSM9DS0_AM,SPIDEV_CS_LSM9DS0_AM, SPIDEV_MODE3, 11*MHZ, 11*MHZ ),
|
||||
SPIDesc("ramtron", SPI_BUS_RAMTRON, SPIDEV_RAMTROM, SPIDEV_CS_RAMTRON, SPIDEV_MODE3, 8*MHZ, 8*MHZ ),
|
||||
SPIDesc("cypress", SPI_BUS_RADIO, SPIDEV_CYRF, SPIDEV_CS_RADIO, SPIDEV_MODE0, 2*MHZ, 2*MHZ),
|
||||
SPIDesc("external0m0", SPI_BUS_EXT, SPIDEV_EXT0, SPIDEV_CS_EXT0, SPIDEV_MODE0, 2*MHZ, 2*MHZ),
|
||||
SPIDesc("external0m1", SPI_BUS_EXT, SPIDEV_EXT0, SPIDEV_CS_EXT0, SPIDEV_MODE1, 2*MHZ, 2*MHZ),
|
||||
SPIDesc("external0m2", SPI_BUS_EXT, SPIDEV_EXT0, SPIDEV_CS_EXT0, SPIDEV_MODE2, 2*MHZ, 2*MHZ),
|
||||
SPIDesc("external0m3", SPI_BUS_EXT, SPIDEV_EXT0, SPIDEV_CS_EXT0, SPIDEV_MODE3, 2*MHZ, 2*MHZ),
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV4
|
||||
SPIDesc("ms5611_int", SPI_BUS_BARO, SPIDEV_BARO, SPIDEV_CS_BARO, SPIDEV_MODE3, 20*MHZ, 20*MHZ),
|
||||
SPIDesc("mpu9250", SPI_BUS_SENSORS, SPIDEV_MPU, SPIDEV_CS_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ ),
|
||||
SPIDesc("icm20608", SPI_BUS_SENSORS, SPIDEV_ICM, SPIDEV_CS_ICM, SPIDEV_MODE3, 1*MHZ, 8*MHZ ),
|
||||
SPIDesc("hmc5843", SPI_BUS_SENSORS, SPIDEV_MAG, SPIDEV_CS_MAG, SPIDEV_MODE3, 11*MHZ, 11*MHZ ),
|
||||
SPIDesc("ramtron", SPI_BUS_RAMTRON, SPIDEV_RAMTROM, SPIDEV_CS_RAMTRON, SPIDEV_MODE3, 8*MHZ, 8*MHZ ),
|
||||
SPIDesc("lis3mdl", SPI_BUS_SENSORS, SPIDEV_MAG, SPIDEV_CS_MAG, SPIDEV_MODE3, 500*KHZ, 500*KHZ),
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2
|
||||
SPIDesc("ms5611", SPI_BUS_SENSORS, SPIDEV_BARO, SPIDEV_CS_BARO, SPIDEV_MODE3, 2*MHZ, 2*MHZ),
|
||||
SPIDesc("mpu6500", SPI_BUS_SENSORS, SPIDEV_MPU, SPIDEV_CS_MPU, SPIDEV_MODE3,500*KHZ, 2*MHZ),
|
||||
SPIDesc("lsm9ds0_am", SPI_BUS_SENSORS, SPIDEV_AM, SPIDEV_CS_AM, SPIDEV_MODE3, 11*MHZ, 11*MHZ),
|
||||
SPIDesc("lsm9ds0_g", SPI_BUS_SENSORS, SPIDEV_GYRO, SPIDEV_CS_GYRO, SPIDEV_MODE3, 11*MHZ, 11*MHZ),
|
||||
SPIDesc("ramtron", SPI_BUS_RAMTRON, SPIDEV_RAMTROM, SPIDEV_CS_RAMTRON, SPIDEV_MODE3, 8*MHZ, 8*MHZ),
|
||||
SPIDesc("ramtron0", 0, SPIDEV_RAMTROM, SPIDEV_CS_RAMTRON, SPIDEV_MODE3, 8*MHZ, 8*MHZ),
|
||||
SPIDesc("ramtron1", 1, SPIDEV_RAMTROM, SPIDEV_CS_RAMTRON, SPIDEV_MODE3, 8*MHZ, 8*MHZ),
|
||||
SPIDesc("ramtron2", 2, SPIDEV_RAMTROM, SPIDEV_CS_RAMTRON, SPIDEV_MODE3, 8*MHZ, 8*MHZ),
|
||||
#endif
|
||||
};
|
||||
// device list comes from hwdef.dat
|
||||
SPIDesc SPIDeviceManager::device_table[] = { HAL_SPI_DEVICE_LIST };
|
||||
|
||||
SPIBus::SPIBus(uint8_t _bus) :
|
||||
DeviceBus(APM_SPI_PRIORITY),
|
||||
@ -379,8 +257,8 @@ bool SPIDevice::set_chip_select(bool set)
|
||||
bus.dma_handle->lock();
|
||||
spiAcquireBus(spi_devices[device_desc.bus].driver); /* Acquire ownership of the bus. */
|
||||
bus.spicfg.end_cb = nullptr;
|
||||
bus.spicfg.ssport = device_desc.port;
|
||||
bus.spicfg.sspad = device_desc.pin;
|
||||
bus.spicfg.ssport = PAL_PORT(device_desc.pal_line);
|
||||
bus.spicfg.sspad = PAL_PAD(device_desc.pal_line);
|
||||
bus.spicfg.cr1 = (uint16_t)(freq_flag | device_desc.mode);
|
||||
bus.spicfg.cr2 = 0;
|
||||
spiStart(spi_devices[device_desc.bus].driver, &bus.spicfg); /* Setup transfer parameters. */
|
||||
|
@ -37,10 +37,10 @@ public:
|
||||
|
||||
struct SPIDesc {
|
||||
SPIDesc(const char *_name, uint8_t _bus,
|
||||
uint8_t _device, ioportid_t _port, uint8_t _pin,
|
||||
uint8_t _device, ioline_t _pal_line,
|
||||
uint16_t _mode, uint32_t _lowspeed, uint32_t _highspeed)
|
||||
: name(_name), bus(_bus), device(_device),
|
||||
port(_port), pin(_pin), mode(_mode),
|
||||
pal_line(_pal_line), mode(_mode),
|
||||
lowspeed(_lowspeed), highspeed(_highspeed)
|
||||
{
|
||||
}
|
||||
@ -48,8 +48,7 @@ struct SPIDesc {
|
||||
const char *name;
|
||||
uint8_t bus;
|
||||
uint8_t device;
|
||||
ioportid_t port;
|
||||
uint8_t pin;
|
||||
ioline_t pal_line;
|
||||
uint16_t mode;
|
||||
uint32_t lowspeed;
|
||||
uint32_t highspeed;
|
||||
|
@ -121,3 +121,24 @@ PE12 FMU_LED_AMBER OUTPUT
|
||||
PE13 TIM1_CH3 TIM1
|
||||
PE14 TIM1_CH4 TIM1
|
||||
PE15 VDD_5V_PERIPH_OC INPUT
|
||||
|
||||
# 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
|
||||
# when moving to ChibiOS
|
||||
SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ
|
||||
SPIDEV ms5611_ext SPI4 DEVID2 BARO_EXT_CS MODE3 20*MHZ 20*MHZ
|
||||
SPIDEV mpu6000 SPI1 DEVID4 MPU_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV mpu9250 SPI1 DEVID4 MPU_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV mpu9250_ext SPI4 DEVID1 MPU_EXT_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV hmc5843 SPI1 DEVID5 MAG_CS MODE3 11*MHZ 11*MHZ
|
||||
SPIDEV lsm9ds0_g SPI1 DEVID4 GYRO_EXT_CS MODE3 11*MHZ 11*MHZ
|
||||
SPIDEV lsm9ds0_am SPI1 DEVID3 ACCEL_EXT_CS MODE3 11*MHZ 11*MHZ
|
||||
SPIDEV lsm9ds0_ext_g SPI4 DEVID4 GYRO_EXT_CS MODE3 11*MHZ 11*MHZ
|
||||
SPIDEV lsm9ds0_ext_am SPI4 DEVID3 ACCEL_EXT_CS MODE3 11*MHZ 11*MHZ
|
||||
SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
SPIDEV cypress SPI4 DEVID11 FRAM_CS MODE0 2*MHZ 2*MHZ
|
||||
SPIDEV external0m0 SPI4 DEVID5 MPU_EXT_CS MODE0 2*MHZ 2*MHZ
|
||||
SPIDEV external0m1 SPI4 DEVID5 MPU_EXT_CS MODE1 2*MHZ 2*MHZ
|
||||
SPIDEV external0m2 SPI4 DEVID5 MPU_EXT_CS MODE2 2*MHZ 2*MHZ
|
||||
SPIDEV external0m3 SPI4 DEVID5 MPU_EXT_CS MODE3 2*MHZ 2*MHZ
|
||||
|
||||
|
@ -131,7 +131,17 @@ PE8 UART7_TX UART7
|
||||
PE9 TIM1_CH1 TIM1 # FMU_CH4
|
||||
PE10 8266_CTS OUTPUT HIGH
|
||||
PE11 TIM1_CH2 TIM1 # FMU_CH3
|
||||
PE12 HMC5983_DRDY INPUT
|
||||
PE12 MAG_DRDY INPUT
|
||||
PE13 TIM1_CH3 TIM1 # FMU_CH2
|
||||
PE14 TIM1_CH4 TIM1 # FMU_CH1
|
||||
PE15 HMC5983_CS SPI1 CS
|
||||
PE15 MAG_CS SPI1 CS
|
||||
|
||||
# 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
|
||||
# when moving to ChibiOS
|
||||
SPIDEV ms5611_int SPI2 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ
|
||||
SPIDEV mpu9250 SPI1 DEVID4 MPU9250_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV icm20608 SPI1 DEVID6 20608_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV hmc5843 SPI1 DEVID5 MAG_CS MODE3 11*MHZ 11*MHZ
|
||||
SPIDEV lis3mdl SPI1 DEVID5 MAG_CS MODE3 500*KHZ 500*KHZ
|
||||
SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
|
@ -143,3 +143,11 @@ PE12 FRAM_CS SPI1 CS
|
||||
PE13 TIM1_CH3 TIM1 # FMU_CH3
|
||||
PE14 TIM1_CH4 TIM1 # FMU_CH4
|
||||
PE15 NRF_CS SPI2 CS
|
||||
|
||||
# SPI device table
|
||||
SPIDEV ms5611 SPI4 DEVID1 BARO_CS MODE3 2*MHZ 2*MHZ
|
||||
SPIDEV mpu6500 SPI4 DEVID2 MPU_CS MODE3 500*KHZ 2*MHZ
|
||||
SPIDEV lsm9ds0_am SPI4 DEVID3 ACCEL_MAG_CS MODE3 11*MHZ 11*MHZ
|
||||
SPIDEV lsm9ds0_g SPI4 DEVID4 GYRO_CS MODE3 11*MHZ 11*MHZ
|
||||
SPIDEV ramtron SPI1 DEVID5 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
SPIDEV radio SPI2 DEVID6 NRF_CS MODE3 2*MHZ 2*MHZ
|
||||
|
@ -33,17 +33,35 @@ bytype = {}
|
||||
# list of configs by label
|
||||
bylabel = {}
|
||||
|
||||
# list of SPI devices
|
||||
spidev = []
|
||||
|
||||
# SPI bus list
|
||||
spi_list = []
|
||||
|
||||
mcu_type = None
|
||||
|
||||
def is_int(str):
|
||||
'''check if a string is an integer'''
|
||||
try:
|
||||
int(str)
|
||||
except Exception:
|
||||
return False
|
||||
return True
|
||||
|
||||
def error(str):
|
||||
'''show an error and exit'''
|
||||
print(str)
|
||||
sys.exit(1)
|
||||
|
||||
def get_alt_function(mcu, pin, function):
|
||||
'''return alternative function number for a pin'''
|
||||
import importlib
|
||||
try:
|
||||
lib = importlib.import_module(mcu)
|
||||
alt_map = lib.AltFunction_map
|
||||
lib = importlib.import_module(mcu)
|
||||
alt_map = lib.AltFunction_map
|
||||
except ImportError:
|
||||
print("Unable to find module for MCU %s" % mcu)
|
||||
sys.exit(1)
|
||||
error("Unable to find module for MCU %s" % mcu)
|
||||
|
||||
if function and function.endswith("_RTS") and (function.startswith('USART') or function.startswith('UART')):
|
||||
# we do software RTS
|
||||
@ -54,8 +72,7 @@ def get_alt_function(mcu, pin, function):
|
||||
if function.startswith(l):
|
||||
s = pin+":"+function
|
||||
if not s in alt_map:
|
||||
print("Unknown pin function %s for MCU %s" % (s, mcu))
|
||||
sys.exit(1)
|
||||
error("Unknown pin function %s for MCU %s" % (s, mcu))
|
||||
return alt_map[s]
|
||||
return None
|
||||
|
||||
@ -66,12 +83,10 @@ def get_ADC1_chan(mcu, pin):
|
||||
lib = importlib.import_module(mcu)
|
||||
ADC1_map = lib.ADC1_map
|
||||
except ImportError:
|
||||
print("Unable to find ADC1_Map for MCU %s" % mcu)
|
||||
sys.exit(1)
|
||||
error("Unable to find ADC1_Map for MCU %s" % mcu)
|
||||
|
||||
if not pin in ADC1_map:
|
||||
print("Unable to find ADC1 channel for pin %s" % pin)
|
||||
sys.exit(1)
|
||||
error("Unable to find ADC1 channel for pin %s" % pin)
|
||||
return ADC1_map[pin]
|
||||
|
||||
class generic_pin(object):
|
||||
@ -193,12 +208,10 @@ def get_config(name, column=0, required=True, default=None):
|
||||
'''get a value from config dictionary'''
|
||||
if not name in config:
|
||||
if required and default is None:
|
||||
print("Error: missing required value %s in hwdef.dat" % name)
|
||||
sys.exit(1)
|
||||
error("Error: missing required value %s in hwdef.dat" % name)
|
||||
return default
|
||||
if len(config[name]) < column+1:
|
||||
print("Error: missing required value %s in hwdef.dat (column %u)" % (name, column))
|
||||
sys.exit(1)
|
||||
error("Error: missing required value %s in hwdef.dat (column %u)" % (name, column))
|
||||
return config[name][column]
|
||||
|
||||
def process_line(line):
|
||||
@ -231,6 +244,8 @@ def process_line(line):
|
||||
af = get_alt_function(mcu_type, a[0], label)
|
||||
if af is not None:
|
||||
p.af = af
|
||||
if a[0] == 'SPIDEV':
|
||||
spidev.append(a[1:])
|
||||
|
||||
|
||||
def write_mcu_config(f):
|
||||
@ -271,16 +286,48 @@ def write_I2C_config(f):
|
||||
devlist = []
|
||||
for dev in i2c_list:
|
||||
if not dev.startswith('I2C') or dev[3] not in "1234":
|
||||
print("Bad I2C_ORDER element %s" % dev)
|
||||
sys.exit(1)
|
||||
error("Bad I2C_ORDER element %s" % dev)
|
||||
n = int(dev[3:])
|
||||
devlist.append('HAL_I2C%u_CONFIG' % n)
|
||||
f.write('#define HAL_I2C%u_CONFIG { &I2CD%u, STM32_I2C_I2C%u_TX_DMA_STREAM, STM32_I2C_I2C%u_RX_DMA_STREAM }\n' % (n, n, n, n))
|
||||
f.write('#define HAL_I2C_DEVICE_LIST %s\n\n' % ','.join(devlist))
|
||||
|
||||
def write_SPI_table(f):
|
||||
'''write SPI device table'''
|
||||
f.write('\n// SPI device table\n')
|
||||
devlist = []
|
||||
for dev in spidev:
|
||||
if len(dev) != 7:
|
||||
print("Badly formed SPIDEV line %s" % dev)
|
||||
name = '"' + dev[0] + '"'
|
||||
bus = dev[1]
|
||||
devid = dev[2]
|
||||
cs = dev[3]
|
||||
mode = dev[4]
|
||||
lowspeed = dev[5]
|
||||
highspeed = dev[6]
|
||||
if not bus.startswith('SPI') or not bus in spi_list:
|
||||
error("Bad SPI bus in SPIDEV line %s" % dev)
|
||||
if not devid.startswith('DEVID') or not is_int(devid[5:]):
|
||||
error("Bad DEVID in SPIDEV line %s" % dev)
|
||||
if not cs in bylabel:
|
||||
error("Bad CS pin in SPIDEV line %s" % dev)
|
||||
if not mode in ['MODE0', 'MODE1', 'MODE2', 'MODE3']:
|
||||
error("Bad MODE in SPIDEV line %s" % dev)
|
||||
if not lowspeed.endswith('*MHZ') and not lowspeed.endswith('*KHZ'):
|
||||
error("Bad lowspeed value %s in SPIDEV line %s" % (lowspeed, dev))
|
||||
if not highspeed.endswith('*MHZ') and not highspeed.endswith('*KHZ'):
|
||||
error("Bad highspeed value %s in SPIDEV line %s" % (highspeed, dev))
|
||||
cs_pin = bylabel[cs]
|
||||
pal_line = 'PAL_LINE(GPIO%s,%uU)' % (cs_pin.port, cs_pin.pin)
|
||||
devidx = len(devlist)
|
||||
f.write('#define HAL_SPI_DEVICE%-2u SPIDesc(%-17s, %2u, %2u, %-19s, SPIDEV_%s, %7s, %7s)\n' % (devidx, name, spi_list.index(bus), int(devid[5:]), pal_line, mode, lowspeed, highspeed))
|
||||
devlist.append('HAL_SPI_DEVICE%u' % devidx)
|
||||
f.write('#define HAL_SPI_DEVICE_LIST %s\n\n' % ','.join(devlist))
|
||||
|
||||
def write_SPI_config(f):
|
||||
'''write SPI config defines'''
|
||||
spi_list = []
|
||||
global spi_list
|
||||
for t in bytype.keys():
|
||||
if t.startswith('SPI'):
|
||||
spi_list.append(t)
|
||||
@ -290,7 +337,8 @@ def write_SPI_config(f):
|
||||
n = int(dev[3:])
|
||||
devlist.append('HAL_SPI%u_CONFIG' % n)
|
||||
f.write('#define HAL_SPI%u_CONFIG { &SPID%u, %u, STM32_SPI_SPI%u_TX_DMA_STREAM, STM32_SPI_SPI%u_RX_DMA_STREAM }\n' % (n, n, n, n, n))
|
||||
f.write('#define HAL_SPI_DEVICE_LIST %s\n\n' % ','.join(devlist))
|
||||
f.write('#define HAL_SPI_BUS_LIST %s\n\n' % ','.join(devlist))
|
||||
write_SPI_table(f)
|
||||
|
||||
def write_UART_config(f):
|
||||
'''write UART config defines'''
|
||||
@ -314,8 +362,7 @@ def write_UART_config(f):
|
||||
elif dev.startswith('OTG'):
|
||||
n = int(dev[3:])
|
||||
else:
|
||||
print("Invalid element %s in UART_ORDER" % dev)
|
||||
sys.exit(1)
|
||||
error("Invalid element %s in UART_ORDER" % dev)
|
||||
devlist.append('HAL_%s_CONFIG' % dev)
|
||||
if dev + "_RTS" in bylabel:
|
||||
p = bylabel[dev + '_RTS']
|
||||
@ -337,8 +384,7 @@ def write_I2C_config(f):
|
||||
devlist = []
|
||||
for dev in i2c_list:
|
||||
if not dev.startswith('I2C') or dev[3] not in "1234":
|
||||
print("Bad I2C_ORDER element %s" % dev)
|
||||
sys.exit(1)
|
||||
error("Bad I2C_ORDER element %s" % dev)
|
||||
n = int(dev[3:])
|
||||
devlist.append('HAL_I2C%u_CONFIG' % n)
|
||||
f.write('#define HAL_I2C%u_CONFIG { &I2CD%u, STM32_I2C_I2C%u_TX_DMA_STREAM, STM32_I2C_I2C%u_RX_DMA_STREAM }\n' % (n, n, n, n))
|
||||
@ -493,8 +539,7 @@ if outdir is None:
|
||||
outdir = '.'
|
||||
|
||||
if not "MCU" in config:
|
||||
print("Missing MCU type in config")
|
||||
sys.exit(1)
|
||||
error("Missing MCU type in config")
|
||||
|
||||
mcu_type = get_config('MCU',1)
|
||||
print("Setup for MCU %s" % mcu_type)
|
||||
|
@ -16,6 +16,12 @@ STM32_VDD 330U
|
||||
STDOUT_SERIAL SD1
|
||||
STDOUT_BAUDRATE 115200
|
||||
|
||||
# order of I2C buses
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER USART1 USART6 USART2
|
||||
|
||||
PC0 MGND INPUT
|
||||
PC1 PWM4_SENSE ADC1
|
||||
PC2 PWM2_SENSE ADC1
|
||||
@ -64,4 +70,9 @@ PC6 TIM3_CH1 TIM3
|
||||
PB15 SPI2_MOSI SPI2
|
||||
PB14 SPI2_MISO SPI2
|
||||
PB13 SPI2_SCK SPI2
|
||||
PB12 OF_CS SPI2 CS
|
||||
PB12 FLOW_CS SPI2 CS
|
||||
|
||||
# SPI Device table
|
||||
SPIDEV cypress SPI1 DEVID1 RADIO_CS MODE0 2*MHZ 2*MHZ
|
||||
SPIDEV pixartflow SPI2 DEVID2 FLOW_CS MODE3 2*MHZ 2*MHZ
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user