Ding dong the wicked witch is dead. Removing pwm_mapping
[betaflight.git] / Makefile
blob4117bbda9149cbfd19f7d266e00d6816217067bd
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 ## 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 ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk)))))
96 OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS))
98 #VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS)
99 VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk))
100 VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS)))
101 VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS)
102 VALID_TARGETS := $(sort $(VALID_TARGETS))
104 ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET))
105 BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk)))))
106 -include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk
107 else
108 BASE_TARGET := $(TARGET)
109 endif
111 ifeq ($(filter $(TARGET),$(OPBL_TARGETS)), $(TARGET))
112 OPBL = yes
113 endif
115 # silently ignore if the file is not present. Allows for target specific.
116 -include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk
118 F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS)
120 ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
121 $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?)
122 endif
124 ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS)),)
125 $(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, or F411. Have you prepared a valid target.mk?)
126 endif
128 128K_TARGETS = $(F1_TARGETS)
129 256K_TARGETS = $(F3_TARGETS)
130 512K_TARGETS = $(F411_TARGETS)
131 1024K_TARGETS = $(F405_TARGETS)
133 # Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already.
134 ifeq ($(FLASH_SIZE),)
135 ifeq ($(TARGET),$(filter $(TARGET),$(1024K_TARGETS)))
136 FLASH_SIZE = 1024
137 else ifeq ($(TARGET),$(filter $(TARGET),$(512K_TARGETS)))
138 FLASH_SIZE = 512
139 else ifeq ($(TARGET),$(filter $(TARGET),$(256K_TARGETS)))
140 FLASH_SIZE = 256
141 else ifeq ($(TARGET),$(filter $(TARGET),$(128K_TARGETS)))
142 FLASH_SIZE = 128
143 else
144 $(error FLASH_SIZE not configured for target $(TARGET))
145 endif
146 endif
148 # note that there is no hardfault debugging startup file assembly handler for other platforms
149 ifeq ($(DEBUG_HARDFAULTS),F3)
150 CFLAGS += -DDEBUG_HARDFAULTS
151 STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S
152 else
153 STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S
154 endif
156 REVISION = $(shell git log -1 --format="%h")
158 FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/build/version.h | awk '{print $$3}' )
159 FC_VER_MINOR := $(shell grep " FC_VERSION_MINOR" src/main/build/version.h | awk '{print $$3}' )
160 FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/build/version.h | awk '{print $$3}' )
162 FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH)
164 # Search path for sources
165 VPATH := $(SRC_DIR):$(SRC_DIR)/startup
166 USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver
167 USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c))
168 FATFS_DIR = $(ROOT)/lib/main/FatFS
169 FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c))
171 CSOURCES := $(shell find $(SRC_DIR) -name '*.c')
173 ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
174 # F3 TARGETS
176 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
177 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
178 EXCLUDES = stm32f30x_crc.c \
179 stm32f30x_can.c
181 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
182 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
184 VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
185 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM1/CoreSupport/*.c \
186 $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c))
188 INCLUDE_DIRS := $(INCLUDE_DIRS) \
189 $(STDPERIPH_DIR)/inc \
190 $(CMSIS_DIR)/CM1/CoreSupport \
191 $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
193 ifneq ($(filter VCP, $(FEATURES)),)
194 INCLUDE_DIRS := $(INCLUDE_DIRS) \
195 $(USBFS_DIR)/inc \
196 $(ROOT)/src/main/vcp
198 VPATH := $(VPATH):$(USBFS_DIR)/src
200 DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\
201 $(USBPERIPH_SRC)
202 endif
204 ifneq ($(filter SDCARD, $(FEATURES)),)
205 INCLUDE_DIRS := $(INCLUDE_DIRS) \
206 $(FATFS_DIR) \
208 VPATH := $(VPATH):$(FATFS_DIR)
209 endif
211 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld
213 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
214 DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
215 # End F3 targets
217 # Start F4 targets
218 else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS)))
220 #STDPERIPH
221 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4xx_StdPeriph_Driver
222 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
223 EXCLUDES = stm32f4xx_crc.c \
224 stm32f4xx_can.c \
225 stm32f4xx_fmc.c \
226 stm32f4xx_sai.c \
227 stm32f4xx_cec.c \
228 stm32f4xx_dsi.c \
229 stm32f4xx_flash_ramfunc.c \
230 stm32f4xx_fmpi2c.c \
231 stm32f4xx_lptim.c \
232 stm32f4xx_qspi.c \
233 stm32f4xx_spdifrx.c \
234 stm32f4xx_cryp.c \
235 stm32f4xx_cryp_aes.c \
236 stm32f4xx_hash_md5.c \
237 stm32f4xx_cryp_des.c \
238 stm32f4xx_rtc.c \
239 stm32f4xx_hash.c \
240 stm32f4xx_dbgmcu.c \
241 stm32f4xx_cryp_tdes.c \
242 stm32f4xx_hash_sha1.c
245 ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS)))
246 EXCLUDES += stm32f4xx_fsmc.c
247 endif
249 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
251 #USB
252 USBCORE_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Core
253 USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/src/*.c))
254 USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver
255 USBOTG_SRC = $(notdir $(wildcard $(USBOTG_DIR)/src/*.c))
256 EXCLUDES = usb_bsp_template.c \
257 usb_conf_template.c \
258 usb_hcd_int.c \
259 usb_hcd.c \
260 usb_otg.c
262 USBOTG_SRC := $(filter-out ${EXCLUDES}, $(USBOTG_SRC))
263 USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc
264 USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/src/*.c))
265 EXCLUDES = usbd_cdc_if_template.c
266 USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
267 VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src
269 DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
270 $(USBOTG_SRC) \
271 $(USBCORE_SRC) \
272 $(USBCDC_SRC)
274 #CMSIS
275 VPATH := $(VPATH):$(CMSIS_DIR)/CM4/CoreSupport:$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx
276 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM4/CoreSupport/*.c \
277 $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx/*.c))
278 INCLUDE_DIRS := $(INCLUDE_DIRS) \
279 $(STDPERIPH_DIR)/inc \
280 $(USBOTG_DIR)/inc \
281 $(USBCORE_DIR)/inc \
282 $(USBCDC_DIR)/inc \
283 $(USBFS_DIR)/inc \
284 $(CMSIS_DIR)/CM4/CoreSupport \
285 $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \
286 $(ROOT)/src/main/vcpf4
288 ifneq ($(filter SDCARD,$(FEATURES)),)
289 INCLUDE_DIRS := $(INCLUDE_DIRS) \
290 $(FATFS_DIR)
291 VPATH := $(VPATH):$(FATFS_DIR)
292 endif
294 #Flags
295 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
297 ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS)))
298 DEVICE_FLAGS = -DSTM32F411xE
299 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld
300 else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS)))
301 DEVICE_FLAGS = -DSTM32F40_41xxx
302 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld
303 else
304 $(error Unknown MCU for F4 target)
305 endif
306 DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
308 # End F4 targets
310 # Start F1 targets
311 else
313 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
314 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
315 EXCLUDES = stm32f10x_crc.c \
316 stm32f10x_cec.c \
317 stm32f10x_can.c
319 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
321 # Search path and source files for the CMSIS sources
322 VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x
323 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \
324 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c))
326 INCLUDE_DIRS := $(INCLUDE_DIRS) \
327 $(STDPERIPH_DIR)/inc \
328 $(CMSIS_DIR)/CM3/CoreSupport \
329 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \
331 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
333 ifneq ($(filter VCP, $(FEATURES)),)
334 INCLUDE_DIRS := $(INCLUDE_DIRS) \
335 $(USBFS_DIR)/inc \
336 $(ROOT)/src/main/vcp
338 VPATH := $(VPATH):$(USBFS_DIR)/src
340 DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC) \
341 $(USBPERIPH_SRC)
343 endif
345 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld
346 ARCH_FLAGS = -mthumb -mcpu=cortex-m3
348 ifeq ($(DEVICE_FLAGS),)
349 DEVICE_FLAGS = -DSTM32F10X_MD
350 endif
351 DEVICE_FLAGS += -DSTM32F10X
353 endif
355 # End F1 targets
357 ifneq ($(BASE_TARGET), $(TARGET))
358 TARGET_FLAGS := $(TARGET_FLAGS) -D$(BASE_TARGET)
359 endif
361 ifneq ($(FLASH_SIZE),)
362 DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE)
363 endif
365 ifneq ($(HSE_VALUE),)
366 DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE)
367 endif
369 TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET)
370 TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
372 ifeq ($(OPBL),yes)
373 TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
374 ifeq ($(TARGET), $(filter $(TARGET),$(F405_TARGETS)))
375 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405_opbl.ld
376 else ifeq ($(TARGET), $(filter $(TARGET),$(F411_TARGETS)))
377 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411_opbl.ld
378 else ifeq ($(TARGET), $(filter $(TARGET),$(F3_TARGETS)))
379 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k_opbl.ld
380 else ifeq ($(TARGET), $(filter $(TARGET),$(F1_TARGETS)))
381 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld
382 endif
383 .DEFAULT_GOAL := binary
384 else
385 .DEFAULT_GOAL := hex
386 endif
388 INCLUDE_DIRS := $(INCLUDE_DIRS) \
389 $(TARGET_DIR)
391 VPATH := $(VPATH):$(TARGET_DIR)
393 COMMON_SRC = \
394 build/build_config.c \
395 build/debug.c \
396 build/version.c \
397 $(TARGET_DIR_SRC) \
398 main.c \
399 fc/mw.c \
400 fc/fc_tasks.c \
401 common/encoding.c \
402 common/filter.c \
403 common/maths.c \
404 common/printf.c \
405 common/streambuf.c \
406 common/typeconversion.c \
407 config/config.c \
408 config/config_eeprom.c \
409 config/feature.c \
410 config/parameter_group.c \
411 fc/runtime_config.c \
412 drivers/adc.c \
413 drivers/buf_writer.c \
414 drivers/bus_i2c_soft.c \
415 drivers/bus_spi.c \
416 drivers/bus_spi_soft.c \
417 drivers/exti.c \
418 drivers/gyro_sync.c \
419 drivers/io.c \
420 drivers/light_led.c \
421 drivers/rx_nrf24l01.c \
422 drivers/rx_spi.c \
423 drivers/rx_xn297.c \
424 drivers/pwm_output.c \
425 drivers/pwm_rx.c \
426 drivers/rcc.c \
427 drivers/serial.c \
428 drivers/serial_uart.c \
429 drivers/sound_beeper.c \
430 drivers/system.c \
431 drivers/timer.c \
432 flight/altitudehold.c \
433 flight/failsafe.c \
434 flight/imu.c \
435 flight/mixer.c \
436 flight/pid.c \
437 flight/pid_legacy.c \
438 flight/pid_betaflight.c \
439 io/beeper.c \
440 fc/rc_controls.c \
441 fc/rc_curves.c \
442 io/serial.c \
443 io/serial_4way.c \
444 io/serial_4way_avrootloader.c \
445 io/serial_4way_stk500v2.c \
446 io/serial_cli.c \
447 io/serial_msp.c \
448 io/statusindicator.c \
449 msp/msp_server_fc.c \
450 rx/ibus.c \
451 rx/jetiexbus.c \
452 rx/msp.c \
453 rx/nrf24_cx10.c \
454 rx/nrf24_inav.c \
455 rx/nrf24_h8_3d.c \
456 rx/nrf24_syma.c \
457 rx/nrf24_v202.c \
458 rx/pwm.c \
459 rx/rx.c \
460 rx/rx_spi.c \
461 rx/sbus.c \
462 rx/spektrum.c \
463 rx/sumd.c \
464 rx/sumh.c \
465 rx/xbus.c \
466 scheduler/scheduler.c \
467 sensors/acceleration.c \
468 sensors/battery.c \
469 sensors/boardalignment.c \
470 sensors/compass.c \
471 sensors/gyro.c \
472 sensors/initialisation.c \
473 $(CMSIS_SRC) \
474 $(DEVICE_STDPERIPH_SRC)
476 HIGHEND_SRC = \
477 blackbox/blackbox.c \
478 blackbox/blackbox_io.c \
479 common/colorconversion.c \
480 drivers/display_ug2864hsweg01.c \
481 flight/gtune.c \
482 flight/navigation.c \
483 flight/gps_conversion.c \
484 io/gps.c \
485 io/ledstrip.c \
486 io/display.c \
487 sensors/sonar.c \
488 sensors/barometer.c \
489 telemetry/telemetry.c \
490 telemetry/frsky.c \
491 telemetry/hott.c \
492 telemetry/smartport.c \
493 telemetry/ltm.c
495 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
496 VCP_SRC = \
497 vcpf4/stm32f4xx_it.c \
498 vcpf4/usb_bsp.c \
499 vcpf4/usbd_desc.c \
500 vcpf4/usbd_usr.c \
501 vcpf4/usbd_cdc_vcp.c \
502 drivers/serial_usb_vcp.c
503 else
504 VCP_SRC = \
505 vcp/hw_config.c \
506 vcp/stm32_it.c \
507 vcp/usb_desc.c \
508 vcp/usb_endp.c \
509 vcp/usb_istr.c \
510 vcp/usb_prop.c \
511 vcp/usb_pwr.c \
512 drivers/serial_usb_vcp.c \
513 drivers/usb_io.c
514 endif
516 STM32F10x_COMMON_SRC = \
517 startup_stm32f10x_md_gcc.S \
518 drivers/adc_stm32f10x.c \
519 drivers/bus_i2c_stm32f10x.c \
520 drivers/dma.c \
521 drivers/gpio_stm32f10x.c \
522 drivers/inverter.c \
523 drivers/serial_softserial.c \
524 drivers/serial_uart_stm32f10x.c \
525 drivers/system_stm32f10x.c \
526 drivers/timer_stm32f10x.c
528 STM32F30x_COMMON_SRC = \
529 startup_stm32f30x_md_gcc.S \
530 target/system_stm32f30x.c \
531 drivers/adc_stm32f30x.c \
532 drivers/bus_i2c_stm32f30x.c \
533 drivers/dma.c \
534 drivers/gpio_stm32f30x.c \
535 drivers/light_ws2811strip_stm32f30x.c \
536 drivers/serial_uart_stm32f30x.c \
537 drivers/system_stm32f30x.c \
538 drivers/timer_stm32f30x.c
540 STM32F4xx_COMMON_SRC = \
541 startup_stm32f40xx.s \
542 target/system_stm32f4xx.c \
543 drivers/accgyro_mpu.c \
544 drivers/adc_stm32f4xx.c \
545 drivers/adc_stm32f4xx.c \
546 drivers/bus_i2c_stm32f10x.c \
547 drivers/gpio_stm32f4xx.c \
548 drivers/inverter.c \
549 drivers/serial_softserial.c \
550 drivers/serial_uart_stm32f4xx.c \
551 drivers/system_stm32f4xx.c \
552 drivers/timer_stm32f4xx.c \
553 drivers/dma_stm32f4xx.c
555 # check if target.mk supplied
556 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
557 TARGET_SRC := $(STM32F4xx_COMMON_SRC) $(TARGET_SRC)
558 else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
559 TARGET_SRC := $(STM32F30x_COMMON_SRC) $(TARGET_SRC)
560 else ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
561 TARGET_SRC := $(STM32F10x_COMMON_SRC) $(TARGET_SRC)
562 endif
564 ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
565 TARGET_SRC += \
566 drivers/flash_m25p16.c \
567 io/flashfs.c
568 endif
570 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS) $(F3_TARGETS)))
571 TARGET_SRC += $(HIGHEND_SRC)
572 else ifneq ($(filter HIGHEND,$(FEATURES)),)
573 TARGET_SRC += $(HIGHEND_SRC)
574 endif
576 TARGET_SRC += $(COMMON_SRC)
578 ifneq ($(filter SDCARD,$(FEATURES)),)
579 TARGET_SRC += \
580 drivers/sdcard.c \
581 drivers/sdcard_standard.c \
582 io/asyncfatfs/asyncfatfs.c \
583 io/asyncfatfs/fat_standard.c
584 endif
586 ifneq ($(filter VCP,$(FEATURES)),)
587 TARGET_SRC += $(VCP_SRC)
588 endif
589 # end target specific make file checks
592 # Search path and source files for the ST stdperiph library
593 VPATH := $(VPATH):$(STDPERIPH_DIR)/src
595 ###############################################################################
596 # Things that might need changing to use different tools
599 # Find out if ccache is installed on the system
600 CCACHE := ccache
601 RESULT = $(shell (which $(CCACHE) > /dev/null 2>&1; echo $$?) )
602 ifneq ($(RESULT),0)
603 CCACHE :=
604 endif
606 # Tool names
607 CC := $(CCACHE) $(ARM_SDK_PREFIX)gcc
608 CPP := $(CCACHE) $(ARM_SDK_PREFIX)g++
609 OBJCOPY := $(ARM_SDK_PREFIX)objcopy
610 SIZE := $(ARM_SDK_PREFIX)size
613 # Tool options.
616 ifeq ($(DEBUG),GDB)
617 OPTIMIZE = -O0
618 LTO_FLAGS = $(OPTIMIZE)
619 else
620 OPTIMIZE = -Os
621 LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
622 endif
624 DEBUG_FLAGS = -ggdb3 -DDEBUG
626 CFLAGS += $(ARCH_FLAGS) \
627 $(LTO_FLAGS) \
628 $(addprefix -D,$(OPTIONS)) \
629 $(addprefix -I,$(INCLUDE_DIRS)) \
630 $(DEBUG_FLAGS) \
631 -std=gnu99 \
632 -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \
633 -ffunction-sections \
634 -fdata-sections \
635 -pedantic \
636 $(DEVICE_FLAGS) \
637 -DUSE_STDPERIPH_DRIVER \
638 -D$(TARGET) \
639 $(TARGET_FLAGS) \
640 -D'__FORKNAME__="$(FORKNAME)"' \
641 -D'__TARGET__="$(TARGET)"' \
642 -D'__REVISION__="$(REVISION)"' \
643 -save-temps=obj \
644 -MMD -MP
646 ASFLAGS = $(ARCH_FLAGS) \
647 -x assembler-with-cpp \
648 $(addprefix -I,$(INCLUDE_DIRS)) \
649 -MMD -MP
651 LDFLAGS = -lm \
652 -nostartfiles \
653 --specs=nano.specs \
654 -lc \
655 -lnosys \
656 $(ARCH_FLAGS) \
657 $(LTO_FLAGS) \
658 $(DEBUG_FLAGS) \
659 -static \
660 -Wl,-gc-sections,-Map,$(TARGET_MAP) \
661 -Wl,-L$(LINKER_DIR) \
662 -Wl,--cref \
663 -Wl,--no-wchar-size-warning \
664 -T$(LD_SCRIPT)
666 ###############################################################################
667 # No user-serviceable parts below
668 ###############################################################################
670 CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \
671 --std=c99 --inline-suppr --quiet --force \
672 $(addprefix -I,$(INCLUDE_DIRS)) \
673 -I/usr/include -I/usr/include/linux
676 # Things we will build
678 TARGET_BIN = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).bin
679 TARGET_HEX = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).hex
680 TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
681 TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC))))
682 TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC))))
683 TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
686 CLEAN_ARTIFACTS := $(TARGET_BIN)
687 CLEAN_ARTIFACTS += $(TARGET_HEX)
688 CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
690 # List of buildable ELF files and their object dependencies.
691 # It would be nice to compute these lists, but that seems to be just beyond make.
693 $(TARGET_HEX): $(TARGET_ELF)
694 $(V0) $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
696 $(TARGET_BIN): $(TARGET_ELF)
697 $(V0) $(OBJCOPY) -O binary $< $@
699 $(TARGET_ELF): $(TARGET_OBJS)
700 $(V1) echo LD $(notdir $@)
701 $(V1) $(CC) -o $@ $^ $(LDFLAGS)
702 $(V0) $(SIZE) $(TARGET_ELF)
704 # Compile
705 $(OBJECT_DIR)/$(TARGET)/%.o: %.c
706 $(V1) mkdir -p $(dir $@)
707 $(V1) echo %% $(notdir $<)
708 $(V1) $(CC) -c -o $@ $(CFLAGS) $<
710 # Assemble
711 $(OBJECT_DIR)/$(TARGET)/%.o: %.s
712 $(V1) mkdir -p $(dir $@)
713 $(V1) echo %% $(notdir $<)
714 $(V1) $(CC) -c -o $@ $(ASFLAGS) $<
716 $(OBJECT_DIR)/$(TARGET)/%.o: %.S
717 $(V1) mkdir -p $(dir $@)
718 $(V1) echo %% $(notdir $<)
719 $(V1) $(CC) -c -o $@ $(ASFLAGS) $<
722 ## all : Build all valid targets
723 all: $(VALID_TARGETS)
725 $(VALID_TARGETS):
726 $(V0) echo "" && \
727 echo "Building $@" && \
728 $(MAKE) binary hex TARGET=$@ && \
729 echo "Building $@ succeeded."
733 CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
734 TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
736 ## clean : clean up temporary / machine-generated files
737 clean:
738 $(V0) echo "Cleaning $(TARGET)"
739 $(V0) rm -f $(CLEAN_ARTIFACTS)
740 $(V0) rm -rf $(OBJECT_DIR)/$(TARGET)
741 $(V0) echo "Cleaning $(TARGET) succeeded."
743 ## clean_test : clean up temporary / machine-generated files (tests)
744 clean_test:
745 $(V0) cd src/test && $(MAKE) clean || true
747 ## clean_<TARGET> : clean up one specific target
748 $(CLEAN_TARGETS) :
749 $(V0) $(MAKE) -j TARGET=$(subst clean_,,$@) clean
751 ## <TARGET>_clean : clean up one specific target (alias for above)
752 $(TARGETS_CLEAN) :
753 $(V0) $(MAKE) -j TARGET=$(subst _clean,,$@) clean
755 ## clean_all : clean all valid targets
756 clean_all:$(CLEAN_TARGETS)
758 ## all_clean : clean all valid targets (alias for above)
759 all_clean:$(TARGETS_CLEAN)
762 flash_$(TARGET): $(TARGET_HEX)
763 $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
764 $(V0) echo -n 'R' >$(SERIAL_DEVICE)
765 $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
767 ## flash : flash firmware (.hex) onto flight controller
768 flash: flash_$(TARGET)
770 st-flash_$(TARGET): $(TARGET_BIN)
771 $(V0) st-flash --reset write $< 0x08000000
773 ## st-flash : flash firmware (.bin) onto flight controller
774 st-flash: st-flash_$(TARGET)
776 binary:
777 $(V0) $(MAKE) -j $(TARGET_BIN)
779 hex:
780 $(V0) $(MAKE) -j $(TARGET_HEX)
782 unbrick_$(TARGET): $(TARGET_HEX)
783 $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
784 $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
786 ## unbrick : unbrick flight controller
787 unbrick: unbrick_$(TARGET)
789 ## cppcheck : run static analysis on C source code
790 cppcheck: $(CSOURCES)
791 $(V0) $(CPPCHECK)
793 cppcheck-result.xml: $(CSOURCES)
794 $(V0) $(CPPCHECK) --xml-version=2 2> cppcheck-result.xml
796 ## mkdirs
797 $(DL_DIR):
798 mkdir -p $@
800 $(TOOLS_DIR):
801 mkdir -p $@
803 $(BUILD_DIR):
804 mkdir -p $@
806 ## help : print this help message and exit
807 help: Makefile
808 $(V0) @echo ""
809 $(V0) @echo "Makefile for the $(FORKNAME) firmware"
810 $(V0) @echo ""
811 $(V0) @echo "Usage:"
812 $(V0) @echo " make [V=<verbosity>] [TARGET=<target>] [OPTIONS=\"<options>\"]"
813 $(V0) @echo "Or:"
814 $(V0) @echo " make <target> [V=<verbosity>] [OPTIONS=\"<options>\"]"
815 $(V0) @echo ""
816 $(V0) @echo "Valid TARGET values are: $(VALID_TARGETS)"
817 $(V0) @echo ""
818 $(V0) @sed -n 's/^## //p' $<
820 ## targets : print a list of all valid target platforms (for consumption by scripts)
821 targets:
822 $(V0) @echo "Valid targets: $(VALID_TARGETS)"
823 $(V0) @echo "Target: $(TARGET)"
824 $(V0) @echo "Base target: $(BASE_TARGET)"
826 ## test : run the cleanflight test suite
827 test:
828 $(V0) cd src/test && $(MAKE) test || true
830 # rebuild everything when makefile changes
831 $(TARGET_OBJS) : Makefile
833 # include auto-generated dependencies
834 -include $(TARGET_DEPS)