diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/defaults.parm new file mode 100644 index 0000000000..8e0cdc620d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/defaults.parm @@ -0,0 +1,7 @@ +#Default Parameters for the mRo Control Zero F7 + +CAN_P1_DRIVER 1 +CAN_SLCAN_CPORT 1 +SERIAL6_PROTOCOL 22 + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef-bl.dat index 2c44887684..e9432613fb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef-bl.dat @@ -1,5 +1,18 @@ -# hw definition file for processing by chibios_hwdef.py -# for F777 bootloader +########################################################################################################################################################### +# mRo Control Zero F7 Flight Controller +# STM32F777IIK6 +# 8x PWM / IO - DMA capable, buffered and level shiftable - 3.3v (default) / 5v Logic +# Front and Rear Connectors: 30pin Molex PicoClasp +# 3x IMUs (BMI088 6DOF, ICM20602 6DOF, ICM20948 9DOF) +# DPS310 Baro, FRAM (256Bb), SDCARD Socket, TC2030 JTAG +# 5x UARTs (2x with hardware flow control), 2x CAN, 1x SPI, 1x I2C +# Onboard 3 color LED and buzzer +# Uncased Weight and Dimensions: +# Weight: 5.3g (.19oz) +# Width: 20mm (.79in) +# Length: 32mm (1.26in) +# M10058 - Initial Release +########################################################################################################################################################### # MCU class and specific type MCU STM32F7xx STM32F777xx @@ -30,13 +43,8 @@ PB3 LED_ACTIVITY2 OUTPUT define HAL_LED_ON 0 - # order of UARTs (and USB) -SERIAL_ORDER OTG1 UART7 - -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). -PE7 UART7_RX UART7 -PE8 UART7_TX UART7 +SERIAL_ORDER OTG1 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef.dat index 5cf6e75fc6..675f9dd086 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef.dat @@ -1,8 +1,29 @@ -# hw definition file for processing by chibios_hwdef.py +########################################################################################################################################################### +# mRo Control Zero F7 Flight Controller +# STM32F777IIK6 +# 8x PWM / IO - DMA capable, buffered and level shiftable - 3.3v (default) / 5v Logic +# Front and Rear Connectors: 30pin Molex PicoClasp +# 3x IMUs (BMI088 6DOF, ICM20602 6DOF, ICM20948 9DOF) +# DPS310 Baro, FRAM (256Bb), SDCARD Socket, TC2030 JTAG +# 5x UARTs (2x with hardware flow control), 2x CAN, 1x SPI, 1x I2C +# Onboard 3 color LED and buzzer +# Uncased Weight and Dimensions: +# Weight: 5.3g (.19oz) +# Width: 20mm (.79in) +# Length: 32mm (1.26in) +# M10058 - Initial Release +########################################################################################################################################################### # MCU class and specific type MCU STM32F7xx STM32F777xx +# ChibiOS system timer +# this is the STM32 timer that ChibiOS will use for the low level +# driver. This must be a 32 bit timer, so Timers 2 or 5 on the STM32F777. +# See hal_st_lld.c in ChibiOS for details + +STM32_ST_USE_TIMER 5 + # board ID for firmware load APJ_BOARD_ID 141 @@ -17,23 +38,18 @@ env OPTIMIZE -O2 # start on 4th sector (1st sector for bootloader, 2 for extra storage) FLASH_RESERVE_START_KB 96 +# use FRAM for storage +define HAL_STORAGE_SIZE 16384 +define HAL_WITH_RAMTRON 1 + # fallback storage in case FRAM is not populated define STORAGE_FLASH_PAGE 1 -# this is the STM32 timer that ChibiOS will use for the low level -# driver. This must be a 32 bit timer, so Timers 2 or 5 on the STM32F777. -# See hal_st_lld.c in ChibiOS for details - -# ChibiOS system timer -STM32_ST_USE_TIMER 5 - -define HAL_STORAGE_SIZE 16384 - # USB setup USB_STRING_MANUFACTURER "mRo" -# RC Input set for Interrupt not DMA -PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW # also USART6_RX for serial RC +# RC Input set for Interrupt not DMA also USART6_RX for serial RC +PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW # Control of Spektrum power pin PE4 SPEKTRUM_PWR OUTPUT LOW GPIO(70) @@ -52,21 +68,15 @@ I2C_ORDER I2C1 # this board only has a single I2C bus so make it external define HAL_I2C_INTERNAL_MASK 0 -# OEM Only -# I2C_ORDER I2C1, I2C2, I2C3 - # order of UARTs (and USB) # UART4 GPS -# USART2 FC -# USART3 FC +# USART2 Telem 1 (Flow Control) +# USART3 Telem 2 (Flow Control) # UART8 FRSKY Telem -# USART6 FC -# UART7 DEBUG +# USART6 RC input (Only RX pin is connected) +# UART7 Additional UART -SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART6 UART7 OTG2 - -# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers -define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2 # Another USART, this one for telem1. This one has RTS and CTS lines. # USART2 telem1 @@ -86,11 +96,7 @@ PD12 USART3_RTS USART3 PA0 UART4_TX UART4 PA1 UART4_RX UART4 NODMA -# USART6 Spare or can be configured as SPI6 -PG14 USART6_TX USART6 NODMA -PG9 USART6_RX USART6 NODMA - -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). Debug Console +# UART7 Spare or Debug Console PE7 UART7_RX UART7 NODMA PE8 UART7_TX UART7 NODMA @@ -125,6 +131,14 @@ PF7 SPI5_SCK SPI5 PF8 SPI5_MISO SPI5 PF9 SPI5_MOSI SPI5 +# GPIOs +# This defines general purpose outputs, mapped to GPIO +# numbers 1 thru 4 for users. +PG9 EXTERN_GPIO1 GPIO(1) +PG13 EXTERN_GPIO2 GPIO(2) +PG12 EXTERN_GPIO3 GPIO(3) +PG14 EXTERN_GPIO4 GPIO(4) + # This is the pin that senses USB being connected. It is an input pin # setup as OPENDRAIN. PA9 VBUS INPUT OPENDRAIN @@ -148,14 +162,6 @@ PA15 TIM2_CH1 TIM2 GPIO(77) ALARM PB8 I2C1_SCL I2C1 PB9 I2C1_SDA I2C1 -# the 2nd I2C bus, OEM Only -# PB10 I2C2_SCL I2C2 -# PB11 I2C2_SDA I2C2 - -# the 3nd I2C bus, OEM Only -# PB6 I2C4_SCL I2C4 -# PB7 I2C4_SDA I2C4 - # Now setup the pins for the microSD card, if available. PC8 SDMMC_D0 SDMMC1 PC9 SDMMC_D1 SDMMC1 @@ -168,8 +174,6 @@ PD2 SDMMC_CMD SDMMC1 # match the SPI device table later in this file. PC2 ICM_20602_CS CS PD7 BARO_CS CS -# The CS pin for FRAM (ramtron). This one is marked as using -# SPEED_VERYLOW, which matches the HAL_PX4 setup. PD10 FRAM_CS CS SPEED_VERYLOW NODMA PE15 ICM_20948_CS CS PF10 BMI088_GYRO_CS CS @@ -181,10 +185,6 @@ PD1 CAN1_TX CAN1 PF5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(72) -# This defines the pins for the 2nd CAN interface, OEM Only. -# PB6 CAN2_TX CAN2 -# PB4 CAN2_RX CAN2 - # Now we start defining some PWM pins. We also map these pins to GPIO # values, so users can set BRD_PWM_COUNT to choose how many of the PWM # outputs on the primary MCU are setup as PWM and how many as @@ -217,10 +217,10 @@ PB5 VDD_BRICK_nVALID INPUT PULLUP SPIDEV dps310 SPI2 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV bmi088_g SPI5 DEVID1 BMI088_GYRO_CS MODE3 5*MHZ 5*MHZ +SPIDEV bmi088_a SPI5 DEVID2 BMI088_ACCEL_CS MODE3 5*MHZ 5*MHZ +SPIDEV icm20608 SPI1 DEVID2 ICM_20602_CS MODE3 2*MHZ 4*MHZ SPIDEV icm20948 SPI1 DEVID1 ICM_20948_CS MODE3 2*MHZ 4*MHZ -SPIDEV icm20608 SPI1 DEVID2 ICM_20602_CS MODE3 2*MHZ 8*MHZ -SPIDEV bmi088_g SPI5 DEVID1 BMI088_GYRO_CS MODE3 10*MHZ 10*MHZ -SPIDEV bmi088_a SPI5 DEVID2 BMI088_ACCEL_CS MODE3 10*MHZ 10*MHZ # Now some defines for logging and terrain data files. define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" @@ -229,9 +229,6 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" # allow to have have a dedicated safety switch pin define HAL_HAVE_SAFETY_SWITCH 1 -# Enable RAMTROM parameter storage. -define HAL_WITH_RAMTRON 1 - # Enable FAT filesystem support (needs a microSD defined via SDMMC). define HAL_OS_FATFS_IO 1 @@ -258,13 +255,13 @@ define HAL_GPIO_B_LED_PIN 1 define HAL_GPIO_C_LED_PIN 2 DMA_PRIORITY SDMMC* -#DMA_NOSHARE SPI1* * -#DMA_NOSHARE SPI5* * # 3 IMUs -IMU Invensensev2 SPI:icm20948 ROTATION_ROLL_180_YAW_90 -IMU Invensense SPI:icm20608 ROTATION_ROLL_180_YAW_90 IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_NONE +IMU Invensense SPI:icm20608 ROTATION_ROLL_180_YAW_90 +IMU Invensensev2 SPI:icm20948 ROTATION_ROLL_180_YAW_90 + +define HAL_DEFAULT_INS_FAST_SAMPLE 7 # 1 baro BARO DPS280 SPI:dps310