Shared altitude control parameters (#13884)
[betaflight.git] / mk / mcu / STM32G4.mk
blob9373d2f05877f6395bffbc502737065a19feb547
2 # G4 Make file include
5 ifeq ($(DEBUG_HARDFAULTS),G4)
6 CFLAGS += -DDEBUG_HARDFAULTS
7 endif
9 #CMSIS
10 CMSIS_DIR := $(ROOT)/lib/main/CMSIS
12 #STDPERIPH
13 STDPERIPH_DIR = $(ROOT)/lib/main/STM32G4/Drivers/STM32G4xx_HAL_Driver
14 STDPERIPH_SRC = \
15 stm32g4xx_hal_adc.c \
16 stm32g4xx_hal_adc_ex.c \
17 stm32g4xx_hal.c \
18 stm32g4xx_hal_cordic.c \
19 stm32g4xx_hal_cortex.c \
20 stm32g4xx_hal_dma.c \
21 stm32g4xx_hal_exti.c \
22 stm32g4xx_hal_fdcan.c \
23 stm32g4xx_hal_flash.c \
24 stm32g4xx_hal_flash_ex.c \
25 stm32g4xx_hal_fmac.c \
26 stm32g4xx_hal_gpio.c \
27 stm32g4xx_hal_i2c.c \
28 stm32g4xx_hal_i2c_ex.c \
29 stm32g4xx_hal_pcd.c \
30 stm32g4xx_hal_pcd_ex.c \
31 stm32g4xx_hal_pwr.c \
32 stm32g4xx_hal_pwr_ex.c \
33 stm32g4xx_hal_rcc.c \
34 stm32g4xx_hal_rcc_ex.c \
35 stm32g4xx_hal_rtc.c \
36 stm32g4xx_hal_rtc_ex.c \
37 stm32g4xx_hal_tim.c \
38 stm32g4xx_hal_tim_ex.c \
39 stm32g4xx_hal_uart.c \
40 stm32g4xx_hal_uart_ex.c \
41 stm32g4xx_ll_dma.c \
42 stm32g4xx_ll_spi.c \
43 stm32g4xx_ll_tim.c \
44 stm32g4xx_ll_usb.c
46 #USB
47 USBCORE_DIR = $(ROOT)/lib/main/STM32G4/Middlewares/ST/STM32_USB_Device_Library/Core
48 USBCORE_SRC = \
49 usbd_core.c \
50 usbd_ctlreq.c \
51 usbd_ioreq.c
53 USBCDC_DIR = $(ROOT)/lib/main/STM32G4/Middlewares/ST/STM32_USB_Device_Library/Class/CDC
54 USBCDC_SRC = usbd_cdc.c
56 USBHID_DIR = $(ROOT)/lib/main/STM32G4/Middlewares/ST/STM32_USB_Device_Library/Class/HID
57 USBHID_SRC = usbd_hid.c
59 USBMSC_DIR = $(ROOT)/lib/main/STM32G4/Middlewares/ST/STM32_USB_Device_Library/Class/MSC
60 USBMSC_SRC = \
61 usbd_msc_bot.c \
62 usbd_msc.c \
63 usbd_msc_data.c \
64 usbd_msc_scsi.c
66 VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src:$(STDPERIPH_DIR)/src
68 DEVICE_STDPERIPH_SRC := \
69 $(STDPERIPH_SRC) \
70 $(USBCORE_SRC) \
71 $(USBCDC_SRC) \
72 $(USBHID_SRC) \
73 $(USBMSC_SRC)
75 #CMSIS
76 VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32G4xx
77 VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
78 CMSIS_SRC :=
79 INCLUDE_DIRS := \
80 $(INCLUDE_DIRS) \
81 $(SRC_DIR)/startup/stm32 \
82 $(STDPERIPH_DIR)/Inc \
83 $(USBCORE_DIR)/Inc \
84 $(USBCDC_DIR)/Inc \
85 $(USBHID_DIR)/Inc \
86 $(USBMSC_DIR)/Inc \
87 $(CMSIS_DIR)/Core/Include \
88 $(ROOT)/lib/main/STM32G4/Drivers/CMSIS/Device/ST/STM32G4xx/Include \
89 $(SRC_DIR)/drivers/mcu/stm32 \
90 $(SRC_DIR)/drivers/mcu/stm32/vcp_hal
92 #Flags
93 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant
95 DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER -DUSE_DMA_RAM -DMAX_MPU_REGIONS=16
97 # G47X_TARGETS includes G47{3,4}{RE,CE,CEU}
99 ifeq ($(TARGET_MCU),STM32G474xx)
100 DEVICE_FLAGS += -DSTM32G474xx
101 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_g474.ld
102 STARTUP_SRC = stm32/startup_stm32g474xx.s
103 MCU_FLASH_SIZE = 512
104 # Override the OPTIMISE_SPEED compiler setting to save flash space on these 512KB targets.
105 # Performance is only slightly affected but around 50 kB of flash are saved.
106 OPTIMISE_SPEED = -O2
107 else
108 $(error Unknown MCU for G4 target)
109 endif
110 DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DSTM32
112 VCP_SRC = \
113 drivers/mcu/stm32/vcp_hal/usbd_desc.c \
114 drivers/mcu/stm32/vcp_hal/usbd_conf_stm32g4xx.c \
115 drivers/mcu/stm32/vcp_hal/usbd_cdc_hid.c \
116 drivers/mcu/stm32/vcp_hal/usbd_cdc_interface.c \
117 drivers/mcu/stm32/serial_usb_vcp.c \
118 drivers/usb_io.c
120 MCU_COMMON_SRC = \
121 drivers/accgyro/accgyro_mpu.c \
122 drivers/bus_i2c_timing.c \
123 drivers/dshot_bitbang_decode.c \
124 drivers/pwm_output_dshot_shared.c \
125 drivers/mcu/stm32/adc_stm32g4xx.c \
126 drivers/mcu/stm32/bus_i2c_hal_init.c \
127 drivers/mcu/stm32/bus_i2c_hal.c \
128 drivers/mcu/stm32/bus_spi_ll.c \
129 drivers/mcu/stm32/debug.c \
130 drivers/mcu/stm32/dma_reqmap_mcu.c \
131 drivers/mcu/stm32/dma_stm32g4xx.c \
132 drivers/mcu/stm32/dshot_bitbang_ll.c \
133 drivers/mcu/stm32/dshot_bitbang.c \
134 drivers/mcu/stm32/exti.c \
135 drivers/mcu/stm32/io_stm32.c \
136 drivers/mcu/stm32/light_ws2811strip_hal.c \
137 drivers/mcu/stm32/memprot_hal.c \
138 drivers/mcu/stm32/memprot_stm32g4xx.c \
139 drivers/mcu/stm32/persistent.c \
140 drivers/mcu/stm32/pwm_output.c \
141 drivers/mcu/stm32/pwm_output_dshot_hal.c \
142 drivers/mcu/stm32/rcc_stm32.c \
143 drivers/mcu/stm32/serial_uart_hal.c \
144 drivers/mcu/stm32/serial_uart_stm32g4xx.c \
145 drivers/mcu/stm32/system_stm32g4xx.c \
146 drivers/mcu/stm32/timer_hal.c \
147 drivers/mcu/stm32/timer_stm32g4xx.c \
148 drivers/mcu/stm32/transponder_ir_io_hal.c \
149 drivers/mcu/stm32/camera_control.c \
150 startup/stm32/system_stm32g4xx.c
152 MCU_EXCLUDES = \
153 drivers/bus_i2c.c
155 # G4's MSC use the same driver layer file with F7
156 MSC_SRC = \
157 drivers/usb_msc_common.c \
158 drivers/mcu/stm32/usb_msc_hal.c \
159 msc/usbd_storage.c \
160 msc/usbd_storage_emfat.c \
161 msc/emfat.c \
162 msc/emfat_file.c \
163 msc/usbd_storage_sdio.c \
164 msc/usbd_storage_sd_spi.c
166 DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
167 DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4