Add support for per-config ROMFS generation.

This commit is contained in:
px4dev 2013-01-16 23:40:40 -08:00
parent 963621c1f3
commit a7a1cc4625
30 changed files with 109 additions and 581 deletions

View File

@ -103,8 +103,6 @@ $(NUTTX_ARCHIVES): $(ARCHIVE_DIR)/%.export: $(NUTTX_SRC) $(NUTTX_APPS)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
$(Q) make -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)/tools && ./configure.sh $(platform)/$(configuration))
@echo Generating ROMFS for $(platform) XXX move this!
$(Q) make -C $(ROMFS_SRC) all
@echo %% Exporting NuttX for $(platform)
$(Q) make -C $(NUTTX_SRC) -r $(MQUIET) export
$(Q) mkdir -p $(dir $@)

1
ROMFS/.gitignore vendored
View File

@ -1 +0,0 @@
/img

View File

@ -1,120 +0,0 @@
#
# Makefile to generate a PX4FMU ROMFS image.
#
# In normal use, 'make install' will generate a new ROMFS header and place it
# into the px4fmu configuration in the appropriate location.
#
#
# Directories of interest
#
SRCROOT ?= $(dir $(lastword $(MAKEFILE_LIST)))
BUILDROOT ?= $(SRCROOT)/img
ROMFS_HEADER ?= $(SRCROOT)/../nuttx/configs/px4fmu/include/nsh_romfsimg.h
#
# List of files to install in the ROMFS, specified as <source>~<destination>
#
ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \
$(SRCROOT)/scripts/rc.sensors~init.d/rc.sensors \
$(SRCROOT)/scripts/rc.logging~init.d/rc.logging \
$(SRCROOT)/scripts/rc.standalone~init.d/rc.standalone \
$(SRCROOT)/scripts/rc.PX4IO~init.d/rc.PX4IO \
$(SRCROOT)/scripts/rc.PX4IOAR~init.d/rc.PX4IOAR \
$(SRCROOT)/scripts/rc.FMU_quad_x~init.d/rc.FMU_quad_x \
$(SRCROOT)/mixers/FMU_pass.mix~mixers/FMU_pass.mix \
$(SRCROOT)/mixers/FMU_Q.mix~mixers/FMU_Q.mix \
$(SRCROOT)/mixers/FMU_X5.mix~mixers/FMU_X5.mix \
$(SRCROOT)/mixers/FMU_AERT.mix~mixers/FMU_AERT.mix \
$(SRCROOT)/mixers/FMU_AET.mix~mixers/FMU_AET.mix \
$(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.mix \
$(SRCROOT)/mixers/FMU_quad_x.mix~mixers/FMU_quad_x.mix \
$(SRCROOT)/mixers/FMU_quad_+.mix~mixers/FMU_quad_+.mix \
$(SRCROOT)/mixers/FMU_hex_x.mix~mixers/FMU_hex_x.mix \
$(SRCROOT)/mixers/FMU_hex_+.mix~mixers/FMU_hex_+.mix \
$(SRCROOT)/mixers/FMU_octo_x.mix~mixers/FMU_octo_x.mix \
$(SRCROOT)/mixers/FMU_octo_+.mix~mixers/FMU_octo_+.mix \
$(SRCROOT)/logging/logconv.m~logging/logconv.m
# the EXTERNAL_SCRIPTS variable is used to add out of tree scripts
# to ROMFS.
ROMFS_FSSPEC += $(EXTERNAL_SCRIPTS)
#
# Add the PX4IO firmware to the spec if someone has dropped it into the
# source directory, or otherwise specified its location.
#
# Normally this is only something you'd do when working on PX4IO; most
# users will upgrade with firmware off the microSD card.
#
PX4IO_FIRMWARE ?= $(SRCROOT)/px4io.bin
ifneq ($(wildcard $(PX4IO_FIRMWARE)),)
ROMFS_FSSPEC += $(PX4IO_FIRMWARE)~px4io.bin
endif
################################################################################
# No user-serviceable parts below
################################################################################
#
# Just the source files from the ROMFS spec, so that we can fail cleanly if they don't
# exist
#
ROMFS_SRCFILES = $(foreach spec,$(ROMFS_FSSPEC),$(firstword $(subst ~, ,$(spec))))
#
# Just the destination directories from the ROMFS spec
#
ROMFS_DIRS = $(sort $(dir $(foreach spec,$(ROMFS_FSSPEC),$(lastword $(subst ~, ,$(spec))))))
#
# Intermediate products
#
ROMFS_IMG = $(BUILDROOT)/romfs.img
ROMFS_WORKDIR = $(BUILDROOT)/romfs
#
# Convenience target for rebuilding the ROMFS header
#
all: $(ROMFS_HEADER)
$(ROMFS_HEADER): $(ROMFS_IMG) $(dir $(ROMFS_HEADER))
@echo Generating the ROMFS header...
@(cd $(dir $(ROMFS_IMG)) && xxd -i $(notdir $(ROMFS_IMG))) > $@
$(ROMFS_IMG): $(ROMFS_WORKDIR)
@echo Generating the ROMFS image...
@genromfs -f $@ -d $(ROMFS_WORKDIR) -V "NSHInitVol"
$(ROMFS_WORKDIR): $(ROMFS_SRCFILES)
@echo Rebuilding the ROMFS work area...
@rm -rf $(ROMFS_WORKDIR)
@mkdir -p $(ROMFS_WORKDIR)
@for dir in $(ROMFS_DIRS) ; do mkdir -p $(ROMFS_WORKDIR)/$$dir; done
@for spec in $(ROMFS_FSSPEC) ; do \
echo $$spec | sed -e 's%^.*~% %' ;\
`echo "cp $$spec" | sed -e 's%~% $(ROMFS_WORKDIR)/%'` ;\
done
$(BUILDROOT):
@mkdir -p $(BUILDROOT)
clean:
@rm -rf $(BUILDROOT)
distclean: clean
@rm -f $(PX4IO_FIRMWARE) $(ROMFS_HEADER)
.PHONY: all install clean distclean
#
# Hacks and fixups
#
SYSTYPE = $(shell uname)
ifeq ($(SYSTYPE),Darwin)
# PATH inherited by Eclipse may not include toolchain install location
export PATH := $(PATH):/usr/local/bin
endif

View File

@ -0,0 +1,50 @@
Delta-wing mixer for PX4FMU
===========================
This file defines mixers suitable for controlling a delta wing aircraft using
PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
assumed to be unused.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch) and 3 (thrust).
See the README for more information on the scaler format.
Elevon mixers
-------------
Three scalers total (output, roll, pitch).
On the assumption that the two elevon servos are physically reversed, the pitch
input is inverted between the two servos.
The scaling factor for roll inputs is adjusted to implement differential travel
for the elevons.
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 3000 5000 0 -10000 10000
S: 0 1 5000 5000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 5000 3000 0 -10000 10000
S: 0 1 -5000 -5000 0 -10000 10000
Output 2
--------
This mixer is empty.
Z:
Motor speed mixer
-----------------
Two scalers total (output, thrust).
This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
range. Inputs below zero are treated as zero.
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000

