Remap some timers
[betaflight.git] / Makefile
blob983c51c90409cdd358ad14dde78a700dc1b76b1a
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 else ifeq ($(V), 0)
49 export V0 := $(AT)
50 export V1 := $(AT)
51 else ifeq ($(V), 1)
52 endif
54 ###############################################################################
55 # Things that need to be maintained as the source changes
58 FORKNAME = betaflight
60 # Working directories
61 ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST))))
62 SRC_DIR = $(ROOT)/src/main
63 OBJECT_DIR = $(ROOT)/obj/main
64 BIN_DIR = $(ROOT)/obj
65 CMSIS_DIR = $(ROOT)/lib/main/CMSIS
66 INCLUDE_DIRS = $(SRC_DIR) \
67 $(ROOT)/src/main/target
68 LINKER_DIR = $(ROOT)/src/main/target/link
70 # Build tools, so we all share the same versions
71 # import macros common to all supported build systems
72 include $(ROOT)/make/system-id.mk
73 # developer preferences, edit these at will, they'll be gitignored
74 include $(ROOT)/make/local.mk
76 # configure some directories that are relative to wherever ROOT_DIR is located
77 TOOLS_DIR := $(ROOT)/tools
78 BUILD_DIR := $(ROOT)/build
79 DL_DIR := $(ROOT)/downloads
81 export RM := rm
83 # import macros that are OS specific
84 include $(ROOT)/make/$(OSFAMILY).mk
86 # include the tools makefile
87 include $(ROOT)/make/tools.mk
89 # default xtal value for F4 targets
90 HSE_VALUE = 8000000
92 # used for turning on features like VCP and SDCARD
93 FEATURES =
95 SAMPLE_TARGETS = ALIENFLIGHTF3 ALIENFLIGHTF4 ANYFCF7 BETAFLIGHTF3 BLUEJAYF4 CC3D FURYF4 NAZE REVO SIRINFPV SPARKY SPRACINGF3 SPRACINGF3EVO STM32F3DISCOVERY
96 ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk)))))
97 OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS))
99 #VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS)
100 VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk))
101 VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS)))
102 VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS)
103 VALID_TARGETS := $(sort $(VALID_TARGETS))
105 ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET))
106 BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk)))))
107 -include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk
108 else
109 BASE_TARGET := $(TARGET)
110 endif
112 ifeq ($(filter $(TARGET),$(OPBL_TARGETS)), $(TARGET))
113 OPBL = yes
114 endif
116 # silently ignore if the file is not present. Allows for target specific.
117 -include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk
119 F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS)
120 F7_TARGETS = $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS)
122 ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
123 $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?)
124 endif
126 ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS)),)
127 $(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?)
128 endif
130 128K_TARGETS = $(F1_TARGETS)
131 256K_TARGETS = $(F3_TARGETS)
132 512K_TARGETS = $(F411_TARGETS) $(F7X5XE_TARGETS)
133 1024K_TARGETS = $(F405_TARGETS) $(F7X5XG_TARGETS)
134 2048K_TARGETS = $(F7X5XI_TARGETS)
136 # Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already.
137 ifeq ($(FLASH_SIZE),)
138 ifeq ($(TARGET),$(filter $(TARGET),$(2048K_TARGETS)))
139 FLASH_SIZE = 2048
140 else ifeq ($(TARGET),$(filter $(TARGET),$(1024K_TARGETS)))
141 FLASH_SIZE = 1024
142 else ifeq ($(TARGET),$(filter $(TARGET),$(512K_TARGETS)))
143 FLASH_SIZE = 512
144 else ifeq ($(TARGET),$(filter $(TARGET),$(256K_TARGETS)))
145 FLASH_SIZE = 256
146 else ifeq ($(TARGET),$(filter $(TARGET),$(128K_TARGETS)))
147 FLASH_SIZE = 128
148 else
149 $(error FLASH_SIZE not configured for target $(TARGET))
150 endif
151 endif
153 # note that there is no hardfault debugging startup file assembly handler for other platforms
154 ifeq ($(DEBUG_HARDFAULTS),F3)
155 CFLAGS += -DDEBUG_HARDFAULTS
156 STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S
157 else
158 STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S
159 endif
161 ifeq ($(DEBUG_HARDFAULTS),F7)
162 CFLAGS += -DDEBUG_HARDFAULTS
163 endif
165 REVISION = $(shell git log -1 --format="%h")
167 FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/build/version.h | awk '{print $$3}' )
168 FC_VER_MINOR := $(shell grep " FC_VERSION_MINOR" src/main/build/version.h | awk '{print $$3}' )
169 FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/build/version.h | awk '{print $$3}' )
171 FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH)
173 # Search path for sources
174 VPATH := $(SRC_DIR):$(SRC_DIR)/startup
175 USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver
176 USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c))
177 FATFS_DIR = $(ROOT)/lib/main/FatFS
178 FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c))
180 CSOURCES := $(shell find $(SRC_DIR) -name '*.c')
182 ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
183 # F3 TARGETS
185 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
186 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
187 EXCLUDES = stm32f30x_crc.c \
188 stm32f30x_can.c
190 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
191 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
193 VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
194 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM1/CoreSupport/*.c \
195 $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c))
197 INCLUDE_DIRS := $(INCLUDE_DIRS) \
198 $(STDPERIPH_DIR)/inc \
199 $(CMSIS_DIR)/CM1/CoreSupport \
200 $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
202 ifneq ($(filter VCP, $(FEATURES)),)
203 INCLUDE_DIRS := $(INCLUDE_DIRS) \
204 $(USBFS_DIR)/inc \
205 $(ROOT)/src/main/vcp
207 VPATH := $(VPATH):$(USBFS_DIR)/src
209 DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\
210 $(USBPERIPH_SRC)
211 endif
213 ifneq ($(filter SDCARD, $(FEATURES)),)
214 INCLUDE_DIRS := $(INCLUDE_DIRS) \
215 $(FATFS_DIR) \
217 VPATH := $(VPATH):$(FATFS_DIR)
218 endif
220 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld
222 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
223 DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
224 # End F3 targets
226 # Start F4 targets
227 else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS)))
229 #STDPERIPH
230 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4xx_StdPeriph_Driver
231 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
232 EXCLUDES = stm32f4xx_crc.c \
233 stm32f4xx_can.c \
234 stm32f4xx_fmc.c \
235 stm32f4xx_sai.c \
236 stm32f4xx_cec.c \
237 stm32f4xx_dsi.c \
238 stm32f4xx_flash_ramfunc.c \
239 stm32f4xx_fmpi2c.c \
240 stm32f4xx_lptim.c \
241 stm32f4xx_qspi.c \
242 stm32f4xx_spdifrx.c \
243 stm32f4xx_cryp.c \
244 stm32f4xx_cryp_aes.c \
245 stm32f4xx_hash_md5.c \
246 stm32f4xx_cryp_des.c \
247 stm32f4xx_rtc.c \
248 stm32f4xx_hash.c \
249 stm32f4xx_dbgmcu.c \
250 stm32f4xx_cryp_tdes.c \
251 stm32f4xx_hash_sha1.c
254 ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS)))
255 EXCLUDES += stm32f4xx_fsmc.c
256 endif
258 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
260 #USB
261 USBCORE_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Core
262 USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/src/*.c))
263 USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver
264 USBOTG_SRC = $(notdir $(wildcard $(USBOTG_DIR)/src/*.c))
265 EXCLUDES = usb_bsp_template.c \
266 usb_conf_template.c \
267 usb_hcd_int.c \
268 usb_hcd.c \
269 usb_otg.c
271 USBOTG_SRC := $(filter-out ${EXCLUDES}, $(USBOTG_SRC))
272 USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc
273 USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/src/*.c))
274 EXCLUDES = usbd_cdc_if_template.c
275 USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
276 VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src
278 DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
279 $(USBOTG_SRC) \
280 $(USBCORE_SRC) \
281 $(USBCDC_SRC)
283 #CMSIS
284 VPATH := $(VPATH):$(CMSIS_DIR)/CM4/CoreSupport:$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx
285 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM4/CoreSupport/*.c \
286 $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx/*.c))
287 INCLUDE_DIRS := $(INCLUDE_DIRS) \
288 $(STDPERIPH_DIR)/inc \
289 $(USBOTG_DIR)/inc \
290 $(USBCORE_DIR)/inc \
291 $(USBCDC_DIR)/inc \
292 $(USBFS_DIR)/inc \
293 $(CMSIS_DIR)/CM4/CoreSupport \
294 $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \
295 $(ROOT)/src/main/vcpf4
297 ifneq ($(filter SDCARD,$(FEATURES)),)
298 INCLUDE_DIRS := $(INCLUDE_DIRS) \
299 $(FATFS_DIR)
300 VPATH := $(VPATH):$(FATFS_DIR)
301 endif
303 #Flags
304 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
306 ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS)))
307 DEVICE_FLAGS = -DSTM32F411xE
308 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld
309 else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS)))
310 DEVICE_FLAGS = -DSTM32F40_41xxx
311 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld
312 else
313 $(error Unknown MCU for F4 target)
314 endif
315 DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
317 # End F4 targets
319 # Start F7 targets
320 else ifeq ($(TARGET),$(filter $(TARGET), $(F7_TARGETS)))
322 #STDPERIPH
323 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F7xx_HAL_Driver
324 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c))
325 EXCLUDES = stm32f7xx_hal_timebase_rtc_wakeup_template.c \
326 stm32f7xx_hal_timebase_rtc_alarm_template.c \
327 stm32f7xx_hal_timebase_tim_template.c
329 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
331 #USB
332 USBCORE_DIR = $(ROOT)/lib/main/Middlewares/ST/STM32_USB_Device_Library/Core
333 USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c))
334 EXCLUDES = usbd_conf_template.c
335 USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC))
337 USBCDC_DIR = $(ROOT)/lib/main/Middlewares/ST/STM32_USB_Device_Library/Class/CDC
338 USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/Src/*.c))
339 EXCLUDES = usbd_cdc_if_template.c
340 USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
342 VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src
344 DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
345 $(USBCORE_SRC) \
346 $(USBCDC_SRC)
348 #CMSIS
349 VPATH := $(VPATH):$(CMSIS_DIR)/CM7/Include:$(CMSIS_DIR)/CM7/Device/ST/STM32F7xx
350 VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
351 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM7/Include/*.c \
352 $(CMSIS_DIR)/CM7/Device/ST/STM32F7xx/*.c))
353 INCLUDE_DIRS := $(INCLUDE_DIRS) \
354 $(STDPERIPH_DIR)/Inc \
355 $(USBCORE_DIR)/Inc \
356 $(USBCDC_DIR)/Inc \
357 $(CMSIS_DIR)/CM7/Include \
358 $(CMSIS_DIR)/CM7/Device/ST/STM32F7xx/Include \
359 $(ROOT)/src/main/vcp_hal
361 ifneq ($(filter SDCARD,$(FEATURES)),)
362 INCLUDE_DIRS := $(INCLUDE_DIRS) \
363 $(FATFS_DIR)
364 VPATH := $(VPATH):$(FATFS_DIR)
365 endif
367 #Flags
368 ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant -Wdouble-promotion
370 ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS)))
371 DEVICE_FLAGS = -DSTM32F745xx -DUSE_HAL_DRIVER -D__FPU_PRESENT
372 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f745.ld
373 else
374 $(error Unknown MCU for F7 target)
375 endif
376 DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
378 TARGET_FLAGS = -D$(TARGET)
380 # End F7 targets
382 # Start F1 targets
383 else
385 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
386 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
387 EXCLUDES = stm32f10x_crc.c \
388 stm32f10x_cec.c \
389 stm32f10x_can.c
391 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
393 # Search path and source files for the CMSIS sources
394 VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x
395 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \
396 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c))
398 INCLUDE_DIRS := $(INCLUDE_DIRS) \
399 $(STDPERIPH_DIR)/inc \
400 $(CMSIS_DIR)/CM3/CoreSupport \
401 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \
403 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
405 ifneq ($(filter VCP, $(FEATURES)),)
406 INCLUDE_DIRS := $(INCLUDE_DIRS) \
407 $(USBFS_DIR)/inc \
408 $(ROOT)/src/main/vcp
410 VPATH := $(VPATH):$(USBFS_DIR)/src
412 DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC) \
413 $(USBPERIPH_SRC)
415 endif
417 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld
418 ARCH_FLAGS = -mthumb -mcpu=cortex-m3
420 ifeq ($(DEVICE_FLAGS),)
421 DEVICE_FLAGS = -DSTM32F10X_MD
422 endif
423 DEVICE_FLAGS += -DSTM32F10X
425 endif
427 # End F1 targets
429 ifneq ($(BASE_TARGET), $(TARGET))
430 TARGET_FLAGS := $(TARGET_FLAGS) -D$(BASE_TARGET)
431 endif
433 ifneq ($(FLASH_SIZE),)
434 DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE)
435 endif
437 ifneq ($(HSE_VALUE),)
438 DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE)
439 endif
441 TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET)
442 TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
444 ifeq ($(OPBL),yes)
445 TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
446 ifeq ($(TARGET), $(filter $(TARGET),$(F405_TARGETS)))
447 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405_opbl.ld
448 else ifeq ($(TARGET), $(filter $(TARGET),$(F411_TARGETS)))
449 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411_opbl.ld
450 else ifeq ($(TARGET), $(filter $(TARGET),$(F3_TARGETS)))
451 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k_opbl.ld
452 else ifeq ($(TARGET), $(filter $(TARGET),$(F1_TARGETS)))
453 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld
454 endif
455 .DEFAULT_GOAL := binary
456 else
457 .DEFAULT_GOAL := hex
458 endif
460 INCLUDE_DIRS := $(INCLUDE_DIRS) \
461 $(ROOT)/lib/main/MAVLink
463 INCLUDE_DIRS := $(INCLUDE_DIRS) \
464 $(TARGET_DIR)
466 VPATH := $(VPATH):$(TARGET_DIR)
468 COMMON_SRC = \
469 build/build_config.c \
470 build/debug.c \
471 build/version.c \
472 $(TARGET_DIR_SRC) \
473 main.c \
474 common/encoding.c \
475 common/filter.c \
476 common/maths.c \
477 common/printf.c \
478 common/streambuf.c \
479 common/typeconversion.c \
480 config/config_eeprom.c \
481 config/feature.c \
482 config/parameter_group.c \
483 drivers/adc.c \
484 drivers/buf_writer.c \
485 drivers/bus_i2c_soft.c \
486 drivers/bus_spi.c \
487 drivers/bus_spi_soft.c \
488 drivers/exti.c \
489 drivers/gyro_sync.c \
490 drivers/io.c \
491 drivers/light_led.c \
492 drivers/rx_nrf24l01.c \
493 drivers/rx_spi.c \
494 drivers/rx_xn297.c \
495 drivers/pwm_output.c \
496 drivers/pwm_rx.c \
497 drivers/rcc.c \
498 drivers/serial.c \
499 drivers/serial_uart.c \
500 drivers/sound_beeper.c \
501 drivers/system.c \
502 drivers/timer.c \
503 fc/config.c \
504 fc/fc_tasks.c \
505 fc/fc_msp.c \
506 fc/mw.c \
507 fc/rc_controls.c \
508 fc/rc_curves.c \
509 fc/runtime_config.c \
510 flight/altitudehold.c \
511 flight/failsafe.c \
512 flight/imu.c \
513 flight/mixer.c \
514 flight/pid.c \
515 flight/servos.c \
516 io/beeper.c \
517 io/serial.c \
518 io/serial_4way.c \
519 io/serial_4way_avrootloader.c \
520 io/serial_4way_stk500v2.c \
521 io/serial_cli.c \
522 io/statusindicator.c \
523 msp/msp_serial.c \
524 rx/ibus.c \
525 rx/jetiexbus.c \
526 rx/msp.c \
527 rx/nrf24_cx10.c \
528 rx/nrf24_inav.c \
529 rx/nrf24_h8_3d.c \
530 rx/nrf24_syma.c \
531 rx/nrf24_v202.c \
532 rx/pwm.c \
533 rx/rx.c \
534 rx/rx_spi.c \
535 rx/sbus.c \
536 rx/spektrum.c \
537 rx/sumd.c \
538 rx/sumh.c \
539 rx/xbus.c \
540 scheduler/scheduler.c \
541 sensors/acceleration.c \
542 sensors/battery.c \
543 sensors/boardalignment.c \
544 sensors/compass.c \
545 sensors/gyro.c \
546 sensors/initialisation.c \
547 $(CMSIS_SRC) \
548 $(DEVICE_STDPERIPH_SRC)
550 HIGHEND_SRC = \
551 blackbox/blackbox.c \
552 blackbox/blackbox_io.c \
553 common/colorconversion.c \
554 drivers/display_ug2864hsweg01.c \
555 drivers/light_ws2811strip.c \
556 drivers/serial_escserial.c \
557 drivers/serial_softserial.c \
558 drivers/sonar_hcsr04.c \
559 flight/gtune.c \
560 flight/navigation.c \
561 flight/gps_conversion.c \
562 io/gps.c \
563 io/ledstrip.c \
564 io/display.c \
565 sensors/sonar.c \
566 sensors/barometer.c \
567 telemetry/telemetry.c \
568 telemetry/frsky.c \
569 telemetry/hott.c \
570 telemetry/smartport.c \
571 telemetry/ltm.c \
572 telemetry/mavlink.c
574 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
575 VCP_SRC = \
576 vcpf4/stm32f4xx_it.c \
577 vcpf4/usb_bsp.c \
578 vcpf4/usbd_desc.c \
579 vcpf4/usbd_usr.c \
580 vcpf4/usbd_cdc_vcp.c \
581 drivers/serial_usb_vcp.c
582 else ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS)))
583 VCP_SRC = \
584 vcp_hal/usbd_desc.c \
585 vcp_hal/usbd_conf.c \
586 vcp_hal/usbd_cdc_interface.c \
587 drivers/serial_usb_vcp_hal.c
588 else
589 VCP_SRC = \
590 vcp/hw_config.c \
591 vcp/stm32_it.c \
592 vcp/usb_desc.c \
593 vcp/usb_endp.c \
594 vcp/usb_istr.c \
595 vcp/usb_prop.c \
596 vcp/usb_pwr.c \
597 drivers/serial_usb_vcp.c \
598 drivers/usb_io.c
599 endif
601 STM32F10x_COMMON_SRC = \
602 startup_stm32f10x_md_gcc.S \
603 drivers/adc_stm32f10x.c \
604 drivers/bus_i2c_stm32f10x.c \
605 drivers/dma.c \
606 drivers/gpio_stm32f10x.c \
607 drivers/inverter.c \
608 drivers/light_ws2811strip_stm32f10x.c \
609 drivers/serial_uart_stm32f10x.c \
610 drivers/system_stm32f10x.c \
611 drivers/timer_stm32f10x.c
613 STM32F30x_COMMON_SRC = \
614 startup_stm32f30x_md_gcc.S \
615 target/system_stm32f30x.c \
616 drivers/adc_stm32f30x.c \
617 drivers/bus_i2c_stm32f30x.c \
618 drivers/dma.c \
619 drivers/gpio_stm32f30x.c \
620 drivers/light_ws2811strip_stm32f30x.c \
621 drivers/pwm_output_stm32f3xx.c \
622 drivers/serial_uart_stm32f30x.c \
623 drivers/system_stm32f30x.c \
624 drivers/timer_stm32f30x.c
626 STM32F4xx_COMMON_SRC = \
627 startup_stm32f40xx.s \
628 target/system_stm32f4xx.c \
629 drivers/accgyro_mpu.c \
630 drivers/adc_stm32f4xx.c \
631 drivers/bus_i2c_stm32f10x.c \
632 drivers/dma_stm32f4xx.c \
633 drivers/gpio_stm32f4xx.c \
634 drivers/inverter.c \
635 drivers/light_ws2811strip_stm32f4xx.c \
636 drivers/pwm_output_stm32f4xx.c \
637 drivers/serial_uart_stm32f4xx.c \
638 drivers/system_stm32f4xx.c \
639 drivers/timer_stm32f4xx.c
641 STM32F7xx_COMMON_SRC = \
642 startup_stm32f745xx.s \
643 target/system_stm32f7xx.c \
644 drivers/accgyro_mpu.c \
645 drivers/adc_stm32f7xx.c \
646 drivers/bus_i2c_hal.c \
647 drivers/dma_stm32f7xx.c \
648 drivers/gpio_stm32f7xx.c \
649 drivers/inverter.c \
650 drivers/bus_spi_hal.c \
651 drivers/pwm_output_stm32f7xx.c \
652 drivers/timer_hal.c \
653 drivers/timer_stm32f7xx.c \
654 drivers/pwm_output_hal.c \
655 drivers/system_stm32f7xx.c \
656 drivers/serial_uart_stm32f7xx.c \
657 drivers/serial_uart_hal.c
659 F7EXCLUDES = drivers/bus_spi.c \
660 drivers/bus_i2c.c \
661 drivers/timer.c \
662 drivers/pwm_output.c \
663 drivers/serial_uart.c
665 # check if target.mk supplied
666 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
667 TARGET_SRC := $(STM32F4xx_COMMON_SRC) $(TARGET_SRC)
668 else ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS)))
669 TARGET_SRC := $(STM32F7xx_COMMON_SRC) $(TARGET_SRC)
670 else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
671 TARGET_SRC := $(STM32F30x_COMMON_SRC) $(TARGET_SRC)
672 else ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
673 TARGET_SRC := $(STM32F10x_COMMON_SRC) $(TARGET_SRC)
674 endif
676 ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
677 TARGET_SRC += \
678 drivers/flash_m25p16.c \
679 io/flashfs.c
680 endif
682 ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS) $(F4_TARGETS) $(F3_TARGETS)))
683 TARGET_SRC += $(HIGHEND_SRC)
684 else ifneq ($(filter HIGHEND,$(FEATURES)),)
685 TARGET_SRC += $(HIGHEND_SRC)
686 endif
688 TARGET_SRC += $(COMMON_SRC)
689 #excludes
690 ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS)))
691 TARGET_SRC := $(filter-out ${F7EXCLUDES}, $(TARGET_SRC))
692 endif
694 ifneq ($(filter SDCARD,$(FEATURES)),)
695 TARGET_SRC += \
696 drivers/sdcard.c \
697 drivers/sdcard_standard.c \
698 io/asyncfatfs/asyncfatfs.c \
699 io/asyncfatfs/fat_standard.c
700 endif
702 ifneq ($(filter VCP,$(FEATURES)),)
703 TARGET_SRC += $(VCP_SRC)
704 endif
705 # end target specific make file checks
708 # Search path and source files for the ST stdperiph library
709 VPATH := $(VPATH):$(STDPERIPH_DIR)/src
711 ###############################################################################
712 # Things that might need changing to use different tools
715 # Find out if ccache is installed on the system
716 CCACHE := ccache
717 RESULT = $(shell (which $(CCACHE) > /dev/null 2>&1; echo $$?) )
718 ifneq ($(RESULT),0)
719 CCACHE :=
720 endif
722 # Tool names
723 CC := $(CCACHE) $(ARM_SDK_PREFIX)gcc
724 CPP := $(CCACHE) $(ARM_SDK_PREFIX)g++
725 OBJCOPY := $(ARM_SDK_PREFIX)objcopy
726 SIZE := $(ARM_SDK_PREFIX)size
729 # Tool options.
732 ifeq ($(DEBUG),GDB)
733 OPTIMIZE = -O0
734 LTO_FLAGS = $(OPTIMIZE)
735 else
736 OPTIMIZE = -Os
737 LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
738 endif
740 DEBUG_FLAGS = -ggdb3 -DDEBUG
742 CFLAGS += $(ARCH_FLAGS) \
743 $(LTO_FLAGS) \
744 $(addprefix -D,$(OPTIONS)) \
745 $(addprefix -I,$(INCLUDE_DIRS)) \
746 $(DEBUG_FLAGS) \
747 -std=gnu99 \
748 -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \
749 -ffunction-sections \
750 -fdata-sections \
751 -pedantic \
752 $(DEVICE_FLAGS) \
753 -DUSE_STDPERIPH_DRIVER \
754 -D$(TARGET) \
755 $(TARGET_FLAGS) \
756 -D'__FORKNAME__="$(FORKNAME)"' \
757 -D'__TARGET__="$(TARGET)"' \
758 -D'__REVISION__="$(REVISION)"' \
759 -save-temps=obj \
760 -MMD -MP
762 ASFLAGS = $(ARCH_FLAGS) \
763 -x assembler-with-cpp \
764 $(addprefix -I,$(INCLUDE_DIRS)) \
765 -MMD -MP
767 LDFLAGS = -lm \
768 -nostartfiles \
769 --specs=nano.specs \
770 -lc \
771 -lnosys \
772 $(ARCH_FLAGS) \
773 $(LTO_FLAGS) \
774 $(DEBUG_FLAGS) \
775 -static \
776 -Wl,-gc-sections,-Map,$(TARGET_MAP) \
777 -Wl,-L$(LINKER_DIR) \
778 -Wl,--cref \
779 -Wl,--no-wchar-size-warning \
780 -T$(LD_SCRIPT)
782 ###############################################################################
783 # No user-serviceable parts below
784 ###############################################################################
786 CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \
787 --std=c99 --inline-suppr --quiet --force \
788 $(addprefix -I,$(INCLUDE_DIRS)) \
789 -I/usr/include -I/usr/include/linux
792 # Things we will build
794 TARGET_BIN = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).bin
795 TARGET_HEX = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).hex
796 TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
797 TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC))))
798 TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC))))
799 TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
802 CLEAN_ARTIFACTS := $(TARGET_BIN)
803 CLEAN_ARTIFACTS += $(TARGET_HEX)
804 CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
806 # List of buildable ELF files and their object dependencies.
807 # It would be nice to compute these lists, but that seems to be just beyond make.
809 $(TARGET_HEX): $(TARGET_ELF)
810 $(V0) $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
812 $(TARGET_BIN): $(TARGET_ELF)
813 $(V0) $(OBJCOPY) -O binary $< $@
815 $(TARGET_ELF): $(TARGET_OBJS)
816 $(V1) echo LD $(notdir $@)
817 $(V1) $(CC) -o $@ $^ $(LDFLAGS)
818 $(V0) $(SIZE) $(TARGET_ELF)
820 # Compile
821 $(OBJECT_DIR)/$(TARGET)/%.o: %.c
822 $(V1) mkdir -p $(dir $@)
823 $(V1) echo %% $(notdir $<)
824 $(V1) $(CC) -c -o $@ $(CFLAGS) $<
826 # Assemble
827 $(OBJECT_DIR)/$(TARGET)/%.o: %.s
828 $(V1) mkdir -p $(dir $@)
829 $(V1) echo %% $(notdir $<)
830 $(V1) $(CC) -c -o $@ $(ASFLAGS) $<
832 $(OBJECT_DIR)/$(TARGET)/%.o: %.S
833 $(V1) mkdir -p $(dir $@)
834 $(V1) echo %% $(notdir $<)
835 $(V1) $(CC) -c -o $@ $(ASFLAGS) $<
837 ## sample : Build all sample (travis) targets
838 sample: $(SAMPLE_TARGETS)
840 ## all : Build all valid targets
841 all: $(VALID_TARGETS)
843 $(VALID_TARGETS):
844 $(V0) echo "" && \
845 echo "Building $@" && \
846 $(MAKE) binary hex TARGET=$@ && \
847 echo "Building $@ succeeded."
851 CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
852 TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
854 ## clean : clean up temporary / machine-generated files
855 clean:
856 $(V0) echo "Cleaning $(TARGET)"
857 $(V0) rm -f $(CLEAN_ARTIFACTS)
858 $(V0) rm -rf $(OBJECT_DIR)/$(TARGET)
859 $(V0) echo "Cleaning $(TARGET) succeeded."
861 ## clean_test : clean up temporary / machine-generated files (tests)
862 clean_test:
863 $(V0) cd src/test && $(MAKE) clean || true
865 ## clean_<TARGET> : clean up one specific target
866 $(CLEAN_TARGETS) :
867 $(V0) $(MAKE) -j TARGET=$(subst clean_,,$@) clean
869 ## <TARGET>_clean : clean up one specific target (alias for above)
870 $(TARGETS_CLEAN) :
871 $(V0) $(MAKE) -j TARGET=$(subst _clean,,$@) clean
873 ## clean_all : clean all valid targets
874 clean_all:$(CLEAN_TARGETS)
876 ## all_clean : clean all valid targets (alias for above)
877 all_clean:$(TARGETS_CLEAN)
880 flash_$(TARGET): $(TARGET_HEX)
881 $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
882 $(V0) echo -n 'R' >$(SERIAL_DEVICE)
883 $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
885 ## flash : flash firmware (.hex) onto flight controller
886 flash: flash_$(TARGET)
888 st-flash_$(TARGET): $(TARGET_BIN)
889 $(V0) st-flash --reset write $< 0x08000000
891 ## st-flash : flash firmware (.bin) onto flight controller
892 st-flash: st-flash_$(TARGET)
894 binary:
895 $(V0) $(MAKE) -j $(TARGET_BIN)
897 hex:
898 $(V0) $(MAKE) -j $(TARGET_HEX)
900 unbrick_$(TARGET): $(TARGET_HEX)
901 $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
902 $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
904 ## unbrick : unbrick flight controller
905 unbrick: unbrick_$(TARGET)
907 ## cppcheck : run static analysis on C source code
908 cppcheck: $(CSOURCES)
909 $(V0) $(CPPCHECK)
911 cppcheck-result.xml: $(CSOURCES)
912 $(V0) $(CPPCHECK) --xml-version=2 2> cppcheck-result.xml
914 # mkdirs
915 $(DL_DIR):
916 mkdir -p $@
918 $(TOOLS_DIR):
919 mkdir -p $@
921 $(BUILD_DIR):
922 mkdir -p $@
924 ## help : print this help message and exit
925 help: Makefile make/tools.mk
926 $(V0) @echo ""
927 $(V0) @echo "Makefile for the $(FORKNAME) firmware"
928 $(V0) @echo ""
929 $(V0) @echo "Usage:"
930 $(V0) @echo " make [V=<verbosity>] [TARGET=<target>] [OPTIONS=\"<options>\"]"
931 $(V0) @echo "Or:"
932 $(V0) @echo " make <target> [V=<verbosity>] [OPTIONS=\"<options>\"]"
933 $(V0) @echo ""
934 $(V0) @echo "Valid TARGET values are: $(VALID_TARGETS)"
935 $(V0) @echo ""
936 $(V0) @sed -n 's/^## //p' $?
938 ## targets : print a list of all valid target platforms (for consumption by scripts)
939 targets:
940 $(V0) @echo "Valid targets: $(VALID_TARGETS)"
941 $(V0) @echo "Target: $(TARGET)"
942 $(V0) @echo "Base target: $(BASE_TARGET)"
944 ## test : run the cleanflight test suite
945 ## junittest : run the cleanflight test suite, producing Junit XML result files.
946 test junittest:
947 $(V0) cd src/test && $(MAKE) $@ || true
949 # rebuild everything when makefile changes
950 $(TARGET_OBJS) : Makefile
952 # include auto-generated dependencies
953 -include $(TARGET_DEPS)