aboutsummaryrefslogtreecommitdiff
path: root/ROMFS
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-12-26 17:06:19 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-12-26 17:06:19 +0100
commit407889ea2c472ed5be950307bb5dc27f07f88006 (patch)
tree0dacd8384fd8a136c27163da1e22a086a0b9d3d5 /ROMFS
parentf3a224e30d8a70418541a6185ce5765b37745a7a (diff)
parent5c51adf5f79266de2b483c2461babd4d673cfffb (diff)
downloadpx4-firmware-407889ea2c472ed5be950307bb5dc27f07f88006.tar.gz
px4-firmware-407889ea2c472ed5be950307bb5dc27f07f88006.tar.bz2
px4-firmware-407889ea2c472ed5be950307bb5dc27f07f88006.zip
Merged master into indoor branch
Diffstat (limited to 'ROMFS')
-rw-r--r--ROMFS/px4fmu_common/init.d/10015_tbs_discovery4
-rw-r--r--ROMFS/px4fmu_common/init.d/10016_3dr_iris4
-rw-r--r--ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d4
-rw-r--r--ROMFS/px4fmu_common/init.d/10018_tbs_endurance31
-rw-r--r--ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil2
-rw-r--r--ROMFS/px4fmu_common/init.d/11001_hexa_cox2
-rw-r--r--ROMFS/px4fmu_common/init.d/12001_octo_cox2
-rw-r--r--ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol16
-rw-r--r--ROMFS/px4fmu_common/init.d/2102_3dr_skywalker2
-rw-r--r--ROMFS/px4fmu_common/init.d/3030_io_camflyer2
-rw-r--r--ROMFS/px4fmu_common/init.d/3031_phantom4
-rw-r--r--ROMFS/px4fmu_common/init.d/3032_skywalker_x52
-rw-r--r--ROMFS/px4fmu_common/init.d/3033_wingwing4
-rw-r--r--ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha4
-rw-r--r--ROMFS/px4fmu_common/init.d/4001_quad_x2
-rw-r--r--ROMFS/px4fmu_common/init.d/4008_ardrone4
-rw-r--r--ROMFS/px4fmu_common/init.d/4010_dji_f3302
-rw-r--r--ROMFS/px4fmu_common/init.d/4011_dji_f4502
-rw-r--r--ROMFS/px4fmu_common/init.d/4012_quad_x_can2
-rw-r--r--ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb2
-rw-r--r--ROMFS/px4fmu_common/init.d/5001_quad_+2
-rw-r--r--ROMFS/px4fmu_common/init.d/6001_hexa_x2
-rw-r--r--ROMFS/px4fmu_common/init.d/7001_hexa_+2
-rw-r--r--ROMFS/px4fmu_common/init.d/8001_octo_x2
-rw-r--r--ROMFS/px4fmu_common/init.d/9001_octo_+2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.autostart16
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_defaults4
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.interface31
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.io2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_defaults2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.sensors4
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.uavcan6
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.vtol_apps15
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.vtol_defaults39
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS204
-rw-r--r--ROMFS/px4fmu_common/mixers/FMU_caipirinha_vtol.mix16
-rw-r--r--ROMFS/px4fmu_common/mixers/skywalker.mix64
-rw-r--r--ROMFS/px4fmu_test/init.d/rc.standalone4
-rw-r--r--ROMFS/px4fmu_test/init.d/rcS10
39 files changed, 387 insertions, 137 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
index c8379e3a1..c1b366de8 100644
--- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
@@ -7,7 +7,7 @@
sh /etc/init.d/rc.mc_defaults
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
# TODO review MC_YAWRATE_I
param set MC_ROLL_P 8.0
@@ -26,5 +26,5 @@ fi
set MIXER FMU_quad_w
-set PWM_OUTPUTS 1234
+set PWM_OUT 1234
set PWM_MIN 1200
diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
index 0b422de7e..3879737a8 100644
--- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
@@ -7,7 +7,7 @@
sh /etc/init.d/rc.mc_defaults
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
# TODO tune roll/pitch separately
param set MC_ROLL_P 7.0
@@ -29,7 +29,7 @@ fi
set MIXER FMU_quad_w
-set PWM_OUTPUTS 1234
+set PWM_OUT 1234
set PWM_MIN 1200
set PWM_MAX 1950
diff --git a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
index a621de7ce..57f77754c 100644
--- a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
+++ b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
@@ -7,7 +7,7 @@
sh /etc/init.d/rc.mc_defaults
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
# TODO tune roll/pitch separately
param set MC_ROLL_P 7.0
@@ -31,4 +31,4 @@ set MIXER FMU_quad_w
set PWM_MIN 1210
set PWM_MAX 2100
-set PWM_OUTPUTS 1234
+set PWM_OUT 1234
diff --git a/ROMFS/px4fmu_common/init.d/10018_tbs_endurance b/ROMFS/px4fmu_common/init.d/10018_tbs_endurance
new file mode 100644
index 000000000..2d5e272bd
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/10018_tbs_endurance
@@ -0,0 +1,31 @@
+#!nsh
+#
+# Team Blacksheep Discovery Long Range Quadcopter
+#
+# Setup: 15 x 6.5" Props, 6S 4000mAh TBS LiPo, TBS 30A ESCs, TBS 400kV Motors
+#
+# Simon Wilks <simon@px4.io>
+#
+
+sh /etc/init.d/rc.mc_defaults
+
+if [ $DO_AUTOCONFIG == yes ]
+then
+ param set MC_ROLL_P 7.0
+ param set MC_ROLLRATE_P 0.07
+ param set MC_ROLLRATE_I 0.02
+ param set MC_ROLLRATE_D 0.003
+ param set MC_PITCH_P 7.0
+ param set MC_PITCHRATE_P 0.1
+ param set MC_PITCHRATE_I 0.05
+ param set MC_PITCHRATE_D 0.003
+ param set MC_YAW_P 2.8
+ param set MC_YAWRATE_P 0.4
+ param set MC_YAWRATE_I 0.1
+ param set MC_YAWRATE_D 0.0
+fi
+
+set MIXER FMU_quad_w
+
+set PWM_OUTPUTS 1234
+set PWM_MIN 1200
diff --git a/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil b/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil
index 00b97d675..f208b692a 100644
--- a/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil
+++ b/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil
@@ -7,7 +7,7 @@
sh /etc/init.d/rc.fw_defaults
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
param set FW_AIRSPD_MIN 12
param set FW_AIRSPD_TRIM 25
diff --git a/ROMFS/px4fmu_common/init.d/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
index e4d96fbd5..50f717e3d 100644
--- a/ROMFS/px4fmu_common/init.d/11001_hexa_cox
+++ b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
@@ -10,4 +10,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_hexa_cox
# Need to set all 8 channels
-set PWM_OUTPUTS 12345678
+set PWM_OUT 12345678
diff --git a/ROMFS/px4fmu_common/init.d/12001_octo_cox b/ROMFS/px4fmu_common/init.d/12001_octo_cox
index f820251ad..e0a838185 100644
--- a/ROMFS/px4fmu_common/init.d/12001_octo_cox
+++ b/ROMFS/px4fmu_common/init.d/12001_octo_cox
@@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_octo_cox
-set PWM_OUTPUTS 12345678
+set PWM_OUT 12345678
diff --git a/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol b/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol
new file mode 100644
index 000000000..7e9a6d3dc
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol
@@ -0,0 +1,16 @@
+#!nsh
+#
+# Generic configuration file for caipirinha VTOL version
+#
+# Roman Bapst <bapstr@ethz.ch>
+#
+
+sh /etc/init.d/rc.vtol_defaults
+
+set MIXER FMU_caipirinha_vtol
+
+set PWM_OUT 12
+set PWM_MAX 2000
+set PWM_RATE 400
+param set VT_MOT_COUNT 2
+param set VT_IDLE_PWM_MC 1080
diff --git a/ROMFS/px4fmu_common/init.d/2102_3dr_skywalker b/ROMFS/px4fmu_common/init.d/2102_3dr_skywalker
index dcc5db824..906f4b1cc 100644
--- a/ROMFS/px4fmu_common/init.d/2102_3dr_skywalker
+++ b/ROMFS/px4fmu_common/init.d/2102_3dr_skywalker
@@ -2,4 +2,4 @@
sh /etc/init.d/rc.fw_defaults
-set MIXER FMU_AERT \ No newline at end of file
+set MIXER skywalker \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/3030_io_camflyer b/ROMFS/px4fmu_common/init.d/3030_io_camflyer
index 0f0cb3a89..fe0269557 100644
--- a/ROMFS/px4fmu_common/init.d/3030_io_camflyer
+++ b/ROMFS/px4fmu_common/init.d/3030_io_camflyer
@@ -4,5 +4,5 @@ sh /etc/init.d/rc.fw_defaults
set MIXER FMU_Q
# Provide ESC a constant 1000 us pulse while disarmed
-set PWM_OUTPUTS 4
+set PWM_OUT 4
set PWM_DISARMED 1000
diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom
index a7749cba6..c7dd1dfc5 100644
--- a/ROMFS/px4fmu_common/init.d/3031_phantom
+++ b/ROMFS/px4fmu_common/init.d/3031_phantom
@@ -7,7 +7,7 @@
sh /etc/init.d/rc.fw_defaults
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
param set FW_AIRSPD_MIN 13
param set FW_AIRSPD_TRIM 15
@@ -36,5 +36,5 @@ fi
set MIXER phantom
# Provide ESC a constant 1000 us pulse
-set PWM_OUTPUTS 4
+set PWM_OUT 4
set PWM_DISARMED 1000
diff --git a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5
index 26c7c95e6..94363bf6a 100644
--- a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5
+++ b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5
@@ -7,7 +7,7 @@
sh /etc/init.d/rc.fw_defaults
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
param set FW_AIRSPD_MIN 15
param set FW_AIRSPD_TRIM 20
diff --git a/ROMFS/px4fmu_common/init.d/3033_wingwing b/ROMFS/px4fmu_common/init.d/3033_wingwing
index 919eefb4a..add905b11 100644
--- a/ROMFS/px4fmu_common/init.d/3033_wingwing
+++ b/ROMFS/px4fmu_common/init.d/3033_wingwing
@@ -7,7 +7,7 @@
sh /etc/init.d/rc.fw_defaults
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
param set BAT_N_CELLS 2
param set FW_AIRSPD_MAX 15
@@ -44,5 +44,5 @@ fi
set MIXER wingwing
# Provide ESC a constant 1000 us pulse
-set PWM_OUTPUTS 4
+set PWM_OUT 4
set PWM_DISARMED 1000
diff --git a/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha
index 9bfd9d9ed..9eafac1c5 100644
--- a/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha
+++ b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha
@@ -7,9 +7,9 @@
sh /etc/init.d/rc.fw_defaults
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
-
+
# TODO: these are the X5 default parameters, update them to the caipi
param set FW_AIRSPD_MIN 15
diff --git a/ROMFS/px4fmu_common/init.d/4001_quad_x b/ROMFS/px4fmu_common/init.d/4001_quad_x
index 8fe8961c5..4677f9fc3 100644
--- a/ROMFS/px4fmu_common/init.d/4001_quad_x
+++ b/ROMFS/px4fmu_common/init.d/4001_quad_x
@@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_quad_x
-set PWM_OUTPUTS 1234
+set PWM_OUT 1234
diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone
index 0488e3928..c3358ef4c 100644
--- a/ROMFS/px4fmu_common/init.d/4008_ardrone
+++ b/ROMFS/px4fmu_common/init.d/4008_ardrone
@@ -8,7 +8,7 @@ sh /etc/init.d/rc.mc_defaults
#
# Load default params for this platform
#
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
# Set all params here, then disable autoconfig
param set MC_ROLL_P 6.0
@@ -24,7 +24,7 @@ then
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.0
param set MC_YAW_FF 0.8
-
+
param set BAT_V_SCALING 0.00838095238
fi
diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330
index f0cc05207..8e5dc76b1 100644
--- a/ROMFS/px4fmu_common/init.d/4010_dji_f330
+++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330
@@ -7,7 +7,7 @@
sh /etc/init.d/4001_quad_x
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
param set MC_ROLL_P 7.0
param set MC_ROLLRATE_P 0.1
diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450
index 1ca716a6b..ea35b3ba9 100644
--- a/ROMFS/px4fmu_common/init.d/4011_dji_f450
+++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450
@@ -7,7 +7,7 @@
sh /etc/init.d/4001_quad_x
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
# TODO REVIEW
param set MC_ROLL_P 7.0
diff --git a/ROMFS/px4fmu_common/init.d/4012_quad_x_can b/ROMFS/px4fmu_common/init.d/4012_quad_x_can
index 5c4a6497a..b1db1dd9a 100644
--- a/ROMFS/px4fmu_common/init.d/4012_quad_x_can
+++ b/ROMFS/px4fmu_common/init.d/4012_quad_x_can
@@ -7,7 +7,7 @@
sh /etc/init.d/4001_quad_x
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
# TODO REVIEW
param set MC_ROLL_P 7.0
diff --git a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb
index 9fe310dde..a1de19d5d 100644
--- a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb
+++ b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb
@@ -9,7 +9,7 @@ echo "HK Micro PCB Quad"
sh /etc/init.d/4001_quad_x
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
param set MC_ROLL_P 7.0
param set MC_ROLLRATE_P 0.1
diff --git a/ROMFS/px4fmu_common/init.d/5001_quad_+ b/ROMFS/px4fmu_common/init.d/5001_quad_+
index 5512aa738..c78911391 100644
--- a/ROMFS/px4fmu_common/init.d/5001_quad_+
+++ b/ROMFS/px4fmu_common/init.d/5001_quad_+
@@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_quad_+
-set PWM_OUTPUTS 1234
+set PWM_OUT 1234
diff --git a/ROMFS/px4fmu_common/init.d/6001_hexa_x b/ROMFS/px4fmu_common/init.d/6001_hexa_x
index 1043ad8ad..0df25b11a 100644
--- a/ROMFS/px4fmu_common/init.d/6001_hexa_x
+++ b/ROMFS/px4fmu_common/init.d/6001_hexa_x
@@ -10,4 +10,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_hexa_x
# Need to set all 8 channels
-set PWM_OUTPUTS 12345678
+set PWM_OUT 12345678
diff --git a/ROMFS/px4fmu_common/init.d/7001_hexa_+ b/ROMFS/px4fmu_common/init.d/7001_hexa_+
index 84ab88883..16c772ee1 100644
--- a/ROMFS/px4fmu_common/init.d/7001_hexa_+
+++ b/ROMFS/px4fmu_common/init.d/7001_hexa_+
@@ -10,4 +10,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_hexa_+
# Need to set all 8 channels
-set PWM_OUTPUTS 12345678
+set PWM_OUT 12345678
diff --git a/ROMFS/px4fmu_common/init.d/8001_octo_x b/ROMFS/px4fmu_common/init.d/8001_octo_x
index 74e304cd9..bae36737f 100644
--- a/ROMFS/px4fmu_common/init.d/8001_octo_x
+++ b/ROMFS/px4fmu_common/init.d/8001_octo_x
@@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_octo_x
-set PWM_OUTPUTS 12345678
+set PWM_OUT 12345678
diff --git a/ROMFS/px4fmu_common/init.d/9001_octo_+ b/ROMFS/px4fmu_common/init.d/9001_octo_+
index f7c06c6c8..ca5439f68 100644
--- a/ROMFS/px4fmu_common/init.d/9001_octo_+
+++ b/ROMFS/px4fmu_common/init.d/9001_octo_+
@@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_octo_+
-set PWM_OUTPUTS 12345678 \ No newline at end of file
+set PWM_OUT 12345678
diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart
index 496a52c5f..20f2be0d9 100644
--- a/ROMFS/px4fmu_common/init.d/rc.autostart
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -15,6 +15,7 @@
# 10000 .. 10999 Wide arm / H frame
# 11000 .. 11999 Hexa Cox
# 12000 .. 12999 Octo Cox
+# 13000 .. 13999 VTOL
#
# Simulation
@@ -220,6 +221,11 @@ then
sh /etc/init.d/10017_steadidrone_qu4d
fi
+if param compare SYS_AUTOSTART 10018 18
+then
+ sh /etc/init.d/10018_tbs_endurance
+fi
+
#
# Hexa Coaxial
#
@@ -237,3 +243,13 @@ if param compare SYS_AUTOSTART 12001
then
sh /etc/init.d/12001_octo_cox
fi
+
+# 13000 is historically reserved for the quadshot
+
+#
+# VTOL caipririnha
+#
+ if param compare SYS_AUTOSTART 13001
+ then
+ sh /etc/init.d/13001_caipirinha_vtol
+ fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
index 3c336f295..fab2a7f18 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
@@ -2,7 +2,7 @@
set VEHICLE_TYPE fw
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
#
# Default parameters for FW
@@ -15,4 +15,4 @@ then
param set FW_T_RLL2THR 15
param set FW_T_SRATE_P 0.01
param set FW_T_TIME_CONST 5
-fi \ No newline at end of file
+fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface
index e44cd0953..bab71be93 100644
--- a/ROMFS/px4fmu_common/init.d/rc.interface
+++ b/ROMFS/px4fmu_common/init.d/rc.interface
@@ -8,12 +8,11 @@ then
#
# Load mixer
#
- set MIXERSD /fs/microsd/etc/mixers/$MIXER.mix
#Use the mixer file from the SD-card if it exists
- if [ -f $MIXERSD ]
+ if [ -f /fs/microsd/etc/mixers/$MIXER.mix ]
then
- set MIXER_FILE $MIXERSD
+ set MIXER_FILE /fs/microsd/etc/mixers/$MIXER.mix
else
set MIXER_FILE /etc/mixers/$MIXER.mix
fi
@@ -32,30 +31,31 @@ then
if mixer load $OUTPUT_DEV $MIXER_FILE
then
- echo "[init] Mixer loaded: $MIXER_FILE"
+ echo "[i] Mixer: $MIXER_FILE"
else
- echo "[init] Error loading mixer: $MIXER_FILE"
- tone_alarm $TUNE_OUT_ERROR
+ echo "[i] Error loading mixer: $MIXER_FILE"
+ tone_alarm $TUNE_ERR
fi
+
+ unset MIXER_FILE
else
if [ $MIXER != skip ]
then
- echo "[init] Mixer not defined"
- tone_alarm $TUNE_OUT_ERROR
+ echo "[i] Mixer not defined"
+ tone_alarm $TUNE_ERR
fi
fi
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ]
then
- if [ $PWM_OUTPUTS != none ]
+ if [ $PWM_OUT != none ]
then
#
# Set PWM output frequency
#
if [ $PWM_RATE != none ]
then
- echo "[init] Set PWM rate: $PWM_RATE"
- pwm rate -c $PWM_OUTPUTS -r $PWM_RATE
+ pwm rate -c $PWM_OUT -r $PWM_RATE
fi
#
@@ -63,18 +63,15 @@ then
#
if [ $PWM_DISARMED != none ]
then
- echo "[init] Set PWM disarmed: $PWM_DISARMED"
- pwm disarmed -c $PWM_OUTPUTS -p $PWM_DISARMED
+ pwm disarmed -c $PWM_OUT -p $PWM_DISARMED
fi
if [ $PWM_MIN != none ]
then
- echo "[init] Set PWM min: $PWM_MIN"
- pwm min -c $PWM_OUTPUTS -p $PWM_MIN
+ pwm min -c $PWM_OUT -p $PWM_MIN
fi
if [ $PWM_MAX != none ]
then
- echo "[init] Set PWM max: $PWM_MAX"
- pwm max -c $PWM_OUTPUTS -p $PWM_MAX
+ pwm max -c $PWM_OUT -p $PWM_MAX
fi
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.io b/ROMFS/px4fmu_common/init.d/rc.io
index e23aebd87..e957626ce 100644
--- a/ROMFS/px4fmu_common/init.d/rc.io
+++ b/ROMFS/px4fmu_common/init.d/rc.io
@@ -16,5 +16,5 @@ then
set PX4IO_LIMIT 200
fi
-echo "[init] Set PX4IO update rate limit: $PX4IO_LIMIT Hz"
+echo "[i] Set PX4IO update rate limit: $PX4IO_LIMIT Hz"
px4io limit $PX4IO_LIMIT
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
index 0df320f49..307a64c4d 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
@@ -2,7 +2,7 @@
set VEHICLE_TYPE mc
-if [ $DO_AUTOCONFIG == yes ]
+if [ $AUTOCNF == yes ]
then
param set MC_ROLL_P 7.0
param set MC_ROLLRATE_P 0.1
diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors
index 858df4f28..973db9017 100644
--- a/ROMFS/px4fmu_common/init.d/rc.sensors
+++ b/ROMFS/px4fmu_common/init.d/rc.sensors
@@ -71,6 +71,10 @@ if px4flow start
then
fi
+if ll40ls start
+then
+fi
+
#
# Start sensors -> preflight_check
#
diff --git a/ROMFS/px4fmu_common/init.d/rc.uavcan b/ROMFS/px4fmu_common/init.d/rc.uavcan
index 9a470a6b8..08ba86d78 100644
--- a/ROMFS/px4fmu_common/init.d/rc.uavcan
+++ b/ROMFS/px4fmu_common/init.d/rc.uavcan
@@ -10,9 +10,9 @@ then
# First sensor publisher to initialize takes lowest instance ID
# This delay ensures that UAVCAN-interfaced sensors would be allocated on lowest instance IDs
sleep 1
- echo "[init] UAVCAN started"
+ echo "[i] UAVCAN started"
else
- echo "[init] ERROR: Could not start UAVCAN"
- tone_alarm $TUNE_OUT_ERROR
+ echo "[i] ERROR: Could not start UAVCAN"
+ tone_alarm $TUNE_ERR
fi
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_apps b/ROMFS/px4fmu_common/init.d/rc.vtol_apps
new file mode 100644
index 000000000..23ade6d78
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.vtol_apps
@@ -0,0 +1,15 @@
+#!nsh
+#
+# Standard apps for vtol:
+# att & pos estimator, att & pos control.
+#
+
+attitude_estimator_ekf start
+#ekf_att_pos_estimator start
+position_estimator_inav start
+
+vtol_att_control start
+mc_att_control start
+mc_pos_control start
+fw_att_control start
+fw_pos_control_l1 start
diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults
new file mode 100644
index 000000000..6dc5a65db
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults
@@ -0,0 +1,39 @@
+#!nsh
+
+set VEHICLE_TYPE vtol
+
+if [ $AUTOCNF == yes ]
+then
+ #
+ #Default controller parameters for MC
+ #
+ param set MC_ROLL_P 6.0
+ param set MC_ROLLRATE_P 0.1
+ param set MC_ROLLRATE_I 0.0
+ param set MC_ROLLRATE_D 0.003
+ param set MC_PITCH_P 6.0
+ param set MC_PITCHRATE_P 0.2
+ param set MC_PITCHRATE_I 0.0
+ param set MC_PITCHRATE_D 0.003
+ param set MC_YAW_P 4
+ param set MC_YAWRATE_P 0.2
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_D 0.0
+ param set MC_YAW_FF 0.3
+
+ #
+ # Default parameters for FW
+ #
+ param set FW_PR_FF 0.3
+ param set FW_PR_I 0.000
+ param set FW_PR_IMAX 0.2
+ param set FW_PR_P 0.02
+ param set FW_RR_FF 0.3
+ param set FW_RR_I 0.00
+ param set FW_RR_IMAX 0.2
+ param set FW_RR_P 0.02
+fi
+
+set PWM_DISARMED 900
+set PWM_MIN 1000
+set PWM_MAX 2000
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index e2691ab58..b0e0c2674 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -1,46 +1,46 @@
#!nsh
#
# PX4FMU startup script.
+#
+# NOTE: COMMENT LINES ARE REMOVED BEFORE STORED IN ROMFS.
+#
#
# Default to auto-start mode.
#
set MODE autostart
-set RC_FILE /fs/microsd/etc/rc.txt
-set CONFIG_FILE /fs/microsd/etc/config.txt
-set EXTRAS_FILE /fs/microsd/etc/extras.txt
+set FRC /fs/microsd/etc/rc.txt
+set FCONFIG /fs/microsd/etc/config.txt
+set FEXTRAS /fs/microsd/etc/extras.txt
-set TUNE_OUT_ERROR ML<<CP4CP4CP4CP4CP4
+set TUNE_ERR ML<<CP4CP4CP4CP4CP4
#
# Try to mount the microSD card.
#
-echo "[init] Looking for microSD..."
+echo "[i] Looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
set LOG_FILE /fs/microsd/bootlog.txt
- echo "[init] microSD mounted: /fs/microsd"
+ echo "[i] microSD mounted: /fs/microsd"
# Start playing the startup tune
tone_alarm start
else
set LOG_FILE /dev/null
- echo "[init] No microSD card found"
- # Play SOS
- tone_alarm error
fi
#
# Look for an init script on the microSD card.
# Disable autostart if the script found.
#
-if [ -f $RC_FILE ]
+if [ -f $FRC ]
then
- echo "[init] Executing init script: $RC_FILE"
- sh $RC_FILE
+ echo "[i] Executing init script: $FRC"
+ sh $FRC
set MODE custom
else
- echo "[init] Init script not found: $RC_FILE"
+ echo "[i] Init script not found: $FRC"
fi
# if this is an APM build then there will be a rc.APM script
@@ -49,17 +49,17 @@ if [ -f /etc/init.d/rc.APM ]
then
if sercon
then
- echo "[init] USB interface connected"
+ echo "[i] USB interface connected"
fi
- echo "[init] Running rc.APM"
+ echo "[i] Running rc.APM"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
fi
if [ $MODE == autostart ]
then
- echo "[init] AUTOSTART mode"
+ echo "[i] AUTOSTART mode"
#
# Start CDC/ACM serial driver
@@ -117,31 +117,31 @@ then
set VEHICLE_TYPE none
set MIXER none
set OUTPUT_MODE none
- set PWM_OUTPUTS none
+ set PWM_OUT none
set PWM_RATE none
set PWM_DISARMED none
set PWM_MIN none
set PWM_MAX none
- set MKBLCTRL_MODE none
+ set MK_MODE none
set FMU_MODE pwm
- set MAVLINK_FLAGS default
+ set MAVLINK_F default
set EXIT_ON_END no
set MAV_TYPE none
- set LOAD_DEFAULT_APPS yes
+ set LOAD_DAPPS yes
set GPS yes
set GPS_FAKE no
set FAILSAFE none
#
- # Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
+ # Set AUTOCNF flag to use it in AUTOSTART scripts
#
if param compare SYS_AUTOCONFIG 1
then
# Wipe out params
param reset_nostart
- set DO_AUTOCONFIG yes
+ set AUTOCNF yes
else
- set DO_AUTOCONFIG no
+ set AUTOCNF no
fi
#
@@ -159,7 +159,7 @@ then
#
if param compare SYS_AUTOSTART 0
then
- echo "[init] No autostart"
+ echo "[i] No autostart"
else
sh /etc/init.d/rc.autostart
fi
@@ -167,18 +167,19 @@ then
#
# Override parameters from user configuration file
#
- if [ -f $CONFIG_FILE ]
+ if [ -f $FCONFIG ]
then
- echo "[init] Config: $CONFIG_FILE"
- sh $CONFIG_FILE
+ echo "[i] Config: $FCONFIG"
+ sh $FCONFIG
else
- echo "[init] Config not found: $CONFIG_FILE"
+ echo "[i] Config not found: $FCONFIG"
fi
+ unset FCONFIG
#
# If autoconfig parameter was set, reset it and save parameters
#
- if [ $DO_AUTOCONFIG == yes ]
+ if [ $AUTOCNF == yes ]
then
param set SYS_AUTOCONFIG 0
param save
@@ -219,18 +220,18 @@ then
set IO_PRESENT yes
else
echo "PX4IO update failed" >> $LOG_FILE
- tone_alarm $TUNE_OUT_ERROR
+ tone_alarm $TUNE_ERR
fi
else
echo "PX4IO update failed" >> $LOG_FILE
- tone_alarm $TUNE_OUT_ERROR
+ tone_alarm $TUNE_ERR
fi
fi
if [ $IO_PRESENT == no ]
then
- echo "[init] ERROR: PX4IO not found"
- tone_alarm $TUNE_OUT_ERROR
+ echo "[i] ERROR: PX4IO not found"
+ tone_alarm $TUNE_ERR
fi
fi
@@ -251,7 +252,7 @@ then
then
# Need IO for output but it not present, disable output
set OUTPUT_MODE none
- echo "[init] ERROR: PX4IO not found, disabling output"
+ echo "[i] ERROR: PX4IO not found, disabling output"
# Avoid using ttyS0 for MAVLink on FMUv1
if ver hwcmp PX4FMU_V1
@@ -294,33 +295,31 @@ then
then
if param compare UAVCAN_ENABLE 0
then
- echo "[init] OVERRIDING UAVCAN_ENABLE = 1"
+ echo "[i] OVERRIDING UAVCAN_ENABLE = 1"
param set UAVCAN_ENABLE 1
fi
fi
if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == uavcan_esc ]
then
- echo "[init] Use PX4IO PWM as primary output"
if px4io start
then
- echo "[init] PX4IO started"
+ echo "[i] PX4IO started"
sh /etc/init.d/rc.io
else
- echo "[init] ERROR: PX4IO start failed"
- tone_alarm $TUNE_OUT_ERROR
+ echo "[i] ERROR: PX4IO start failed"
+ tone_alarm $TUNE_ERR
fi
fi
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
then
- echo "[init] Use FMU as primary output"
if fmu mode_$FMU_MODE
then
- echo "[init] FMU mode_$FMU_MODE started"
+ echo "[i] FMU mode_$FMU_MODE started"
else
- echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
- tone_alarm $TUNE_OUT_ERROR
+ echo "[i] ERROR: FMU mode_$FMU_MODE start failed"
+ tone_alarm $TUNE_ERR
fi
if ver hwcmp PX4FMU_V1
@@ -338,36 +337,34 @@ then
if [ $OUTPUT_MODE == mkblctrl ]
then
- echo "[init] Use MKBLCTRL as primary output"
set MKBLCTRL_ARG ""
- if [ $MKBLCTRL_MODE == x ]
+ if [ $MK_MODE == x ]
then
set MKBLCTRL_ARG "-mkmode x"
fi
- if [ $MKBLCTRL_MODE == + ]
+ if [ $MK_MODE == + ]
then
set MKBLCTRL_ARG "-mkmode +"
fi
if mkblctrl $MKBLCTRL_ARG
then
- echo "[init] MKBLCTRL started"
+ echo "[i] MK started"
else
- echo "[init] ERROR: MKBLCTRL start failed"
- tone_alarm $TUNE_OUT_ERROR
+ echo "[i] ERROR: MK start failed"
+ tone_alarm $TUNE_ERR
fi
fi
if [ $OUTPUT_MODE == hil ]
then
- echo "[init] Use HIL as primary output"
if hil mode_port2_pwm8
then
- echo "[init] HIL output started"
+ echo "[i] HIL output started"
else
- echo "[init] ERROR: HIL output start failed"
- tone_alarm $TUNE_OUT_ERROR
+ echo "[i] ERROR: HIL output start failed"
+ tone_alarm $TUNE_ERR
fi
fi
@@ -380,11 +377,11 @@ then
then
if px4io start
then
- echo "[init] PX4IO started"
+ echo "[i] PX4IO started"
sh /etc/init.d/rc.io
else
- echo "[init] ERROR: PX4IO start failed"
- tone_alarm $TUNE_OUT_ERROR
+ echo "[i] ERROR: PX4IO start failed"
+ tone_alarm $TUNE_ERR
fi
fi
else
@@ -392,10 +389,10 @@ then
then
if fmu mode_$FMU_MODE
then
- echo "[init] FMU mode_$FMU_MODE started"
+ echo "[i] FMU mode_$FMU_MODE started"
else
- echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
- tone_alarm $TUNE_OUT_ERROR
+ echo "[i] ERROR: FMU mode_$FMU_MODE start failed"
+ tone_alarm $TUNE_ERR
fi
if ver hwcmp PX4FMU_V1
@@ -413,23 +410,24 @@ then
fi
fi
- if [ $MAVLINK_FLAGS == default ]
+ if [ $MAVLINK_F == default ]
then
# Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
if [ $TTYS1_BUSY == yes ]
then
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
- set MAVLINK_FLAGS "-r 1000 -d /dev/ttyS0"
+ set MAVLINK_F "-r 1000 -d /dev/ttyS0"
# Exit from nsh to free port for mavlink
set EXIT_ON_END yes
else
# Start MAVLink on default port: ttyS1
- set MAVLINK_FLAGS "-r 1000"
+ set MAVLINK_F "-r 1000"
fi
fi
- mavlink start $MAVLINK_FLAGS
+ mavlink start $MAVLINK_F
+ unset MAVLINK_F
#
# MAVLink onboard / TELEM2
@@ -451,15 +449,16 @@ then
if [ $GPS == yes ]
then
- echo "[init] Start GPS"
+ echo "[i] Start GPS"
if [ $GPS_FAKE == yes ]
then
- echo "[init] Faking GPS"
+ echo "[i] Faking GPS"
gps start -f
else
gps start
fi
fi
+ unset GPS_FAKE
#
# Start up ARDrone Motor interface
@@ -474,7 +473,7 @@ then
#
if [ $VEHICLE_TYPE == fw ]
then
- echo "[init] Vehicle type: FIXED WING"
+ echo "[i] FIXED WING"
if [ $MIXER == none ]
then
@@ -494,7 +493,7 @@ then
sh /etc/init.d/rc.interface
# Start standard fixedwing apps
- if [ $LOAD_DEFAULT_APPS == yes ]
+ if [ $LOAD_DAPPS == yes ]
then
sh /etc/init.d/rc.fw_apps
fi
@@ -505,11 +504,11 @@ then
#
if [ $VEHICLE_TYPE == mc ]
then
- echo "[init] Vehicle type: MULTICOPTER"
+ echo "[i] MULTICOPTER"
if [ $MIXER == none ]
then
- echo "Default mixer for multicopter not defined"
+ echo "Mixer undefined"
fi
if [ $MAV_TYPE == none ]
@@ -553,13 +552,52 @@ then
sh /etc/init.d/rc.interface
# Start standard multicopter apps
- if [ $LOAD_DEFAULT_APPS == yes ]
+ if [ $LOAD_DAPPS == yes ]
then
sh /etc/init.d/rc.mc_apps
fi
fi
#
+ # VTOL setup
+ #
+ if [ $VEHICLE_TYPE == vtol ]
+ then
+ echo "[init] Vehicle type: VTOL"
+
+ if [ $MIXER == none ]
+ then
+ echo "Default mixer for vtol not defined"
+ fi
+
+ if [ $MAV_TYPE == none ]
+ then
+ # Use mixer to detect vehicle type
+ if [ $MIXER == FMU_caipirinha_vtol ]
+ then
+ set MAV_TYPE 19
+ fi
+ fi
+
+ # Still no MAV_TYPE found
+ if [ $MAV_TYPE == none ]
+ then
+ echo "Unknown MAV_TYPE"
+ else
+ param set MAV_TYPE $MAV_TYPE
+ fi
+
+ # Load mixer and configure outputs
+ sh /etc/init.d/rc.interface
+
+ # Start standard vtol apps
+ if [ $LOAD_DAPPS == yes ]
+ then
+ sh /etc/init.d/rc.vtol_apps
+ fi
+ fi
+
+ #
# Start the navigator
#
navigator start
@@ -569,24 +607,38 @@ then
#
if [ $VEHICLE_TYPE == none ]
then
- echo "[init] Vehicle type: No autostart ID found"
+ echo "[i] No autostart ID found"
fi
# Start any custom addons
- if [ -f $EXTRAS_FILE ]
+ if [ -f $FEXTRAS ]
then
- echo "[init] Starting addons script: $EXTRAS_FILE"
- sh $EXTRAS_FILE
+ echo "[i] Addons script: $FEXTRAS"
+ sh $FEXTRAS
else
- echo "[init] No addons script: $EXTRAS_FILE"
+ echo "[i] No addons script: $FEXTRAS"
fi
+ unset FEXTRAS
if [ $EXIT_ON_END == yes ]
then
- echo "[init] Exit from nsh"
+ echo "Exit from nsh"
exit
fi
+ unset EXIT_ON_END
+
+ # Run no SD alarm last
+ if [ $LOG_FILE == /dev/null ]
+ then
+ echo "[i] No microSD card found"
+ # Play SOS
+ tone_alarm error
+ fi
# End of autostart
fi
+
+# There is no further processing, so we can free some RAM
+# XXX potentially unset all script variables.
+unset TUNE_ERR
diff --git a/ROMFS/px4fmu_common/mixers/FMU_caipirinha_vtol.mix b/ROMFS/px4fmu_common/mixers/FMU_caipirinha_vtol.mix
new file mode 100644
index 000000000..5ae0f5588
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/FMU_caipirinha_vtol.mix
@@ -0,0 +1,16 @@
+#!nsh
+# Caipirinha vtol mixer for PX4FMU
+#
+#===========================
+R: 2- 10000 10000 10000 0
+
+#mixer for the elevons
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 1 0 10000 10000 0 -10000 10000
+S: 1 1 10000 10000 0 -10000 10000
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 1 0 10000 10000 0 -10000 10000
+S: 1 1 -10000 -10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/skywalker.mix b/ROMFS/px4fmu_common/mixers/skywalker.mix
new file mode 100644
index 000000000..04d677e56
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/skywalker.mix
@@ -0,0 +1,64 @@
+Mixer for Skywalker Airframe
+==================================================
+
+This file defines mixers suitable for controlling a fixed wing aircraft with
+aileron, rudder, elevator and throttle controls using PX4FMU. The configuration
+assumes the aileron servo(s) are connected to PX4FMU servo output 0, the
+elevator to output 1, the rudder to output 2 and the throttle to output 3.
+
+Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
+(roll), 1 (pitch) and 3 (thrust).
+
+Aileron mixer
+-------------
+Two scalers total (output, roll).
+
+This mixer assumes that the aileron servos are set up correctly mechanically;
+depending on the actual configuration it may be necessary to reverse the scaling
+factors (to reverse the servo movement) and adjust the offset, scaling and
+endpoints to suit.
+
+As there is only one output, if using two servos adjustments to compensate for
+differences between the servos must be made mechanically. To obtain the correct
+motion using a Y cable, the servos can be positioned reversed from one another.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 0 -10000 -10000 0 -10000 10000
+
+Elevator mixer
+------------
+Two scalers total (output, roll).
+
+This mixer assumes that the elevator servo is set up correctly mechanically;
+depending on the actual configuration it may be necessary to reverse the scaling
+factors (to reverse the servo movement) and adjust the offset, scaling and
+endpoints to suit.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 1 10000 10000 0 -10000 10000
+
+Rudder mixer
+------------
+Two scalers total (output, yaw).
+
+This mixer assumes that the rudder servo is set up correctly mechanically;
+depending on the actual configuration it may be necessary to reverse the scaling
+factors (to reverse the servo movement) and adjust the offset, scaling and
+endpoints to suit.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 2 10000 10000 0 -10000 10000
+
+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
diff --git a/ROMFS/px4fmu_test/init.d/rc.standalone b/ROMFS/px4fmu_test/init.d/rc.standalone
index 67e95215b..5c7470d12 100644
--- a/ROMFS/px4fmu_test/init.d/rc.standalone
+++ b/ROMFS/px4fmu_test/init.d/rc.standalone
@@ -3,11 +3,11 @@
# Flight startup script for PX4FMU standalone configuration.
#
-echo "[init] doing standalone PX4FMU startup..."
+echo "[i] doing standalone PX4FMU startup..."
#
# Start the ORB
#
uorb start
-echo "[init] startup done"
+echo "[i] startup done"
diff --git a/ROMFS/px4fmu_test/init.d/rcS b/ROMFS/px4fmu_test/init.d/rcS
index bc248ac04..ef032de5c 100644
--- a/ROMFS/px4fmu_test/init.d/rcS
+++ b/ROMFS/px4fmu_test/init.d/rcS
@@ -6,7 +6,7 @@ uorb start
if sercon
then
- echo "[init] USB interface connected"
+ echo "[i] USB interface connected"
# Try to get an USB console
nshterm /dev/ttyACM0 &
@@ -15,14 +15,14 @@ fi
#
# Try to mount the microSD card.
#
-echo "[init] looking for microSD..."
+echo "[i] looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
- echo "[init] card mounted at /fs/microsd"
+ echo "[i] card mounted at /fs/microsd"
# Start playing the startup tune
tone_alarm start
else
- echo "[init] no microSD card found"
+ echo "[i] no microSD card found"
# Play SOS
tone_alarm error
fi
@@ -104,4 +104,4 @@ then
else
echo
echo "Some Unit Tests FAILED:${unit_test_failure_list}"
-fi \ No newline at end of file
+fi