Fixes for NAZE (and potentially other target) uart issues
[betaflight.git] / Makefile
blobfa0c53e5adef3ac6472aea2c8db53aca4f27ebf1
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 REVISION = $(shell git log -1 --format="%h")
163 FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/build/version.h | awk '{print $$3}' )
164 FC_VER_MINOR := $(shell grep " FC_VERSION_MINOR" src/main/build/version.h | awk '{print $$3}' )
165 FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/build/version.h | awk '{print $$3}' )
167 FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH)
169 # Search path for sources
170 VPATH := $(SRC_DIR):$(SRC_DIR)/startup
171 USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver
172 USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c))
173 FATFS_DIR = $(ROOT)/lib/main/FatFS
174 FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c))
176 CSOURCES := $(shell find $(SRC_DIR) -name '*.c')
178 ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
179 # F3 TARGETS
181 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
182 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
183 EXCLUDES = stm32f30x_crc.c \
184 stm32f30x_can.c
186 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
187 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
189 VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
190 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM1/CoreSupport/*.c \
191 $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c))
193 INCLUDE_DIRS := $(INCLUDE_DIRS) \
194 $(STDPERIPH_DIR)/inc \
195 $(CMSIS_DIR)/CM1/CoreSupport \
196 $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
198 ifneq ($(filter VCP, $(FEATURES)),)
199 INCLUDE_DIRS := $(INCLUDE_DIRS) \
200 $(USBFS_DIR)/inc \
201 $(ROOT)/src/main/vcp
203 VPATH := $(VPATH):$(USBFS_DIR)/src
205 DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\
206 $(USBPERIPH_SRC)
207 endif
209 ifneq ($(filter SDCARD, $(FEATURES)),)
210 INCLUDE_DIRS := $(INCLUDE_DIRS) \
211 $(FATFS_DIR) \
213 VPATH := $(VPATH):$(FATFS_DIR)
214 endif
216 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld
218 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
219 DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
220 # End F3 targets
222 # Start F4 targets
223 else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS)))
225 #STDPERIPH
226 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4xx_StdPeriph_Driver
227 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
228 EXCLUDES = stm32f4xx_crc.c \
229 stm32f4xx_can.c \
230 stm32f4xx_fmc.c \
231 stm32f4xx_sai.c \
232 stm32f4xx_cec.c \
233 stm32f4xx_dsi.c \
234 stm32f4xx_flash_ramfunc.c \
235 stm32f4xx_fmpi2c.c \
236 stm32f4xx_lptim.c \
237 stm32f4xx_qspi.c \
238 stm32f4xx_spdifrx.c \
239 stm32f4xx_cryp.c \
240 stm32f4xx_cryp_aes.c \
241 stm32f4xx_hash_md5.c \
242 stm32f4xx_cryp_des.c \
243 stm32f4xx_rtc.c \
244 stm32f4xx_hash.c \
245 stm32f4xx_dbgmcu.c \
246 stm32f4xx_cryp_tdes.c \
247 stm32f4xx_hash_sha1.c
250 ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS)))
251 EXCLUDES += stm32f4xx_fsmc.c
252 endif
254 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
256 #USB
257 USBCORE_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Core
258 USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/src/*.c))
259 USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver
260 USBOTG_SRC = $(notdir $(wildcard $(USBOTG_DIR)/src/*.c))
261 EXCLUDES = usb_bsp_template.c \
262 usb_conf_template.c \
263 usb_hcd_int.c \
264 usb_hcd.c \
265 usb_otg.c
267 USBOTG_SRC := $(filter-out ${EXCLUDES}, $(USBOTG_SRC))
268 USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc
269 USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/src/*.c))
270 EXCLUDES = usbd_cdc_if_template.c
271 USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
272 VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src
274 DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
275 $(USBOTG_SRC) \
276 $(USBCORE_SRC) \
277 $(USBCDC_SRC)
279 #CMSIS
280 VPATH := $(VPATH):$(CMSIS_DIR)/CM4/CoreSupport:$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx
281 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM4/CoreSupport/*.c \
282 $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx/*.c))
283 INCLUDE_DIRS := $(INCLUDE_DIRS) \
284 $(STDPERIPH_DIR)/inc \
285 $(USBOTG_DIR)/inc \
286 $(USBCORE_DIR)/inc \
287 $(USBCDC_DIR)/inc \
288 $(USBFS_DIR)/inc \
289 $(CMSIS_DIR)/CM4/CoreSupport \
290 $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \
291 $(ROOT)/src/main/vcpf4
293 ifneq ($(filter SDCARD,$(FEATURES)),)
294 INCLUDE_DIRS := $(INCLUDE_DIRS) \
295 $(FATFS_DIR)
296 VPATH := $(VPATH):$(FATFS_DIR)
297 endif
299 #Flags
300 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
302 ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS)))
303 DEVICE_FLAGS = -DSTM32F411xE
304 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld
305 else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS)))
306 DEVICE_FLAGS = -DSTM32F40_41xxx
307 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld
308 else
309 $(error Unknown MCU for F4 target)
310 endif
311 DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
313 # End F4 targets
315 # Start F7 targets
316 else ifeq ($(TARGET),$(filter $(TARGET), $(F7_TARGETS)))
318 #STDPERIPH
319 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F7xx_HAL_Driver
320 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c))
321 EXCLUDES = stm32f7xx_hal_timebase_rtc_wakeup_template.c \
322 stm32f7xx_hal_timebase_rtc_alarm_template.c \
323 stm32f7xx_hal_timebase_tim_template.c
325 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
327 #USB
328 USBCORE_DIR = $(ROOT)/lib/main/Middlewares/ST/STM32_USB_Device_Library/Core
329 USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c))
330 EXCLUDES = usbd_conf_template.c
331 USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC))
333 USBCDC_DIR = $(ROOT)/lib/main/Middlewares/ST/STM32_USB_Device_Library/Class/CDC
334 USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/Src/*.c))
335 EXCLUDES = usbd_cdc_if_template.c
336 USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
338 VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src
340 DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
341 $(USBCORE_SRC) \
342 $(USBCDC_SRC)
344 #CMSIS
345 VPATH := $(VPATH):$(CMSIS_DIR)/CM7/Include:$(CMSIS_DIR)/CM7/Device/ST/STM32F7xx
346 VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
347 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM7/Include/*.c \
348 $(CMSIS_DIR)/CM7/Device/ST/STM32F7xx/*.c))
349 INCLUDE_DIRS := $(INCLUDE_DIRS) \
350 $(STDPERIPH_DIR)/Inc \
351 $(USBCORE_DIR)/Inc \
352 $(USBCDC_DIR)/Inc \
353 $(CMSIS_DIR)/CM7/Include \
354 $(CMSIS_DIR)/CM7/Device/ST/STM32F7xx/Include \
355 $(ROOT)/src/main/vcp_hal
357 ifneq ($(filter SDCARD,$(FEATURES)),)
358 INCLUDE_DIRS := $(INCLUDE_DIRS) \
359 $(FATFS_DIR)
360 VPATH := $(VPATH):$(FATFS_DIR)
361 endif
363 #Flags
364 ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant -Wdouble-promotion
366 ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS)))
367 DEVICE_FLAGS = -DSTM32F745xx -DUSE_HAL_DRIVER -D__FPU_PRESENT -DDEBUG_HARDFAULTS
368 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f745.ld
369 else
370 $(error Unknown MCU for F7 target)
371 endif
372 DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
374 TARGET_FLAGS = -D$(TARGET)
376 # End F7 targets
378 # Start F1 targets
379 else
381 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
382 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
383 EXCLUDES = stm32f10x_crc.c \
384 stm32f10x_cec.c \
385 stm32f10x_can.c
387 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
389 # Search path and source files for the CMSIS sources
390 VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x
391 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \
392 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c))
394 INCLUDE_DIRS := $(INCLUDE_DIRS) \
395 $(STDPERIPH_DIR)/inc \
396 $(CMSIS_DIR)/CM3/CoreSupport \
397 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \
399 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
401 ifneq ($(filter VCP, $(FEATURES)),)
402 INCLUDE_DIRS := $(INCLUDE_DIRS) \
403 $(USBFS_DIR)/inc \
404 $(ROOT)/src/main/vcp
406 VPATH := $(VPATH):$(USBFS_DIR)/src
408 DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC) \
409 $(USBPERIPH_SRC)
411 endif
413 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld
414 ARCH_FLAGS = -mthumb -mcpu=cortex-m3
416 ifeq ($(DEVICE_FLAGS),)
417 DEVICE_FLAGS = -DSTM32F10X_MD
418 endif
419 DEVICE_FLAGS += -DSTM32F10X
421 endif
423 # End F1 targets
425 ifneq ($(BASE_TARGET), $(TARGET))
426 TARGET_FLAGS := $(TARGET_FLAGS) -D$(BASE_TARGET)
427 endif
429 ifneq ($(FLASH_SIZE),)
430 DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE)
431 endif
433 ifneq ($(HSE_VALUE),)
434 DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE)
435 endif
437 TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET)
438 TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
440 ifeq ($(OPBL),yes)
441 TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
442 ifeq ($(TARGET), $(filter $(TARGET),$(F405_TARGETS)))
443 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405_opbl.ld
444 else ifeq ($(TARGET), $(filter $(TARGET),$(F411_TARGETS)))
445 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411_opbl.ld
446 else ifeq ($(TARGET), $(filter $(TARGET),$(F3_TARGETS)))
447 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k_opbl.ld
448 else ifeq ($(TARGET), $(filter $(TARGET),$(F1_TARGETS)))
449 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld
450 endif
451 .DEFAULT_GOAL := binary
452 else
453 .DEFAULT_GOAL := hex
454 endif
456 INCLUDE_DIRS := $(INCLUDE_DIRS) \
457 $(ROOT)/lib/main/MAVLink
459 INCLUDE_DIRS := $(INCLUDE_DIRS) \
460 $(TARGET_DIR)
462 VPATH := $(VPATH):$(TARGET_DIR)
464 COMMON_SRC = \
465 build/build_config.c \
466 build/debug.c \
467 build/version.c \
468 $(TARGET_DIR_SRC) \
469 main.c \
470 common/encoding.c \
471 common/filter.c \
472 common/maths.c \
473 common/printf.c \
474 common/streambuf.c \
475 common/typeconversion.c \
476 config/config_eeprom.c \
477 config/feature.c \
478 config/parameter_group.c \
479 drivers/adc.c \
480 drivers/buf_writer.c \
481 drivers/bus_i2c_soft.c \
482 drivers/bus_spi.c \
483 drivers/bus_spi_soft.c \
484 drivers/exti.c \
485 drivers/gyro_sync.c \
486 drivers/io.c \
487 drivers/light_led.c \
488 drivers/rx_nrf24l01.c \
489 drivers/rx_spi.c \
490 drivers/rx_xn297.c \
491 drivers/pwm_output.c \
492 drivers/pwm_rx.c \
493 drivers/rcc.c \
494 drivers/serial.c \
495 drivers/serial_uart.c \
496 drivers/sound_beeper.c \
497 drivers/system.c \
498 drivers/timer.c \
499 fc/config.c \
500 fc/fc_tasks.c \
501 fc/fc_msp.c \
502 fc/mw.c \
503 fc/rc_controls.c \
504 fc/rc_curves.c \
505 fc/runtime_config.c \
506 flight/altitudehold.c \
507 flight/failsafe.c \
508 flight/imu.c \
509 flight/mixer.c \
510 flight/pid.c \
511 io/beeper.c \
512 io/serial.c \
513 io/serial_4way.c \
514 io/serial_4way_avrootloader.c \
515 io/serial_4way_stk500v2.c \
516 io/serial_cli.c \
517 io/statusindicator.c \
518 msp/msp_serial.c \
519 rx/ibus.c \
520 rx/jetiexbus.c \
521 rx/msp.c \
522 rx/nrf24_cx10.c \
523 rx/nrf24_inav.c \
524 rx/nrf24_h8_3d.c \
525 rx/nrf24_syma.c \
526 rx/nrf24_v202.c \
527 rx/pwm.c \
528 rx/rx.c \
529 rx/rx_spi.c \
530 rx/sbus.c \
531 rx/spektrum.c \
532 rx/sumd.c \
533 rx/sumh.c \
534 rx/xbus.c \
535 scheduler/scheduler.c \
536 sensors/acceleration.c \
537 sensors/battery.c \
538 sensors/boardalignment.c \
539 sensors/compass.c \
540 sensors/gyro.c \
541 sensors/initialisation.c \
542 $(CMSIS_SRC) \
543 $(DEVICE_STDPERIPH_SRC)
545 HIGHEND_SRC = \
546 blackbox/blackbox.c \
547 blackbox/blackbox_io.c \
548 common/colorconversion.c \
549 drivers/display_ug2864hsweg01.c \
550 drivers/light_ws2811strip.c \
551 drivers/serial_escserial.c \
552 drivers/serial_softserial.c \
553 drivers/sonar_hcsr04.c \
554 flight/gtune.c \
555 flight/navigation.c \
556 flight/gps_conversion.c \
557 io/gps.c \
558 io/ledstrip.c \
559 io/display.c \
560 sensors/sonar.c \
561 sensors/barometer.c \
562 telemetry/telemetry.c \
563 telemetry/frsky.c \
564 telemetry/hott.c \
565 telemetry/smartport.c \
566 telemetry/ltm.c \
567 telemetry/mavlink.c
569 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
570 VCP_SRC = \
571 vcpf4/stm32f4xx_it.c \
572 vcpf4/usb_bsp.c \
573 vcpf4/usbd_desc.c \
574 vcpf4/usbd_usr.c \
575 vcpf4/usbd_cdc_vcp.c \
576 drivers/serial_usb_vcp.c
577 else ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS)))
578 VCP_SRC = \
579 vcp_hal/usbd_desc.c \
580 vcp_hal/usbd_conf.c \
581 vcp_hal/usbd_cdc_interface.c \
582 drivers/serial_usb_vcp_hal.c
583 else
584 VCP_SRC = \
585 vcp/hw_config.c \
586 vcp/stm32_it.c \
587 vcp/usb_desc.c \
588 vcp/usb_endp.c \
589 vcp/usb_istr.c \
590 vcp/usb_prop.c \
591 vcp/usb_pwr.c \
592 drivers/serial_usb_vcp.c \
593 drivers/usb_io.c
594 endif
596 STM32F10x_COMMON_SRC = \
597 startup_stm32f10x_md_gcc.S \
598 drivers/adc_stm32f10x.c \
599 drivers/bus_i2c_stm32f10x.c \
600 drivers/dma.c \
601 drivers/gpio_stm32f10x.c \
602 drivers/inverter.c \
603 drivers/light_ws2811strip_stm32f10x.c \
604 drivers/serial_uart_stm32f10x.c \
605 drivers/system_stm32f10x.c \
606 drivers/timer_stm32f10x.c
608 STM32F30x_COMMON_SRC = \
609 startup_stm32f30x_md_gcc.S \
610 target/system_stm32f30x.c \
611 drivers/adc_stm32f30x.c \
612 drivers/bus_i2c_stm32f30x.c \
613 drivers/dma.c \
614 drivers/gpio_stm32f30x.c \
615 drivers/light_ws2811strip_stm32f30x.c \
616 drivers/pwm_output_stm32f3xx.c \
617 drivers/serial_uart_stm32f30x.c \
618 drivers/system_stm32f30x.c \
619 drivers/timer_stm32f30x.c
621 STM32F4xx_COMMON_SRC = \
622 startup_stm32f40xx.s \
623 target/system_stm32f4xx.c \
624 drivers/accgyro_mpu.c \
625 drivers/adc_stm32f4xx.c \
626 drivers/bus_i2c_stm32f10x.c \
627 drivers/dma_stm32f4xx.c \
628 drivers/gpio_stm32f4xx.c \
629 drivers/inverter.c \
630 drivers/light_ws2811strip_stm32f4xx.c \
631 drivers/pwm_output_stm32f4xx.c \
632 drivers/serial_uart_stm32f4xx.c \
633 drivers/system_stm32f4xx.c \
634 drivers/timer_stm32f4xx.c
636 STM32F7xx_COMMON_SRC = \
637 startup_stm32f745xx.s \
638 target/system_stm32f7xx.c \
639 drivers/accgyro_mpu.c \
640 drivers/adc_stm32f7xx.c \
641 drivers/bus_i2c_hal.c \
642 drivers/dma_stm32f7xx.c \
643 drivers/gpio_stm32f7xx.c \
644 drivers/inverter.c \
645 drivers/bus_spi_hal.c \
646 drivers/pwm_output_stm32f7xx.c \
647 drivers/timer_hal.c \
648 drivers/timer_stm32f7xx.c \
649 drivers/pwm_output_hal.c \
650 drivers/system_stm32f7xx.c \
651 drivers/serial_uart_stm32f7xx.c \
652 drivers/serial_uart_hal.c
654 F7EXCLUDES = drivers/bus_spi.c \
655 drivers/bus_i2c.c \
656 drivers/timer.c \
657 drivers/pwm_output.c \
658 drivers/serial_uart.c
660 # check if target.mk supplied
661 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
662 TARGET_SRC := $(STM32F4xx_COMMON_SRC) $(TARGET_SRC)
663 else ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS)))
664 TARGET_SRC := $(STM32F7xx_COMMON_SRC) $(TARGET_SRC)
665 else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
666 TARGET_SRC := $(STM32F30x_COMMON_SRC) $(TARGET_SRC)
667 else ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
668 TARGET_SRC := $(STM32F10x_COMMON_SRC) $(TARGET_SRC)
669 endif
671 ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
672 TARGET_SRC += \
673 drivers/flash_m25p16.c \
674 io/flashfs.c
675 endif
677 ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS) $(F4_TARGETS) $(F3_TARGETS)))
678 TARGET_SRC += $(HIGHEND_SRC)
679 else ifneq ($(filter HIGHEND,$(FEATURES)),)
680 TARGET_SRC += $(HIGHEND_SRC)
681 endif
683 TARGET_SRC += $(COMMON_SRC)
684 #excludes
685 ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS)))
686 TARGET_SRC := $(filter-out ${F7EXCLUDES}, $(TARGET_SRC))
687 endif
689 ifneq ($(filter SDCARD,$(FEATURES)),)
690 TARGET_SRC += \
691 drivers/sdcard.c \
692 drivers/sdcard_standard.c \
693 io/asyncfatfs/asyncfatfs.c \
694 io/asyncfatfs/fat_standard.c
695 endif
697 ifneq ($(filter VCP,$(FEATURES)),)
698 TARGET_SRC += $(VCP_SRC)
699 endif
700 # end target specific make file checks
703 # Search path and source files for the ST stdperiph library
704 VPATH := $(VPATH):$(STDPERIPH_DIR)/src
706 ###############################################################################
707 # Things that might need changing to use different tools
710 # Find out if ccache is installed on the system
711 CCACHE := ccache
712 RESULT = $(shell (which $(CCACHE) > /dev/null 2>&1; echo $$?) )
713 ifneq ($(RESULT),0)
714 CCACHE :=
715 endif
717 # Tool names
718 CC := $(CCACHE) $(ARM_SDK_PREFIX)gcc
719 CPP := $(CCACHE) $(ARM_SDK_PREFIX)g++
720 OBJCOPY := $(ARM_SDK_PREFIX)objcopy
721 SIZE := $(ARM_SDK_PREFIX)size
724 # Tool options.
727 ifeq ($(DEBUG),GDB)
728 OPTIMIZE = -O0
729 LTO_FLAGS = $(OPTIMIZE)
730 else
731 OPTIMIZE = -Os
732 LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
733 endif
735 DEBUG_FLAGS = -ggdb3 -DDEBUG
737 CFLAGS += $(ARCH_FLAGS) \
738 $(LTO_FLAGS) \
739 $(addprefix -D,$(OPTIONS)) \
740 $(addprefix -I,$(INCLUDE_DIRS)) \
741 $(DEBUG_FLAGS) \
742 -std=gnu99 \
743 -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \
744 -ffunction-sections \
745 -fdata-sections \
746 -pedantic \
747 $(DEVICE_FLAGS) \
748 -DUSE_STDPERIPH_DRIVER \
749 -D$(TARGET) \
750 $(TARGET_FLAGS) \
751 -D'__FORKNAME__="$(FORKNAME)"' \
752 -D'__TARGET__="$(TARGET)"' \
753 -D'__REVISION__="$(REVISION)"' \
754 -save-temps=obj \
755 -MMD -MP
757 ASFLAGS = $(ARCH_FLAGS) \
758 -x assembler-with-cpp \
759 $(addprefix -I,$(INCLUDE_DIRS)) \
760 -MMD -MP
762 LDFLAGS = -lm \
763 -nostartfiles \
764 --specs=nano.specs \
765 -lc \
766 -lnosys \
767 $(ARCH_FLAGS) \
768 $(LTO_FLAGS) \
769 $(DEBUG_FLAGS) \
770 -static \
771 -Wl,-gc-sections,-Map,$(TARGET_MAP) \
772 -Wl,-L$(LINKER_DIR) \
773 -Wl,--cref \
774 -Wl,--no-wchar-size-warning \
775 -T$(LD_SCRIPT)
777 ###############################################################################
778 # No user-serviceable parts below
779 ###############################################################################
781 CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \
782 --std=c99 --inline-suppr --quiet --force \
783 $(addprefix -I,$(INCLUDE_DIRS)) \
784 -I/usr/include -I/usr/include/linux
787 # Things we will build
789 TARGET_BIN = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).bin
790 TARGET_HEX = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).hex
791 TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
792 TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC))))
793 TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC))))
794 TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
797 CLEAN_ARTIFACTS := $(TARGET_BIN)
798 CLEAN_ARTIFACTS += $(TARGET_HEX)
799 CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
801 # List of buildable ELF files and their object dependencies.
802 # It would be nice to compute these lists, but that seems to be just beyond make.
804 $(TARGET_HEX): $(TARGET_ELF)
805 $(V0) $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
807 $(TARGET_BIN): $(TARGET_ELF)
808 $(V0) $(OBJCOPY) -O binary $< $@
810 $(TARGET_ELF): $(TARGET_OBJS)
811 $(V1) echo LD $(notdir $@)
812 $(V1) $(CC) -o $@ $^ $(LDFLAGS)
813 $(V0) $(SIZE) $(TARGET_ELF)
815 # Compile
816 $(OBJECT_DIR)/$(TARGET)/%.o: %.c
817 $(V1) mkdir -p $(dir $@)
818 $(V1) echo %% $(notdir $<)
819 $(V1) $(CC) -c -o $@ $(CFLAGS) $<
821 # Assemble
822 $(OBJECT_DIR)/$(TARGET)/%.o: %.s
823 $(V1) mkdir -p $(dir $@)
824 $(V1) echo %% $(notdir $<)
825 $(V1) $(CC) -c -o $@ $(ASFLAGS) $<
827 $(OBJECT_DIR)/$(TARGET)/%.o: %.S
828 $(V1) mkdir -p $(dir $@)
829 $(V1) echo %% $(notdir $<)
830 $(V1) $(CC) -c -o $@ $(ASFLAGS) $<
832 ## sample : Build all sample (travis) targets
833 sample: $(SAMPLE_TARGETS)
835 ## all : Build all valid targets
836 all: $(VALID_TARGETS)
838 $(VALID_TARGETS):
839 $(V0) echo "" && \
840 echo "Building $@" && \
841 $(MAKE) binary hex TARGET=$@ && \
842 echo "Building $@ succeeded."
846 CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
847 TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
849 ## clean : clean up temporary / machine-generated files
850 clean:
851 $(V0) echo "Cleaning $(TARGET)"
852 $(V0) rm -f $(CLEAN_ARTIFACTS)
853 $(V0) rm -rf $(OBJECT_DIR)/$(TARGET)
854 $(V0) echo "Cleaning $(TARGET) succeeded."
856 ## clean_test : clean up temporary / machine-generated files (tests)
857 clean_test:
858 $(V0) cd src/test && $(MAKE) clean || true
860 ## clean_<TARGET> : clean up one specific target
861 $(CLEAN_TARGETS) :
862 $(V0) $(MAKE) -j TARGET=$(subst clean_,,$@) clean
864 ## <TARGET>_clean : clean up one specific target (alias for above)
865 $(TARGETS_CLEAN) :
866 $(V0) $(MAKE) -j TARGET=$(subst _clean,,$@) clean
868 ## clean_all : clean all valid targets
869 clean_all:$(CLEAN_TARGETS)
871 ## all_clean : clean all valid targets (alias for above)
872 all_clean:$(TARGETS_CLEAN)
875 flash_$(TARGET): $(TARGET_HEX)
876 $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
877 $(V0) echo -n 'R' >$(SERIAL_DEVICE)
878 $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
880 ## flash : flash firmware (.hex) onto flight controller
881 flash: flash_$(TARGET)
883 st-flash_$(TARGET): $(TARGET_BIN)
884 $(V0) st-flash --reset write $< 0x08000000
886 ## st-flash : flash firmware (.bin) onto flight controller
887 st-flash: st-flash_$(TARGET)
889 binary:
890 $(V0) $(MAKE) -j $(TARGET_BIN)
892 hex:
893 $(V0) $(MAKE) -j $(TARGET_HEX)
895 unbrick_$(TARGET): $(TARGET_HEX)
896 $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
897 $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
899 ## unbrick : unbrick flight controller
900 unbrick: unbrick_$(TARGET)
902 ## cppcheck : run static analysis on C source code
903 cppcheck: $(CSOURCES)
904 $(V0) $(CPPCHECK)
906 cppcheck-result.xml: $(CSOURCES)
907 $(V0) $(CPPCHECK) --xml-version=2 2> cppcheck-result.xml
909 # mkdirs
910 $(DL_DIR):
911 mkdir -p $@
913 $(TOOLS_DIR):
914 mkdir -p $@
916 $(BUILD_DIR):
917 mkdir -p $@
919 ## help : print this help message and exit
920 help: Makefile make/tools.mk
921 $(V0) @echo ""
922 $(V0) @echo "Makefile for the $(FORKNAME) firmware"
923 $(V0) @echo ""
924 $(V0) @echo "Usage:"
925 $(V0) @echo " make [V=<verbosity>] [TARGET=<target>] [OPTIONS=\"<options>\"]"
926 $(V0) @echo "Or:"
927 $(V0) @echo " make <target> [V=<verbosity>] [OPTIONS=\"<options>\"]"
928 $(V0) @echo ""
929 $(V0) @echo "Valid TARGET values are: $(VALID_TARGETS)"
930 $(V0) @echo ""
931 $(V0) @sed -n 's/^## //p' $?
933 ## targets : print a list of all valid target platforms (for consumption by scripts)
934 targets:
935 $(V0) @echo "Valid targets: $(VALID_TARGETS)"
936 $(V0) @echo "Target: $(TARGET)"
937 $(V0) @echo "Base target: $(BASE_TARGET)"
939 ## test : run the cleanflight test suite
940 ## junittest : run the cleanflight test suite, producing Junit XML result files.
941 test junittest:
942 $(V0) cd src/test && $(MAKE) $@ || true
944 # rebuild everything when makefile changes
945 $(TARGET_OBJS) : Makefile
947 # include auto-generated dependencies
948 -include $(TARGET_DEPS)