# hw definition file for processing by chibios_pins.py # MCU class and specific type # MCU class and specific type MCU STM32F4xx STM32F427xx # crystal frequency OSCILLATOR_HZ 24000000 # flash size FLASH_SIZE_KB 2048 STM32_ST_USE_TIMER 5 # bootloader starts firmware at 64k FLASH_RESERVE_START_KB 64 # store parameters in pages 2 and 3 define STORAGE_FLASH_PAGE 2 define HAL_STORAGE_SIZE 16384 # board ID for firmware load APJ_BOARD_ID 1402 # setup build for a peripheral firmware env AP_PERIPH 1 define PERIPH_FW TRUE define HAL_BUILD_AP_PERIPH define HAL_SUPPORT_RCOUT_SERIAL 0 # use the app descriptor needed by MissionPlanner for CAN upload env APP_DESCRIPTOR MissionPlanner # disable dual GPS and GPS blending to save flash space define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 define HAL_NO_GCS define HAL_NO_MONITOR_THREAD define HAL_DISABLE_LOOP_DELAY define HAL_USE_RTC FALSE define DISABLE_SERIAL_ESC_COMM TRUE define NO_DATAFLASH TRUE define HAL_NO_RCIN_THREAD define HAL_BARO_ALLOW_INIT_NO_BARO define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE define HAL_DISABLE_ADC_DRIVER FALSE define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.Pixracer_periph" # reserve 256 bytes for comms between app and bootloader RAM_RESERVE_START 256 env DISABLE_SCRIPTING 1 MAIN_STACK 0x2000 PROCESS_STACK 0x6000 # listen for reboot command from uploader.py script # undefine to disable. Use -1 to allow on all ports, otherwise serial number index defined in SERIAL_ORDER starting at 0 define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 # default to all pins low to avoid ESD issues DEFAULTGPIO OUTPUT LOW PULLDOWN # --------- Peripherals ----------- define HAL_PERIPH_ENABLE_ADSB define HAL_PERIPH_ADSB_PORT_DEFAULT 2 define HAL_PERIPH_ENABLE_AIRSPEED define HAL_AIRSPEED_BUS_DEFAULT 0 define AIRSPEED_MAX_SENSORS 1 define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_GPS_PORT_DEFAULT 3 define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_BARO define HAL_PERIPH_ENABLE_BATTERY define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_RANGEFINDER define HAL_PERIPH_RANGEFINDER_PORT_DEFAULT 1 define RANGEFINDER_MAX_INSTANCES 1 define HAL_PERIPH_ENABLE_NOTIFY # --------- LED ----------- # a LED to flash PB1 LED OUTPUT LOW # --------- ANALOG ----------- # analog pins PA2 BATT_VOLTAGE_SENS ADC1 PA3 BATT_CURRENT_SENS ADC1 # define default battery setup define HAL_BATT_VOLT_PIN 2 define HAL_BATT_CURR_PIN 3 define HAL_BATT_VOLT_SCALE 10.1 define HAL_BATT_CURR_SCALE 17.0 #---------------- SERIAL ----------------------------- # order of UARTs # --------------------------------------- # | sr0 | sr1 | sr2 | sr3 | sr4 | sr5 | sr6 # AP Name GPS # --------------------------------------- SERIAL_ORDER OTG1 USART2 USART3 UART4 EMPTY EMPTY UART7 PA9 VBUS INPUT PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 # USART1 is ESP8266 unused # PB6 USART1_TX USART1 # PB7 USART1_RX USART1 # USART2 serial2 GPS1 PD3 USART2_CTS USART2 PD4 USART2_RTS USART2 PD5 USART2_TX USART2 PD6 USART2_RX USART2 # USART3 serial3 telem1 PD8 USART3_TX USART3 NODMA PD9 USART3_RX USART3 PD11 USART3_CTS USART3 PD12 USART3_RTS USART3 # UART4 is GPS2 PA0 UART4_TX UART4 NODMA PA1 UART4_RX UART4 NODMA # UART7 is debug PE7 UART7_RX UART7 NODMA PE8 UART7_TX UART7 NODMA # UART8 serial4 FrSky unused # PE0 UART8_RX UART8 # PE1 UART8_TX UART8 # SWD debugging PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD #---------------- I2C ----------------------------- # only one I2C bus in normal config PB8 I2C1_SCL I2C1 PB9 I2C1_SDA I2C1 define HAL_USE_I2C TRUE define STM32_I2C_USE_I2C1 TRUE define HAL_I2C_CLEAR_ON_TIMEOUT 0 define HAL_I2C_INTERNAL_MASK 0 # only one I2C bus I2C_ORDER I2C1 # also probe all types of external I2C compasses define HAL_PROBE_EXTERNAL_I2C_COMPASSES #------------------- SPI ----------------------------- # spi bus for Sensors PA5 SPI1_SCK SPI1 PA6 SPI1_MISO SPI1 PA7 SPI1_MOSI SPI1 PE12 MAG_DRDY INPUT PE15 MAG_CS CS PB10 SPI2_SCK SPI2 PB14 SPI2_MISO SPI2 PB15 SPI2_MOSI SPI2 PD7 BARO_CS CS # PD10 FRAM_CS 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 2*MHZ 4*MHZ //future use # SPIDEV icm20608 SPI1 DEVID6 20608_CS MODE3 2*MHZ 8*MHZ //future use 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 //unused # one barometer BARO MS56XX SPI:ms5611_int # 2 compasses. R15 has LIS3MDL instead of HMC5843 COMPASS HMC5843 SPI:hmc5843 false ROTATION_PITCH_180 COMPASS LIS3MDL SPI:lis3mdl false ROTATION_NONE # COMPASS AK8963:probe_mpu9250 0 ROTATION_ROLL_180_YAW_9 --------------- ALARM ----------------- # PWM output for buzzer PA15 TIM2_CH1 TIM2 GPIO(77) ALARM --------------- CAN ----------------- # enable CAN support PD0 CAN1_RX CAN1 PD1 CAN1_TX CAN1 define HAL_CAN_DRIVER_DEFAULT 1 # --------PWMS ----------- PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51) PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) define BOARD_PWM_COUNT_DEFAULT 6