Added MPU9250 to acc lookup table. Duplication. Missing in Allowed Values printout...
[betaflight.git] / Makefile
blob777c04026df44bd2fac35e8fa95e959010ee6f24
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 ###############################################################################
41 # Things that need to be maintained as the source changes
44 FORKNAME = betaflight
46 # Working directories
47 ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST))))
48 SRC_DIR = $(ROOT)/src/main
49 OBJECT_DIR = $(ROOT)/obj/main
50 BIN_DIR = $(ROOT)/obj
51 CMSIS_DIR = $(ROOT)/lib/main/CMSIS
52 INCLUDE_DIRS = $(SRC_DIR) \
53 $(ROOT)/src/main/target
54 LINKER_DIR = $(ROOT)/src/main/target
56 # default xtal value for F4 targets
57 HSE_VALUE = 8000000
59 # used for turning on features like VCP and SDCARD
60 FEATURES =
62 ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk)))))
63 OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS))
65 #VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS)
66 VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk))
67 VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS)))
68 VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS)
69 VALID_TARGETS := $(sort $(VALID_TARGETS))
71 ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET))
72 BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk)))))
73 -include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk
74 else
75 BASE_TARGET := $(TARGET)
76 endif
78 ifeq ($(filter $(TARGET),$(OPBL_TARGETS)), $(TARGET))
79 OPBL = yes
80 endif
82 # silently ignore if the file is not present. Allows for target specific.
83 -include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk
85 F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS)
87 ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
88 $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?)
89 endif
91 ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS)),)
92 $(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?)
93 endif
95 128K_TARGETS = $(F1_TARGETS)
96 256K_TARGETS = $(F3_TARGETS)
97 512K_TARGETS = $(F411_TARGETS)
98 1024K_TARGETS = $(F405_TARGETS)
100 # Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already.
101 ifeq ($(FLASH_SIZE),)
102 ifeq ($(TARGET),$(filter $(TARGET),$(1024K_TARGETS)))
103 FLASH_SIZE = 1024
104 else ifeq ($(TARGET),$(filter $(TARGET),$(512K_TARGETS)))
105 FLASH_SIZE = 512
106 else ifeq ($(TARGET),$(filter $(TARGET),$(256K_TARGETS)))
107 FLASH_SIZE = 256
108 else ifeq ($(TARGET),$(filter $(TARGET),$(128K_TARGETS)))
109 FLASH_SIZE = 128
110 else
111 $(error FLASH_SIZE not configured for target $(TARGET))
112 endif
113 endif
115 # note that there is no hardfault debugging startup file assembly handler for other platforms
116 ifeq ($(DEBUG_HARDFAULTS),F3)
117 CFLAGS += -DDEBUG_HARDFAULTS
118 STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S
119 else
120 STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S
121 endif
123 REVISION = $(shell git log -1 --format="%h")
125 FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/version.h | awk '{print $$3}' )
126 FC_VER_MINOR := $(shell grep " FC_VERSION_MINOR" src/main/version.h | awk '{print $$3}' )
127 FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/version.h | awk '{print $$3}' )
129 FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH)
131 # Search path for sources
132 VPATH := $(SRC_DIR):$(SRC_DIR)/startup
133 USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver
134 USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c))
135 FATFS_DIR = $(ROOT)/lib/main/FatFS
136 FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c))
138 CSOURCES := $(shell find $(SRC_DIR) -name '*.c')
140 ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
141 # F3 TARGETS
143 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
144 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
145 EXCLUDES = stm32f30x_crc.c \
146 stm32f30x_can.c
148 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
149 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
151 VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
152 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM1/CoreSupport/*.c \
153 $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c))
155 INCLUDE_DIRS := $(INCLUDE_DIRS) \
156 $(STDPERIPH_DIR)/inc \
157 $(CMSIS_DIR)/CM1/CoreSupport \
158 $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
160 ifneq ($(filter VCP, $(FEATURES)),)
161 INCLUDE_DIRS := $(INCLUDE_DIRS) \
162 $(USBFS_DIR)/inc \
163 $(ROOT)/src/main/vcp
165 VPATH := $(VPATH):$(USBFS_DIR)/src
167 DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\
168 $(USBPERIPH_SRC)
169 endif
171 ifneq ($(filter SDCARD, $(FEATURES)),)
172 INCLUDE_DIRS := $(INCLUDE_DIRS) \
173 $(FATFS_DIR) \
175 VPATH := $(VPATH):$(FATFS_DIR)
176 endif
178 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld
180 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
181 DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
182 # End F3 targets
184 # Start F4 targets
185 else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS)))
187 #STDPERIPH
188 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4xx_StdPeriph_Driver
189 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
190 EXCLUDES = stm32f4xx_crc.c \
191 stm32f4xx_can.c \
192 stm32f4xx_fmc.c \
193 stm32f4xx_sai.c \
194 stm32f4xx_cec.c \
195 stm32f4xx_dsi.c \
196 stm32f4xx_flash_ramfunc.c \
197 stm32f4xx_fmpi2c.c \
198 stm32f4xx_lptim.c \
199 stm32f4xx_qspi.c \
200 stm32f4xx_spdifrx.c \
201 stm32f4xx_cryp.c \
202 stm32f4xx_cryp_aes.c \
203 stm32f4xx_hash_md5.c \
204 stm32f4xx_cryp_des.c \
205 stm32f4xx_rtc.c \
206 stm32f4xx_hash.c \
207 stm32f4xx_dbgmcu.c \
208 stm32f4xx_cryp_tdes.c \
209 stm32f4xx_hash_sha1.c
212 ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS)))
213 EXCLUDES += stm32f4xx_fsmc.c
214 endif
216 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
218 #USB
219 USBCORE_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Core
220 USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/src/*.c))
221 USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver
222 USBOTG_SRC = $(notdir $(wildcard $(USBOTG_DIR)/src/*.c))
223 EXCLUDES = usb_bsp_template.c \
224 usb_conf_template.c \
225 usb_hcd_int.c \
226 usb_hcd.c \
227 usb_otg.c
229 USBOTG_SRC := $(filter-out ${EXCLUDES}, $(USBOTG_SRC))
230 USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc
231 USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/src/*.c))
232 EXCLUDES = usbd_cdc_if_template.c
233 USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
234 VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src
236 DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
237 $(USBOTG_SRC) \
238 $(USBCORE_SRC) \
239 $(USBCDC_SRC)
241 #CMSIS
242 VPATH := $(VPATH):$(CMSIS_DIR)/CM4/CoreSupport:$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx
243 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM4/CoreSupport/*.c \
244 $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx/*.c))
245 INCLUDE_DIRS := $(INCLUDE_DIRS) \
246 $(STDPERIPH_DIR)/inc \
247 $(USBOTG_DIR)/inc \
248 $(USBCORE_DIR)/inc \
249 $(USBCDC_DIR)/inc \
250 $(USBFS_DIR)/inc \
251 $(CMSIS_DIR)/CM4/CoreSupport \
252 $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \
253 $(ROOT)/src/main/vcpf4
255 ifneq ($(filter SDCARD,$(FEATURES)),)
256 INCLUDE_DIRS := $(INCLUDE_DIRS) \
257 $(FATFS_DIR)
258 VPATH := $(VPATH):$(FATFS_DIR)
259 endif
261 #Flags
262 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
264 ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS)))
265 DEVICE_FLAGS = -DSTM32F411xE
266 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld
267 else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS)))
268 DEVICE_FLAGS = -DSTM32F40_41xxx
269 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld
270 else
271 $(error Unknown MCU for F4 target)
272 endif
273 DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
275 # End F4 targets
277 # Start F1 targets
278 else
280 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
281 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
282 EXCLUDES = stm32f10x_crc.c \
283 stm32f10x_cec.c \
284 stm32f10x_can.c
286 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
288 # Search path and source files for the CMSIS sources
289 VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x
290 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \
291 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c))
293 INCLUDE_DIRS := $(INCLUDE_DIRS) \
294 $(STDPERIPH_DIR)/inc \
295 $(CMSIS_DIR)/CM3/CoreSupport \
296 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \
298 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
300 ifneq ($(filter VCP, $(FEATURES)),)
301 INCLUDE_DIRS := $(INCLUDE_DIRS) \
302 $(USBFS_DIR)/inc \
303 $(ROOT)/src/main/vcp
305 VPATH := $(VPATH):$(USBFS_DIR)/src
307 DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC) \
308 $(USBPERIPH_SRC)
310 endif
312 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld
313 ARCH_FLAGS = -mthumb -mcpu=cortex-m3
315 ifeq ($(DEVICE_FLAGS),)
316 DEVICE_FLAGS = -DSTM32F10X_MD
317 endif
318 DEVICE_FLAGS += -DSTM32F10X
320 endif
322 # End F1 targets
324 ifneq ($(BASE_TARGET), $(TARGET))
325 TARGET_FLAGS := $(TARGET_FLAGS) -D$(BASE_TARGET)
326 endif
328 ifneq ($(FLASH_SIZE),)
329 DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE)
330 endif
332 TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET)
333 TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
335 ifeq ($(OPBL),yes)
336 TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
337 ifeq ($(TARGET), $(filter $(TARGET),$(F405_TARGETS)))
338 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405_opbl.ld
339 else ifeq ($(TARGET), $(filter $(TARGET),$(F411_TARGETS)))
340 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411_opbl.ld
341 else ifeq ($(TARGET), $(filter $(TARGET),$(F3_TARGETS)))
342 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k_opbl.ld
343 else ifeq ($(TARGET), $(filter $(TARGET),$(F1_TARGETS)))
344 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld
345 endif
346 .DEFAULT_GOAL := binary
347 else
348 .DEFAULT_GOAL := hex
349 endif
351 INCLUDE_DIRS := $(INCLUDE_DIRS) \
352 $(TARGET_DIR)
354 VPATH := $(VPATH):$(TARGET_DIR)
356 COMMON_SRC = \
357 build_config.c \
358 debug.c \
359 version.c \
360 $(TARGET_DIR_SRC) \
361 main.c \
362 mw.c \
363 common/encoding.c \
364 common/filter.c \
365 common/maths.c \
366 common/printf.c \
367 common/typeconversion.c \
368 config/config.c \
369 config/runtime_config.c \
370 drivers/adc.c \
371 drivers/buf_writer.c \
372 drivers/bus_i2c_soft.c \
373 drivers/bus_spi.c \
374 drivers/exti.c \
375 drivers/gyro_sync.c \
376 drivers/io.c \
377 drivers/light_led.c \
378 drivers/pwm_mapping.c \
379 drivers/pwm_output.c \
380 drivers/pwm_rx.c \
381 drivers/rcc.c \
382 drivers/serial.c \
383 drivers/serial_uart.c \
384 drivers/sound_beeper.c \
385 drivers/system.c \
386 drivers/timer.c \
387 flight/altitudehold.c \
388 flight/failsafe.c \
389 flight/imu.c \
390 flight/mixer.c \
391 flight/pid.c \
392 io/beeper.c \
393 io/rc_controls.c \
394 io/rc_curves.c \
395 io/serial.c \
396 io/serial_4way.c \
397 io/serial_4way_avrootloader.c \
398 io/serial_4way_stk500v2.c \
399 io/serial_cli.c \
400 io/serial_msp.c \
401 io/statusindicator.c \
402 rx/ibus.c \
403 rx/jetiexbus.c \
404 rx/msp.c \
405 rx/pwm.c \
406 rx/rx.c \
407 rx/sbus.c \
408 rx/spektrum.c \
409 rx/sumd.c \
410 rx/sumh.c \
411 rx/xbus.c \
412 scheduler/scheduler.c \
413 scheduler/scheduler_tasks.c \
414 sensors/acceleration.c \
415 sensors/battery.c \
416 sensors/boardalignment.c \
417 sensors/compass.c \
418 sensors/gyro.c \
419 sensors/initialisation.c \
420 $(CMSIS_SRC) \
421 $(DEVICE_STDPERIPH_SRC)
423 HIGHEND_SRC = \
424 blackbox/blackbox.c \
425 blackbox/blackbox_io.c \
426 common/colorconversion.c \
427 drivers/display_ug2864hsweg01.c \
428 flight/gtune.c \
429 flight/navigation.c \
430 flight/gps_conversion.c \
431 io/gps.c \
432 io/ledstrip.c \
433 io/display.c \
434 sensors/sonar.c \
435 sensors/barometer.c \
436 telemetry/telemetry.c \
437 telemetry/frsky.c \
438 telemetry/hott.c \
439 telemetry/smartport.c \
440 telemetry/ltm.c
442 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
443 VCP_SRC = \
444 vcpf4/stm32f4xx_it.c \
445 vcpf4/usb_bsp.c \
446 vcpf4/usbd_desc.c \
447 vcpf4/usbd_usr.c \
448 vcpf4/usbd_cdc_vcp.c \
449 drivers/serial_usb_vcp.c
450 else
451 VCP_SRC = \
452 vcp/hw_config.c \
453 vcp/stm32_it.c \
454 vcp/usb_desc.c \
455 vcp/usb_endp.c \
456 vcp/usb_istr.c \
457 vcp/usb_prop.c \
458 vcp/usb_pwr.c \
459 drivers/serial_usb_vcp.c \
460 drivers/usb_io.c
461 endif
463 STM32F10x_COMMON_SRC = \
464 startup_stm32f10x_md_gcc.S \
465 drivers/adc_stm32f10x.c \
466 drivers/bus_i2c_stm32f10x.c \
467 drivers/dma.c \
468 drivers/gpio_stm32f10x.c \
469 drivers/inverter.c \
470 drivers/serial_softserial.c \
471 drivers/serial_uart_stm32f10x.c \
472 drivers/system_stm32f10x.c \
473 drivers/timer_stm32f10x.c
475 STM32F30x_COMMON_SRC = \
476 startup_stm32f30x_md_gcc.S \
477 target/system_stm32f30x.c \
478 drivers/adc_stm32f30x.c \
479 drivers/bus_i2c_stm32f30x.c \
480 drivers/dma.c \
481 drivers/gpio_stm32f30x.c \
482 drivers/light_ws2811strip_stm32f30x.c \
483 drivers/serial_uart_stm32f30x.c \
484 drivers/system_stm32f30x.c \
485 drivers/timer_stm32f30x.c
487 STM32F4xx_COMMON_SRC = \
488 startup_stm32f40xx.s \
489 target/system_stm32f4xx.c \
490 drivers/accgyro_mpu.c \
491 drivers/adc_stm32f4xx.c \
492 drivers/adc_stm32f4xx.c \
493 drivers/bus_i2c_stm32f10x.c \
494 drivers/gpio_stm32f4xx.c \
495 drivers/inverter.c \
496 drivers/serial_softserial.c \
497 drivers/serial_uart_stm32f4xx.c \
498 drivers/system_stm32f4xx.c \
499 drivers/timer_stm32f4xx.c \
500 drivers/dma_stm32f4xx.c
502 # check if target.mk supplied
503 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
504 TARGET_SRC := $(STM32F4xx_COMMON_SRC) $(TARGET_SRC)
505 else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
506 TARGET_SRC := $(STM32F30x_COMMON_SRC) $(TARGET_SRC)
507 else ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
508 TARGET_SRC := $(STM32F10x_COMMON_SRC) $(TARGET_SRC)
509 endif
511 ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
512 TARGET_SRC += \
513 drivers/flash_m25p16.c \
514 io/flashfs.c
515 endif
517 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS) $(F3_TARGETS)))
518 TARGET_SRC += $(HIGHEND_SRC)
519 else ifneq ($(filter HIGHEND,$(FEATURES)),)
520 TARGET_SRC += $(HIGHEND_SRC)
521 endif
523 TARGET_SRC += $(COMMON_SRC)
525 ifneq ($(filter SDCARD,$(FEATURES)),)
526 TARGET_SRC += \
527 drivers/sdcard.c \
528 drivers/sdcard_standard.c \
529 io/asyncfatfs/asyncfatfs.c \
530 io/asyncfatfs/fat_standard.c
531 endif
533 ifneq ($(filter VCP,$(FEATURES)),)
534 TARGET_SRC += $(VCP_SRC)
535 endif
536 # end target specific make file checks
539 # Search path and source files for the ST stdperiph library
540 VPATH := $(VPATH):$(STDPERIPH_DIR)/src
542 ###############################################################################
543 # Things that might need changing to use different tools
546 # Find out if ccache is installed on the system
547 CCACHE := ccache
548 RESULT = $(shell (which $(CCACHE) > /dev/null 2>&1; echo $$?) )
549 ifneq ($(RESULT),0)
550 CCACHE :=
551 endif
553 # Tool names
554 CC := $(CCACHE) arm-none-eabi-gcc
555 OBJCOPY := arm-none-eabi-objcopy
556 SIZE := arm-none-eabi-size
559 # Tool options.
562 ifeq ($(DEBUG),GDB)
563 OPTIMIZE = -O0
564 LTO_FLAGS = $(OPTIMIZE)
565 else
566 OPTIMIZE = -Os
567 LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
568 endif
570 DEBUG_FLAGS = -ggdb3 -DDEBUG
572 CFLAGS += $(ARCH_FLAGS) \
573 $(LTO_FLAGS) \
574 $(addprefix -D,$(OPTIONS)) \
575 $(addprefix -I,$(INCLUDE_DIRS)) \
576 $(DEBUG_FLAGS) \
577 -std=gnu99 \
578 -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \
579 -ffunction-sections \
580 -fdata-sections \
581 -pedantic \
582 $(DEVICE_FLAGS) \
583 -DUSE_STDPERIPH_DRIVER \
584 -D$(TARGET) \
585 $(TARGET_FLAGS) \
586 -D'__FORKNAME__="$(FORKNAME)"' \
587 -D'__TARGET__="$(TARGET)"' \
588 -D'__REVISION__="$(REVISION)"' \
589 -save-temps=obj \
590 -MMD -MP
592 ASFLAGS = $(ARCH_FLAGS) \
593 -x assembler-with-cpp \
594 $(addprefix -I,$(INCLUDE_DIRS)) \
595 -MMD -MP
597 LDFLAGS = -lm \
598 -nostartfiles \
599 --specs=nano.specs \
600 -lc \
601 -lnosys \
602 $(ARCH_FLAGS) \
603 $(LTO_FLAGS) \
604 $(DEBUG_FLAGS) \
605 -static \
606 -Wl,-gc-sections,-Map,$(TARGET_MAP) \
607 -Wl,-L$(LINKER_DIR) \
608 -Wl,--cref \
609 -Wl,--no-wchar-size-warning \
610 -T$(LD_SCRIPT)
612 ###############################################################################
613 # No user-serviceable parts below
614 ###############################################################################
616 CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \
617 --std=c99 --inline-suppr --quiet --force \
618 $(addprefix -I,$(INCLUDE_DIRS)) \
619 -I/usr/include -I/usr/include/linux
622 # Things we will build
624 TARGET_BIN = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).bin
625 TARGET_HEX = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).hex
626 TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
627 TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC))))
628 TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC))))
629 TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
632 CLEAN_ARTIFACTS := $(TARGET_BIN)
633 CLEAN_ARTIFACTS += $(TARGET_HEX)
634 CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
636 # List of buildable ELF files and their object dependencies.
637 # It would be nice to compute these lists, but that seems to be just beyond make.
639 $(TARGET_HEX): $(TARGET_ELF)
640 $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
642 $(TARGET_BIN): $(TARGET_ELF)
643 $(OBJCOPY) -O binary $< $@
645 $(TARGET_ELF): $(TARGET_OBJS)
646 @echo LD $(notdir $@)
647 @$(CC) -o $@ $^ $(LDFLAGS)
648 $(SIZE) $(TARGET_ELF)
650 # Compile
651 $(OBJECT_DIR)/$(TARGET)/%.o: %.c
652 @mkdir -p $(dir $@)
653 @echo %% $(notdir $<)
654 @$(CC) -c -o $@ $(CFLAGS) $<
656 # Assemble
657 $(OBJECT_DIR)/$(TARGET)/%.o: %.s
658 @mkdir -p $(dir $@)
659 @echo %% $(notdir $<)
660 @$(CC) -c -o $@ $(ASFLAGS) $<
662 $(OBJECT_DIR)/$(TARGET)/%.o: %.S
663 @mkdir -p $(dir $@)
664 @echo %% $(notdir $<)
665 @$(CC) -c -o $@ $(ASFLAGS) $<
668 ## all : Build all valid targets
669 all: $(VALID_TARGETS)
671 $(VALID_TARGETS):
672 echo "" && \
673 echo "Building $@" && \
674 $(MAKE) binary hex TARGET=$@ && \
675 echo "Building $@ succeeded."
679 CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
680 TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
682 ## clean : clean up temporary / machine-generated files
683 clean:
684 echo "Cleaning $(TARGET)"
685 rm -f $(CLEAN_ARTIFACTS)
686 rm -rf $(OBJECT_DIR)/$(TARGET)
687 echo "Cleaning $(TARGET) succeeded."
689 ## clean_test : clean up temporary / machine-generated files (tests)
690 clean_test:
691 cd src/test && $(MAKE) clean || true
693 ## clean_<TARGET> : clean up one specific target
694 $(CLEAN_TARGETS) :
695 $(MAKE) -j TARGET=$(subst clean_,,$@) clean
697 ## <TARGET>_clean : clean up one specific target (alias for above)
698 $(TARGETS_CLEAN) :
699 $(MAKE) -j TARGET=$(subst _clean,,$@) clean
701 ## clean_all : clean all valid targets
702 clean_all:$(CLEAN_TARGETS)
704 ## all_clean : clean all valid targets (alias for above)
705 all_clean:$(TARGETS_CLEAN)
708 flash_$(TARGET): $(TARGET_HEX)
709 stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
710 echo -n 'R' >$(SERIAL_DEVICE)
711 stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
713 ## flash : flash firmware (.hex) onto flight controller
714 flash: flash_$(TARGET)
716 st-flash_$(TARGET): $(TARGET_BIN)
717 st-flash --reset write $< 0x08000000
719 ## st-flash : flash firmware (.bin) onto flight controller
720 st-flash: st-flash_$(TARGET)
722 binary:
723 $(MAKE) -j $(TARGET_BIN)
725 hex:
726 $(MAKE) -j $(TARGET_HEX)
728 unbrick_$(TARGET): $(TARGET_HEX)
729 stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
730 stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
732 ## unbrick : unbrick flight controller
733 unbrick: unbrick_$(TARGET)
735 ## cppcheck : run static analysis on C source code
736 cppcheck: $(CSOURCES)
737 $(CPPCHECK)
739 cppcheck-result.xml: $(CSOURCES)
740 $(CPPCHECK) --xml-version=2 2> cppcheck-result.xml
742 ## help : print this help message and exit
743 help: Makefile
744 @echo ""
745 @echo "Makefile for the $(FORKNAME) firmware"
746 @echo ""
747 @echo "Usage:"
748 @echo " make [TARGET=<target>] [OPTIONS=\"<options>\"]"
749 @echo "Or:"
750 @echo " make <target> [OPTIONS=\"<options>\"]"
751 @echo ""
752 @echo "Valid TARGET values are: $(VALID_TARGETS)"
753 @echo ""
754 @sed -n 's/^## //p' $<
756 ## targets : print a list of all valid target platforms (for consumption by scripts)
757 targets:
758 @echo "Valid targets: $(VALID_TARGETS)"
759 @echo "Target: $(TARGET)"
760 @echo "Base target: $(BASE_TARGET)"
762 ## test : run the cleanflight test suite
763 test:
764 cd src/test && $(MAKE) test || true
766 # rebuild everything when makefile changes
767 $(TARGET_OBJS) : Makefile
769 # include auto-generated dependencies
770 -include $(TARGET_DEPS)