From b4029dd824cec7a0b53c62e960f80d90ddc6e13c Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 7 Jul 2013 17:53:55 -0700 Subject: Pull v2 pieces up to build with the merge --- makefiles/board_px4fmu-v2.mk | 10 +++ makefiles/board_px4fmuv2.mk | 10 --- makefiles/board_px4io-v2.mk | 10 +++ makefiles/board_px4iov2.mk | 10 --- makefiles/config_px4fmu-v2_default.mk | 122 ++++++++++++++++++++++++++++++++++ makefiles/config_px4fmu-v2_test.mk | 40 +++++++++++ makefiles/config_px4fmuv2_default.mk | 122 ---------------------------------- makefiles/config_px4fmuv2_test.mk | 45 ------------- makefiles/config_px4io-v2_default.mk | 10 +++ makefiles/config_px4iov2_default.mk | 10 --- makefiles/setup.mk | 1 - makefiles/upload.mk | 2 +- 12 files changed, 193 insertions(+), 199 deletions(-) create mode 100644 makefiles/board_px4fmu-v2.mk delete mode 100644 makefiles/board_px4fmuv2.mk create mode 100644 makefiles/board_px4io-v2.mk delete mode 100644 makefiles/board_px4iov2.mk create mode 100644 makefiles/config_px4fmu-v2_default.mk create mode 100644 makefiles/config_px4fmu-v2_test.mk delete mode 100644 makefiles/config_px4fmuv2_default.mk delete mode 100644 makefiles/config_px4fmuv2_test.mk create mode 100644 makefiles/config_px4io-v2_default.mk delete mode 100644 makefiles/config_px4iov2_default.mk (limited to 'makefiles') diff --git a/makefiles/board_px4fmu-v2.mk b/makefiles/board_px4fmu-v2.mk new file mode 100644 index 000000000..4b3b7e585 --- /dev/null +++ b/makefiles/board_px4fmu-v2.mk @@ -0,0 +1,10 @@ +# +# Board-specific definitions for the PX4FMUv2 +# + +# +# Configure the toolchain +# +CONFIG_ARCH = CORTEXM4F + +include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/board_px4fmuv2.mk b/makefiles/board_px4fmuv2.mk deleted file mode 100644 index 4b3b7e585..000000000 --- a/makefiles/board_px4fmuv2.mk +++ /dev/null @@ -1,10 +0,0 @@ -# -# Board-specific definitions for the PX4FMUv2 -# - -# -# Configure the toolchain -# -CONFIG_ARCH = CORTEXM4F - -include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/board_px4io-v2.mk b/makefiles/board_px4io-v2.mk new file mode 100644 index 000000000..ee6b6125e --- /dev/null +++ b/makefiles/board_px4io-v2.mk @@ -0,0 +1,10 @@ +# +# Board-specific definitions for the PX4IOv2 +# + +# +# Configure the toolchain +# +CONFIG_ARCH = CORTEXM3 + +include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/board_px4iov2.mk b/makefiles/board_px4iov2.mk deleted file mode 100644 index ee6b6125e..000000000 --- a/makefiles/board_px4iov2.mk +++ /dev/null @@ -1,10 +0,0 @@ -# -# Board-specific definitions for the PX4IOv2 -# - -# -# Configure the toolchain -# -CONFIG_ARCH = CORTEXM3 - -include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk new file mode 100644 index 000000000..c4499048c --- /dev/null +++ b/makefiles/config_px4fmu-v2_default.mk @@ -0,0 +1,122 @@ +# +# Makefile for the px4fmu_default configuration +# + +# +# Use the configuration's ROMFS. +# +ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common + +# +# Board support modules +# +MODULES += drivers/device +MODULES += drivers/stm32 +MODULES += drivers/stm32/adc +MODULES += drivers/stm32/tone_alarm +MODULES += drivers/px4fmu +MODULES += drivers/px4io +MODULES += drivers/boards/px4fmuv2 +MODULES += drivers/rgbled +MODULES += drivers/lsm303d +MODULES += drivers/l3gd20 +#MODULES += drivers/mpu6000 +MODULES += drivers/hmc5883 +MODULES += drivers/ms5611 +MODULES += drivers/mb12xx +MODULES += drivers/gps +MODULES += drivers/hil +MODULES += drivers/hott_telemetry +MODULES += drivers/blinkm +MODULES += modules/sensors + +# +# System commands +# +MODULES += systemcmds/ramtron +MODULES += systemcmds/bl_update +MODULES += systemcmds/boardinfo +MODULES += systemcmds/mixer +MODULES += systemcmds/param +MODULES += systemcmds/perf +MODULES += systemcmds/preflight_check +MODULES += systemcmds/pwm +MODULES += systemcmds/reboot +MODULES += systemcmds/top +MODULES += systemcmds/tests + +# +# General system control +# +MODULES += modules/commander +MODULES += modules/mavlink +MODULES += modules/mavlink_onboard + +# +# Estimation modules (EKF / other filters) +# +MODULES += modules/attitude_estimator_ekf +MODULES += modules/position_estimator_mc +MODULES += modules/position_estimator +MODULES += modules/att_pos_estimator_ekf + +# +# Vehicle Control +# +MODULES += modules/fixedwing_backside +MODULES += modules/fixedwing_att_control +MODULES += modules/fixedwing_pos_control +MODULES += modules/multirotor_att_control +MODULES += modules/multirotor_pos_control + +# +# Logging +# +MODULES += modules/sdlog + +# +# Library modules +# +MODULES += modules/systemlib +MODULES += modules/systemlib/mixer +MODULES += modules/mathlib +MODULES += modules/controllib +MODULES += modules/uORB + +# +# Libraries +# +LIBRARIES += modules/mathlib/CMSIS + +# +# Demo apps +# +#MODULES += examples/math_demo +# Tutorial code from +# https://pixhawk.ethz.ch/px4/dev/hello_sky +#MODULES += examples/px4_simple_app + +# Tutorial code from +# https://pixhawk.ethz.ch/px4/dev/daemon +#MODULES += examples/px4_daemon_app + +# Tutorial code from +# https://pixhawk.ethz.ch/px4/dev/debug_values +#MODULES += examples/px4_mavlink_debug + +# +# Transitional support - add commands from the NuttX export archive. +# +# In general, these should move to modules over time. +# +# Each entry here is ... but we use a helper macro +# to make the table a bit more readable. +# +define _B + $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4) +endef + +# command priority stack entrypoint +BUILTIN_COMMANDS := \ + $(call _B, sercon, , 2048, sercon_main ) \ + $(call _B, serdis, , 2048, serdis_main ) diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk new file mode 100644 index 000000000..9b3013a5b --- /dev/null +++ b/makefiles/config_px4fmu-v2_test.mk @@ -0,0 +1,40 @@ +# +# Makefile for the px4fmu_default configuration +# + +# +# Use the configuration's ROMFS. +# +ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_test + +# +# Board support modules +# +MODULES += drivers/device +MODULES += drivers/stm32 +MODULES += drivers/boards/px4fmuv2 +MODULES += systemcmds/perf +MODULES += systemcmds/reboot + +# +# Library modules +# +MODULES += modules/systemlib +MODULES += modules/uORB + +# +# Transitional support - add commands from the NuttX export archive. +# +# In general, these should move to modules over time. +# +# Each entry here is ... but we use a helper macro +# to make the table a bit more readable. +# +define _B + $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4) +endef + +# command priority stack entrypoint +BUILTIN_COMMANDS := \ + $(call _B, sercon, , 2048, sercon_main ) \ + $(call _B, serdis, , 2048, serdis_main ) diff --git a/makefiles/config_px4fmuv2_default.mk b/makefiles/config_px4fmuv2_default.mk deleted file mode 100644 index c4499048c..000000000 --- a/makefiles/config_px4fmuv2_default.mk +++ /dev/null @@ -1,122 +0,0 @@ -# -# Makefile for the px4fmu_default configuration -# - -# -# Use the configuration's ROMFS. -# -ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common - -# -# Board support modules -# -MODULES += drivers/device -MODULES += drivers/stm32 -MODULES += drivers/stm32/adc -MODULES += drivers/stm32/tone_alarm -MODULES += drivers/px4fmu -MODULES += drivers/px4io -MODULES += drivers/boards/px4fmuv2 -MODULES += drivers/rgbled -MODULES += drivers/lsm303d -MODULES += drivers/l3gd20 -#MODULES += drivers/mpu6000 -MODULES += drivers/hmc5883 -MODULES += drivers/ms5611 -MODULES += drivers/mb12xx -MODULES += drivers/gps -MODULES += drivers/hil -MODULES += drivers/hott_telemetry -MODULES += drivers/blinkm -MODULES += modules/sensors - -# -# System commands -# -MODULES += systemcmds/ramtron -MODULES += systemcmds/bl_update -MODULES += systemcmds/boardinfo -MODULES += systemcmds/mixer -MODULES += systemcmds/param -MODULES += systemcmds/perf -MODULES += systemcmds/preflight_check -MODULES += systemcmds/pwm -MODULES += systemcmds/reboot -MODULES += systemcmds/top -MODULES += systemcmds/tests - -# -# General system control -# -MODULES += modules/commander -MODULES += modules/mavlink -MODULES += modules/mavlink_onboard - -# -# Estimation modules (EKF / other filters) -# -MODULES += modules/attitude_estimator_ekf -MODULES += modules/position_estimator_mc -MODULES += modules/position_estimator -MODULES += modules/att_pos_estimator_ekf - -# -# Vehicle Control -# -MODULES += modules/fixedwing_backside -MODULES += modules/fixedwing_att_control -MODULES += modules/fixedwing_pos_control -MODULES += modules/multirotor_att_control -MODULES += modules/multirotor_pos_control - -# -# Logging -# -MODULES += modules/sdlog - -# -# Library modules -# -MODULES += modules/systemlib -MODULES += modules/systemlib/mixer -MODULES += modules/mathlib -MODULES += modules/controllib -MODULES += modules/uORB - -# -# Libraries -# -LIBRARIES += modules/mathlib/CMSIS - -# -# Demo apps -# -#MODULES += examples/math_demo -# Tutorial code from -# https://pixhawk.ethz.ch/px4/dev/hello_sky -#MODULES += examples/px4_simple_app - -# Tutorial code from -# https://pixhawk.ethz.ch/px4/dev/daemon -#MODULES += examples/px4_daemon_app - -# Tutorial code from -# https://pixhawk.ethz.ch/px4/dev/debug_values -#MODULES += examples/px4_mavlink_debug - -# -# Transitional support - add commands from the NuttX export archive. -# -# In general, these should move to modules over time. -# -# Each entry here is ... but we use a helper macro -# to make the table a bit more readable. -# -define _B - $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4) -endef - -# command priority stack entrypoint -BUILTIN_COMMANDS := \ - $(call _B, sercon, , 2048, sercon_main ) \ - $(call _B, serdis, , 2048, serdis_main ) diff --git a/makefiles/config_px4fmuv2_test.mk b/makefiles/config_px4fmuv2_test.mk deleted file mode 100644 index 0bd6c18e5..000000000 --- a/makefiles/config_px4fmuv2_test.mk +++ /dev/null @@ -1,45 +0,0 @@ -# -# Makefile for the px4fmu_default configuration -# - -# -# Use the configuration's ROMFS. -# -ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_test - -# -# Board support modules -# -MODULES += drivers/device -MODULES += drivers/stm32 -MODULES += drivers/px4io -MODULES += drivers/boards/px4fmuv2 -MODULES += systemcmds/perf -MODULES += systemcmds/reboot - -# needed because things use it for logging -MODULES += modules/mavlink - -# -# Library modules -# -MODULES += modules/systemlib -MODULES += modules/systemlib/mixer -MODULES += modules/uORB - -# -# Transitional support - add commands from the NuttX export archive. -# -# In general, these should move to modules over time. -# -# Each entry here is ... but we use a helper macro -# to make the table a bit more readable. -# -define _B - $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4) -endef - -# command priority stack entrypoint -BUILTIN_COMMANDS := \ - $(call _B, sercon, , 2048, sercon_main ) \ - $(call _B, serdis, , 2048, serdis_main ) diff --git a/makefiles/config_px4io-v2_default.mk b/makefiles/config_px4io-v2_default.mk new file mode 100644 index 000000000..f9f35d629 --- /dev/null +++ b/makefiles/config_px4io-v2_default.mk @@ -0,0 +1,10 @@ +# +# Makefile for the px4iov2_default configuration +# + +# +# Board support modules +# +MODULES += drivers/stm32 +MODULES += drivers/boards/px4iov2 +MODULES += modules/px4iofirmware \ No newline at end of file diff --git a/makefiles/config_px4iov2_default.mk b/makefiles/config_px4iov2_default.mk deleted file mode 100644 index f9f35d629..000000000 --- a/makefiles/config_px4iov2_default.mk +++ /dev/null @@ -1,10 +0,0 @@ -# -# Makefile for the px4iov2_default configuration -# - -# -# Board support modules -# -MODULES += drivers/stm32 -MODULES += drivers/boards/px4iov2 -MODULES += modules/px4iofirmware \ No newline at end of file diff --git a/makefiles/setup.mk b/makefiles/setup.mk index 92461fafb..a0e880a0d 100644 --- a/makefiles/setup.mk +++ b/makefiles/setup.mk @@ -45,7 +45,6 @@ export PX4_INCLUDE_DIR = $(abspath $(PX4_BASE)/src/include)/ export PX4_MODULE_SRC = $(abspath $(PX4_BASE)/src)/ export PX4_MK_DIR = $(abspath $(PX4_BASE)/makefiles)/ export NUTTX_SRC = $(abspath $(PX4_BASE)/NuttX/nuttx)/ -export NUTTX_APP_SRC = $(abspath $(PX4_BASE)/NuttX/apps)/ export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink)/ export ROMFS_SRC = $(abspath $(PX4_BASE)/ROMFS)/ export IMAGE_DIR = $(abspath $(PX4_BASE)/Images)/ diff --git a/makefiles/upload.mk b/makefiles/upload.mk index 4b01b447d..c55e3f188 100644 --- a/makefiles/upload.mk +++ b/makefiles/upload.mk @@ -27,7 +27,7 @@ all: upload-$(METHOD)-$(BOARD) upload-serial-px4fmu-v1: $(BUNDLE) $(UPLOADER) $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE) -upload-serial-px4fmuv2: $(BUNDLE) $(UPLOADER) +upload-serial-px4fmu-v2: $(BUNDLE) $(UPLOADER) $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE) # -- cgit v1.2.3