Makefile improvement
[betaflight.git] / Makefile
bloba1fcd08848fce11c07e8961fe59d5fc940532e6e
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 cleanflight firmware.
10 # Invoke this with 'make help' to see the list of supported targets.
13 ###############################################################################
14 # Things that the user might override on the commandline
17 # The target to build, see VALID_TARGETS below
18 TARGET ?= NAZE
20 # Compile-time options
21 OPTIONS ?=
23 # compile for OpenPilot BootLoader support
24 OPBL ?=no
26 # Debugger optons, must be empty or GDB
27 DEBUG ?=
29 # Serial port/Device for flashing
30 SERIAL_DEVICE ?= /dev/ttyUSB0
32 ###############################################################################
33 # Things that need to be maintained as the source changes
36 FORKNAME = cleanflight
38 VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC MASSIVEF3
40 # Valid targets for OP BootLoader support
41 OPBL_VALID_TARGETS = CC3D
43 REVISION = $(shell git log -1 --format="%h")
45 # Working directories
46 ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST))))
47 SRC_DIR = $(ROOT)/src/main
48 OBJECT_DIR = $(ROOT)/obj/main
49 BIN_DIR = $(ROOT)/obj
50 CMSIS_DIR = $(ROOT)/lib/main/CMSIS
51 INCLUDE_DIRS = $(SRC_DIR)
52 LINKER_DIR = $(ROOT)/src/main/target
54 # Search path for sources
55 VPATH := $(SRC_DIR):$(SRC_DIR)/startup
57 ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO MASSIVEF3))
59 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
60 USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver
62 USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c))
63 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
65 EXCLUDES = stm32f30x_crc.c \
66 stm32f30x_can.c
68 STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
70 DEVICE_STDPERIPH_SRC = $(USBPERIPH_SRC) \
71 $(STDPERIPH_SRC)
74 VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x:$(USBFS_DIR)/src
75 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM1/CoreSupport/*.c \
76 $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c))
78 INCLUDE_DIRS := $(INCLUDE_DIRS) \
79 $(STDPERIPH_DIR)/inc \
80 $(USBFS_DIR)/inc \
81 $(CMSIS_DIR)/CM1/CoreSupport \
82 $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x \
83 $(ROOT)/src/main/vcp
85 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_256k.ld
87 ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
88 DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
89 TARGET_FLAGS = -D$(TARGET)
90 ifeq ($(TARGET),CHEBUZZF3)
91 # CHEBUZZ is a VARIANT of STM32F3DISCOVERY
92 TARGET_FLAGS := $(TARGET_FLAGS) -DSTM32F3DISCOVERY
93 endif
95 ifeq ($(TARGET),MASSIVEF3)
96 # MASSIVEF3 is a VARIANT of STM32F3DISCOVERY
97 TARGET_FLAGS := $(TARGET_FLAGS) -DSTM32F3DISCOVERY
98 endif
101 else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC))
104 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
106 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
108 # Search path and source files for the CMSIS sources
109 VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x
110 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \
111 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c))
113 INCLUDE_DIRS := $(INCLUDE_DIRS) \
114 $(STDPERIPH_DIR)/inc \
115 $(CMSIS_DIR)/CM3/CoreSupport \
116 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \
118 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_256k.ld
120 ARCH_FLAGS = -mthumb -mcpu=cortex-m3
121 TARGET_FLAGS = -D$(TARGET) -pedantic
122 DEVICE_FLAGS = -DSTM32F10X_HD -DSTM32F10X
124 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
126 else
128 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
130 STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
132 # Search path and source files for the CMSIS sources
133 VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x
134 CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \
135 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c))
137 INCLUDE_DIRS := $(INCLUDE_DIRS) \
138 $(STDPERIPH_DIR)/inc \
139 $(CMSIS_DIR)/CM3/CoreSupport \
140 $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \
142 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_128k.ld
144 ARCH_FLAGS = -mthumb -mcpu=cortex-m3
145 TARGET_FLAGS = -D$(TARGET) -pedantic
146 DEVICE_FLAGS = -DSTM32F10X_MD -DSTM32F10X
148 DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
150 endif
152 TARGET_DIR = $(ROOT)/src/main/target/$(TARGET)
153 TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
155 INCLUDE_DIRS := $(INCLUDE_DIRS) \
156 $(TARGET_DIR)
158 VPATH := $(VPATH):$(TARGET_DIR)
160 COMMON_SRC = build_config.c \
161 version.c \
162 $(TARGET_SRC) \
163 config/config.c \
164 config/runtime_config.c \
165 common/maths.c \
166 common/printf.c \
167 common/typeconversion.c \
168 main.c \
169 mw.c \
170 flight/altitudehold.c \
171 flight/failsafe.c \
172 flight/flight.c \
173 flight/imu.c \
174 flight/mixer.c \
175 drivers/bus_i2c_soft.c \
176 drivers/serial.c \
177 drivers/sound_beeper.c \
178 drivers/system.c \
179 io/beeper.c \
180 io/rc_controls.c \
181 io/rc_curves.c \
182 io/serial.c \
183 io/serial_cli.c \
184 io/serial_msp.c \
185 io/statusindicator.c \
186 rx/rx.c \
187 rx/pwm.c \
188 rx/msp.c \
189 rx/sbus.c \
190 rx/sumd.c \
191 rx/sumh.c \
192 rx/spektrum.c \
193 sensors/acceleration.c \
194 sensors/battery.c \
195 sensors/boardalignment.c \
196 sensors/compass.c \
197 sensors/gyro.c \
198 sensors/initialisation.c \
199 $(CMSIS_SRC) \
200 $(DEVICE_STDPERIPH_SRC)
202 HIGHEND_SRC = flight/autotune.c \
203 flight/navigation.c \
204 flight/gps_conversion.c \
205 common/colorconversion.c \
206 io/gps.c \
207 io/ledstrip.c \
208 io/display.c \
209 telemetry/telemetry.c \
210 telemetry/frsky.c \
211 telemetry/hott.c \
212 telemetry/msp.c \
213 sensors/sonar.c \
214 sensors/barometer.c
216 NAZE_SRC = startup_stm32f10x_md_gcc.S \
217 drivers/accgyro_adxl345.c \
218 drivers/accgyro_bma280.c \
219 drivers/accgyro_l3g4200d.c \
220 drivers/accgyro_mma845x.c \
221 drivers/accgyro_mpu3050.c \
222 drivers/accgyro_mpu6050.c \
223 drivers/accgyro_spi_mpu6500.c \
224 drivers/adc.c \
225 drivers/adc_stm32f10x.c \
226 drivers/barometer_bmp085.c \
227 drivers/barometer_ms5611.c \
228 drivers/bus_spi.c \
229 drivers/bus_i2c_stm32f10x.c \
230 drivers/compass_hmc5883l.c \
231 drivers/display_ug2864hsweg01.h \
232 drivers/gpio_stm32f10x.c \
233 drivers/inverter.c \
234 drivers/light_led_stm32f10x.c \
235 drivers/light_ws2811strip.c \
236 drivers/light_ws2811strip_stm32f10x.c \
237 drivers/sonar_hcsr04.c \
238 drivers/pwm_mapping.c \
239 drivers/pwm_output.c \
240 drivers/pwm_rx.c \
241 drivers/serial_softserial.c \
242 drivers/serial_uart.c \
243 drivers/serial_uart_stm32f10x.c \
244 drivers/sound_beeper_stm32f10x.c \
245 drivers/system_stm32f10x.c \
246 drivers/timer.c \
247 hardware_revision.c \
248 $(HIGHEND_SRC) \
249 $(COMMON_SRC)
251 EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \
252 drivers/accgyro_adxl345.c \
253 drivers/accgyro_bma280.c \
254 drivers/accgyro_l3g4200d.c \
255 drivers/accgyro_mma845x.c \
256 drivers/accgyro_mpu3050.c \
257 drivers/accgyro_mpu6050.c \
258 drivers/accgyro_spi_mpu6000.c \
259 drivers/accgyro_spi_mpu6500.c \
260 drivers/adc.c \
261 drivers/adc_stm32f10x.c \
262 drivers/barometer_bmp085.c \
263 drivers/barometer_ms5611.c \
264 drivers/bus_i2c_stm32f10x.c \
265 drivers/bus_spi.c \
266 drivers/compass_hmc5883l.c \
267 drivers/display_ug2864hsweg01.h \
268 drivers/gpio_stm32f10x.c \
269 drivers/light_led_stm32f10x.c \
270 drivers/light_ws2811strip.c \
271 drivers/light_ws2811strip_stm32f10x.c \
272 drivers/pwm_mapping.c \
273 drivers/pwm_output.c \
274 drivers/pwm_rx.c \
275 drivers/serial_softserial.c \
276 drivers/serial_uart.c \
277 drivers/serial_uart_stm32f10x.c \
278 drivers/sonar_hcsr04.c \
279 drivers/sound_beeper_stm32f10x.c \
280 drivers/system_stm32f10x.c \
281 drivers/timer.c \
282 $(HIGHEND_SRC) \
283 $(COMMON_SRC)
285 OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
286 drivers/accgyro_mpu6050.c \
287 drivers/adc.c \
288 drivers/adc_stm32f10x.c \
289 drivers/barometer_bmp085.c \
290 drivers/bus_i2c_stm32f10x.c \
291 drivers/bus_spi.c \
292 drivers/compass_hmc5883l.c \
293 drivers/gpio_stm32f10x.c \
294 drivers/light_led_stm32f10x.c \
295 drivers/light_ws2811strip.c \
296 drivers/light_ws2811strip_stm32f10x.c \
297 drivers/pwm_mapping.c \
298 drivers/pwm_output.c \
299 drivers/pwm_rx.c \
300 drivers/serial_softserial.c \
301 drivers/serial_uart.c \
302 drivers/serial_uart_stm32f10x.c \
303 drivers/sonar_hcsr04.c \
304 drivers/sound_beeper_stm32f10x.c \
305 drivers/system_stm32f10x.c \
306 drivers/timer.c \
307 $(HIGHEND_SRC) \
308 $(COMMON_SRC)
310 ifeq ($(TARGET),CJMCU)
311 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_64k.ld
312 endif
314 ifeq ($(OPBL),yes)
315 ifneq ($(filter $(TARGET),$(OPBL_VALID_TARGETS)),)
316 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_128k_opbl.ld
317 .DEFAULT_GOAL := binary
318 else
319 $(error OPBL specified with a unsupported target)
320 endif
321 endif
323 CJMCU_SRC = startup_stm32f10x_md_gcc.S \
324 drivers/adc.c \
325 drivers/adc_stm32f10x.c \
326 drivers/accgyro_mpu6050.c \
327 drivers/bus_i2c_stm32f10x.c \
328 drivers/compass_hmc5883l.c \
329 drivers/gpio_stm32f10x.c \
330 drivers/light_led_stm32f10x.c \
331 drivers/pwm_mapping.c \
332 drivers/pwm_output.c \
333 drivers/pwm_rx.c \
334 drivers/serial_uart.c \
335 drivers/serial_uart_stm32f10x.c \
336 drivers/sound_beeper_stm32f10x.c \
337 drivers/system_stm32f10x.c \
338 drivers/timer.c \
339 $(COMMON_SRC)
341 CC3D_SRC = startup_stm32f10x_md_gcc.S \
342 drivers/accgyro_spi_mpu6000.c \
343 drivers/adc.c \
344 drivers/adc_stm32f10x.c \
345 drivers/bus_spi.c \
346 drivers/gpio_stm32f10x.c \
347 drivers/inverter.c \
348 drivers/light_led_stm32f10x.c \
349 drivers/light_ws2811strip.c \
350 drivers/light_ws2811strip_stm32f10x.c \
351 drivers/pwm_mapping.c \
352 drivers/pwm_output.c \
353 drivers/pwm_rx.c \
354 drivers/serial_softserial.c \
355 drivers/serial_uart.c \
356 drivers/serial_uart_stm32f10x.c \
357 drivers/sound_beeper_stm32f10x.c \
358 drivers/system_stm32f10x.c \
359 drivers/timer.c \
360 $(HIGHEND_SRC) \
361 $(COMMON_SRC)
363 STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S \
364 drivers/adc.c \
365 drivers/adc_stm32f30x.c \
366 drivers/bus_i2c_stm32f30x.c \
367 drivers/bus_spi.c \
368 drivers/gpio_stm32f30x.c \
369 drivers/light_led_stm32f30x.c \
370 drivers/light_ws2811strip.c \
371 drivers/light_ws2811strip_stm32f30x.c \
372 drivers/pwm_mapping.c \
373 drivers/pwm_output.c \
374 drivers/pwm_rx.c \
375 drivers/serial_uart.c \
376 drivers/serial_uart_stm32f30x.c \
377 drivers/serial_usb_vcp.c \
378 drivers/sound_beeper_stm32f30x.c \
379 drivers/system_stm32f30x.c \
380 drivers/timer.c \
381 vcp/hw_config.c \
382 vcp/stm32_it.c \
383 vcp/usb_desc.c \
384 vcp/usb_endp.c \
385 vcp/usb_istr.c \
386 vcp/usb_prop.c \
387 vcp/usb_pwr.c
389 NAZE32PRO_SRC = $(STM32F30x_COMMON_SRC) \
390 $(HIGHEND_SRC) \
391 $(COMMON_SRC)
393 STM32F3DISCOVERY_COMMON_SRC = $(STM32F30x_COMMON_SRC) \
394 drivers/accgyro_l3gd20.c \
395 drivers/accgyro_l3gd20.c \
396 drivers/accgyro_lsm303dlhc.c
398 STM32F3DISCOVERY_SRC = $(STM32F3DISCOVERY_COMMON_SRC) \
399 drivers/accgyro_adxl345.c \
400 drivers/accgyro_bma280.c \
401 drivers/accgyro_mma845x.c \
402 drivers/accgyro_mpu3050.c \
403 drivers/accgyro_mpu6050.c \
404 drivers/accgyro_l3g4200d.c \
405 $(HIGHEND_SRC) \
406 $(COMMON_SRC)
408 CHEBUZZF3_SRC = $(STM32F3DISCOVERY_SRC) \
409 $(HIGHEND_SRC) \
410 $(COMMON_SRC)
412 MASSIVEF3_SRC = $(STM32F3DISCOVERY_SRC) \
413 $(HIGHEND_SRC) \
414 $(COMMON_SRC)
416 ifeq ($(TARGET),MASSIVEF3)
417 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_128k.ld
418 endif
420 # Search path and source files for the ST stdperiph library
421 VPATH := $(VPATH):$(STDPERIPH_DIR)/src
423 ###############################################################################
424 # Things that might need changing to use different tools
427 # Tool names
428 CC = arm-none-eabi-gcc
429 OBJCOPY = arm-none-eabi-objcopy
430 SIZE = arm-none-eabi-size
433 # Tool options.
436 ifeq ($(DEBUG),GDB)
437 OPTIMIZE = -O0
438 LTO_FLAGS = $(OPTIMIZE)
439 else
440 OPTIMIZE = -Os
441 LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
442 endif
444 DEBUG_FLAGS = -ggdb3
446 CFLAGS = $(ARCH_FLAGS) \
447 $(LTO_FLAGS) \
448 $(addprefix -D,$(OPTIONS)) \
449 $(addprefix -I,$(INCLUDE_DIRS)) \
450 $(DEBUG_FLAGS) \
451 -std=gnu99 \
452 -Wall -Wextra -Wunsafe-loop-optimizations \
453 -ffunction-sections \
454 -fdata-sections \
455 $(DEVICE_FLAGS) \
456 -DUSE_STDPERIPH_DRIVER \
457 $(TARGET_FLAGS) \
458 -D'__FORKNAME__="$(FORKNAME)"' \
459 -D'__TARGET__="$(TARGET)"' \
460 -D'__REVISION__="$(REVISION)"' \
461 -save-temps=obj \
464 ASFLAGS = $(ARCH_FLAGS) \
465 -x assembler-with-cpp \
466 $(addprefix -I,$(INCLUDE_DIRS)) \
469 LDFLAGS = -lm \
470 -nostartfiles \
471 --specs=nano.specs \
472 -lc \
473 -lnosys \
474 $(ARCH_FLAGS) \
475 $(LTO_FLAGS) \
476 $(DEBUG_FLAGS) \
477 -static \
478 -Wl,-gc-sections,-Map,$(TARGET_MAP) \
479 -T$(LD_SCRIPT)
481 ###############################################################################
482 # No user-serviceable parts below
483 ###############################################################################
486 # Things we will build
488 ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
489 $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS))
490 endif
492 TARGET_BIN = $(BIN_DIR)/$(FORKNAME)_$(TARGET).bin
493 TARGET_HEX = $(BIN_DIR)/$(FORKNAME)_$(TARGET).hex
494 TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
495 TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC))))
496 TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC))))
497 TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
499 # List of buildable ELF files and their object dependencies.
500 # It would be nice to compute these lists, but that seems to be just beyond make.
502 $(TARGET_HEX): $(TARGET_ELF)
503 $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
505 $(TARGET_BIN): $(TARGET_ELF)
506 $(OBJCOPY) -O binary $< $@
508 $(TARGET_ELF): $(TARGET_OBJS)
509 $(CC) -o $@ $^ $(LDFLAGS)
510 $(SIZE) $(TARGET_ELF)
512 # Compile
513 $(OBJECT_DIR)/$(TARGET)/%.o: %.c
514 @mkdir -p $(dir $@)
515 @echo %% $(notdir $<)
516 @$(CC) -c -o $@ $(CFLAGS) $<
518 # Assemble
519 $(OBJECT_DIR)/$(TARGET)/%.o: %.s
520 @mkdir -p $(dir $@)
521 @echo %% $(notdir $<)
522 @$(CC) -c -o $@ $(ASFLAGS) $<
524 $(OBJECT_DIR)/$(TARGET)/%.o: %.S
525 @mkdir -p $(dir $@)
526 @echo %% $(notdir $<)
527 @$(CC) -c -o $@ $(ASFLAGS) $<
529 clean:
530 rm -f $(TARGET_BIN) $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
531 rm -rf $(OBJECT_DIR)/$(TARGET)
533 flash_$(TARGET): $(TARGET_HEX)
534 stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
535 echo -n 'R' >$(SERIAL_DEVICE)
536 stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
538 flash: flash_$(TARGET)
540 binary: $(TARGET_BIN)
542 unbrick_$(TARGET): $(TARGET_HEX)
543 stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
544 stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
546 unbrick: unbrick_$(TARGET)
548 help:
549 @echo ""
550 @echo "Makefile for the $(FORKNAME) firmware"
551 @echo ""
552 @echo "Usage:"
553 @echo " make [TARGET=<target>] [OPTIONS=\"<options>\"]"
554 @echo ""
555 @echo "Valid TARGET values are: $(VALID_TARGETS)"
556 @echo ""
558 # rebuild everything when makefile changes
559 $(TARGET_OBJS) : Makefile
561 # include auto-generated dependencies
562 -include $(TARGET_DEPS)