View File

@ -1,67 +0,0 @@
#!nsh
#
# Flight startup script for PX4FMU with PWM outputs.
#
# Disable the USB interface
set USB no
# Disable autostarting other apps
set MODE custom
echo "[init] doing PX4FMU Quad startup..."
#
# Start the ORB
#
uorb start
#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
if [ -f /fs/microsd/parameters ]
then
param load /fs/microsd/parameters
fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
#
param set MAV_TYPE 2
#
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start the sensors and test them.
#
sh /etc/init.d/rc.sensors
#
# Start the commander.
#
commander start
#
# Start the attitude estimator
#
attitude_estimator_ekf start
echo "[init] starting PWM output"
fmu mode_pwm
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Start attitude control
#
multirotor_att_control start
echo "[init] startup done, exiting"
exit

View File

@ -1,80 +0,0 @@
#!nsh
# Disable USB and autostart
set USB no
set MODE camflyer
#
# Start the ORB
#
uorb start
#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
if [ -f /fs/microsd/parameters ]
then
param load /fs/microsd/parameters
fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
#
param set MAV_TYPE 1
#
# Start the sensors.
#
sh /etc/init.d/rc.sensors
#
# Start MAVLink
#
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
#
# Start the commander.
#
commander start
#
# Start GPS interface
#
gps start
#
# Start the attitude estimator
#
kalman_demo start
#
# Start PX4IO interface
#
px4io start
#
# Load mixer and start controllers
#
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
control_demo start
#
# Start logging
#
sdlog start -s 10
#
# Start system state
#
if blinkm start
then
echo "using BlinkM for state indication"
blinkm systemstate
else
echo "no BlinkM found, OK."
fi

View File

@ -1,98 +0,0 @@
#!nsh
#
# Flight startup script for PX4FMU on PX4IOAR carrier board.
#
# Disable the USB interface
set USB no
# Disable autostarting other apps
set MODE ardrone
echo "[init] doing PX4IOAR startup..."
#
# Start the ORB
#
uorb start
#
# Init the parameter storage
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
if [ -f /fs/microsd/parameters ]
then
param load /fs/microsd/parameters
fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
#
param set MAV_TYPE 2
#
# Start the sensors.
#
sh /etc/init.d/rc.sensors
#
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start the commander.
#
commander start
#
# Start the attitude estimator
#
attitude_estimator_ekf start
#
# Configure PX4FMU for operation with PX4IOAR
#
fmu mode_gpio_serial
#
# Fire up the multi rotor attitude controller
#
multirotor_att_control start
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
#
# Start GPS capture
#
gps start
#
# Start logging
#
sdlog start -s 10
#
# Start system state
#
if blinkm start
then
echo "using BlinkM for state indication"
blinkm systemstate
else
echo "no BlinkM found, OK."
fi
#
# startup is done; we don't want the shell because we
# use the same UART for telemetry
#
echo "[init] startup done"
exit

