mirror of https://github.com/ArduPilot/ardupilot
build: remove AVR boards
This commit is contained in:
parent
0151853c21
commit
0e6da397d1
|
@ -24,15 +24,8 @@ include $(MK_DIR)/targets.mk
|
|||
include $(MK_DIR)/sketch_sources.mk
|
||||
|
||||
ifneq ($(MAKECMDGOALS),clean)
|
||||
|
||||
# board specific includes
|
||||
ifeq ($(HAL_BOARD),HAL_BOARD_APM1)
|
||||
include $(MK_DIR)/board_avr.mk
|
||||
endif
|
||||
|
||||
ifeq ($(HAL_BOARD),HAL_BOARD_APM2)
|
||||
include $(MK_DIR)/board_avr.mk
|
||||
endif
|
||||
|
||||
ifeq ($(HAL_BOARD),HAL_BOARD_SITL)
|
||||
include $(MK_DIR)/board_native.mk
|
||||
endif
|
||||
|
|
200
mk/board_avr.mk
200
mk/board_avr.mk
|
@ -1,200 +0,0 @@
|
|||
TOOLCHAIN = AVR
|
||||
|
||||
include $(MK_DIR)/find_arduino.mk
|
||||
include $(MK_DIR)/find_tools.mk
|
||||
|
||||
#
|
||||
# Tool options
|
||||
#
|
||||
DEFINES = -DF_CPU=$(F_CPU)
|
||||
DEFINES += -DSKETCH=\"$(SKETCH)\" -DAPM_BUILD_DIRECTORY=APM_BUILD_$(SKETCH)
|
||||
DEFINES += $(EXTRAFLAGS)
|
||||
DEFINES += -DCONFIG_HAL_BOARD=$(HAL_BOARD)
|
||||
WARNFLAGS = -Wformat -Wall -Wshadow -Wpointer-arith -Wcast-align
|
||||
WARNFLAGS += -Wwrite-strings -Wformat=2 -Wno-unused-parameter -Wno-missing-field-initializers
|
||||
WARNFLAGSCXX = -Wno-reorder
|
||||
DEPFLAGS = -MD -MT $@
|
||||
|
||||
CXXOPTS = -ffunction-sections -fdata-sections -fno-exceptions -fsigned-char -fno-use-cxa-atexit
|
||||
COPTS = -ffunction-sections -fdata-sections -fsigned-char
|
||||
|
||||
ASOPTS = -x assembler-with-cpp
|
||||
LISTOPTS = -adhlns=$(@:.o=.lst)
|
||||
|
||||
NATIVE_CPUFLAGS = -D_GNU_SOURCE
|
||||
NATIVE_CPULDFLAGS = -g
|
||||
NATIVE_OPTFLAGS = -O0 -g
|
||||
|
||||
AVR_CPUFLAGS = -mmcu=$(MCU) -mcall-prologues
|
||||
AVR_CPULDFLAGS = -Wl,-m,avr6
|
||||
AVR_OPTFLAGS = -Os
|
||||
|
||||
CPUFLAGS= $($(TOOLCHAIN)_CPUFLAGS)
|
||||
CPULDFLAGS= $($(TOOLCHAIN)_CPULDFLAGS)
|
||||
OPTFLAGS= $($(TOOLCHAIN)_OPTFLAGS)
|
||||
|
||||
CXXFLAGS = -g $(CPUFLAGS) $(DEFINES) -Wa,$(LISTOPTS) $(OPTFLAGS)
|
||||
CXXFLAGS += -std=gnu++11 $(WARNFLAGS) $(WARNFLAGSCXX) $(DEPFLAGS) $(CXXOPTS)
|
||||
CFLAGS = -g $(CPUFLAGS) $(DEFINES) -Wa,$(LISTOPTS) $(OPTFLAGS)
|
||||
CFLAGS += $(WARNFLAGS) $(DEPFLAGS) $(COPTS)
|
||||
ASFLAGS = -g $(CPUFLAGS) $(DEFINES) -Wa,$(LISTOPTS) $(DEPFLAGS)
|
||||
ASFLAGS += $(ASOPTS)
|
||||
LDFLAGS = -g $(CPUFLAGS) $(OPTFLAGS) $(WARNFLAGS)
|
||||
LDFLAGS += -Wl,--gc-sections -Wl,-Map -Wl,$(SKETCHMAP)
|
||||
|
||||
ifneq ($(BOARD),mega)
|
||||
LDFLAGS += $(CPULDFLAGS)
|
||||
endif
|
||||
|
||||
# under certain situations with certain avr-gcc versions the --relax flag causes
|
||||
# a bug. Give the user a way to disable this flag per-sketch.
|
||||
# I know this is a rotten hack but we're really close to sunset on AVR.
|
||||
EXCLUDE_RELAX := $(wildcard $(SRCROOT)/norelax.inoflag)
|
||||
ifeq ($(EXCLUDE_RELAX),)
|
||||
LDFLAGS += -Wl,--relax
|
||||
endif
|
||||
|
||||
LIBS = -lm
|
||||
|
||||
ifeq ($(VERBOSE),)
|
||||
v = @
|
||||
else
|
||||
v =
|
||||
endif
|
||||
|
||||
# Library object files
|
||||
LIBOBJS := $(SKETCHLIBOBJS)
|
||||
|
||||
HARDWARE ?= arduino
|
||||
BOARD ?= mega2560
|
||||
|
||||
# Find the hardware directory to use
|
||||
HARDWARE_DIR := $(firstword $(wildcard $(SKETCHBOOK)/hardware/$(HARDWARE) \
|
||||
$(ARDUINO)/hardware/$(HARDWARE)/avr \
|
||||
$(ARDUINO)/hardware/$(HARDWARE) \
|
||||
)\
|
||||
)
|
||||
ifeq ($(HARDWARE_DIR),)
|
||||
$(error ERROR: hardware directory for $(HARDWARE) not found)
|
||||
endif
|
||||
|
||||
# Find the boards.txt that we are using
|
||||
BOARDFILE := $(wildcard $(HARDWARE_DIR)/boards.txt)
|
||||
ifeq ($(BOARDFILE),)
|
||||
$(error ERROR: could not locate boards.txt for hardware $(HARDWARE))
|
||||
endif
|
||||
|
||||
# Extract needed build parameters from the boardfile
|
||||
MCU := $(shell grep $(BOARD).build.mcu $(BOARDFILE) | cut -d = -f 2)
|
||||
F_CPU := $(shell grep $(BOARD).build.f_cpu $(BOARDFILE) | cut -d = -f 2)
|
||||
HARDWARE_CORE := $(shell grep $(BOARD).build.core $(BOARDFILE) | cut -d = -f 2)
|
||||
UPLOAD_SPEED := $(shell grep $(BOARD).upload.speed $(BOARDFILE) | cut -d = -f 2)
|
||||
|
||||
# User can define USERAVRDUDEFLAGS = -V in their config.mk to skip verification
|
||||
USERAVRDUDEFLAGS ?=
|
||||
#make sure the avrdude conf file is referenced correctly in cygwin
|
||||
ifneq ($(findstring CYGWIN, $(SYSTYPE)),)
|
||||
USERAVRDUDEFLAGS := -C $(ARDUINO)/hardware/tools/avr/etc/avrdude.conf
|
||||
endif
|
||||
#make sure the avrdude conf file is referenced correctly in mingw
|
||||
ifneq ($(findstring MINGW, $(SYSTYPE)),)
|
||||
USERAVRDUDEFLAGS := -C $(ARDUINO)/hardware/tools/avr/etc/avrdude.conf
|
||||
endif
|
||||
#make sure the avrdude conf file is referenced correctly in darwin
|
||||
ifneq ($(findstring Darwin, $(SYSTYPE)),)
|
||||
USERAVRDUDEFLAGS := -C $(ARDUINO)/hardware/tools/avr/etc/avrdude.conf
|
||||
endif
|
||||
|
||||
ifeq ($(UPLOAD_PROTOCOL),)
|
||||
UPLOAD_PROTOCOL := $(shell grep $(BOARD).upload.protocol $(BOARDFILE) | cut -d = -f 2)
|
||||
endif
|
||||
|
||||
# Adding override for mega since boards.txt uses stk500 instead of
|
||||
# arduino on 22 release
|
||||
ifeq ($(BOARD),mega)
|
||||
UPLOAD_PROTOCOL := arduino
|
||||
endif
|
||||
|
||||
#On Cygwin, the wiring programmer will perform the DTR reset for us
|
||||
ifneq ($(findstring CYGWIN, $(SYSTYPE)),)
|
||||
UPLOAD_PROTOCOL := wiring
|
||||
endif
|
||||
|
||||
ifeq ($(MCU),)
|
||||
$(error ERROR: Could not locate board $(BOARD) in $(BOARDFILE))
|
||||
endif
|
||||
|
||||
################################################################################
|
||||
# Built products
|
||||
#
|
||||
|
||||
# The ELF file
|
||||
SKETCHELF = $(BUILDROOT)/$(SKETCH).elf
|
||||
BUILDELF = $(notdir $(SKETCHELF))
|
||||
|
||||
# HEX file
|
||||
SKETCHHEX = $(BUILDROOT)/$(SKETCH).hex
|
||||
|
||||
# EEP file
|
||||
SKETCHEEP = $(BUILDROOT)/$(SKETCH).eep
|
||||
|
||||
# Map file
|
||||
SKETCHMAP = $(BUILDROOT)/$(SKETCH).map
|
||||
|
||||
# All of the objects that may be built
|
||||
ALLOBJS = $(SKETCHOBJS) $(LIBOBJS)
|
||||
|
||||
# All of the dependency files that may be generated
|
||||
ALLDEPS = $(ALLOBJS:%.o=%.d)
|
||||
|
||||
################################################################################
|
||||
# Targets
|
||||
#
|
||||
|
||||
all: $(SKETCHELF) $(SKETCHEEP) $(SKETCHHEX)
|
||||
|
||||
print-%:
|
||||
echo "$*=$($*)"
|
||||
|
||||
.PHONY: upload
|
||||
upload: $(SKETCHHEX)
|
||||
$(AVRDUDE) -c $(UPLOAD_PROTOCOL) -p $(MCU) -P $(PORT) -b$(UPLOAD_SPEED) $(USERAVRDUDEFLAGS) -U flash:w:$(SKETCHHEX):i
|
||||
|
||||
debug:
|
||||
$(AVARICE) --mkII --capture --jtag usb :4242 & \
|
||||
gnome-terminal -x $(GDB) $(SKETCHELF) & \
|
||||
echo -e '\n\nat the gdb prompt type "target remote localhost:4242"'
|
||||
|
||||
# this allows you to flash your image via JTAG for when you
|
||||
# have completely broken your USB
|
||||
jtag-program:
|
||||
$(AVARICE) --mkII --jtag usb --erase --program --file $(SKETCHELF)
|
||||
|
||||
################################################################################
|
||||
# Rules
|
||||
#
|
||||
|
||||
# fetch dependency info from a previous build if any of it exists
|
||||
-include $(ALLDEPS)
|
||||
|
||||
# Link the final object
|
||||
$(SKETCHELF): $(SKETCHOBJS) $(LIBOBJS)
|
||||
$(RULEHDR)
|
||||
$(v)$(LD) $(LDFLAGS) -o $@ $^ $(LIBS)
|
||||
$(v)cp $(SKETCHELF) $(BUILDELF)
|
||||
@echo "Firmware is in $(BUILDELF)"
|
||||
|
||||
# Create the hex file
|
||||
$(SKETCHHEX): $(SKETCHELF)
|
||||
$(RULEHDR)
|
||||
$(v)$(OBJCOPY) -O ihex -R .eeprom $< $@
|
||||
|
||||
# Create the eep file
|
||||
$(SKETCHEEP): $(SKETCHELF)
|
||||
$(RULEHDR)
|
||||
$(v)$(OBJCOPY) -O ihex -j.eeprom --set-section-flags=.eeprom=alloc,load --no-change-warnings --change-section-lma .eeprom=0 $< $@
|
||||
|
||||
SKETCH_INCLUDES = $(SKETCHLIBINCLUDES)
|
||||
SLIB_INCLUDES = -I$(dir $<)/utility $(SKETCHLIBINCLUDES)
|
||||
|
||||
include $(MK_DIR)/build_rules.mk
|
|
@ -193,16 +193,6 @@ HAL_BOARD = HAL_BOARD_VRBRAIN
|
|||
HAL_BOARD_SUBTYPE = HAL_BOARD_SUBTYPE_NONE
|
||||
endif
|
||||
|
||||
ifneq ($(findstring apm1, $(MAKECMDGOALS)),)
|
||||
HAL_BOARD = HAL_BOARD_APM1
|
||||
HAL_BOARD_SUBTYPE = HAL_BOARD_SUBTYPE_AVR_APM1
|
||||
endif
|
||||
|
||||
ifneq ($(findstring apm2, $(MAKECMDGOALS)),)
|
||||
HAL_BOARD = HAL_BOARD_APM2
|
||||
HAL_BOARD_SUBTYPE = HAL_BOARD_SUBTYPE_AVR_APM2
|
||||
endif
|
||||
|
||||
ifneq ($(findstring flymaple, $(MAKECMDGOALS)),)
|
||||
HAL_BOARD = HAL_BOARD_FLYMAPLE
|
||||
endif
|
||||
|
|
|
@ -7,7 +7,6 @@
|
|||
#
|
||||
ifeq ($(SYSTYPE),Darwin)
|
||||
# use the tools that come with Arduino
|
||||
TOOLPATH := $(ARDUINO)/hardware/tools/avr/bin
|
||||
# use BWK awk
|
||||
AWK = awk
|
||||
FIND_TOOL = $(firstword $(wildcard $(addsuffix /$(1),$(TOOLPATH))))
|
||||
|
@ -35,15 +34,6 @@ NATIVE_LD := g++
|
|||
NATIVE_GDB := gdb
|
||||
NATIVE_OBJCOPY := objcopy
|
||||
|
||||
AVR_CXX := $(call FIND_TOOL,avr-g++)
|
||||
AVR_CC := $(call FIND_TOOL,avr-gcc)
|
||||
AVR_AS := $(call FIND_TOOL,avr-gcc)
|
||||
AVR_AR := $(call FIND_TOOL,avr-ar)
|
||||
AVR_LD := $(call FIND_TOOL,avr-gcc)
|
||||
AVR_GDB := $(call FIND_TOOL,avr-gdb)
|
||||
AVR_OBJCOPY := $(call FIND_TOOL,avr-objcopy)
|
||||
|
||||
AVRDUDE := $(call FIND_TOOL,avrdude)
|
||||
AVARICE := $(call FIND_TOOL,avarice)
|
||||
|
||||
# Tools for Maple/Flymaple
|
||||
|
|
|
@ -20,8 +20,6 @@ help:
|
|||
@echo " Targets"
|
||||
@echo " -------"
|
||||
@echo ""
|
||||
@echo " apm1 - the APM1 board"
|
||||
@echo " apm2 - the APM2 board"
|
||||
@echo " px4-v1 - the PX4v1 board"
|
||||
@echo " px4-v2 - the Pixhawk"
|
||||
@echo " pxf - the Beagle Bone Black (BBB) + PXF cape combination"
|
||||
|
|
|
@ -9,18 +9,8 @@ sitl-arm: HAL_BOARD = HAL_BOARD_SITL
|
|||
sitl-arm: TOOLCHAIN = RPI
|
||||
sitl-arm: all
|
||||
|
||||
apm1: HAL_BOARD = HAL_BOARD_APM1
|
||||
apm1: TOOLCHAIN = AVR
|
||||
apm1: all
|
||||
|
||||
apm1-1280: HAL_BOARD = HAL_BOARD_APM1
|
||||
apm1-1280: TOOLCHAIN = AVR
|
||||
apm1-1280: all
|
||||
apm1-1280: BOARD = mega
|
||||
|
||||
apm2: HAL_BOARD = HAL_BOARD_APM2
|
||||
apm2: TOOLCHAIN = AVR
|
||||
apm2: all
|
||||
apm1 apm1-1280 apm2 apm2beta:
|
||||
$(error $@ is deprecated on master branch; use master-AVR)
|
||||
|
||||
flymaple: HAL_BOARD = HAL_BOARD_FLYMAPLE
|
||||
flymaple: TOOLCHAIN = ARM
|
||||
|
@ -111,9 +101,6 @@ USED_FRAMES := $(foreach frame,$(FRAMES), $(findstring $(frame), $(MAKECMDGOALS)
|
|||
$(foreach board,$(USED_BOARDS),$(eval $(call board_template,$(board))))
|
||||
$(foreach board,$(USED_BOARDS),$(foreach frame,$(USED_FRAMES),$(eval $(call frame_template,$(board),$(frame)))))
|
||||
|
||||
apm2beta: EXTRAFLAGS += "-DAPM2_BETA_HARDWARE "
|
||||
apm2beta: apm2
|
||||
|
||||
sitl-mount: EXTRAFLAGS += "-DMOUNT=ENABLED"
|
||||
sitl-mount: sitl
|
||||
|
||||
|
|
Loading…
Reference in New Issue