aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--Makefile39
-rw-r--r--ROMFS/px4fmu_common/init.d/01_fmu_quad_x52
-rw-r--r--ROMFS/px4fmu_common/init.d/02_io_quad_x88
-rw-r--r--ROMFS/px4fmu_common/init.d/08_ardrone73
-rw-r--r--ROMFS/px4fmu_common/init.d/09_ardrone_flow67
-rw-r--r--ROMFS/px4fmu_common/init.d/10_io_f33080
-rw-r--r--ROMFS/px4fmu_common/init.d/15_io_tbs91
-rw-r--r--ROMFS/px4fmu_common/init.d/30_io_camflyer64
-rw-r--r--ROMFS/px4fmu_common/init.d/31_io_phantom93
-rw-r--r--ROMFS/px4fmu_common/init.d/40_io_segway82
-rw-r--r--ROMFS/px4fmu_common/init.d/666_fmu_q_x550 (renamed from ROMFS/px4fmu_common/init.d/666_fmu_quad_x550)78
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.io23
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.logging7
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.multirotor10
-rwxr-xr-xROMFS/px4fmu_common/init.d/rcS293
-rw-r--r--makefiles/config_px4fmu-v1_default.mk1
-rw-r--r--makefiles/config_px4fmu-v2_default.mk4
-rw-r--r--makefiles/firmware.mk22
-rw-r--r--makefiles/setup.mk1
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp18
-rw-r--r--src/modules/commander/commander.cpp19
-rw-r--r--src/modules/commander/mag_calibration.cpp10
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp2
-rw-r--r--src/modules/sensors/sensor_params.c10
-rw-r--r--src/modules/sensors/sensors.cpp37
-rw-r--r--src/modules/systemlib/module.mk3
-rw-r--r--src/modules/systemlib/rc_check.c148
-rw-r--r--src/modules/systemlib/rc_check.h52
-rw-r--r--src/systemcmds/preflight_check/preflight_check.c97
29 files changed, 618 insertions, 946 deletions
diff --git a/Makefile b/Makefile
index f7cab05c8..cbf0da6c9 100644
--- a/Makefile
+++ b/Makefile
@@ -114,14 +114,27 @@ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4:
@$(ECHO) %%%%
@$(ECHO) %%%% Building $(config) in $(work_dir)
@$(ECHO) %%%%
- $(Q) mkdir -p $(work_dir)
- $(Q) make -r -C $(work_dir) \
+ $(Q) $(MKDIR) -p $(work_dir)
+ $(Q) $(MAKE) -r -C $(work_dir) \
-f $(PX4_MK_DIR)firmware.mk \
CONFIG=$(config) \
WORK_DIR=$(work_dir) \
$(FIRMWARE_GOAL)
#
+# Make FMU firmwares depend on pre-packaged IO binaries.
+#
+# This is a pretty vile hack, since it hard-codes knowledge of the FMU->IO dependency
+# and forces the _default config in all cases. There has to be a better way to do this...
+#
+FMU_VERSION = $(patsubst px4fmu-%,%,$(word 1, $(subst _, ,$(1))))
+define FMU_DEP
+$(BUILD_DIR)$(1).build/firmware.px4: $(IMAGE_DIR)px4io-$(call FMU_VERSION,$(1))_default.px4
+endef
+FMU_CONFIGS := $(filter px4fmu%,$(CONFIGS))
+$(foreach config,$(FMU_CONFIGS),$(eval $(call FMU_DEP,$(config))))
+
+#
# Build the NuttX export archives.
#
# Note that there are no explicit dependencies extended from these
@@ -147,12 +160,12 @@ $(ARCHIVE_DIR)%.export: configuration = nsh
$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC)
@$(ECHO) %% Configuring NuttX for $(board)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
- $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
+ $(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
@$(ECHO) %% Exporting NuttX for $(board)
- $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export
- $(Q) mkdir -p $(dir $@)
+ $(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export
+ $(Q) $(MKDIR) -p $(dir $@)
$(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
$(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board))
@@ -168,11 +181,11 @@ BOARD = $(BOARDS)
menuconfig: $(NUTTX_SRC)
@$(ECHO) %% Configuring NuttX for $(BOARD)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
- $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
+ $(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(BOARD) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(BOARD)/nsh)
@$(ECHO) %% Running menuconfig for $(BOARD)
- $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) menuconfig
+ $(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) menuconfig
@$(ECHO) %% Saving configuration file
$(Q)$(COPY) $(NUTTX_SRC).config $(PX4_BASE)nuttx-configs/$(BOARD)/nsh/defconfig
else
@@ -191,7 +204,7 @@ $(NUTTX_SRC):
# Testing targets
#
testbuild:
- $(Q) (cd $(PX4_BASE) && make distclean && make archives && make -j8)
+ $(Q) (cd $(PX4_BASE) && $(MAKE) distclean && $(MAKE) archives && $(MAKE) -j8)
#
# Cleanup targets. 'clean' should remove all built products and force
@@ -206,8 +219,8 @@ clean:
.PHONY: distclean
distclean: clean
$(Q) $(REMOVE) $(ARCHIVE_DIR)*.export
- $(Q) make -C $(NUTTX_SRC) -r $(MQUIET) distclean
- $(Q) (cd $(NUTTX_SRC)/configs && find . -maxdepth 1 -type l -delete)
+ $(Q) $(MAKE) -C $(NUTTX_SRC) -r $(MQUIET) distclean
+ $(Q) (cd $(NUTTX_SRC)/configs && $(FIND) . -maxdepth 1 -type l -delete)
#
# Print some help text
@@ -229,9 +242,9 @@ help:
@$(ECHO) " A limited set of configs can be built with CONFIGS=<list-of-configs>"
@$(ECHO) ""
@for config in $(CONFIGS); do \
- echo " $$config"; \
- echo " Build just the $$config firmware configuration."; \
- echo ""; \
+ $(ECHO) " $$config"; \
+ $(ECHO) " Build just the $$config firmware configuration."; \
+ $(ECHO) ""; \
done
@$(ECHO) " clean"
@$(ECHO) " Remove all firmware build pieces."
diff --git a/ROMFS/px4fmu_common/init.d/01_fmu_quad_x b/ROMFS/px4fmu_common/init.d/01_fmu_quad_x
index 8223b3ea5..f57e4bd68 100644
--- a/ROMFS/px4fmu_common/init.d/01_fmu_quad_x
+++ b/ROMFS/px4fmu_common/init.d/01_fmu_quad_x
@@ -1,28 +1,6 @@
#!nsh
-#
-# Flight startup script for PX4FMU with PWM outputs.
-#
-
-# disable USB and autostart
-set USB no
-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/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
+
+echo "[init] 01_fmu_quad_x: PX4FMU Quad X with PWM outputs"
#
# Load default params for this platform
@@ -52,11 +30,10 @@ fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
-
+
#
# Start MAVLink
#
@@ -64,19 +41,24 @@ mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
-# Start common for all multirotors apps
+# Start PWM output
#
-sh /etc/init.d/rc.multirotor
+fmu mode_pwm
#
-# Start PWM output
+# Load mixer
#
-fmu mode_pwm
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
+
+#
+# Set PWM output frequency
+#
pwm -u 400 -m 0xff
-
-# Try to get an USB console
-nshterm /dev/ttyACM0 &
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
# Exit, because /dev/ttyS0 is needed for MAVLink
-#exit
+exit
diff --git a/ROMFS/px4fmu_common/init.d/02_io_quad_x b/ROMFS/px4fmu_common/init.d/02_io_quad_x
index 49483d14f..a37c26ad1 100644
--- a/ROMFS/px4fmu_common/init.d/02_io_quad_x
+++ b/ROMFS/px4fmu_common/init.d/02_io_quad_x
@@ -1,26 +1,6 @@
#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
+
+echo "[init] 02_io_quad_x: PX4FMU+PX4IO Quad X with PWM outputs"
#
# Load default params for this platform
@@ -28,74 +8,40 @@ fi
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
+ # TODO
+
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
fi
-
+
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
-# Start MAVLink (depends on orb)
+# Start MAVLink
#
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
-
-#
-# Start the commander (depends on orb, mavlink)
-#
-commander start
-
-#
-# Start PX4IO interface (depends on orb, commander)
-#
-px4io start
-
-#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
#
-# Disable px4io topic limiting
-#
-px4io limit 200
-
-#
-# Start the sensors (depends on orb, px4io)
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start GPS interface (depends on orb)
-#
-gps start
-
-#
-# Start the attitude estimator (depends on orb)
+# Start and configure PX4IO interface
#
-attitude_estimator_ekf start
-
+sh /etc/init.d/rc.io
+
#
-# Load mixer and start controllers (depends on px4io)
+# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-pwm -u 400 -m 0xff
-multirotor_att_control start
-
+
#
-# Start logging once armed
+# Set PWM output frequency
#
-sdlog2 start -r 50 -a -b 14
-
+pwm -u 400 -m 0xff
+
#
-# Start system state
+# Start common for all multirotors apps
#
-if blinkm start
-then
- blinkm systemstate
-fi
+sh /etc/init.d/rc.multirotor
diff --git a/ROMFS/px4fmu_common/init.d/08_ardrone b/ROMFS/px4fmu_common/init.d/08_ardrone
index 5bb1491e9..eb9f82f77 100644
--- a/ROMFS/px4fmu_common/init.d/08_ardrone
+++ b/ROMFS/px4fmu_common/init.d/08_ardrone
@@ -1,86 +1,45 @@
#!nsh
-#
-# Flight startup script for PX4FMU on PX4IOAR carrier board.
-#
-
-echo "[init] doing PX4IOAR startup..."
-
-#
-# Start the ORB
-#
-uorb start
+
+echo "[init] 08_ardrone: PX4FMU on PX4IOAR carrier board"
#
-# Load microSD params
+# Load default params for this platform
#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
+if param compare SYS_AUTOCONFIG 1
then
- param load /fs/microsd/params
+ # Set all params here, then disable autoconfig
+ # TODO
+
+ param set SYS_AUTOCONFIG 0
+ param save /fs/microsd/params
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
-# Configure PX4FMU for operation with PX4IOAR
-#
-fmu mode_gpio_serial
-
-#
-# 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
-
+
#
-# Fire up the multi rotor attitude controller
+# Configure PX4FMU for operation with PX4IOAR
#
-multirotor_att_control start
+fmu mode_gpio_serial
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
-
-#
-# Start logging once armed
-#
-sdlog2 start -r 50 -a -b 14
-
-#
-# Start GPS capture
-#
-gps start
#
-# startup is done; we don't want the shell because we
-# use the same UART for telemetry
+# Start common for all multirotors apps
#
-echo "[init] startup done"
-
-# Try to get an USB console
-nshterm /dev/ttyACM0 &
-
+sh /etc/init.d/rc.multirotor
+
# Exit, because /dev/ttyS0 is needed for MAVLink
exit
diff --git a/ROMFS/px4fmu_common/init.d/09_ardrone_flow b/ROMFS/px4fmu_common/init.d/09_ardrone_flow
index a223ef7aa..44fbb79b7 100644
--- a/ROMFS/px4fmu_common/init.d/09_ardrone_flow
+++ b/ROMFS/px4fmu_common/init.d/09_ardrone_flow
@@ -1,36 +1,41 @@
#!nsh
+
+echo "[init] 09_ardrone_flow: PX4FMU on PX4IOAR carrier board with PX4FLOW"
+
#
-# Flight startup script for PX4FMU on PX4IOAR carrier board.
-#
-
-echo "[init] doing PX4IOAR startup..."
-
-#
-# Start the ORB
-#
-uorb start
-
-#
-# Load microSD params
+# Load default params for this platform
#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
+if param compare SYS_AUTOCONFIG 1
then
- param load /fs/microsd/params
+ # Set all params here, then disable autoconfig
+ # TODO
+
+ param set SYS_AUTOCONFIG 0
+ param save /fs/microsd/params
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
+# Start MAVLink and MAVLink Onboard (PX4FLOW Sensor)
+#
+mavlink start -d /dev/ttyS0 -b 57600
+mavlink_onboard start -d /dev/ttyS3 -b 115200
+usleep 5000
+
+#
# Configure PX4FMU for operation with PX4IOAR
#
fmu mode_gpio_serial
+
+#
+# Fire up the AR.Drone interface.
+#
+ardrone_interface start -d /dev/ttyS1
#
# Start the sensors.
@@ -38,13 +43,6 @@ fmu mode_gpio_serial
sh /etc/init.d/rc.sensors
#
-# Start MAVLink and MAVLink Onboard (Flow Sensor)
-#
-mavlink start -d /dev/ttyS0 -b 57600
-mavlink_onboard start -d /dev/ttyS3 -b 115200
-usleep 5000
-
-#
# Start the commander.
#
commander start
@@ -73,25 +71,6 @@ flow_position_control start
# Fire up the flow speed controller
#
flow_speed_control start
-
-#
-# Fire up the AR.Drone interface.
-#
-ardrone_interface start -d /dev/ttyS1
-
-#
-# Start logging once armed
-#
-sdlog2 start -r 50 -a -b 14
-#
-# startup is done; we don't want the shell because we
-# use the same UART for telemetry
-#
-echo "[init] startup done"
-
-# Try to get an USB console
-nshterm /dev/ttyACM0 &
-
# Exit, because /dev/ttyS0 is needed for MAVLink
exit
diff --git a/ROMFS/px4fmu_common/init.d/10_io_f330 b/ROMFS/px4fmu_common/init.d/10_io_f330
index 50842764a..7b6509bf8 100644
--- a/ROMFS/px4fmu_common/init.d/10_io_f330
+++ b/ROMFS/px4fmu_common/init.d/10_io_f330
@@ -1,12 +1,6 @@
#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO on an F330 quad.
-#
-#
-# Start the ORB (first app to start)
-#
-uorb start
+echo "[init] 10_io_f330: PX4FMU+PX4IO on a DJI F330 quad frame"
#
# Load default params for this platform
@@ -35,8 +29,7 @@ fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
@@ -47,71 +40,28 @@ mavlink start
usleep 5000
#
-# Start the commander (depends on orb, mavlink)
+# Start and configure PX4IO interface
#
-commander start
+sh /etc/init.d/rc.io
#
-# Start PX4IO interface (depends on orb, commander)
+# Set PWM values for DJI ESCs
#
-if px4io start
-then
- #
- # This sets a PWM right after startup (regardless of safety button)
- #
- px4io idle 900 900 900 900
-
- pwm -u 400 -m 0xff
-
- #
- # Allow PX4IO to recover from midair restarts.
- # this is very unlikely, but quite safe and robust.
- px4io recovery
-
-
-
- #
- # The values are for spinning motors when armed using DJI ESCs
- #
- px4io min 1200 1200 1200 1200
-
- #
- # Upper limits could be higher, this is on the safe side
- #
- px4io max 1800 1800 1800 1800
+px4io idle 900 900 900 900
+px4io min 1200 1200 1200 1200
+px4io max 1800 1800 1800 1800
- mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-
-else
- # SOS
- tone_alarm 6
-fi
-
-#
-# Start the sensors (depends on orb, px4io)
-#
-sh /etc/init.d/rc.sensors
-
#
-# Start GPS interface (depends on orb)
+# Load mixer
#
-gps start
-
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
+
#
-# Start the attitude estimator (depends on orb)
+# Set PWM output frequency
#
-attitude_estimator_ekf start
-
-multirotor_att_control start
+pwm -u 400 -m 0xff
#
-# Disable px4io topic limiting and start logging
+# Start common for all multirotors apps
#
-if [ $BOARD == fmuv1 ]
-then
- px4io limit 200
- sdlog2 start -r 50 -a -b 16
-else
- px4io limit 400
- sdlog2 start -r 200 -a -b 16
-fi
+sh /etc/init.d/rc.multirotor
diff --git a/ROMFS/px4fmu_common/init.d/15_io_tbs b/ROMFS/px4fmu_common/init.d/15_io_tbs
index 237bb4267..b4f063e52 100644
--- a/ROMFS/px4fmu_common/init.d/15_io_tbs
+++ b/ROMFS/px4fmu_common/init.d/15_io_tbs
@@ -1,27 +1,6 @@
#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO on a Team Blacksheep Discovery quad
-# with stock DJI ESCs, motors and props.
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
+echo "[init] 15_io_tbs: PX4FMU+PX4IO on a Team Blacksheep Discovery quad"
#
# Load default params for this platform
@@ -47,11 +26,10 @@ then
param save /fs/microsd/params
fi
-
+
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
@@ -62,77 +40,28 @@ mavlink start
usleep 5000
#
-# Start the commander (depends on orb, mavlink)
-#
-commander start
-
-#
-# Start PX4IO interface (depends on orb, commander)
-#
-px4io start
-pwm -u 400 -m 0xff
-
+# Start and configure PX4IO interface
#
-# Allow PX4IO to recover from midair restarts.
-# This is very unlikely, but quite safe and robust.
-px4io recovery
+sh /etc/init.d/rc.io
#
-# This sets a PWM right after startup (regardless of safety button)
+# Set PWM values for DJI ESCs
#
px4io idle 900 900 900 900
-
-#
-# The values are for spinning motors when armed using DJI ESCs
-#
px4io min 1180 1180 1180 1180
-
-#
-# Upper limits could be higher, this is on the safe side
-#
px4io max 1800 1800 1800 1800
#
# Load the mixer for a quad with wide arms
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
-
-#
-# Start the sensors (depends on orb, px4io)
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start GPS interface (depends on orb)
-#
-gps start
-
-#
-# Start the attitude estimator (depends on orb)
-#
-attitude_estimator_ekf start
#
-# Start the controllers (depends on orb)
+# Set PWM output frequency
#
-multirotor_att_control start
+pwm -u 400 -m 0xff
#
-# Disable px4io topic limiting and start logging
+# Start common for all multirotors apps
#
-if [ $BOARD == fmuv1 ]
-then
- px4io limit 200
- sdlog2 start -r 50 -a -b 16
- if blinkm start
- then
- blinkm systemstate
- fi
-else
- px4io limit 400
- sdlog2 start -r 200 -a -b 16
- if rgbled start
- then
- #rgbled systemstate
- fi
-fi
+sh /etc/init.d/rc.multirotor
diff --git a/ROMFS/px4fmu_common/init.d/30_io_camflyer b/ROMFS/px4fmu_common/init.d/30_io_camflyer
index 5090b98a4..c9d5d6632 100644
--- a/ROMFS/px4fmu_common/init.d/30_io_camflyer
+++ b/ROMFS/px4fmu_common/init.d/30_io_camflyer
@@ -1,26 +1,6 @@
#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
+
+cho "[init] 30_io_camflyer: PX4FMU+PX4IO on Camflyer"
#
# Load default params for this platform
@@ -28,40 +8,19 @@ fi
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
+ # TODO
+
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 1 = fixed wing
#
param set MAV_TYPE 1
#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-if [ -f /fs/microsd/px4io.bin ]
-then
- echo "PX4IO Firmware found. Checking Upgrade.."
- if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- then
- echo "No newer version, skipping upgrade."
- else
- echo "Loading /fs/microsd/px4io.bin"
- if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
- then
- cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
- else
- echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
- echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
- fi
- fi
-fi
-
-#
# Start MAVLink (depends on orb)
#
mavlink start -d /dev/ttyS1 -b 57600
@@ -106,16 +65,3 @@ kalman_demo start
#
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
control_demo start
-
-#
-# Start logging
-#
-sdlog2 start -r 50 -a -b 14
-
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
diff --git a/ROMFS/px4fmu_common/init.d/31_io_phantom b/ROMFS/px4fmu_common/init.d/31_io_phantom
index 5090b98a4..0deffe3f1 100644
--- a/ROMFS/px4fmu_common/init.d/31_io_phantom
+++ b/ROMFS/px4fmu_common/init.d/31_io_phantom
@@ -1,26 +1,6 @@
#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
+
+echo "[init] 31_io_phantom: PX4FMU+PX4IO on Phantom"
#
# Load default params for this platform
@@ -28,76 +8,50 @@ fi
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
+ # TODO
+
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 1 = fixed wing
#
param set MAV_TYPE 1
-
-#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-if [ -f /fs/microsd/px4io.bin ]
-then
- echo "PX4IO Firmware found. Checking Upgrade.."
- if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- then
- echo "No newer version, skipping upgrade."
- else
- echo "Loading /fs/microsd/px4io.bin"
- if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
- then
- cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
- else
- echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
- echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
- fi
- fi
-fi
-
+
#
# Start MAVLink (depends on orb)
#
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
-
-#
-# Start the commander (depends on orb, mavlink)
-#
-commander start
-
-#
-# Start PX4IO interface (depends on orb, commander)
+
#
-px4io start
-
+# Start and configure PX4IO interface
#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
+sh /etc/init.d/rc.io
#
# Set actuator limit to 100 Hz update (50 Hz PWM)
px4io limit 100
#
-# Start the sensors (depends on orb, px4io)
+# Start the commander
+#
+commander start
+
+#
+# Start the sensors
#
sh /etc/init.d/rc.sensors
#
-# Start GPS interface (depends on orb)
+# Start GPS interface
#
gps start
#
-# Start the attitude estimator (depends on orb)
+# Start the attitude estimator
#
kalman_demo start
@@ -106,16 +60,3 @@ kalman_demo start
#
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
control_demo start
-
-#
-# Start logging
-#
-sdlog2 start -r 50 -a -b 14
-
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
diff --git a/ROMFS/px4fmu_common/init.d/40_io_segway b/ROMFS/px4fmu_common/init.d/40_io_segway
index 5742d685a..2890f43be 100644
--- a/ROMFS/px4fmu_common/init.d/40_io_segway
+++ b/ROMFS/px4fmu_common/init.d/40_io_segway
@@ -1,26 +1,4 @@
#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
#
# Load default params for this platform
@@ -28,39 +6,18 @@ fi
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
+ # TODO
+
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 10 = ground rover
#
param set MAV_TYPE 10
-
-#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-if [ -f /fs/microsd/px4io.bin ]
-then
- echo "PX4IO Firmware found. Checking Upgrade.."
- if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- then
- echo "No newer version, skipping upgrade."
- else
- echo "Loading /fs/microsd/px4io.bin"
- if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
- then
- cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
- else
- echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
- echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
- fi
- fi
-fi
-
+
#
# Start MAVLink (depends on orb)
#
@@ -68,26 +25,16 @@ mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
#
-# Start the commander (depends on orb, mavlink)
+# Start and configure PX4IO interface
#
-commander start
+sh /etc/init.d/rc.io
#
-# Start PX4IO interface (depends on orb, commander)
-#
-px4io start
-
+# Start the commander (depends on orb, mavlink)
#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
+commander start
#
-# Disable px4io topic limiting
-#
-px4io limit 200
-
-#
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
@@ -107,16 +54,3 @@ attitude_estimator_ekf start
#
md25 start 3 0x58
segway start
-
-#
-# Start logging
-#
-sdlog2 start -r 50 -a -b 14
-
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
diff --git a/ROMFS/px4fmu_common/init.d/666_fmu_quad_x550 b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
index a7ffffaee..2c8218013 100644
--- a/ROMFS/px4fmu_common/init.d/666_fmu_quad_x550
+++ b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
@@ -1,28 +1,6 @@
#!nsh
-#
-# Flight startup script for PX4FMU with PWM outputs.
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-echo "[init] doing PX4FMU Quad startup 666_fmu_quad_X550..."
-
-#
-# Start the ORB
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
+
+echo "[init] 666_fmu_q_x550: PX4FMU Quad X550 with PWM outputs"
#
# Load default params for this platform
@@ -52,8 +30,7 @@ fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
@@ -62,55 +39,26 @@ param set MAV_TYPE 2
#
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 GPS interface (depends on orb)
-#
-gps start
-
-#
-# Start the attitude estimator
-#
-attitude_estimator_ekf start
+# Start PWM output
#
-# Start the position estimator
-#
-position_estimator_inav start
-
-echo "[init] starting PWM output"
fmu mode_pwm
-mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-pwm -u 400 -m 0xff
-
+
#
-# Start attitude control
+# Load mixer
#
-multirotor_att_control start
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
-# Start position control
+# Set PWM output frequency
#
-multirotor_pos_control start
+pwm -u 400 -m 0xff
#
-# Start logging
+# Start common for all multirotors apps
#
-sdlog2 start -r 50 -a -b 14
+sh /etc/init.d/rc.multirotor
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
+# Exit, because /dev/ttyS0 is needed for MAVLink
+exit
diff --git a/ROMFS/px4fmu_common/init.d/rc.io b/ROMFS/px4fmu_common/init.d/rc.io
new file mode 100644
index 000000000..85f00e582
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.io
@@ -0,0 +1,23 @@
+#
+# Start PX4IO interface (depends on orb, commander)
+#
+if px4io start
+then
+ #
+ # Allow PX4IO to recover from midair restarts.
+ # this is very unlikely, but quite safe and robust.
+ px4io recovery
+
+ #
+ # Disable px4io topic limiting
+ #
+ if [ $BOARD == fmuv1 ]
+ then
+ px4io limit 200
+ else
+ px4io limit 400
+ fi
+else
+ # SOS
+ tone_alarm 6
+fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.logging b/ROMFS/px4fmu_common/init.d/rc.logging
index 09c2d00d1..dc4be8055 100644
--- a/ROMFS/px4fmu_common/init.d/rc.logging
+++ b/ROMFS/px4fmu_common/init.d/rc.logging
@@ -5,5 +5,10 @@
if [ -d /fs/microsd ]
then
- sdlog start
+ if [ $BOARD == fmuv1 ]
+ then
+ sdlog2 start -r 50 -a -b 16
+ else
+ sdlog2 start -r 200 -a -b 16
+ fi
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.multirotor b/ROMFS/px4fmu_common/init.d/rc.multirotor
index 81184f363..73f1b3742 100644
--- a/ROMFS/px4fmu_common/init.d/rc.multirotor
+++ b/ROMFS/px4fmu_common/init.d/rc.multirotor
@@ -37,13 +37,3 @@ multirotor_att_control start
# Start position control
#
multirotor_pos_control start
-
-#
-# Start logging
-#
-if [ $BOARD == fmuv1 ]
-then
- sdlog2 start -r 50 -a -b 16
-else
- sdlog2 start -r 200 -a -b 16
-fi
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 6b624b278..6a82acdcc 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -57,162 +57,171 @@ fi
if [ $MODE == autostart ]
then
-
-#
-# Start terminal
-#
-if sercon
-then
- echo "USB connected"
-else
- # second attempt
- sercon &
-fi
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-if ramtron start
-then
- param select /ramtron/params
- if [ -f /ramtron/params ]
+ #
+ # Start terminal
+ #
+ if sercon
then
- param load /ramtron/params
+ echo "USB connected"
+ else
+ # second attempt
+ sercon &
fi
-else
- param select /fs/microsd/params
- if [ -f /fs/microsd/params ]
+
+ #
+ # Start the ORB (first app to start)
+ #
+ uorb start
+
+ #
+ # Load microSD params
+ #
+ if ramtron start
then
- param load /fs/microsd/params
+ param select /ramtron/params
+ if [ -f /ramtron/params ]
+ then
+ param load /ramtron/params
+ fi
+ else
+ param select /fs/microsd/params
+ if [ -f /fs/microsd/params ]
+ then
+ param load /fs/microsd/params
+ fi
fi
-fi
-
-#
-# Start system state indicator
-#
-if rgbled start
-then
- echo "Using external RGB Led"
-else
- if blinkm start
+
+ #
+ # Start system state indicator
+ #
+ if rgbled start
then
- blinkm systemstate
+ echo "Using external RGB Led"
+ else
+ if blinkm start
+ then
+ blinkm systemstate
+ fi
fi
-fi
-
-#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-if [ -f /fs/microsd/px4io.bin ]
-then
- echo "PX4IO Firmware found. Checking Upgrade.."
- if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.cur
+
+ #
+ # Start logging
+ #
+ sh /etc/init.d/rc.logging
+
+ #
+ # Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
+ #
+ if [ -f /fs/microsd/px4io.bin ]
then
- echo "No newer version, skipping upgrade."
- else
- echo "Loading /fs/microsd/px4io.bin"
- if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io.log
+ echo "PX4IO Firmware found. Checking Upgrade.."
+ if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.cur
then
- cp /fs/microsd/px4io.bin /fs/microsd/px4io.cur
- echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io.log
+ echo "No newer version, skipping upgrade."
else
- echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io.log
- echo "Failed to upgrade px4io firmware - check if px4io is in bootloader mode"
+ echo "Loading /fs/microsd/px4io.bin"
+ if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io.log
+ then
+ cp /fs/microsd/px4io.bin /fs/microsd/px4io.cur
+ echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io.log
+ else
+ echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io.log
+ echo "Failed to upgrade px4io firmware - check if px4io is in bootloader mode"
+ fi
fi
fi
-fi
-
-#
-# Check if auto-setup from one of the standard scripts is wanted
-# SYS_AUTOSTART = 0 means no autostart (default)
-#
-if param compare SYS_AUTOSTART 1
-then
- sh /etc/init.d/01_fmu_quad_x
- set MODE custom
-fi
-
-if param compare SYS_AUTOSTART 2
-then
- sh /etc/init.d/02_io_quad_x
- set MODE custom
-fi
-
-if param compare SYS_AUTOSTART 8
-then
- sh /etc/init.d/08_ardrone
- set MODE custom
-fi
-
-if param compare SYS_AUTOSTART 9
-then
- sh /etc/init.d/09_ardrone_flow
- set MODE custom
-fi
-
-if param compare SYS_AUTOSTART 10
-then
- sh /etc/init.d/10_io_f330
- set MODE custom
-fi
-
-if param compare SYS_AUTOSTART 15
-then
- sh /etc/init.d/15_io_tbs
- set MODE custom
-fi
-
-if param compare SYS_AUTOSTART 30
-then
- sh /etc/init.d/30_io_camflyer
- set MODE custom
-fi
-
-if param compare SYS_AUTOSTART 31
-then
- sh /etc/init.d/31_io_phantom
- set MODE custom
-fi
-
-# Try to get an USB console
-nshterm /dev/ttyACM0 &
-
-# If none of the autostart scripts triggered, get a minimal setup
-if [ $MODE == autostart ]
-then
- # Telemetry port is on both FMU boards ttyS1
- mavlink start -b 57600 -d /dev/ttyS1
- usleep 5000
-
- # Start commander
- commander start
-
- # Start px4io if present
- if px4io start
+
+ #
+ # Check if auto-setup from one of the standard scripts is wanted
+ # SYS_AUTOSTART = 0 means no autostart (default)
+ #
+ if param compare SYS_AUTOSTART 1
then
- echo "PX4IO driver started"
- else
- if fmu mode_serial
+ sh /etc/init.d/01_fmu_quad_x
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 2
+ then
+ sh /etc/init.d/02_io_quad_x
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 8
+ then
+ sh /etc/init.d/08_ardrone
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 9
+ then
+ sh /etc/init.d/09_ardrone_flow
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 10
+ then
+ sh /etc/init.d/10_io_f330
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 15
+ then
+ sh /etc/init.d/15_io_tbs
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 30
+ then
+ sh /etc/init.d/30_io_camflyer
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 31
+ then
+ sh /etc/init.d/31_io_phantom
+ set MODE custom
+ fi
+
+ # Try to get an USB console
+ nshterm /dev/ttyACM0 &
+
+ # Start any custom extensions that might be missing
+ if [ -f /fs/microsd/etc/rc.local ]
+ then
+ sh /fs/microsd/etc/rc.local
+ fi
+
+ # If none of the autostart scripts triggered, get a minimal setup
+ if [ $MODE == autostart ]
+ then
+ # Telemetry port is on both FMU boards ttyS1
+ mavlink start -b 57600 -d /dev/ttyS1
+ usleep 5000
+
+ # Start commander
+ commander start
+
+ # Start px4io if present
+ if px4io start
then
- echo "FMU driver started"
+ echo "PX4IO driver started"
+ else
+ if fmu mode_serial
+ then
+ echo "FMU driver started"
+ fi
fi
+
+ # Start sensors
+ sh /etc/init.d/rc.sensors
+
+ # Start one of the estimators
+ attitude_estimator_ekf start
+
+ # Start GPS
+ gps start
+
fi
-
- # Start sensors
- sh /etc/init.d/rc.sensors
-
- # Start one of the estimators
- attitude_estimator_ekf start
-
- # Start GPS
- gps start
-
-fi
-
# End of autostart
fi
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index bb0c1550f..fff43c6b4 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -6,6 +6,7 @@
# Use the configuration's ROMFS.
#
ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
+ROMFS_OPTIONAL_FILES = $(PX4_BASE)/Images/px4io-v1_default.bin
#
# Board support modules
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index c5131262b..ab0da3559 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -3,9 +3,11 @@
#
#
-# Use the configuration's ROMFS.
+# Use the configuration's ROMFS, copy the px4iov2 firmware into
+# the ROMFS if it's available
#
ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
+ROMFS_OPTIONAL_FILES = $(PX4_BASE)/Images/px4io-v2_default.bin
#
# Board support modules
diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk
index 8a027a0a8..b3e50501c 100644
--- a/makefiles/firmware.mk
+++ b/makefiles/firmware.mk
@@ -322,7 +322,7 @@ endif
# a root from several templates. That would be a nice feature.
#
-# Add dependencies on anything in the ROMFS root
+# Add dependencies on anything in the ROMFS root directory
ROMFS_FILES += $(wildcard \
$(ROMFS_ROOT)/* \
$(ROMFS_ROOT)/*/* \
@@ -334,7 +334,14 @@ ifeq ($(ROMFS_FILES),)
$(error ROMFS_ROOT $(ROMFS_ROOT) specifies a directory containing no files)
endif
ROMFS_DEPS += $(ROMFS_FILES)
+
+# Extra files that may be copied into the ROMFS /extras directory
+# ROMFS_EXTRA_FILES are required, ROMFS_OPTIONAL_FILES are optional
+ROMFS_EXTRA_FILES += $(wildcard $(ROMFS_OPTIONAL_FILES))
+ROMFS_DEPS += $(ROMFS_EXTRA_FILES)
+
ROMFS_IMG = romfs.img
+ROMFS_SCRATCH = romfs_scratch
ROMFS_CSRC = $(ROMFS_IMG:.img=.c)
ROMFS_OBJ = $(ROMFS_CSRC:.c=.o)
LIBS += $(ROMFS_OBJ)
@@ -345,9 +352,18 @@ $(ROMFS_OBJ): $(ROMFS_IMG) $(GLOBAL_DEPS)
$(call BIN_TO_OBJ,$<,$@,romfs_img)
# Generate the ROMFS image from the root
-$(ROMFS_IMG): $(ROMFS_DEPS) $(GLOBAL_DEPS)
+$(ROMFS_IMG): $(ROMFS_SCRATCH) $(ROMFS_DEPS) $(GLOBAL_DEPS)
@$(ECHO) "ROMFS: $@"
- $(Q) $(GENROMFS) -f $@ -d $(ROMFS_ROOT) -V "NSHInitVol"
+ $(Q) $(GENROMFS) -f $@ -d $(ROMFS_SCRATCH) -V "NSHInitVol"
+
+# Construct the ROMFS scratch root from the canonical root
+$(ROMFS_SCRATCH): $(ROMFS_DEPS) $(GLOBAL_DEPS)
+ $(Q) $(MKDIR) -p $(ROMFS_SCRATCH)
+ $(Q) $(COPYDIR) $(ROMFS_ROOT)/* $(ROMFS_SCRATCH)
+ifneq ($(ROMFS_EXTRA_FILES),)
+ $(Q) $(MKDIR) -p $(ROMFS_SCRATCH)/extras
+ $(Q) $(COPY) $(ROMFS_EXTRA_FILES) $(ROMFS_SCRATCH)/extras
+endif
EXTRA_CLEANS += $(ROMGS_OBJ) $(ROMFS_IMG)
diff --git a/makefiles/setup.mk b/makefiles/setup.mk
index 42f9a8a7f..183b143d6 100644
--- a/makefiles/setup.mk
+++ b/makefiles/setup.mk
@@ -73,6 +73,7 @@ export RMDIR = rm -rf
export GENROMFS = genromfs
export TOUCH = touch
export MKDIR = mkdir
+export FIND = find
export ECHO = echo
export UNZIP_CMD = unzip
export PYTHON = python
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index c2b2e9258..82df7c37d 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -136,6 +136,7 @@ int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], flo
int do_accel_calibration(int mavlink_fd) {
/* announce change */
mavlink_log_info(mavlink_fd, "accel calibration started");
+ mavlink_log_info(mavlink_fd, "accel cal progress <0> percent");
/* measure and calculate offsets & scales */
float accel_offs[3];
@@ -211,17 +212,28 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
}
int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
+
+ unsigned done_count = 0;
+
while (true) {
bool done = true;
- char str[80];
+ char str[60];
int str_ptr;
str_ptr = sprintf(str, "keep vehicle still:");
+ unsigned old_done_count = done_count;
+ done_count = 0;
for (int i = 0; i < 6; i++) {
if (!data_collected[i]) {
str_ptr += sprintf(&(str[str_ptr]), " %s", orientation_strs[i]);
done = false;
+ } else {
+ done_count++;
}
}
+
+ if (old_done_count != done_count)
+ mavlink_log_info(mavlink_fd, "accel cal progress <%u> percent", 17 * done_count);
+
if (done)
break;
mavlink_log_info(mavlink_fd, str);
@@ -236,8 +248,8 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
continue;
}
- sprintf(str, "meas started: %s", orientation_strs[orient]);
- mavlink_log_info(mavlink_fd, str);
+ // sprintf(str,
+ mavlink_log_info(mavlink_fd, "accel meas started: %s", orientation_strs[orient]);
read_accelerometer_avg(sensor_combined_sub, &(accel_ref[orient][0]), samples_num);
str_ptr = sprintf(str, "meas result for %s: [ %.2f %.2f %.2f ]", orientation_strs[orient],
(double)accel_ref[orient][0],
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index f5a9d4088..74cd5e36a 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -84,6 +84,7 @@
#include <systemlib/systemlib.h>
#include <systemlib/err.h>
#include <systemlib/cpuload.h>
+#include <systemlib/rc_check.h>
#include "px4_custom_mode.h"
#include "commander_helper.h"
@@ -322,11 +323,10 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
switch (cmd->command) {
case VEHICLE_CMD_DO_SET_MODE: {
uint8_t base_mode = (uint8_t) cmd->param1;
- union px4_custom_mode custom_mode;
- custom_mode.data_float = cmd->param2;
+ uint8_t custom_main_mode = (uint8_t) cmd->param2;
// TODO remove debug code
- mavlink_log_critical(mavlink_fd, "[cmd] command setmode: %d %d", base_mode, custom_mode);
+ mavlink_log_critical(mavlink_fd, "[cmd] command setmode: %d %d", base_mode, custom_main_mode);
/* set arming state */
transition_result_t arming_res = TRANSITION_NOT_CHANGED;
@@ -356,19 +356,19 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
/* use autopilot-specific mode */
- if (custom_mode.main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) {
+ if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) {
/* MANUAL */
main_res = main_state_transition(status, MAIN_STATE_MANUAL);
- } else if (custom_mode.main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) {
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) {
/* SEATBELT */
main_res = main_state_transition(status, MAIN_STATE_SEATBELT);
- } else if (custom_mode.main_mode == PX4_CUSTOM_MAIN_MODE_EASY) {
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_EASY) {
/* EASY */
main_res = main_state_transition(status, MAIN_STATE_EASY);
- } else if (custom_mode.main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
/* AUTO */
main_res = main_state_transition(status, MAIN_STATE_AUTO);
}
@@ -617,6 +617,8 @@ int commander_thread_main(int argc, char *argv[])
bool updated = false;
+ bool rc_calibration_ok = (OK == rc_calibration_check());
+
/* Subscribe to safety topic */
int safety_sub = orb_subscribe(ORB_ID(safety));
memset(&safety, 0, sizeof(safety));
@@ -727,6 +729,9 @@ int commander_thread_main(int argc, char *argv[])
param_get(_param_system_id, &(status.system_id));
param_get(_param_component_id, &(status.component_id));
status_changed = true;
+
+ /* Re-check RC calibration */
+ rc_calibration_ok = (OK == rc_calibration_check());
}
}
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index 9263c6a15..42f0190c7 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -100,6 +100,8 @@ int do_mag_calibration(int mavlink_fd)
close(fd);
+ mavlink_log_info(mavlink_fd, "mag cal progress <20> percent");
+
/* calibrate offsets */
// uint64_t calibration_start = hrt_absolute_time();
@@ -135,9 +137,8 @@ int do_mag_calibration(int mavlink_fd)
axis_index++;
- char buf[50];
- sprintf(buf, "please rotate around %c", axislabels[axis_index]);
- mavlink_log_info(mavlink_fd, buf);
+ mavlink_log_info(mavlink_fd, "please rotate in a figure 8 or around %c", axislabels[axis_index]);
+ mavlink_log_info(mavlink_fd, "mag cal progress <%u> percent", 20 + (calibration_maxcount * 50) / calibration_counter);
tune_neutral();
axis_deadline += calibration_interval / 3;
@@ -251,6 +252,8 @@ int do_mag_calibration(int mavlink_fd)
warnx("Setting Z mag scale failed!\n");
}
+ mavlink_log_info(mavlink_fd, "mag cal progress <90> percent");
+
/* auto-save to EEPROM */
int save_ret = param_save_default();
@@ -274,6 +277,7 @@ int do_mag_calibration(int mavlink_fd)
mavlink_log_info(mavlink_fd, buf);
mavlink_log_info(mavlink_fd, "mag calibration done");
+ mavlink_log_info(mavlink_fd, "mag cal progress <100> percent");
return OK;
/* third beep by cal end routine */
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index eb28af1a1..af43542da 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -201,7 +201,7 @@ handle_message(mavlink_message_t *msg)
custom_mode.data = new_mode.custom_mode;
/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
vcmd.param1 = new_mode.base_mode;
- vcmd.param2 = custom_mode.data_float;
+ vcmd.param2 = custom_mode.main_mode;
vcmd.param3 = 0;
vcmd.param4 = 0;
vcmd.param5 = 0;
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index b45317dbe..fd2a6318e 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -157,7 +157,6 @@ PARAM_DEFINE_FLOAT(RC14_MAX, 2000);
PARAM_DEFINE_FLOAT(RC14_REV, 1.0f);
PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f);
-PARAM_DEFINE_INT32(RC_TYPE, 1); /** 1 = FUTABA, 2 = Spektrum, 3 = Graupner HoTT, 4 = Turnigy 9x */
PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */
PARAM_DEFINE_INT32(RC_DSM_BIND, 0); /* 0 = Idle, 1 = Start DSM2 bind, 2 = Start DSMX bind */
@@ -184,10 +183,7 @@ PARAM_DEFINE_INT32(RC_MAP_FLAPS, 0);
PARAM_DEFINE_INT32(RC_MAP_AUX1, 0); /**< default function: camera yaw / azimuth */
PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera pitch / tilt */
-PARAM_DEFINE_INT32(RC_MAP_AUX3, 0); /**< default function: camera trigger */
-PARAM_DEFINE_INT32(RC_MAP_AUX4, 0); /**< default function: camera roll */
-PARAM_DEFINE_INT32(RC_MAP_AUX5, 0); /**< default function: payload drop */
-PARAM_DEFINE_FLOAT(RC_SCALE_ROLL, 0.4f);
-PARAM_DEFINE_FLOAT(RC_SCALE_PITCH, 0.4f);
-PARAM_DEFINE_FLOAT(RC_SCALE_YAW, 1.0f);
+PARAM_DEFINE_FLOAT(RC_SCALE_ROLL, 0.6f);
+PARAM_DEFINE_FLOAT(RC_SCALE_PITCH, 0.6f);
+PARAM_DEFINE_FLOAT(RC_SCALE_YAW, 2.0f);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index ded39c465..e857b1c2f 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -305,8 +305,6 @@ private:
int board_rotation;
int external_mag_rotation;
- int rc_type;
-
int rc_map_roll;
int rc_map_pitch;
int rc_map_yaw;
@@ -342,9 +340,6 @@ private:
param_t max[_rc_max_chan_count];
param_t rev[_rc_max_chan_count];
param_t dz[_rc_max_chan_count];
- param_t rc_type;
-
- param_t rc_demix;
param_t gyro_offset[3];
param_t gyro_scale[3];
@@ -566,8 +561,6 @@ Sensors::Sensors() :
}
- _parameter_handles.rc_type = param_find("RC_TYPE");
-
/* mandatory input switched, mapped to channels 1-4 per default */
_parameter_handles.rc_map_roll = param_find("RC_MAP_ROLL");
_parameter_handles.rc_map_pitch = param_find("RC_MAP_PITCH");
@@ -692,11 +685,6 @@ Sensors::parameters_update()
if (!rc_valid)
warnx("WARNING WARNING WARNING\n\nRC CALIBRATION NOT SANE!\n\n");
- /* remote control type */
- if (param_get(_parameter_handles.rc_type, &(_parameters.rc_type)) != OK) {
- warnx("Failed getting remote control type");
- }
-
/* channel mapping */
if (param_get(_parameter_handles.rc_map_roll, &(_parameters.rc_map_roll)) != OK) {
warnx("Failed getting roll chan index");
@@ -738,26 +726,11 @@ Sensors::parameters_update()
// warnx("Failed getting offboard control mode sw chan index");
// }
- if (param_get(_parameter_handles.rc_map_aux1, &(_parameters.rc_map_aux1)) != OK) {
- warnx("Failed getting mode aux 1 index");
- }
-
- if (param_get(_parameter_handles.rc_map_aux2, &(_parameters.rc_map_aux2)) != OK) {
- warnx("Failed getting mode aux 2 index");
- }
-
- if (param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3)) != OK) {
- warnx("Failed getting mode aux 3 index");
- }
-
- if (param_get(_parameter_handles.rc_map_aux4, &(_parameters.rc_map_aux4)) != OK) {
- warnx("Failed getting mode aux 4 index");
- }
-
- if (param_get(_parameter_handles.rc_map_aux5, &(_parameters.rc_map_aux5)) != OK) {
- warnx("Failed getting mode aux 5 index");
- }
-
+ param_get(_parameter_handles.rc_map_aux1, &(_parameters.rc_map_aux1));
+ param_get(_parameter_handles.rc_map_aux2, &(_parameters.rc_map_aux2));
+ param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3));
+ param_get(_parameter_handles.rc_map_aux4, &(_parameters.rc_map_aux4));
+ param_get(_parameter_handles.rc_map_aux5, &(_parameters.rc_map_aux5));
param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll));
param_get(_parameter_handles.rc_scale_pitch, &(_parameters.rc_scale_pitch));
param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw));
diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk
index 94c744c03..843cda722 100644
--- a/src/modules/systemlib/module.mk
+++ b/src/modules/systemlib/module.mk
@@ -48,4 +48,5 @@ SRCS = err.c \
systemlib.c \
airspeed.c \
system_params.c \
- mavlink_log.c
+ mavlink_log.c \
+ rc_check.c
diff --git a/src/modules/systemlib/rc_check.c b/src/modules/systemlib/rc_check.c
new file mode 100644
index 000000000..9d47d8000
--- /dev/null
+++ b/src/modules/systemlib/rc_check.c
@@ -0,0 +1,148 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file rc_check.c
+ *
+ * RC calibration check
+ */
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <fcntl.h>
+
+#include <systemlib/rc_check.h>
+#include <systemlib/param/param.h>
+#include <mavlink/mavlink_log.h>
+#include <uORB/topics/rc_channels.h>
+
+int rc_calibration_check(void) {
+
+ char nbuf[20];
+ param_t _parameter_handles_min, _parameter_handles_trim, _parameter_handles_max,
+ _parameter_handles_rev, _parameter_handles_dz;
+
+ int mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+
+ float param_min, param_max, param_trim, param_rev, param_dz;
+
+ /* first check channel mappings */
+ /* check which map param applies */
+ // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) {
+ // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1);
+ // /* give system time to flush error message in case there are more */
+ // usleep(100000);
+ // count++;
+ // }
+
+
+
+ for (int i = 0; i < RC_CHANNELS_MAX; i++) {
+ /* should the channel be enabled? */
+ uint8_t count = 0;
+
+ /* min values */
+ sprintf(nbuf, "RC%d_MIN", i + 1);
+ _parameter_handles_min = param_find(nbuf);
+ param_get(_parameter_handles_min, &param_min);
+
+ /* trim values */
+ sprintf(nbuf, "RC%d_TRIM", i + 1);
+ _parameter_handles_trim = param_find(nbuf);
+ param_get(_parameter_handles_trim, &param_trim);
+
+ /* max values */
+ sprintf(nbuf, "RC%d_MAX", i + 1);
+ _parameter_handles_max = param_find(nbuf);
+ param_get(_parameter_handles_max, &param_max);
+
+ /* channel reverse */
+ sprintf(nbuf, "RC%d_REV", i + 1);
+ _parameter_handles_rev = param_find(nbuf);
+ param_get(_parameter_handles_rev, &param_rev);
+
+ /* channel deadzone */
+ sprintf(nbuf, "RC%d_DZ", i + 1);
+ _parameter_handles_dz = param_find(nbuf);
+ param_get(_parameter_handles_dz, &param_dz);
+
+ /* assert min..center..max ordering */
+ if (param_min < 500) {
+ count++;
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MIN < 500", i+1);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ }
+ if (param_max > 2500) {
+ count++;
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAX > 2500", i+1);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ }
+ if (param_trim < param_min) {
+ count++;
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM < MIN", i+1);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ }
+ if (param_trim > param_max) {
+ count++;
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM > MAX", i+1);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ }
+
+ /* assert deadzone is sane */
+ if (param_dz > 500) {
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_DZ > 500", i+1);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ count++;
+ }
+
+ /* check which map param applies */
+ // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) {
+ // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1);
+ // /* give system time to flush error message in case there are more */
+ // usleep(100000);
+ // count++;
+ // }
+
+ /* sanity checks pass, enable channel */
+ if (count) {
+ mavlink_log_critical(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
+ usleep(100000);
+ }
+ }
+}
diff --git a/src/modules/systemlib/rc_check.h b/src/modules/systemlib/rc_check.h
new file mode 100644
index 000000000..e2238d151
--- /dev/null
+++ b/src/modules/systemlib/rc_check.h
@@ -0,0 +1,52 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file rc_check.h
+ *
+ * RC calibration check
+ */
+
+#pragma once
+
+ __BEGIN_DECLS
+
+/**
+ * Check the RC calibration
+ *
+ * @return 0 / OK if RC calibration is ok, index + 1 of the first
+ * channel that failed else (so 1 == first channel failed)
+ */
+__EXPORT int rc_calibration_check(void);
+
+__END_DECLS
diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c
index e7d9ce85f..4c19dcffb 100644
--- a/src/systemcmds/preflight_check/preflight_check.c
+++ b/src/systemcmds/preflight_check/preflight_check.c
@@ -57,6 +57,7 @@
#include <drivers/drv_baro.h>
#include <mavlink/mavlink_log.h>
+#include <systemlib/rc_check.h>
__EXPORT int preflight_check_main(int argc, char *argv[]);
static int led_toggle(int leds, int led);
@@ -139,101 +140,7 @@ int preflight_check_main(int argc, char *argv[])
/* ---- RC CALIBRATION ---- */
- param_t _parameter_handles_min, _parameter_handles_trim, _parameter_handles_max,
- _parameter_handles_rev, _parameter_handles_dz;
-
- float param_min, param_max, param_trim, param_rev, param_dz;
-
- bool rc_ok = true;
- char nbuf[20];
-
- /* first check channel mappings */
- /* check which map param applies */
- // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) {
- // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1);
- // /* give system time to flush error message in case there are more */
- // usleep(100000);
- // count++;
- // }
-
- for (int i = 0; i < 12; i++) {
- /* should the channel be enabled? */
- uint8_t count = 0;
-
- /* min values */
- sprintf(nbuf, "RC%d_MIN", i + 1);
- _parameter_handles_min = param_find(nbuf);
- param_get(_parameter_handles_min, &param_min);
-
- /* trim values */
- sprintf(nbuf, "RC%d_TRIM", i + 1);
- _parameter_handles_trim = param_find(nbuf);
- param_get(_parameter_handles_trim, &param_trim);
-
- /* max values */
- sprintf(nbuf, "RC%d_MAX", i + 1);
- _parameter_handles_max = param_find(nbuf);
- param_get(_parameter_handles_max, &param_max);
-
- /* channel reverse */
- sprintf(nbuf, "RC%d_REV", i + 1);
- _parameter_handles_rev = param_find(nbuf);
- param_get(_parameter_handles_rev, &param_rev);
-
- /* channel deadzone */
- sprintf(nbuf, "RC%d_DZ", i + 1);
- _parameter_handles_dz = param_find(nbuf);
- param_get(_parameter_handles_dz, &param_dz);
-
- /* assert min..center..max ordering */
- if (param_min < 500) {
- count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MIN < 500", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- }
- if (param_max > 2500) {
- count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAX > 2500", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- }
- if (param_trim < param_min) {
- count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM < MIN", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- }
- if (param_trim > param_max) {
- count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM > MAX", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- }
-
- /* assert deadzone is sane */
- if (param_dz > 500) {
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_DZ > 500", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- count++;
- }
-
- /* check which map param applies */
- // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) {
- // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1);
- // /* give system time to flush error message in case there are more */
- // usleep(100000);
- // count++;
- // }
-
- /* sanity checks pass, enable channel */
- if (count) {
- mavlink_log_critical(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
- usleep(100000);
- rc_ok = false;
- }
- }
+ bool rc_ok = (OK == rc_calibration_check());
/* require RC ok to keep system_ok */
system_ok &= rc_ok;