View File

@ -1,66 +0,0 @@
#!nsh
#
# If we are still in flight mode, work out what airframe
# configuration we have and start up accordingly.
#
if [ $MODE != autostart ]
then
echo "[init] automatic startup cancelled by user script"
else
echo "[init] detecting attached hardware..."
#
# Assume that we are PX4FMU in standalone mode
#
set BOARD PX4FMU
#
# Are we attached to a PX4IOAR (AR.Drone carrier board)?
#
if boardinfo test name PX4IOAR
then
set BOARD PX4IOAR
if [ -f /etc/init.d/rc.PX4IOAR ]
then
echo "[init] reading /etc/init.d/rc.PX4IOAR"
usleep 500
sh /etc/init.d/rc.PX4IOAR
fi
else
echo "[init] PX4IOAR not detected"
fi
#
# Are we attached to a PX4IO?
#
if boardinfo test name PX4IO
then
set BOARD PX4IO
if [ -f /etc/init.d/rc.PX4IO ]
then
echo "[init] reading /etc/init.d/rc.PX4IO"
usleep 500
sh /etc/init.d/rc.PX4IO
fi
else
echo "[init] PX4IO not detected"
fi
#
# Looks like we are stand-alone
#
if [ $BOARD == PX4FMU ]
then
echo "[init] no expansion board detected"
if [ -f /etc/init.d/rc.standalone ]
then
echo "[init] reading /etc/init.d/rc.standalone"
sh /etc/init.d/rc.standalone
fi
fi
#
# We may not reach here if the airframe-specific script exits the shell.
#
echo "[init] startup done."
fi

View File

@ -1,10 +0,0 @@
#!nsh
#
# Test jig startup script
#
echo "[testing] doing production test.."
tests jig
echo "[testing] testing done"

View File

@ -1,9 +0,0 @@
#!nsh
#
# Initialise logging services.
#
if [ -d /fs/microsd ]
then
sdlog start
fi

View File

@ -1,34 +0,0 @@
#!nsh
#
# Standard startup script for PX4FMU onboard sensor drivers.
#
#
# Start sensor drivers here.
#
ms5611 start
adc start
if mpu6000 start
then
echo "using MPU6000 and HMC5883L"
hmc5883 start
else
echo "using L3GD20 and LSM303D"
l3gd20 start
lsm303 start
fi
#
# Start the sensor collection task.
# IMPORTANT: this also loads param offsets
# ALWAYS start this task before the
# preflight_check.
#
sensors start
#
# Check sensors - run AFTER 'sensors start'
#
preflight_check

View File

@ -1,13 +0,0 @@
#!nsh
#
# Flight startup script for PX4FMU standalone configuration.
#
echo "[init] doing standalone PX4FMU startup..."
#
# Start the ORB
#
uorb start
echo "[init] startup done"

View File

@ -1,79 +0,0 @@
#!nsh
#
# PX4FMU startup script.
#
# This script is responsible for:
#
# - mounting the microSD card (if present)
# - running the user startup script from the microSD card (if present)
# - detecting the configuration of the system and picking a suitable
# startup script to continue with
#
# Note: DO NOT add configuration-specific commands to this script;
# add them to the per-configuration scripts instead.
#
#
# Default to auto-start mode. An init script on the microSD card
# can change this to prevent automatic startup of the flight script.
#
set MODE autostart
set USB autoconnect
#
# Start playing the startup tune
#
tone_alarm start
#
# Try to mount the microSD card.
#
echo "[init] looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "[init] card mounted at /fs/microsd"
else
echo "[init] no microSD card found"
fi
#
# Look for an init script on the microSD card.
#
# To prevent automatic startup in the current flight mode,
# the script should set MODE to some other value.
#
if [ -f /fs/microsd/etc/rc ]
then
echo "[init] reading /fs/microsd/etc/rc"
sh /fs/microsd/etc/rc
fi
# Also consider rc.txt files
if [ -f /fs/microsd/etc/rc.txt ]
then
echo "[init] reading /fs/microsd/etc/rc.txt"
sh /fs/microsd/etc/rc.txt
fi
#
# Check for USB host
#
if [ $USB != autoconnect ]
then
echo "[init] not connecting USB"
else
if sercon
then
echo "[init] USB interface connected"
else
echo "[init] No USB connected"
fi
fi
# if this is an APM build then there will be a rc.APM script
# from an EXTERNAL_SCRIPTS build option
if [ -f /etc/init.d/rc.APM ]
then
echo Running rc.APM
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
fi

