Max waypoint number as a per-target define (#395)
[betaflight.git] / Makefile
blob4afd1d1bff941eb071c82ca941889993b21f9df9
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 iNav 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 = inav
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 TARGET_FLAGS = -D$(TARGET)
183 # End F3 targets
185 # Start F4 targets
186 else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS)))
188 #STDPERIPH
189 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4xx_StdPeriph_Driver
190 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
191 EXCLUDES = stm32f4xx_crc.c \
192 stm32f4xx_can.c \
193 stm32f4xx_fmc.c \
194 stm32f4xx_sai.c \
195 stm32f4xx_cec.c \
196 stm32f4xx_dsi.c \
197 stm32f4xx_flash_ramfunc.c \
198 stm32f4xx_fmpi2c.c \
199 stm32f4xx_lptim.c \
200 stm32f4xx_qspi.c \
201 stm32f4xx_spdifrx.c \
202 stm32f4xx_cryp.c \
203 stm32f4xx_cryp_aes.c \
204 stm32f4xx_hash_md5.c \
205 stm32f4xx_cryp_des.c \
206 stm32f4xx_rtc.c \
207 stm32f4xx_hash.c \
208 stm32f4xx_dbgmcu.c \
209 stm32f4xx_cryp_tdes.c \
210 stm32f4xx_hash_sha1.c
213 ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS)))
214 EXCLUDES += stm32f4xx_fsmc.c
215 endif
217 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
219 #USB
220 USBCORE_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Core
221 USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/src/*.c))
222 USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver
223 USBOTG_SRC = $(notdir $(wildcard $(USBOTG_DIR)/src/*.c))
224 EXCLUDES = usb_bsp_template.c \
225 usb_conf_template.c \
226 usb_hcd_int.c \
227 usb_hcd.c \
228 usb_otg.c
230 USBOTG_SRC := $(filter-out ${EXCLUDES}, $(USBOTG_SRC))
231 USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc
232 USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/src/*.c))
233 EXCLUDES = usbd_cdc_if_template.c
234 USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
235 VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src
237 DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
238 $(USBOTG_SRC) \
239 $(USBCORE_SRC) \
240 $(USBCDC_SRC)
242 #CMSIS
243 VPATH := $(VPATH):$(CMSIS_DIR)/CM4/CoreSupport:$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx
244 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM4/CoreSupport/*.c \
245 $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx/*.c))
246 INCLUDE_DIRS := $(INCLUDE_DIRS) \
247 $(STDPERIPH_DIR)/inc \
248 $(USBOTG_DIR)/inc \
249 $(USBCORE_DIR)/inc \
250 $(USBCDC_DIR)/inc \
251 $(USBFS_DIR)/inc \
252 $(CMSIS_DIR)/CM4/CoreSupport \
253 $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \
254 $(ROOT)/src/main/vcpf4
256 ifneq ($(filter SDCARD,$(FEATURES)),)
257 INCLUDE_DIRS := $(INCLUDE_DIRS) \
258 $(FATFS_DIR)
259 VPATH := $(VPATH):$(FATFS_DIR)
260 endif
262 #Flags
263 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
265 ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS)))
266 DEVICE_FLAGS = -DSTM32F411xE
267 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld
268 else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS)))
269 DEVICE_FLAGS = -DSTM32F40_41xxx
270 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld
271 else
272 $(error Unknown MCU for F4 target)
273 endif
274 DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
276 TARGET_FLAGS = -D$(TARGET)
277 # End F4 targets
279 # Start F1 targets
280 else
282 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
283 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
284 EXCLUDES = stm32f10x_crc.c \
285 stm32f10x_cec.c \
286 stm32f10x_can.c
288 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
290 # Search path and source files for the CMSIS sources
291 VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x
292 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \
293 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c))
295 INCLUDE_DIRS := $(INCLUDE_DIRS) \
296 $(STDPERIPH_DIR)/inc \
297 $(CMSIS_DIR)/CM3/CoreSupport \
298 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \
300 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
302 ifneq ($(filter VCP, $(FEATURES)),)
303 INCLUDE_DIRS := $(INCLUDE_DIRS) \
304 $(USBFS_DIR)/inc \
305 $(ROOT)/src/main/vcp
307 VPATH := $(VPATH):$(USBFS_DIR)/src
309 DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC) \
310 $(USBPERIPH_SRC)
312 endif
314 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld
315 ARCH_FLAGS = -mthumb -mcpu=cortex-m3
316 TARGET_FLAGS := -D$(TARGET) -pedantic $(TARGET_FLAGS)
318 ifeq ($(DEVICE_FLAGS),)
319 DEVICE_FLAGS = -DSTM32F10X_MD
320 endif
321 DEVICE_FLAGS += -DSTM32F10X
323 endif
325 # End F1 targets
327 ifneq ($(BASE_TARGET), $(TARGET))
328 TARGET_FLAGS := $(TARGET_FLAGS) -D$(BASE_TARGET)
329 endif
331 ifneq ($(FLASH_SIZE),)
332 DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE)
333 endif
335 TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET)
336 TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
338 ifeq ($(OPBL),yes)
339 TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
340 ifeq ($(TARGET), $(filter $(TARGET),$(F405_TARGETS)))
341 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405_opbl.ld
342 else ifeq ($(TARGET), $(filter $(TARGET),$(F411_TARGETS)))
343 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411_opbl.ld
344 else ifeq ($(TARGET), $(filter $(TARGET),$(F3_TARGETS)))
345 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k_opbl.ld
346 else ifeq ($(TARGET), $(filter $(TARGET),$(F1_TARGETS)))
347 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld
348 endif
349 .DEFAULT_GOAL := binary
350 else
351 .DEFAULT_GOAL := hex
352 endif
354 INCLUDE_DIRS := $(INCLUDE_DIRS) \
355 $(TARGET_DIR)
357 VPATH := $(VPATH):$(TARGET_DIR)
359 COMMON_SRC = \
360 build_config.c \
361 debug.c \
362 version.c \
363 $(TARGET_DIR_SRC) \
364 main.c \
365 mw.c \
366 common/encoding.c \
367 common/filter.c \
368 common/maths.c \
369 common/printf.c \
370 common/typeconversion.c \
371 config/config.c \
372 config/runtime_config.c \
373 drivers/adc.c \
374 drivers/buf_writer.c \
375 drivers/bus_i2c_soft.c \
376 drivers/bus_spi.c \
377 drivers/bus_spi_soft.c \
378 drivers/gps_i2cnav.c \
379 drivers/gyro_sync.c \
380 drivers/io.c \
381 drivers/light_led.c \
382 drivers/rx_nrf24l01.c \
383 drivers/rx_xn297.c \
384 drivers/pwm_mapping.c \
385 drivers/pwm_output.c \
386 drivers/pwm_rx.c \
387 drivers/rcc.c \
388 drivers/serial.c \
389 drivers/serial_uart.c \
390 drivers/sound_beeper.c \
391 drivers/system.c \
392 drivers/timer.c \
393 flight/failsafe.c \
394 flight/imu.c \
395 flight/hil.c \
396 flight/mixer.c \
397 flight/pid.c \
398 io/beeper.c \
399 io/rc_controls.c \
400 io/rc_curves.c \
401 io/serial.c \
402 io/serial_4way.c \
403 io/serial_4way_avrootloader.c \
404 io/serial_4way_stk500v2.c \
405 io/serial_cli.c \
406 io/serial_msp.c \
407 io/statusindicator.c \
408 rx/ibus.c \
409 rx/msp.c \
410 rx/nrf24.c \
411 rx/nrf24_cx10.c \
412 rx/nrf24_ref.c \
413 rx/nrf24_h8_3d.c \
414 rx/nrf24_syma.c \
415 rx/nrf24_v202.c \
416 rx/pwm.c \
417 rx/rx.c \
418 rx/sbus.c \
419 rx/spektrum.c \
420 rx/sumd.c \
421 rx/sumh.c \
422 rx/xbus.c \
423 scheduler/scheduler.c \
424 scheduler/scheduler_tasks.c \
425 sensors/acceleration.c \
426 sensors/battery.c \
427 sensors/boardalignment.c \
428 sensors/compass.c \
429 sensors/gyro.c \
430 sensors/initialisation.c \
431 $(CMSIS_SRC) \
432 $(DEVICE_STDPERIPH_SRC)
434 HIGHEND_SRC = \
435 blackbox/blackbox.c \
436 blackbox/blackbox_io.c \
437 common/colorconversion.c \
438 drivers/display_ug2864hsweg01.c \
439 flight/navigation_rewrite.c \
440 flight/navigation_rewrite_multicopter.c \
441 flight/navigation_rewrite_fixedwing.c \
442 flight/navigation_rewrite_pos_estimator.c \
443 flight/navigation_rewrite_geo.c \
444 flight/gps_conversion.c \
445 io/gps.c \
446 io/gps_ublox.c \
447 io/gps_nmea.c \
448 io/gps_naza.c \
449 io/gps_i2cnav.c \
450 io/ledstrip.c \
451 io/display.c \
452 sensors/rangefinder.c \
453 sensors/barometer.c \
454 telemetry/telemetry.c \
455 telemetry/frsky.c \
456 telemetry/hott.c \
457 telemetry/smartport.c \
458 telemetry/mavlink.c \
459 telemetry/ltm.c
461 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
462 VCP_SRC = \
463 vcpf4/stm32f4xx_it.c \
464 vcpf4/usb_bsp.c \
465 vcpf4/usbd_desc.c \
466 vcpf4/usbd_usr.c \
467 vcpf4/usbd_cdc_vcp.c \
468 drivers/serial_usb_vcp.c
469 else
470 VCP_SRC = \
471 vcp/hw_config.c \
472 vcp/stm32_it.c \
473 vcp/usb_desc.c \
474 vcp/usb_endp.c \
475 vcp/usb_istr.c \
476 vcp/usb_prop.c \
477 vcp/usb_pwr.c \
478 drivers/serial_usb_vcp.c
479 endif
481 STM32F10x_COMMON_SRC = \
482 startup_stm32f10x_md_gcc.S \
483 drivers/adc_stm32f10x.c \
484 drivers/bus_i2c_stm32f10x.c \
485 drivers/gpio_stm32f10x.c \
486 drivers/inverter.c \
487 drivers/serial_softserial.c \
488 drivers/serial_uart_stm32f10x.c \
489 drivers/system_stm32f10x.c \
490 drivers/timer_stm32f10x.c
492 STM32F30x_COMMON_SRC = \
493 startup_stm32f30x_md_gcc.S \
494 target/system_stm32f30x.c \
495 drivers/adc_stm32f30x.c \
496 drivers/bus_i2c_stm32f30x.c \
497 drivers/gpio_stm32f30x.c \
498 drivers/light_ws2811strip.c \
499 drivers/light_ws2811strip_stm32f30x.c \
500 drivers/serial_uart_stm32f30x.c \
501 drivers/system_stm32f30x.c \
502 drivers/timer_stm32f30x.c
504 STM32F4xx_COMMON_SRC = \
505 startup_stm32f40xx.s \
506 target/system_stm32f4xx.c \
507 drivers/accgyro_mpu.c \
508 drivers/adc_stm32f4xx.c \
509 drivers/adc_stm32f4xx.c \
510 drivers/bus_i2c_stm32f10x.c \
511 drivers/gpio_stm32f4xx.c \
512 drivers/inverter.c \
513 drivers/serial_softserial.c \
514 drivers/serial_uart_stm32f4xx.c \
515 drivers/system_stm32f4xx.c \
516 drivers/timer_stm32f4xx.c \
517 drivers/dma_stm32f4xx.c
519 # check if target.mk supplied
520 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
521 TARGET_SRC := $(STM32F4xx_COMMON_SRC) $(TARGET_SRC)
522 else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
523 TARGET_SRC := $(STM32F30x_COMMON_SRC) $(TARGET_SRC)
524 else ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
525 TARGET_SRC := $(STM32F10x_COMMON_SRC) $(TARGET_SRC)
526 endif
528 ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
529 TARGET_SRC += \
530 drivers/flash_m25p16.c \
531 io/flashfs.c
532 endif
534 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS) $(F3_TARGETS)))
535 TARGET_SRC += $(HIGHEND_SRC)
536 else ifneq ($(filter HIGHEND,$(FEATURES)),)
537 TARGET_SRC += $(HIGHEND_SRC)
538 endif
540 TARGET_SRC += $(COMMON_SRC)
542 ifneq ($(filter SDCARD,$(FEATURES)),)
543 TARGET_SRC += \
544 drivers/sdcard.c \
545 drivers/sdcard_standard.c \
546 io/asyncfatfs/asyncfatfs.c \
547 io/asyncfatfs/fat_standard.c
548 endif
550 ifneq ($(filter VCP,$(FEATURES)),)
551 TARGET_SRC += $(VCP_SRC)
552 endif
553 # end target specific make file checks
556 # Search path and source files for the ST stdperiph library
557 VPATH := $(VPATH):$(STDPERIPH_DIR)/src
559 ###############################################################################
560 # Things that might need changing to use different tools
563 # Tool names
564 CC = arm-none-eabi-gcc
565 OBJCOPY = arm-none-eabi-objcopy
566 SIZE = arm-none-eabi-size
569 # Tool options.
572 ifeq ($(DEBUG),GDB)
573 OPTIMIZE = -O0
574 LTO_FLAGS = $(OPTIMIZE)
575 else
576 OPTIMIZE = -Os
577 LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
578 endif
580 DEBUG_FLAGS = -ggdb3 -DDEBUG
582 CFLAGS += $(ARCH_FLAGS) \
583 $(LTO_FLAGS) \
584 $(addprefix -D,$(OPTIONS)) \
585 $(addprefix -I,$(INCLUDE_DIRS)) \
586 $(DEBUG_FLAGS) \
587 -std=gnu99 \
588 -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \
589 -ffunction-sections \
590 -fdata-sections \
591 $(DEVICE_FLAGS) \
592 -DUSE_STDPERIPH_DRIVER \
593 $(TARGET_FLAGS) \
594 -D'__FORKNAME__="$(FORKNAME)"' \
595 -D'__TARGET__="$(TARGET)"' \
596 -D'__REVISION__="$(REVISION)"' \
597 -save-temps=obj \
598 -MMD -MP
600 ASFLAGS = $(ARCH_FLAGS) \
601 -x assembler-with-cpp \
602 $(addprefix -I,$(INCLUDE_DIRS)) \
603 -MMD -MP
605 LDFLAGS = -lm \
606 -nostartfiles \
607 --specs=nano.specs \
608 -lc \
609 -lnosys \
610 $(ARCH_FLAGS) \
611 $(LTO_FLAGS) \
612 $(DEBUG_FLAGS) \
613 -static \
614 -Wl,-gc-sections,-Map,$(TARGET_MAP) \
615 -Wl,-L$(LINKER_DIR) \
616 -Wl,--cref \
617 -T$(LD_SCRIPT)
619 ###############################################################################
620 # No user-serviceable parts below
621 ###############################################################################
623 CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \
624 --std=c99 --inline-suppr --quiet --force \
625 $(addprefix -I,$(INCLUDE_DIRS)) \
626 -I/usr/include -I/usr/include/linux
629 # Things we will build
631 TARGET_BIN = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).bin
632 TARGET_HEX = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).hex
633 TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
634 TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC))))
635 TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC))))
636 TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
639 CLEAN_ARTIFACTS := $(TARGET_BIN)
640 CLEAN_ARTIFACTS += $(TARGET_HEX)
641 CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
643 # List of buildable ELF files and their object dependencies.
644 # It would be nice to compute these lists, but that seems to be just beyond make.
646 $(TARGET_HEX): $(TARGET_ELF)
647 $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
649 $(TARGET_BIN): $(TARGET_ELF)
650 $(OBJCOPY) -O binary $< $@
652 $(TARGET_ELF): $(TARGET_OBJS)
653 @echo LD $(notdir $@)
654 @$(CC) -o $@ $^ $(LDFLAGS)
655 $(SIZE) $(TARGET_ELF)
657 # Compile
658 $(OBJECT_DIR)/$(TARGET)/%.o: %.c
659 @mkdir -p $(dir $@)
660 @echo %% $(notdir $<)
661 @$(CC) -c -o $@ $(CFLAGS) $<
663 # Assemble
664 $(OBJECT_DIR)/$(TARGET)/%.o: %.s
665 @mkdir -p $(dir $@)
666 @echo %% $(notdir $<)
667 @$(CC) -c -o $@ $(ASFLAGS) $<
669 $(OBJECT_DIR)/$(TARGET)/%.o: %.S
670 @mkdir -p $(dir $@)
671 @echo %% $(notdir $<)
672 @$(CC) -c -o $@ $(ASFLAGS) $<
675 ## all : Build all valid targets
676 all: $(VALID_TARGETS)
678 $(VALID_TARGETS):
679 echo "" && \
680 echo "Building $@" && \
681 $(MAKE) -j binary hex TARGET=$@ && \
682 echo "Building $@ succeeded."
684 ## clean : clean up all temporary / machine-generated files
685 clean:
686 rm -f $(CLEAN_ARTIFACTS)
687 rm -rf $(OBJECT_DIR)/$(TARGET)
689 ## clean_test : clean up all temporary / machine-generated files (tests)
690 clean_test:
691 cd src/test && $(MAKE) clean || true
693 ## clean_all_targets : clean all valid target platforms
694 clean_all:
695 for clean_target in $(VALID_TARGETS); do \
696 echo "" && \
697 echo "Cleaning $$clean_target" && \
698 $(MAKE) -j TARGET=$$clean_target clean || \
699 break; \
700 echo "Cleaning $$clean_target succeeded."; \
701 done
703 flash_$(TARGET): $(TARGET_HEX)
704 stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
705 echo -n 'R' >$(SERIAL_DEVICE)
706 stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
708 ## flash : flash firmware (.hex) onto flight controller
709 flash: flash_$(TARGET)
711 st-flash_$(TARGET): $(TARGET_BIN)
712 st-flash --reset write $< 0x08000000
714 ## st-flash : flash firmware (.bin) onto flight controller
715 st-flash: st-flash_$(TARGET)
717 binary: $(TARGET_BIN)
718 hex: $(TARGET_HEX)
720 unbrick_$(TARGET): $(TARGET_HEX)
721 stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
722 stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
724 ## unbrick : unbrick flight controller
725 unbrick: unbrick_$(TARGET)
727 ## cppcheck : run static analysis on C source code
728 cppcheck: $(CSOURCES)
729 $(CPPCHECK)
731 cppcheck-result.xml: $(CSOURCES)
732 $(CPPCHECK) --xml-version=2 2> cppcheck-result.xml
734 ## help : print this help message and exit
735 help: Makefile
736 @echo ""
737 @echo "Makefile for the $(FORKNAME) firmware"
738 @echo ""
739 @echo "Usage:"
740 @echo " make [TARGET=<target>] [OPTIONS=\"<options>\"]"
741 @echo "Or:"
742 @echo " make <target> [OPTIONS=\"<options>\"]"
743 @echo ""
744 @echo "Valid TARGET values are: $(VALID_TARGETS)"
745 @echo ""
746 @sed -n 's/^## //p' $<
748 ## targets : print a list of all valid target platforms (for consumption by scripts)
749 targets:
750 @echo "Valid targets: $(VALID_TARGETS)"
751 @echo "Target: $(TARGET)"
752 @echo "Base target: $(BASE_TARGET)"
754 ## test : run the cleanflight test suite
755 test:
756 cd src/test && $(MAKE) test || true
758 # rebuild everything when makefile changes
759 $(TARGET_OBJS) : Makefile
761 # include auto-generated dependencies
762 -include $(TARGET_DEPS)