From 5375bb5b86e266157ceceef08c367da711b8144e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 1 Jun 2013 01:04:32 +0200 Subject: Cleanup, WIP, needs a NuttX checkout to Firmware/NuttX now --- makefiles/board_px4fmu-v1.mk | 10 +++ makefiles/board_px4fmu.mk | 10 --- makefiles/board_px4io-v1.mk | 10 +++ makefiles/board_px4io.mk | 10 --- makefiles/config_px4fmu-v1_default.mk | 132 ++++++++++++++++++++++++++++++++++ makefiles/config_px4fmu_default.mk | 132 ---------------------------------- makefiles/config_px4io-v1_default.mk | 10 +++ makefiles/config_px4io_default.mk | 10 --- makefiles/setup.mk | 4 +- 9 files changed, 164 insertions(+), 164 deletions(-) create mode 100644 makefiles/board_px4fmu-v1.mk delete mode 100644 makefiles/board_px4fmu.mk create mode 100644 makefiles/board_px4io-v1.mk delete mode 100644 makefiles/board_px4io.mk create mode 100644 makefiles/config_px4fmu-v1_default.mk delete mode 100644 makefiles/config_px4fmu_default.mk create mode 100644 makefiles/config_px4io-v1_default.mk delete mode 100644 makefiles/config_px4io_default.mk (limited to 'makefiles') diff --git a/makefiles/board_px4fmu-v1.mk b/makefiles/board_px4fmu-v1.mk new file mode 100644 index 000000000..837069644 --- /dev/null +++ b/makefiles/board_px4fmu-v1.mk @@ -0,0 +1,10 @@ +# +# Board-specific definitions for the PX4FMU +# + +# +# Configure the toolchain +# +CONFIG_ARCH = CORTEXM4F + +include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/board_px4fmu.mk b/makefiles/board_px4fmu.mk deleted file mode 100644 index 837069644..000000000 --- a/makefiles/board_px4fmu.mk +++ /dev/null @@ -1,10 +0,0 @@ -# -# Board-specific definitions for the PX4FMU -# - -# -# Configure the toolchain -# -CONFIG_ARCH = CORTEXM4F - -include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/board_px4io-v1.mk b/makefiles/board_px4io-v1.mk new file mode 100644 index 000000000..b0eb2dae7 --- /dev/null +++ b/makefiles/board_px4io-v1.mk @@ -0,0 +1,10 @@ +# +# Board-specific definitions for the PX4IO +# + +# +# Configure the toolchain +# +CONFIG_ARCH = CORTEXM3 + +include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/board_px4io.mk b/makefiles/board_px4io.mk deleted file mode 100644 index b0eb2dae7..000000000 --- a/makefiles/board_px4io.mk +++ /dev/null @@ -1,10 +0,0 @@ -# -# Board-specific definitions for the PX4IO -# - -# -# Configure the toolchain -# -CONFIG_ARCH = CORTEXM3 - -include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk new file mode 100644 index 000000000..37a05c90f --- /dev/null +++ b/makefiles/config_px4fmu-v1_default.mk @@ -0,0 +1,132 @@ +# +# 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/led +MODULES += drivers/px4io +MODULES += drivers/px4fmu +MODULES += drivers/boards/px4fmu +MODULES += drivers/ardrone_interface +MODULES += drivers/l3gd20 +MODULES += drivers/bma180 +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 += drivers/mkblctrl +MODULES += drivers/md25 +MODULES += drivers/ets_airspeed +MODULES += modules/sensors + +# +# System commands +# +MODULES += systemcmds/eeprom +MODULES += systemcmds/bl_update +MODULES += systemcmds/boardinfo +MODULES += systemcmds/i2c +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 +MODULES += modules/gpio_led + +# +# 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 + +# Tutorial code from +# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control +MODULES += examples/fixedwing_control + +# +# 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_default.mk b/makefiles/config_px4fmu_default.mk deleted file mode 100644 index 37a05c90f..000000000 --- a/makefiles/config_px4fmu_default.mk +++ /dev/null @@ -1,132 +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/led -MODULES += drivers/px4io -MODULES += drivers/px4fmu -MODULES += drivers/boards/px4fmu -MODULES += drivers/ardrone_interface -MODULES += drivers/l3gd20 -MODULES += drivers/bma180 -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 += drivers/mkblctrl -MODULES += drivers/md25 -MODULES += drivers/ets_airspeed -MODULES += modules/sensors - -# -# System commands -# -MODULES += systemcmds/eeprom -MODULES += systemcmds/bl_update -MODULES += systemcmds/boardinfo -MODULES += systemcmds/i2c -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 -MODULES += modules/gpio_led - -# -# 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 - -# Tutorial code from -# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control -MODULES += examples/fixedwing_control - -# -# 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-v1_default.mk b/makefiles/config_px4io-v1_default.mk new file mode 100644 index 000000000..cf70391bc --- /dev/null +++ b/makefiles/config_px4io-v1_default.mk @@ -0,0 +1,10 @@ +# +# Makefile for the px4io_default configuration +# + +# +# Board support modules +# +MODULES += drivers/stm32 +MODULES += drivers/boards/px4io +MODULES += modules/px4iofirmware \ No newline at end of file diff --git a/makefiles/config_px4io_default.mk b/makefiles/config_px4io_default.mk deleted file mode 100644 index cf70391bc..000000000 --- a/makefiles/config_px4io_default.mk +++ /dev/null @@ -1,10 +0,0 @@ -# -# Makefile for the px4io_default configuration -# - -# -# Board support modules -# -MODULES += drivers/stm32 -MODULES += drivers/boards/px4io -MODULES += modules/px4iofirmware \ No newline at end of file diff --git a/makefiles/setup.mk b/makefiles/setup.mk index 111193093..92461fafb 100644 --- a/makefiles/setup.mk +++ b/makefiles/setup.mk @@ -44,8 +44,8 @@ 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)/ -export NUTTX_APP_SRC = $(abspath $(PX4_BASE)/apps)/ +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)/ -- cgit v1.2.3 From 198df9c82ef94c17f8fe240957fbef1a796f8712 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 1 Jun 2013 15:14:53 +0200 Subject: All apps compiling and linked (listed in NSH help), but not executing yet --- Images/px4fmu-v1.prototype | 12 ++++++++++++ Images/px4fmu.prototype | 12 ------------ Images/px4io-v1.prototype | 12 ++++++++++++ Images/px4io.prototype | 12 ------------ ROMFS/px4fmu_common/init.d/rcS | 7 ++++++- makefiles/config_px4fmu-v1_default.mk | 3 ++- 6 files changed, 32 insertions(+), 26 deletions(-) create mode 100644 Images/px4fmu-v1.prototype delete mode 100644 Images/px4fmu.prototype create mode 100644 Images/px4io-v1.prototype delete mode 100644 Images/px4io.prototype (limited to 'makefiles') diff --git a/Images/px4fmu-v1.prototype b/Images/px4fmu-v1.prototype new file mode 100644 index 000000000..da88f8490 --- /dev/null +++ b/Images/px4fmu-v1.prototype @@ -0,0 +1,12 @@ +{ + "board_id": 5, + "magic": "PX4FWv1", + "description": "Firmware for the PX4FMU board", + "image": "", + "build_time": 0, + "summary": "PX4FMU", + "version": "0.1", + "image_size": 0, + "git_identity": "", + "board_revision": 0 +} diff --git a/Images/px4fmu.prototype b/Images/px4fmu.prototype deleted file mode 100644 index da88f8490..000000000 --- a/Images/px4fmu.prototype +++ /dev/null @@ -1,12 +0,0 @@ -{ - "board_id": 5, - "magic": "PX4FWv1", - "description": "Firmware for the PX4FMU board", - "image": "", - "build_time": 0, - "summary": "PX4FMU", - "version": "0.1", - "image_size": 0, - "git_identity": "", - "board_revision": 0 -} diff --git a/Images/px4io-v1.prototype b/Images/px4io-v1.prototype new file mode 100644 index 000000000..d00b7e5d9 --- /dev/null +++ b/Images/px4io-v1.prototype @@ -0,0 +1,12 @@ +{ + "board_id": 7, + "magic": "PX4FWv1", + "description": "Firmware for the PX4IO board", + "image": "", + "build_time": 0, + "summary": "PX4IO", + "version": "0.1", + "image_size": 0, + "git_identity": "", + "board_revision": 0 +} diff --git a/Images/px4io.prototype b/Images/px4io.prototype deleted file mode 100644 index d00b7e5d9..000000000 --- a/Images/px4io.prototype +++ /dev/null @@ -1,12 +0,0 @@ -{ - "board_id": 7, - "magic": "PX4FWv1", - "description": "Firmware for the PX4IO board", - "image": "", - "build_time": 0, - "summary": "PX4IO", - "version": "0.1", - "image_size": 0, - "git_identity": "", - "board_revision": 0 -} diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index c0a70f7dd..0efcc5db9 100755 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -69,7 +69,12 @@ else then echo "[init] USB interface connected" else - echo "[init] No USB connected" + if [ -f /dev/ttyACM0 ] + echo "[init] NSH via USB" + then + else + echo "[init] No USB connected" + fi fi fi diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk index 37a05c90f..4fc61e97d 100644 --- a/makefiles/config_px4fmu-v1_default.mk +++ b/makefiles/config_px4fmu-v1_default.mk @@ -129,4 +129,5 @@ endef # command priority stack entrypoint BUILTIN_COMMANDS := \ $(call _B, sercon, , 2048, sercon_main ) \ - $(call _B, serdis, , 2048, serdis_main ) + $(call _B, serdis, , 2048, serdis_main ) \ + $(call _B, sysinfo, , 2048, sysinfo_main ) -- cgit v1.2.3 From 971e8103014412d8453b010063318cf46e996288 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 2 Jun 2013 00:11:56 +0200 Subject: Adjust upload target name for v1.x FMU --- makefiles/upload.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'makefiles') diff --git a/makefiles/upload.mk b/makefiles/upload.mk index 5ef92728f..4b01b447d 100644 --- a/makefiles/upload.mk +++ b/makefiles/upload.mk @@ -24,7 +24,7 @@ endif .PHONY: all upload-$(METHOD)-$(BOARD) all: upload-$(METHOD)-$(BOARD) -upload-serial-px4fmu: $(BUNDLE) $(UPLOADER) +upload-serial-px4fmu-v1: $(BUNDLE) $(UPLOADER) $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE) upload-serial-px4fmuv2: $(BUNDLE) $(UPLOADER) -- cgit v1.2.3