View File

@ -4,5 +4,6 @@
CONFIG = px4fmu_default
SRCS = $(PX4_BASE)/platforms/empty.c
ROMFS_ROOT = $(PX4_BASE)/ROMFS/$(CONFIG)
include $(PX4_BASE)/makefiles/firmware.mk

View File

@ -23,6 +23,11 @@
# to the directory 'build' under the directory containing the
# parent Makefile.
#
# ROMFS_ROOT:
# If set to the path to a directory, a ROMFS image will be generated
# containing the files under the directory and linked into the final
# image.
#
################################################################################
# Paths and configuration
@ -71,6 +76,7 @@ MKFW = $(PX4_BASE)/Tools/px_mkfw.py
COPY = cp
REMOVE = rm -f
RMDIR = rm -rf
GENROMFS = genromfs
#
# Sanity-check the PLATFORM variable and then get the platform config.
@ -134,6 +140,29 @@ LIB_DIRS += $(NUTTX_EXPORT_DIR)/libs
LIBS += -lapps -lnuttx
LINK_DEPS += $(wildcard $(addsuffix /*.a,$(LIB_DIRS)))
################################################################################
# ROMFS generation
################################################################################
#
# Note that we can't just put romfs.c in SRCS, as it's depended on by the
# NuttX export library. Instead, we have to treat it like a library.
#
ifneq ($(ROMFS_ROOT),)
ROMFS_DEPS += $(wildcard \
(ROMFS_ROOT)/* \
(ROMFS_ROOT)/*/* \
(ROMFS_ROOT)/*/*/* \
(ROMFS_ROOT)/*/*/*/* \
(ROMFS_ROOT)/*/*/*/*/* \
(ROMFS_ROOT)/*/*/*/*/*/*)
ROMFS_IMG = $(WORK_DIR)/romfs.img
ROMFS_CSRC = $(ROMFS_IMG:.img=.c)
ROMFS_OBJ = $(ROMFS_CSRC:.c=.o)
LIBS += $(ROMFS_OBJ)
LINK_DEPS += $(ROMFS_OBJ)
endif
################################################################################
# Build rules
################################################################################
@ -159,7 +188,7 @@ all: $(PRODUCT_BUNDLE)
OBJS = $(foreach src,$(SRCS),$(WORK_DIR)/$(src).o)
#
# Rules
# SRCS -> OBJS rules
#
$(filter %.c.o,$(OBJS)): $(WORK_DIR)/%.c.o: %.c $(GLOBAL_DEPS)
@ -174,11 +203,19 @@ $(filter %.S.o,$(OBJS)): $(WORK_DIR)/%.S.o: %.S $(GLOBAL_DEPS)
@mkdir -p $(dir $@)
$(call ASSEMBLE,$<,$@)
#
# Build directory setup rules
#
$(NUTTX_CONFIG_HEADER): $(NUTTX_ARCHIVE)
@echo %% Unpacking $(NUTTX_ARCHIVE)
$(Q) unzip -q -o -d $(WORK_DIR) $(NUTTX_ARCHIVE)
$(Q) touch $@
#
# Built product rules
#
$(PRODUCT_BUNDLE): $(PRODUCT_BIN)
@echo %% Generating $@
$(Q) $(MKFW) --prototype $(IMAGE_DIR)/$(PLATFORM).prototype \
@ -191,6 +228,25 @@ $(PRODUCT_BIN): $(PRODUCT_SYM)
$(PRODUCT_SYM): $(OBJS) $(GLOBAL_DEPS) $(LINK_DEPS)
$(call LINK,$@,$(OBJS))
#
# ROMFS rules
#
$(ROMFS_OBJ): $(ROMFS_CSRC)
$(call COMPILE,$<,$@)
$(ROMFS_CSRC): $(ROMFS_IMG)
@echo %% generating $@
$(Q) (cd $(dir $<) && xxd -i $(notdir $<)) > $@
$(ROMFS_IMG): $(ROMFS_DEPS)
@echo %% generating $@
$(Q) $(GENROMFS) -f $@ -d $(ROMFS_ROOT) -V "NSHInitVol"
#
# Utility rules
#
upload: $(PRODUCT_BUNDLE) $(PRODUCT_BIN)
$(Q) make -f $(PX4_MK_INCLUDE)/upload.mk \
METHOD=serial \

View File

@ -1,5 +1,5 @@
#
# Rules and tools for uploading firmware.
# Rules and tools for uploading firmware to various PX4 boards.
#
UPLOADER = $(PX4_BASE)/Tools/px_uploader.py