8 $(addprefix pg
/, $(notdir $(wildcard $(SRC_DIR
)/pg
/*.c
))) \
9 $(addprefix common
/,$(notdir $(wildcard $(SRC_DIR
)/common
/*.c
))) \
10 $(addprefix config
/,$(notdir $(wildcard $(SRC_DIR
)/config
/*.c
))) \
16 drivers
/dshot_dpwm.c \
17 drivers
/dshot_command.c \
18 drivers
/buf_writer.c \
20 drivers
/bus_i2c_config.c \
21 drivers
/bus_i2c_busdev.c \
22 drivers
/bus_i2c_soft.c \
23 drivers
/bus_octospi.c \
24 drivers
/bus_quadspi.c \
26 drivers
/bus_spi_config.c \
27 drivers
/bus_spi_pinconfig.c \
30 drivers
/display_canvas.c \
31 drivers
/dma_common.c \
37 drivers
/pin_pull_up_down.c \
40 drivers
/serial_pinconfig.c \
41 drivers
/serial_uart.c \
42 drivers
/serial_uart_pinconfig.c \
43 drivers
/sound_beeper.c \
44 drivers
/stack_check.c \
46 drivers
/timer_common.c \
47 drivers
/transponder_ir_arcitimer.c \
48 drivers
/transponder_ir_ilap.c \
49 drivers
/transponder_ir_erlt.c \
59 io
/smartaudio_protocol.c \
60 io
/statusindicator.c \
68 scheduler
/scheduler.c \
69 sensors
/adcinternal.c \
73 target
/config_helper.c \
75 fc/controlrate_profile.c \
76 drivers
/camera_control.c \
77 drivers
/accgyro
/gyro_sync.c \
79 drivers
/rx
/rx_xn297.c \
81 drivers
/serial_softserial.c \
90 flight
/dyn_notch_filter.c \
92 flight
/feedforward.c \
95 flight
/mixer_tricopter.c \
100 flight
/servos_tricopter.c \
102 io
/serial_4way_avrootloader.c \
103 io
/serial_4way_stk500v2.c \
119 io
/spektrum_vtx_control.c \
126 sensors
/acceleration.c \
127 sensors
/acceleration_init.c \
128 sensors
/boardalignment.c \
131 sensors
/gyro_init.c \
132 sensors
/initialisation.c \
133 blackbox
/blackbox.c \
134 blackbox
/blackbox_encoding.c \
135 blackbox
/blackbox_io.c \
137 cms
/cms_menu_blackbox.c \
138 cms
/cms_menu_failsafe.c \
139 cms
/cms_menu_firmware.c \
140 cms
/cms_menu_gps_rescue.c\
142 cms
/cms_menu_ledstrip.c \
143 cms
/cms_menu_main.c \
144 cms
/cms_menu_misc.c \
146 cms
/cms_menu_power.c \
147 cms
/cms_menu_saveexit.c \
148 cms
/cms_menu_vtx_common.c \
149 cms
/cms_menu_vtx_rtc6705.c \
150 cms
/cms_menu_vtx_smartaudio.c \
151 cms
/cms_menu_vtx_tramp.c \
152 cms
/cms_menu_persistent_stats.c \
153 drivers
/display_ug2864hsweg01.c \
154 drivers
/light_ws2811strip.c \
155 drivers
/rangefinder
/rangefinder_hcsr04.c \
156 drivers
/rangefinder
/rangefinder_lidartf.c \
157 drivers
/serial_escserial.c \
158 drivers
/vtx_common.c \
159 drivers
/vtx_table.c \
161 io
/displayport_frsky_osd.c \
162 io
/displayport_max7456.c \
163 io
/displayport_msp.c \
164 io
/displayport_oled.c \
165 io
/displayport_srxl.c \
166 io
/displayport_crsf.c \
167 io
/displayport_hott.c \
177 sensors
/barometer.c \
178 sensors
/rangefinder.c \
179 telemetry
/telemetry.c \
183 telemetry
/frsky_hub.c \
185 telemetry
/jetiexbus.c \
186 telemetry
/smartport.c \
188 telemetry
/mavlink.c \
189 telemetry
/msp_shared.c \
191 telemetry
/ibus_shared.c \
192 sensors
/esc_sensor.c \
195 io
/vtx_smartaudio.c \
199 cms
/cms_menu_vtx_msp.c
201 ifneq ($(SIMULATOR_BUILD
),yes
)
204 $(addprefix drivers
/accgyro
/,$(notdir $(wildcard $(SRC_DIR
)/drivers
/accgyro
/*.c
))) \
205 $(ROOT
)/lib
/main
/BoschSensortec
/BMI270-Sensor-API
/bmi270_maximum_fifo.c \
206 $(addprefix drivers
/barometer
/,$(notdir $(wildcard $(SRC_DIR
)/drivers
/barometer
/*.c
))) \
207 $(addprefix drivers
/compass
/,$(notdir $(wildcard $(SRC_DIR
)/drivers
/compass
/*.c
))) \
209 drivers
/vtx_rtc6705.c \
210 drivers
/vtx_rtc6705_soft_spi.c
214 GYRO_DEFINE
:= $(shell grep
" USE_GYRO_" $(CONFIG_FILE
) | awk
'{print $$2}' )
215 LEGACY_GYRO_DEFINES
:= USE_GYRO_L3GD20
216 ifneq ($(findstring $(GYRO_DEFINE
),$(LEGACY_GYRO_DEFINES
)),)
219 $(addprefix drivers
/accgyro_legacy
/,$(notdir $(wildcard $(SRC_DIR
)/drivers
/accgyro_legacy
/*.c
)))
226 rx
/cc2500_frsky_shared.c \
227 rx
/cc2500_frsky_d.c \
228 rx
/cc2500_frsky_x.c \
230 rx
/cc2500_redpine.c \
232 rx
/cyrf6936_spektrum.c \
233 drivers
/rx
/expresslrs_driver.c \
235 rx
/expresslrs_common.c \
236 rx
/expresslrs_telemetry.c \
237 drivers
/rx
/rx_cc2500.c \
238 drivers
/rx
/rx_a7105.c \
239 drivers
/rx
/rx_cyrf6936.c \
240 drivers
/rx
/rx_sx127x.c \
241 drivers
/rx
/rx_sx1280.c
245 drivers
/flash_m25p16.c \
246 drivers
/flash_w25n01g.c \
247 drivers
/flash_w25q128fv.c \
248 drivers
/flash_w25m.c \
253 drivers
/sdcard_spi.c \
254 drivers
/sdcard_sdio_baremetal.c \
255 drivers
/sdcard_standard.c \
256 io
/asyncfatfs
/asyncfatfs.c \
257 io
/asyncfatfs
/fat_standard.c
259 INCLUDE_DIRS
:= $(INCLUDE_DIRS
) \
261 VPATH
:= $(VPATH
):$(FATFS_DIR
)
265 COMMON_DEVICE_SRC
= \
267 $(DEVICE_STDPERIPH_SRC
)
269 COMMON_SRC
:= $(COMMON_SRC
) $(COMMON_DEVICE_SRC
) $(RX_SRC
)
272 TARGET_FLAGS
:= -DUSE_EXST
$(TARGET_FLAGS
)
275 ifeq ($(RAM_BASED
),yes
)
276 TARGET_FLAGS
:= -DUSE_EXST
-DCONFIG_IN_RAM
-DRAMBASED
$(TARGET_FLAGS
)
279 ifeq ($(SIMULATOR_BUILD
),yes
)
280 TARGET_FLAGS
:= -DSIMULATOR_BUILD
$(TARGET_FLAGS
)
283 SPEED_OPTIMISED_SRC
:= ""
284 SIZE_OPTIMISED_SRC
:= ""
286 SPEED_OPTIMISED_SRC
:= $(SPEED_OPTIMISED_SRC
) \
291 common
/typeconversion.c \
292 drivers
/accgyro
/accgyro_mpu.c \
293 drivers
/accgyro
/accgyro_mpu3050.c \
294 drivers
/accgyro
/accgyro_spi_bmi160.c \
295 drivers
/accgyro
/accgyro_spi_bmi270.c \
296 drivers
/accgyro
/accgyro_spi_lsm6dso.c \
297 drivers
/accgyro_legacy
/accgyro_adxl345.c \
298 drivers
/accgyro_legacy
/accgyro_bma280.c \
299 drivers
/accgyro_legacy
/accgyro_l3g4200d.c \
300 drivers
/accgyro_legacy
/accgyro_l3gd20.c \
301 drivers
/accgyro_legacy
/accgyro_lsm303dlhc.c \
302 drivers
/accgyro_legacy
/accgyro_mma845x.c \
304 drivers
/buf_writer.c \
306 drivers
/bus_quadspi.c \
310 drivers
/pwm_output.c \
313 drivers
/serial_uart.c \
320 fc/runtime_config.c \
321 flight
/dyn_notch_filter.c \
325 flight
/rpm_filter.c \
338 scheduler
/scheduler.c \
339 sensors
/acceleration.c \
340 sensors
/boardalignment.c \
343 $(DEVICE_STDPERIPH_SRC
) \
345 SIZE_OPTIMISED_SRC
:= $(SIZE_OPTIMISED_SRC
) \
346 $(shell find
$(SRC_DIR
) -name
'*_init.c') \
347 bus_bst_stm32f30x.c \
350 drivers
/accgyro
/accgyro_fake.c \
351 drivers
/barometer
/barometer_bmp085.c \
352 drivers
/barometer
/barometer_bmp280.c \
353 drivers
/barometer
/barometer_fake.c \
354 drivers
/barometer
/barometer_ms5611.c \
355 drivers
/barometer
/barometer_lps.c \
356 drivers
/barometer
/barometer_qmp6988.c \
357 drivers
/barometer
/barometer_2smpb_02b.c \
358 drivers
/bus_i2c_config.c \
359 drivers
/bus_i2c_timing.c \
360 drivers
/bus_spi_config.c \
361 drivers
/bus_spi_pinconfig.c \
362 drivers
/compass
/compass_ak8963.c \
363 drivers
/compass
/compass_ak8975.c \
364 drivers
/compass
/compass_fake.c \
365 drivers
/compass
/compass_hmc5883l.c \
366 drivers
/compass
/compass_qmc5883l.c \
367 drivers
/compass
/compass_lis3mdl.c \
368 drivers
/display_ug2864hsweg01.c \
370 drivers
/light_ws2811strip.c \
371 drivers
/serial_escserial.c \
372 drivers
/serial_pinconfig.c \
373 drivers
/serial_tcp.c \
374 drivers
/serial_uart_pinconfig.c \
375 drivers
/serial_usb_vcp.c \
376 drivers
/vtx_rtc6705_soft_spi.c \
377 drivers
/vtx_rtc6705.c \
378 drivers
/vtx_common.c \
381 config
/config_eeprom.c \
383 config
/config_streamer.c \
384 config
/simplified_tuning.c \
389 io
/serial_4way_avrootloader.c \
390 io
/serial_4way_stk500v2.c \
391 io
/transponder_ir.c \
395 cms
/cms_menu_blackbox.c \
396 cms
/cms_menu_failsafe.c \
397 cms
/cms_menu_firmware.c \
398 cms
/cms_menu_gps_rescue.c\
400 cms
/cms_menu_ledstrip.c \
401 cms
/cms_menu_main.c \
402 cms
/cms_menu_misc.c \
404 cms
/cms_menu_power.c \
405 cms
/cms_menu_saveexit.c \
406 cms
/cms_menu_vtx_common.c \
407 cms
/cms_menu_vtx_rtc6705.c \
408 cms
/cms_menu_vtx_smartaudio.c \
409 cms
/cms_menu_vtx_tramp.c \
410 cms
/cms_menu_persistent_stats.c \
413 io
/vtx_smartaudio.c \
416 io
/spektrum_vtx_control.c \
422 cms
/cms_menu_vtx_msp.c
424 # Gyro driver files that only contain initialization and configuration code - not runtime code
425 SIZE_OPTIMISED_SRC
:= $(SIZE_OPTIMISED_SRC
) \
426 drivers
/accgyro
/accgyro_mpu6050.c \
427 drivers
/accgyro
/accgyro_mpu6500.c \
428 drivers
/accgyro
/accgyro_spi_mpu6000.c \
429 drivers
/accgyro
/accgyro_spi_mpu6500.c \
430 drivers
/accgyro
/accgyro_spi_mpu9250.c \
431 drivers
/accgyro
/accgyro_spi_icm20689.c \
432 drivers
/accgyro
/accgyro_spi_icm426xx.c \
433 drivers
/accgyro
/accgyro_spi_lsm6dso_init.c
436 # F4 and F7 optimizations
437 SPEED_OPTIMISED_SRC
:= $(SPEED_OPTIMISED_SRC
) \
438 drivers
/bus_i2c_hal.c \
439 drivers
/bus_spi_ll.c \
442 drivers
/pwm_output_dshot.c \
443 drivers
/pwm_output_dshot_shared.c \
444 drivers
/pwm_output_dshot_hal.c
446 SIZE_OPTIMISED_SRC
:= $(SIZE_OPTIMISED_SRC
) \
447 drivers
/bus_i2c_hal_init.c
449 # check if target.mk supplied
450 SRC
:= $(STARTUP_SRC
) $(MCU_COMMON_SRC
) $(TARGET_SRC
) $(VARIANT_SRC
)
452 # Files that should not be optimized, useful for debugging IMPRECISE cpu faults.
453 # Specify FULL PATH, e.g. "./lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_sdmmc.c"
454 NOT_OPTIMISED_SRC
:= $(NOT_OPTIMISED_SRC
) \
458 INCLUDE_DIRS
+= $(DSP_LIB
)/Include
459 SRC
+= $(wildcard $(DSP_LIB
)/Source
/*/*.S
)
463 SRC
+= $(FLASH_SRC
) $(MSC_SRC
) $(SDCARD_SRC
) $(COMMON_SRC
)
466 SRC
:= $(filter-out $(MCU_EXCLUDES
), $(SRC
))
470 # end target specific make file checks
472 # Search path and source files for the Open Location Code library
473 OLC_DIR
= $(ROOT
)/lib
/main
/google
/olc
476 INCLUDE_DIRS
+= $(OLC_DIR
)
477 SRC
+= $(OLC_DIR
)/olc.c
478 SIZE_OPTIMISED_SRC
+= $(OLC_DIR
)/olc.c