3D Mode Fix // Dshot 3D Mode implementation
[betaflight.git] / Makefile
blob01511d2ec1c40b5ff60b66a5eb4c730bb4280adf
1 ###############################################################################
2 # "THE BEER-WARE LICENSE" (Revision 42):
3 # <msmith@FreeBSD.ORG> wrote this file. As long as you retain this notice you
4 # can do whatever you want with this stuff. If we meet some day, and you think
5 # this stuff is worth it, you can buy me a beer in return
6 ###############################################################################
8 # Makefile for building the betaflight firmware.
10 # Invoke this with 'make help' to see the list of supported targets.
12 ###############################################################################
15 # Things that the user might override on the commandline
18 # The target to build, see VALID_TARGETS below
19 TARGET ?= NAZE
21 # Compile-time options
22 OPTIONS ?=
24 # compile for OpenPilot BootLoader support
25 OPBL ?= no
27 # Debugger optons, must be empty or GDB
28 DEBUG ?=
30 # Insert the debugging hardfault debugger
31 # releases should not be built with this flag as it does not disable pwm output
32 DEBUG_HARDFAULTS ?=
34 # Serial port/Device for flashing
35 SERIAL_DEVICE ?= $(firstword $(wildcard /dev/ttyUSB*) no-port-found)
37 # Flash size (KB). Some low-end chips actually have more flash than advertised, use this to override.
38 FLASH_SIZE ?=
40 ## V : Set verbosity level based on the V= parameter
41 ## V=0 Low
42 ## V=1 High
43 export AT := @
45 ifndef V
46 export V0 :=
47 export V1 := $(AT)
48 export STDOUT :=
49 else ifeq ($(V), 0)
50 export V0 := $(AT)
51 export V1 := $(AT)
52 export STDOUT:= "> /dev/null"
53 export MAKE := $(MAKE) --no-print-directory
54 else ifeq ($(V), 1)
55 export V0 :=
56 export V1 :=
57 export STDOUT :=
58 endif
60 ###############################################################################
61 # Things that need to be maintained as the source changes
64 FORKNAME = betaflight
66 # Working directories
67 ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST))))
68 SRC_DIR = $(ROOT)/src/main
69 OBJECT_DIR = $(ROOT)/obj/main
70 BIN_DIR = $(ROOT)/obj
71 CMSIS_DIR = $(ROOT)/lib/main/CMSIS
72 INCLUDE_DIRS = $(SRC_DIR) \
73 $(ROOT)/src/main/target
74 LINKER_DIR = $(ROOT)/src/main/target/link
76 # Build tools, so we all share the same versions
77 # import macros common to all supported build systems
78 include $(ROOT)/make/system-id.mk
79 # developer preferences, edit these at will, they'll be gitignored
80 include $(ROOT)/make/local.mk
82 # configure some directories that are relative to wherever ROOT_DIR is located
83 TOOLS_DIR := $(ROOT)/tools
84 BUILD_DIR := $(ROOT)/build
85 DL_DIR := $(ROOT)/downloads
87 export RM := rm
89 # import macros that are OS specific
90 include $(ROOT)/make/$(OSFAMILY).mk
92 # include the tools makefile
93 include $(ROOT)/make/tools.mk
95 # default xtal value for F4 targets
96 HSE_VALUE = 8000000
98 # used for turning on features like VCP and SDCARD
99 FEATURES =
101 SAMPLE_TARGETS = ALIENFLIGHTF3 ALIENFLIGHTF4 ANYFCF7 BETAFLIGHTF3 BLUEJAYF4 CC3D FURYF4 NAZE REVO SIRINFPV SPARKY SPRACINGF3 SPRACINGF3EVO STM32F3DISCOVERY
102 ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk)))))
103 OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS))
105 #VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS)
106 VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk))
107 VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS)))
108 VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS)
109 VALID_TARGETS := $(sort $(VALID_TARGETS))
111 ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET))
112 BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk)))))
113 -include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk
114 else
115 BASE_TARGET := $(TARGET)
116 endif
118 ifeq ($(filter $(TARGET),$(OPBL_TARGETS)), $(TARGET))
119 OPBL = yes
120 endif
122 # silently ignore if the file is not present. Allows for target specific.
123 -include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk
125 F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS)
126 F7_TARGETS = $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS)
128 ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
129 $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?)
130 endif
132 ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS)),)
133 $(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, F411 or F7x5. Have you prepared a valid target.mk?)
134 endif
136 128K_TARGETS = $(F1_TARGETS)
137 256K_TARGETS = $(F3_TARGETS)
138 512K_TARGETS = $(F411_TARGETS) $(F7X5XE_TARGETS)
139 1024K_TARGETS = $(F405_TARGETS) $(F7X5XG_TARGETS)
140 2048K_TARGETS = $(F7X5XI_TARGETS)
142 # Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already.
143 ifeq ($(FLASH_SIZE),)
144 ifeq ($(TARGET),$(filter $(TARGET),$(2048K_TARGETS)))
145 FLASH_SIZE = 2048
146 else ifeq ($(TARGET),$(filter $(TARGET),$(1024K_TARGETS)))
147 FLASH_SIZE = 1024
148 else ifeq ($(TARGET),$(filter $(TARGET),$(512K_TARGETS)))
149 FLASH_SIZE = 512
150 else ifeq ($(TARGET),$(filter $(TARGET),$(256K_TARGETS)))
151 FLASH_SIZE = 256
152 else ifeq ($(TARGET),$(filter $(TARGET),$(128K_TARGETS)))
153 FLASH_SIZE = 128
154 else
155 $(error FLASH_SIZE not configured for target $(TARGET))
156 endif
157 endif
159 # note that there is no hardfault debugging startup file assembly handler for other platforms
160 ifeq ($(DEBUG_HARDFAULTS),F3)
161 CFLAGS += -DDEBUG_HARDFAULTS
162 STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S
163 else
164 STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S
165 endif
167 ifeq ($(DEBUG_HARDFAULTS),F7)
168 CFLAGS += -DDEBUG_HARDFAULTS
169 endif
171 REVISION = $(shell git log -1 --format="%h")
173 FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/build/version.h | awk '{print $$3}' )
174 FC_VER_MINOR := $(shell grep " FC_VERSION_MINOR" src/main/build/version.h | awk '{print $$3}' )
175 FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/build/version.h | awk '{print $$3}' )
177 FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH)
179 # Search path for sources
180 VPATH := $(SRC_DIR):$(SRC_DIR)/startup
181 USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver
182 USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c))
183 FATFS_DIR = $(ROOT)/lib/main/FatFS
184 FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c))
186 CSOURCES := $(shell find $(SRC_DIR) -name '*.c')
188 ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
189 # F3 TARGETS
191 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
192 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
193 EXCLUDES = stm32f30x_crc.c \
194 stm32f30x_can.c
196 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
197 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
199 VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
200 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM1/CoreSupport/*.c \
201 $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c))
203 INCLUDE_DIRS := $(INCLUDE_DIRS) \
204 $(STDPERIPH_DIR)/inc \
205 $(CMSIS_DIR)/CM1/CoreSupport \
206 $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
208 ifneq ($(filter VCP, $(FEATURES)),)
209 INCLUDE_DIRS := $(INCLUDE_DIRS) \
210 $(USBFS_DIR)/inc \
211 $(ROOT)/src/main/vcp
213 VPATH := $(VPATH):$(USBFS_DIR)/src
215 DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\
216 $(USBPERIPH_SRC)
217 endif
219 ifneq ($(filter SDCARD, $(FEATURES)),)
220 INCLUDE_DIRS := $(INCLUDE_DIRS) \
221 $(FATFS_DIR) \
223 VPATH := $(VPATH):$(FATFS_DIR)
224 endif
226 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld
228 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
229 DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
230 # End F3 targets
232 # Start F4 targets
233 else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS)))
235 #STDPERIPH
236 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4xx_StdPeriph_Driver
237 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
238 EXCLUDES = stm32f4xx_crc.c \
239 stm32f4xx_can.c \
240 stm32f4xx_fmc.c \
241 stm32f4xx_sai.c \
242 stm32f4xx_cec.c \
243 stm32f4xx_dsi.c \
244 stm32f4xx_flash_ramfunc.c \
245 stm32f4xx_fmpi2c.c \
246 stm32f4xx_lptim.c \
247 stm32f4xx_qspi.c \
248 stm32f4xx_spdifrx.c \
249 stm32f4xx_cryp.c \
250 stm32f4xx_cryp_aes.c \
251 stm32f4xx_hash_md5.c \
252 stm32f4xx_cryp_des.c \
253 stm32f4xx_rtc.c \
254 stm32f4xx_hash.c \
255 stm32f4xx_dbgmcu.c \
256 stm32f4xx_cryp_tdes.c \
257 stm32f4xx_hash_sha1.c
260 ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS)))
261 EXCLUDES += stm32f4xx_fsmc.c
262 endif
264 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
266 #USB
267 USBCORE_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Core
268 USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/src/*.c))
269 USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver
270 USBOTG_SRC = $(notdir $(wildcard $(USBOTG_DIR)/src/*.c))
271 EXCLUDES = usb_bsp_template.c \
272 usb_conf_template.c \
273 usb_hcd_int.c \
274 usb_hcd.c \
275 usb_otg.c
277 USBOTG_SRC := $(filter-out ${EXCLUDES}, $(USBOTG_SRC))
278 USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc
279 USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/src/*.c))
280 EXCLUDES = usbd_cdc_if_template.c
281 USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
282 VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src
284 DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
285 $(USBOTG_SRC) \
286 $(USBCORE_SRC) \
287 $(USBCDC_SRC)
289 #CMSIS
290 VPATH := $(VPATH):$(CMSIS_DIR)/CM4/CoreSupport:$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx
291 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM4/CoreSupport/*.c \
292 $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx/*.c))
293 INCLUDE_DIRS := $(INCLUDE_DIRS) \
294 $(STDPERIPH_DIR)/inc \
295 $(USBOTG_DIR)/inc \
296 $(USBCORE_DIR)/inc \
297 $(USBCDC_DIR)/inc \
298 $(USBFS_DIR)/inc \
299 $(CMSIS_DIR)/CM4/CoreSupport \
300 $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \
301 $(ROOT)/src/main/vcpf4
303 ifneq ($(filter SDCARD,$(FEATURES)),)
304 INCLUDE_DIRS := $(INCLUDE_DIRS) \
305 $(FATFS_DIR)
306 VPATH := $(VPATH):$(FATFS_DIR)
307 endif
309 #Flags
310 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
312 ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS)))
313 DEVICE_FLAGS = -DSTM32F411xE
314 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld
315 else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS)))
316 DEVICE_FLAGS = -DSTM32F40_41xxx
317 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld
318 else
319 $(error Unknown MCU for F4 target)
320 endif
321 DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
323 # End F4 targets
325 # Start F7 targets
326 else ifeq ($(TARGET),$(filter $(TARGET), $(F7_TARGETS)))
328 #STDPERIPH
329 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F7xx_HAL_Driver
330 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c))
331 EXCLUDES = stm32f7xx_hal_timebase_rtc_wakeup_template.c \
332 stm32f7xx_hal_timebase_rtc_alarm_template.c \
333 stm32f7xx_hal_timebase_tim_template.c
335 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
337 #USB
338 USBCORE_DIR = $(ROOT)/lib/main/Middlewares/ST/STM32_USB_Device_Library/Core
339 USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c))
340 EXCLUDES = usbd_conf_template.c
341 USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC))
343 USBCDC_DIR = $(ROOT)/lib/main/Middlewares/ST/STM32_USB_Device_Library/Class/CDC
344 USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/Src/*.c))
345 EXCLUDES = usbd_cdc_if_template.c
346 USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
348 VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src
350 DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
351 $(USBCORE_SRC) \
352 $(USBCDC_SRC)
354 #CMSIS
355 VPATH := $(VPATH):$(CMSIS_DIR)/CM7/Include:$(CMSIS_DIR)/CM7/Device/ST/STM32F7xx
356 VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
357 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM7/Include/*.c \
358 $(CMSIS_DIR)/CM7/Device/ST/STM32F7xx/*.c))
359 INCLUDE_DIRS := $(INCLUDE_DIRS) \
360 $(STDPERIPH_DIR)/Inc \
361 $(USBCORE_DIR)/Inc \
362 $(USBCDC_DIR)/Inc \
363 $(CMSIS_DIR)/CM7/Include \
364 $(CMSIS_DIR)/CM7/Device/ST/STM32F7xx/Include \
365 $(ROOT)/src/main/vcp_hal
367 ifneq ($(filter SDCARD,$(FEATURES)),)
368 INCLUDE_DIRS := $(INCLUDE_DIRS) \
369 $(FATFS_DIR)
370 VPATH := $(VPATH):$(FATFS_DIR)
371 endif
373 #Flags
374 ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant -Wdouble-promotion
376 ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS)))
377 DEVICE_FLAGS = -DSTM32F745xx -DUSE_HAL_DRIVER -D__FPU_PRESENT
378 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f745.ld
379 else
380 $(error Unknown MCU for F7 target)
381 endif
382 DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
384 TARGET_FLAGS = -D$(TARGET)
386 # End F7 targets
388 # Start F1 targets
389 else
391 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
392 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
393 EXCLUDES = stm32f10x_crc.c \
394 stm32f10x_cec.c \
395 stm32f10x_can.c
397 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
399 # Search path and source files for the CMSIS sources
400 VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x
401 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \
402 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c))
404 INCLUDE_DIRS := $(INCLUDE_DIRS) \
405 $(STDPERIPH_DIR)/inc \
406 $(CMSIS_DIR)/CM3/CoreSupport \
407 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \
409 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
411 ifneq ($(filter VCP, $(FEATURES)),)
412 INCLUDE_DIRS := $(INCLUDE_DIRS) \
413 $(USBFS_DIR)/inc \
414 $(ROOT)/src/main/vcp
416 VPATH := $(VPATH):$(USBFS_DIR)/src
418 DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC) \
419 $(USBPERIPH_SRC)
421 endif
423 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld
424 ARCH_FLAGS = -mthumb -mcpu=cortex-m3
426 ifeq ($(DEVICE_FLAGS),)
427 DEVICE_FLAGS = -DSTM32F10X_MD
428 endif
429 DEVICE_FLAGS += -DSTM32F10X
431 endif
433 # End F1 targets
435 ifneq ($(BASE_TARGET), $(TARGET))
436 TARGET_FLAGS := $(TARGET_FLAGS) -D$(BASE_TARGET)
437 endif
439 ifneq ($(FLASH_SIZE),)
440 DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE)
441 endif
443 ifneq ($(HSE_VALUE),)
444 DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE)
445 endif
447 TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET)
448 TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
450 ifeq ($(OPBL),yes)
451 TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
452 ifeq ($(TARGET), $(filter $(TARGET),$(F405_TARGETS)))
453 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405_opbl.ld
454 else ifeq ($(TARGET), $(filter $(TARGET),$(F411_TARGETS)))
455 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411_opbl.ld
456 else ifeq ($(TARGET), $(filter $(TARGET),$(F3_TARGETS)))
457 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k_opbl.ld
458 else ifeq ($(TARGET), $(filter $(TARGET),$(F1_TARGETS)))
459 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld
460 endif
461 .DEFAULT_GOAL := binary
462 else
463 .DEFAULT_GOAL := hex
464 endif
466 INCLUDE_DIRS := $(INCLUDE_DIRS) \
467 $(ROOT)/lib/main/MAVLink
469 INCLUDE_DIRS := $(INCLUDE_DIRS) \
470 $(TARGET_DIR)
472 VPATH := $(VPATH):$(TARGET_DIR)
474 COMMON_SRC = \
475 build/build_config.c \
476 build/debug.c \
477 build/version.c \
478 $(TARGET_DIR_SRC) \
479 main.c \
480 common/encoding.c \
481 common/filter.c \
482 common/maths.c \
483 common/printf.c \
484 common/streambuf.c \
485 common/typeconversion.c \
486 config/config_eeprom.c \
487 config/feature.c \
488 config/parameter_group.c \
489 drivers/adc.c \
490 drivers/buf_writer.c \
491 drivers/bus_i2c_soft.c \
492 drivers/bus_spi.c \
493 drivers/bus_spi_soft.c \
494 drivers/display.c \
495 drivers/exti.c \
496 drivers/gyro_sync.c \
497 drivers/io.c \
498 drivers/light_led.c \
499 drivers/resource.c \
500 drivers/rx_nrf24l01.c \
501 drivers/rx_spi.c \
502 drivers/rx_xn297.c \
503 drivers/pwm_output.c \
504 drivers/pwm_rx.c \
505 drivers/rcc.c \
506 drivers/serial.c \
507 drivers/serial_uart.c \
508 drivers/sound_beeper.c \
509 drivers/system.c \
510 drivers/timer.c \
511 fc/config.c \
512 fc/fc_tasks.c \
513 fc/fc_msp.c \
514 fc/mw.c \
515 fc/rc_controls.c \
516 fc/rc_curves.c \
517 fc/runtime_config.c \
518 flight/altitudehold.c \
519 flight/failsafe.c \
520 flight/imu.c \
521 flight/mixer.c \
522 flight/pid.c \
523 flight/servos.c \
524 io/beeper.c \
525 io/serial.c \
526 io/serial_4way.c \
527 io/serial_4way_avrootloader.c \
528 io/serial_4way_stk500v2.c \
529 io/serial_cli.c \
530 io/statusindicator.c \
531 msp/msp_serial.c \
532 rx/ibus.c \
533 rx/jetiexbus.c \
534 rx/msp.c \
535 rx/nrf24_cx10.c \
536 rx/nrf24_inav.c \
537 rx/nrf24_h8_3d.c \
538 rx/nrf24_syma.c \
539 rx/nrf24_v202.c \
540 rx/pwm.c \
541 rx/rx.c \
542 rx/rx_spi.c \
543 rx/crsf.c \
544 rx/sbus.c \
545 rx/spektrum.c \
546 rx/sumd.c \
547 rx/sumh.c \
548 rx/xbus.c \
549 scheduler/scheduler.c \
550 sensors/acceleration.c \
551 sensors/battery.c \
552 sensors/boardalignment.c \
553 sensors/compass.c \
554 sensors/gyro.c \
555 sensors/initialisation.c \
556 $(CMSIS_SRC) \
557 $(DEVICE_STDPERIPH_SRC)
559 HIGHEND_SRC = \
560 blackbox/blackbox.c \
561 blackbox/blackbox_io.c \
562 cms/cms.c \
563 cms/cms_menu_blackbox.c \
564 cms/cms_menu_builtin.c \
565 cms/cms_menu_imu.c \
566 cms/cms_menu_ledstrip.c \
567 cms/cms_menu_misc.c \
568 cms/cms_menu_osd.c \
569 cms/cms_menu_vtx.c \
570 common/colorconversion.c \
571 drivers/display_ug2864hsweg01.c \
572 drivers/light_ws2811strip.c \
573 drivers/serial_escserial.c \
574 drivers/serial_softserial.c \
575 drivers/sonar_hcsr04.c \
576 flight/gtune.c \
577 flight/navigation.c \
578 flight/gps_conversion.c \
579 io/dashboard.c \
580 io/displayport_max7456.c \
581 io/displayport_msp.c \
582 io/displayport_oled.c \
583 io/gps.c \
584 io/ledstrip.c \
585 io/osd.c \
586 sensors/sonar.c \
587 sensors/barometer.c \
588 telemetry/telemetry.c \
589 telemetry/crsf.c \
590 telemetry/frsky.c \
591 telemetry/hott.c \
592 telemetry/smartport.c \
593 telemetry/ltm.c \
594 telemetry/mavlink.c \
595 telemetry/esc_telemetry.c \
597 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
598 VCP_SRC = \
599 vcpf4/stm32f4xx_it.c \
600 vcpf4/usb_bsp.c \
601 vcpf4/usbd_desc.c \
602 vcpf4/usbd_usr.c \
603 vcpf4/usbd_cdc_vcp.c \
604 drivers/serial_usb_vcp.c
605 else ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS)))
606 VCP_SRC = \
607 vcp_hal/usbd_desc.c \
608 vcp_hal/usbd_conf.c \
609 vcp_hal/usbd_cdc_interface.c \
610 drivers/serial_usb_vcp_hal.c
611 else
612 VCP_SRC = \
613 vcp/hw_config.c \
614 vcp/stm32_it.c \
615 vcp/usb_desc.c \
616 vcp/usb_endp.c \
617 vcp/usb_istr.c \
618 vcp/usb_prop.c \
619 vcp/usb_pwr.c \
620 drivers/serial_usb_vcp.c \
621 drivers/usb_io.c
622 endif
624 STM32F10x_COMMON_SRC = \
625 startup_stm32f10x_md_gcc.S \
626 drivers/adc_stm32f10x.c \
627 drivers/bus_i2c_stm32f10x.c \
628 drivers/dma.c \
629 drivers/gpio_stm32f10x.c \
630 drivers/inverter.c \
631 drivers/light_ws2811strip_stm32f10x.c \
632 drivers/serial_uart_stm32f10x.c \
633 drivers/system_stm32f10x.c \
634 drivers/timer_stm32f10x.c
636 STM32F30x_COMMON_SRC = \
637 startup_stm32f30x_md_gcc.S \
638 target/system_stm32f30x.c \
639 drivers/adc_stm32f30x.c \
640 drivers/bus_i2c_stm32f30x.c \
641 drivers/dma.c \
642 drivers/gpio_stm32f30x.c \
643 drivers/light_ws2811strip_stm32f30x.c \
644 drivers/pwm_output_stm32f3xx.c \
645 drivers/serial_uart_stm32f30x.c \
646 drivers/system_stm32f30x.c \
647 drivers/timer_stm32f30x.c
649 STM32F4xx_COMMON_SRC = \
650 startup_stm32f40xx.s \
651 target/system_stm32f4xx.c \
652 drivers/accgyro_mpu.c \
653 drivers/adc_stm32f4xx.c \
654 drivers/bus_i2c_stm32f10x.c \
655 drivers/dma_stm32f4xx.c \
656 drivers/gpio_stm32f4xx.c \
657 drivers/inverter.c \
658 drivers/light_ws2811strip_stm32f4xx.c \
659 drivers/pwm_output_stm32f4xx.c \
660 drivers/serial_uart_stm32f4xx.c \
661 drivers/system_stm32f4xx.c \
662 drivers/timer_stm32f4xx.c
664 STM32F7xx_COMMON_SRC = \
665 startup_stm32f745xx.s \
666 target/system_stm32f7xx.c \
667 drivers/accgyro_mpu.c \
668 drivers/adc_stm32f7xx.c \
669 drivers/bus_i2c_hal.c \
670 drivers/dma_stm32f7xx.c \
671 drivers/gpio_stm32f7xx.c \
672 drivers/inverter.c \
673 drivers/bus_spi_hal.c \
674 drivers/pwm_output_stm32f7xx.c \
675 drivers/timer_hal.c \
676 drivers/timer_stm32f7xx.c \
677 drivers/pwm_output_hal.c \
678 drivers/system_stm32f7xx.c \
679 drivers/serial_uart_stm32f7xx.c \
680 drivers/serial_uart_hal.c
682 F7EXCLUDES = drivers/bus_spi.c \
683 drivers/bus_i2c.c \
684 drivers/timer.c \
685 drivers/pwm_output.c \
686 drivers/serial_uart.c
688 # check if target.mk supplied
689 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
690 TARGET_SRC := $(STM32F4xx_COMMON_SRC) $(TARGET_SRC)
691 else ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS)))
692 TARGET_SRC := $(STM32F7xx_COMMON_SRC) $(TARGET_SRC)
693 else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
694 TARGET_SRC := $(STM32F30x_COMMON_SRC) $(TARGET_SRC)
695 else ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
696 TARGET_SRC := $(STM32F10x_COMMON_SRC) $(TARGET_SRC)
697 endif
699 ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
700 TARGET_SRC += \
701 drivers/flash_m25p16.c \
702 io/flashfs.c
703 endif
705 ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS) $(F4_TARGETS) $(F3_TARGETS)))
706 TARGET_SRC += $(HIGHEND_SRC)
707 else ifneq ($(filter HIGHEND,$(FEATURES)),)
708 TARGET_SRC += $(HIGHEND_SRC)
709 endif
711 TARGET_SRC += $(COMMON_SRC)
712 #excludes
713 ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS)))
714 TARGET_SRC := $(filter-out ${F7EXCLUDES}, $(TARGET_SRC))
715 endif
717 ifneq ($(filter SDCARD,$(FEATURES)),)
718 TARGET_SRC += \
719 drivers/sdcard.c \
720 drivers/sdcard_standard.c \
721 io/asyncfatfs/asyncfatfs.c \
722 io/asyncfatfs/fat_standard.c
723 endif
725 ifneq ($(filter VCP,$(FEATURES)),)
726 TARGET_SRC += $(VCP_SRC)
727 endif
728 # end target specific make file checks
731 # Search path and source files for the ST stdperiph library
732 VPATH := $(VPATH):$(STDPERIPH_DIR)/src
734 ###############################################################################
735 # Things that might need changing to use different tools
738 # Find out if ccache is installed on the system
739 CCACHE := ccache
740 RESULT = $(shell (which $(CCACHE) > /dev/null 2>&1; echo $$?) )
741 ifneq ($(RESULT),0)
742 CCACHE :=
743 endif
745 # Tool names
746 CROSS_CC := $(CCACHE) $(ARM_SDK_PREFIX)gcc
747 CROSS_CXX := $(CCACHE) $(ARM_SDK_PREFIX)g++
748 OBJCOPY := $(ARM_SDK_PREFIX)objcopy
749 SIZE := $(ARM_SDK_PREFIX)size
752 # Tool options.
755 ifeq ($(DEBUG),GDB)
756 OPTIMIZE = -O0
757 LTO_FLAGS = $(OPTIMIZE)
758 else
759 OPTIMIZE = -Os
760 LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
761 endif
763 DEBUG_FLAGS = -ggdb3 -DDEBUG
765 CFLAGS += $(ARCH_FLAGS) \
766 $(LTO_FLAGS) \
767 $(addprefix -D,$(OPTIONS)) \
768 $(addprefix -I,$(INCLUDE_DIRS)) \
769 $(DEBUG_FLAGS) \
770 -std=gnu99 \
771 -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \
772 -ffunction-sections \
773 -fdata-sections \
774 -pedantic \
775 $(DEVICE_FLAGS) \
776 -DUSE_STDPERIPH_DRIVER \
777 -D$(TARGET) \
778 $(TARGET_FLAGS) \
779 -D'__FORKNAME__="$(FORKNAME)"' \
780 -D'__TARGET__="$(TARGET)"' \
781 -D'__REVISION__="$(REVISION)"' \
782 -save-temps=obj \
783 -MMD -MP
785 ASFLAGS = $(ARCH_FLAGS) \
786 -x assembler-with-cpp \
787 $(addprefix -I,$(INCLUDE_DIRS)) \
788 -MMD -MP
790 LDFLAGS = -lm \
791 -nostartfiles \
792 --specs=nano.specs \
793 -lc \
794 -lnosys \
795 $(ARCH_FLAGS) \
796 $(LTO_FLAGS) \
797 $(DEBUG_FLAGS) \
798 -static \
799 -Wl,-gc-sections,-Map,$(TARGET_MAP) \
800 -Wl,-L$(LINKER_DIR) \
801 -Wl,--cref \
802 -Wl,--no-wchar-size-warning \
803 -T$(LD_SCRIPT)
805 ###############################################################################
806 # No user-serviceable parts below
807 ###############################################################################
809 CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \
810 --std=c99 --inline-suppr --quiet --force \
811 $(addprefix -I,$(INCLUDE_DIRS)) \
812 -I/usr/include -I/usr/include/linux
815 # Things we will build
817 TARGET_BIN = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).bin
818 TARGET_HEX = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).hex
819 TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
820 TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC))))
821 TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC))))
822 TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
825 CLEAN_ARTIFACTS := $(TARGET_BIN)
826 CLEAN_ARTIFACTS += $(TARGET_HEX)
827 CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
829 # List of buildable ELF files and their object dependencies.
830 # It would be nice to compute these lists, but that seems to be just beyond make.
832 $(TARGET_HEX): $(TARGET_ELF)
833 $(V0) $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
835 $(TARGET_BIN): $(TARGET_ELF)
836 $(V0) $(OBJCOPY) -O binary $< $@
838 $(TARGET_ELF): $(TARGET_OBJS)
839 $(V1) echo Linking $(TARGET)
840 $(V1) $(CROSS_CC) -o $@ $^ $(LDFLAGS)
841 $(V0) $(SIZE) $(TARGET_ELF)
843 # Compile
844 $(OBJECT_DIR)/$(TARGET)/%.o: %.c
845 $(V1) mkdir -p $(dir $@)
846 $(V1) echo "%% $(notdir $<)" "$(STDOUT)"
847 $(V1) $(CROSS_CC) -c -o $@ $(CFLAGS) $<
849 # Assemble
850 $(OBJECT_DIR)/$(TARGET)/%.o: %.s
851 $(V1) mkdir -p $(dir $@)
852 $(V1) echo "%% $(notdir $<)" "$(STDOUT)"
853 $(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $<
855 $(OBJECT_DIR)/$(TARGET)/%.o: %.S
856 $(V1) mkdir -p $(dir $@)
857 $(V1) echo "%% $(notdir $<)" "$(STDOUT)"
858 $(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $<
860 ## sample : Build all sample (travis) targets
861 sample: $(SAMPLE_TARGETS)
863 ## all : Build all valid targets
864 all: $(VALID_TARGETS)
866 $(VALID_TARGETS):
867 $(V0) echo "" && \
868 echo "Building $@" && \
869 $(MAKE) binary hex TARGET=$@ && \
870 echo "Building $@ succeeded."
874 CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
875 TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
877 ## clean : clean up temporary / machine-generated files
878 clean:
879 $(V0) echo "Cleaning $(TARGET)"
880 $(V0) rm -f $(CLEAN_ARTIFACTS)
881 $(V0) rm -rf $(OBJECT_DIR)/$(TARGET)
882 $(V0) echo "Cleaning $(TARGET) succeeded."
884 ## clean_test : clean up temporary / machine-generated files (tests)
885 clean_test:
886 $(V0) cd src/test && $(MAKE) clean || true
888 ## clean_<TARGET> : clean up one specific target
889 $(CLEAN_TARGETS) :
890 $(V0) $(MAKE) -j TARGET=$(subst clean_,,$@) clean
892 ## <TARGET>_clean : clean up one specific target (alias for above)
893 $(TARGETS_CLEAN) :
894 $(V0) $(MAKE) -j TARGET=$(subst _clean,,$@) clean
896 ## clean_all : clean all valid targets
897 clean_all:$(CLEAN_TARGETS)
899 ## all_clean : clean all valid targets (alias for above)
900 all_clean:$(TARGETS_CLEAN)
903 flash_$(TARGET): $(TARGET_HEX)
904 $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
905 $(V0) echo -n 'R' >$(SERIAL_DEVICE)
906 $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
908 ## flash : flash firmware (.hex) onto flight controller
909 flash: flash_$(TARGET)
911 st-flash_$(TARGET): $(TARGET_BIN)
912 $(V0) st-flash --reset write $< 0x08000000
914 ## st-flash : flash firmware (.bin) onto flight controller
915 st-flash: st-flash_$(TARGET)
917 binary:
918 $(V0) $(MAKE) -j $(TARGET_BIN)
920 hex:
921 $(V0) $(MAKE) -j $(TARGET_HEX)
923 unbrick_$(TARGET): $(TARGET_HEX)
924 $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
925 $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
927 ## unbrick : unbrick flight controller
928 unbrick: unbrick_$(TARGET)
930 ## cppcheck : run static analysis on C source code
931 cppcheck: $(CSOURCES)
932 $(V0) $(CPPCHECK)
934 cppcheck-result.xml: $(CSOURCES)
935 $(V0) $(CPPCHECK) --xml-version=2 2> cppcheck-result.xml
937 # mkdirs
938 $(DL_DIR):
939 mkdir -p $@
941 $(TOOLS_DIR):
942 mkdir -p $@
944 $(BUILD_DIR):
945 mkdir -p $@
947 ## help : print this help message and exit
948 help: Makefile make/tools.mk
949 $(V0) @echo ""
950 $(V0) @echo "Makefile for the $(FORKNAME) firmware"
951 $(V0) @echo ""
952 $(V0) @echo "Usage:"
953 $(V0) @echo " make [V=<verbosity>] [TARGET=<target>] [OPTIONS=\"<options>\"]"
954 $(V0) @echo "Or:"
955 $(V0) @echo " make <target> [V=<verbosity>] [OPTIONS=\"<options>\"]"
956 $(V0) @echo ""
957 $(V0) @echo "Valid TARGET values are: $(VALID_TARGETS)"
958 $(V0) @echo ""
959 $(V0) @sed -n 's/^## //p' $?
961 ## targets : print a list of all valid target platforms (for consumption by scripts)
962 targets:
963 $(V0) @echo "Valid targets: $(VALID_TARGETS)"
964 $(V0) @echo "Target: $(TARGET)"
965 $(V0) @echo "Base target: $(BASE_TARGET)"
967 ## test : run the cleanflight test suite
968 ## junittest : run the cleanflight test suite, producing Junit XML result files.
969 test junittest:
970 $(V0) cd src/test && $(MAKE) $@
972 # rebuild everything when makefile changes
973 $(TARGET_OBJS) : Makefile
975 # include auto-generated dependencies
976 -include $(TARGET_DEPS)