7 $(addprefix pg
/,$(notdir $(wildcard $(SRC_DIR
)/pg
/*.c
))) \
8 $(addprefix common
/,$(notdir $(wildcard $(SRC_DIR
)/common
/*.c
))) \
9 $(addprefix config
/,$(notdir $(wildcard $(SRC_DIR
)/config
/*.c
))) \
13 drivers
/buf_writer.c \
15 drivers
/bus_i2c_config.c \
16 drivers
/bus_i2c_busdev.c \
17 drivers
/bus_i2c_soft.c \
19 drivers
/bus_spi_config.c \
20 drivers
/bus_spi_pinconfig.c \
23 drivers
/dma_reqmap.c \
32 drivers
/serial_pinconfig.c \
33 drivers
/serial_uart.c \
34 drivers
/serial_uart_pinconfig.c \
35 drivers
/sound_beeper.c \
36 drivers
/stack_check.c \
38 drivers
/timer_common.c \
40 drivers
/transponder_ir_arcitimer.c \
41 drivers
/transponder_ir_ilap.c \
42 drivers
/transponder_ir_erlt.c \
53 io
/smartaudio_protocol.c \
54 io
/statusindicator.c \
62 scheduler
/scheduler.c \
63 sensors
/adcinternal.c \
67 target
/config_helper.c \
69 fc/controlrate_profile.c \
70 drivers
/camera_control.c \
71 drivers
/accgyro
/gyro_sync.c \
72 drivers
/pwm_esc_detect.c \
73 drivers
/pwm_output.c \
75 drivers
/rx
/rx_xn297.c \
77 drivers
/serial_softserial.c \
86 flight
/gyroanalyse.c \
89 flight
/mixer_tricopter.c \
93 flight
/servos_tricopter.c \
95 io
/serial_4way_avrootloader.c \
96 io
/serial_4way_stk500v2.c \
108 io
/spektrum_vtx_control.c \
114 sensors
/acceleration.c \
115 sensors
/boardalignment.c \
118 sensors
/initialisation.c \
119 blackbox
/blackbox.c \
120 blackbox
/blackbox_encoding.c \
121 blackbox
/blackbox_io.c \
123 cms
/cms_menu_blackbox.c \
124 cms
/cms_menu_builtin.c \
125 cms
/cms_menu_failsafe.c \
126 cms
/cms_menu_gps_rescue.c\
128 cms
/cms_menu_ledstrip.c \
129 cms
/cms_menu_misc.c \
131 cms
/cms_menu_power.c \
132 cms
/cms_menu_saveexit.c \
133 cms
/cms_menu_vtx_rtc6705.c \
134 cms
/cms_menu_vtx_smartaudio.c \
135 cms
/cms_menu_vtx_tramp.c \
136 drivers
/display_ug2864hsweg01.c \
137 drivers
/light_ws2811strip.c \
138 drivers
/rangefinder
/rangefinder_hcsr04.c \
139 drivers
/rangefinder
/rangefinder_lidartf.c \
140 drivers
/serial_escserial.c \
141 drivers
/vtx_common.c \
142 drivers
/vtx_table.c \
144 io
/displayport_max7456.c \
145 io
/displayport_msp.c \
146 io
/displayport_oled.c \
147 io
/displayport_srxl.c \
148 io
/displayport_crsf.c \
149 io
/displayport_hott.c \
157 sensors
/barometer.c \
158 sensors
/rangefinder.c \
159 telemetry
/telemetry.c \
162 telemetry
/frsky_hub.c \
164 telemetry
/jetiexbus.c \
165 telemetry
/smartport.c \
167 telemetry
/mavlink.c \
168 telemetry
/msp_shared.c \
170 telemetry
/ibus_shared.c \
171 sensors
/esc_sensor.c \
175 io
/vtx_smartaudio.c \
179 COMMON_DEVICE_SRC
= \
181 $(DEVICE_STDPERIPH_SRC
)
183 COMMON_SRC
:= $(COMMON_SRC
) $(COMMON_DEVICE_SRC
)
185 ifeq ($(SIMULATOR_BUILD
),yes
)
186 TARGET_FLAGS
:= -DSIMULATOR_BUILD
$(TARGET_FLAGS
)
189 SPEED_OPTIMISED_SRC
:= ""
190 SIZE_OPTIMISED_SRC
:= ""
192 ifneq ($(TARGET
),$(filter $(TARGET
),$(F1_TARGETS
)))
193 SPEED_OPTIMISED_SRC
:= $(SPEED_OPTIMISED_SRC
) \
197 common
/typeconversion.c \
198 drivers
/accgyro
/accgyro_fake.c \
199 drivers
/accgyro
/accgyro_mpu.c \
200 drivers
/accgyro
/accgyro_mpu3050.c \
201 drivers
/accgyro
/accgyro_mpu6050.c \
202 drivers
/accgyro
/accgyro_mpu6500.c \
203 drivers
/accgyro
/accgyro_spi_bmi160.c \
204 drivers
/accgyro
/accgyro_spi_icm20689.c \
205 drivers
/accgyro
/accgyro_spi_mpu6000.c \
206 drivers
/accgyro
/accgyro_spi_mpu6500.c \
207 drivers
/accgyro
/accgyro_spi_mpu9250.c \
208 drivers
/accgyro_legacy
/accgyro_adxl345.c \
209 drivers
/accgyro_legacy
/accgyro_bma280.c \
210 drivers
/accgyro_legacy
/accgyro_l3g4200d.c \
211 drivers
/accgyro_legacy
/accgyro_l3gd20.c \
212 drivers
/accgyro_legacy
/accgyro_lsm303dlhc.c \
213 drivers
/accgyro_legacy
/accgyro_mma845x.c \
215 drivers
/buf_writer.c \
220 drivers
/pwm_output.c \
223 drivers
/serial_uart.c \
230 fc/runtime_config.c \
231 flight
/gyroanalyse.c \
235 flight
/rpm_filter.c \
246 scheduler
/scheduler.c \
247 sensors
/acceleration.c \
248 sensors
/boardalignment.c \
251 $(DEVICE_STDPERIPH_SRC
) \
253 SIZE_OPTIMISED_SRC
:= $(SIZE_OPTIMISED_SRC
) \
254 bus_bst_stm32f30x.c \
257 drivers
/barometer
/barometer_bmp085.c \
258 drivers
/barometer
/barometer_bmp280.c \
259 drivers
/barometer
/barometer_fake.c \
260 drivers
/barometer
/barometer_ms5611.c \
261 drivers
/barometer
/barometer_lps.c \
262 drivers
/barometer
/barometer_qmp6988.c \
263 drivers
/bus_i2c_config.c \
264 drivers
/bus_spi_config.c \
265 drivers
/bus_spi_pinconfig.c \
266 drivers
/compass
/compass_ak8963.c \
267 drivers
/compass
/compass_ak8975.c \
268 drivers
/compass
/compass_fake.c \
269 drivers
/compass
/compass_hmc5883l.c \
270 drivers
/compass
/compass_qmc5883l.c \
271 drivers
/compass
/compass_lis3mdl.c \
272 drivers
/display_ug2864hsweg01.c \
274 drivers
/light_ws2811strip.c \
275 drivers
/light_ws2811strip_hal.c \
276 drivers
/light_ws2811strip_stdperiph.c \
277 drivers
/serial_escserial.c \
278 drivers
/serial_pinconfig.c \
279 drivers
/serial_tcp.c \
280 drivers
/serial_uart_init.c \
281 drivers
/serial_uart_pinconfig.c \
282 drivers
/serial_usb_vcp.c \
283 drivers
/transponder_ir_io_hal.c \
284 drivers
/transponder_ir_io_stdperiph.c \
285 drivers
/vtx_rtc6705_soft_spi.c \
286 drivers
/vtx_rtc6705.c \
287 drivers
/vtx_common.c \
290 config
/config_eeprom.c \
292 config
/config_streamer.c \
297 io
/serial_4way_avrootloader.c \
298 io
/serial_4way_stk500v2.c \
299 io
/transponder_ir.c \
303 cms
/cms_menu_blackbox.c \
304 cms
/cms_menu_builtin.c \
305 cms
/cms_menu_failsafe.c \
306 cms
/cms_menu_gps_rescue.c\
308 cms
/cms_menu_ledstrip.c \
309 cms
/cms_menu_misc.c \
311 cms
/cms_menu_power.c \
312 cms
/cms_menu_saveexit.c \
313 cms
/cms_menu_vtx_rtc6705.c \
314 cms
/cms_menu_vtx_smartaudio.c \
315 cms
/cms_menu_vtx_tramp.c \
319 io
/vtx_smartaudio.c \
322 io
/spektrum_vtx_control.c \
327 # F4 and F7 optimizations
328 ifneq ($(TARGET
),$(filter $(TARGET
),$(F3_TARGETS
)))
329 SPEED_OPTIMISED_SRC
:= $(SPEED_OPTIMISED_SRC
) \
330 drivers
/bus_i2c_hal.c \
331 drivers
/bus_spi_ll.c \
333 drivers
/pwm_output_dshot.c \
334 drivers
/pwm_output_dshot_shared.c \
335 drivers
/pwm_output_dshot_hal.c
339 # check if target.mk supplied
340 SRC
:= $(STARTUP_SRC
) $(MCU_COMMON_SRC
) $(TARGET_SRC
) $(VARIANT_SRC
)
342 # Files that should not be optimized, useful for debugging IMPRECISE cpu faults.
343 # Specify FULL PATH, e.g. "./lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_sdmmc.c"
344 NOT_OPTIMISED_SRC
:= $(NOT_OPTIMISED_SRC
) \
348 INCLUDE_DIRS
+= $(DSP_LIB
)/Include
350 SRC
+= $(DSP_LIB
)/Source
/BasicMathFunctions
/arm_mult_f32.c
351 SRC
+= $(DSP_LIB
)/Source
/TransformFunctions
/arm_rfft_fast_f32.c
352 SRC
+= $(DSP_LIB
)/Source
/TransformFunctions
/arm_cfft_f32.c
353 SRC
+= $(DSP_LIB
)/Source
/TransformFunctions
/arm_rfft_fast_init_f32.c
354 SRC
+= $(DSP_LIB
)/Source
/TransformFunctions
/arm_cfft_radix8_f32.c
355 SRC
+= $(DSP_LIB
)/Source
/CommonTables
/arm_common_tables.c
357 SRC
+= $(DSP_LIB
)/Source
/ComplexMathFunctions
/arm_cmplx_mag_f32.c
358 SRC
+= $(DSP_LIB
)/Source
/StatisticsFunctions
/arm_max_f32.c
360 SRC
+= $(wildcard $(DSP_LIB
)/Source
/*/*.S
)
363 ifneq ($(filter ONBOARDFLASH
,$(FEATURES
)),)
366 drivers
/flash_m25p16.c \
367 drivers
/flash_w25m.c \
376 SRC
:= $(filter-out $(MCU_EXCLUDES
), $(SRC
))
378 ifneq ($(filter SDCARD_SPI
,$(FEATURES
)),)
381 drivers
/sdcard_spi.c \
382 drivers
/sdcard_standard.c \
383 io
/asyncfatfs
/asyncfatfs.c \
384 io
/asyncfatfs
/fat_standard.c \
388 ifneq ($(filter SDCARD_SDIO
,$(FEATURES
)),)
391 drivers
/sdcard_sdio_baremetal.c \
392 drivers
/sdcard_standard.c \
393 io
/asyncfatfs
/asyncfatfs.c \
394 io
/asyncfatfs
/fat_standard.c \
399 ifneq ($(filter VCP
,$(FEATURES
)),)
403 ifneq ($(filter MSC
,$(FEATURES
)),)
406 # end target specific make file checks
408 # Search path and source files for the ST stdperiph library
409 VPATH
:= $(VPATH
):$(STDPERIPH_DIR
)/src