aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/px4fmu_common/init.d/10015_tbs_discovery85
-rw-r--r--ROMFS/px4fmu_common/init.d/10016_3dr_iris98
-rw-r--r--ROMFS/px4fmu_common/init.d/1001_rc_quad.hil134
-rw-r--r--ROMFS/px4fmu_common/init.d/2100_mpx_easystar58
-rw-r--r--ROMFS/px4fmu_common/init.d/4010_dji_f33073
-rw-r--r--ROMFS/px4fmu_common/init.d/4011_dji_f45088
-rw-r--r--ROMFS/px4fmu_common/init.d/4012_hk_x55029
-rw-r--r--ROMFS/px4fmu_common/init.d/40_io_segway51
-rw-r--r--ROMFS/px4fmu_common/init.d/666_fmu_q_x55076
-rw-r--r--ROMFS/px4fmu_common/init.d/800_sdlogger51
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.autostart141
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl113
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.custom_io_esc120
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fixedwing34
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_apps19
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_interface18
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.hexa94
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.io32
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.logging4
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_apps24
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_interface75
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.multirotor39
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.octo94
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.sensors4
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.standalone13
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.usb33
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS480
-rw-r--r--makefiles/config_px4fmu-v1_backside.mk1
-rw-r--r--makefiles/config_px4fmu-v1_default.mk1
-rw-r--r--makefiles/config_px4fmu-v2_default.mk1
-rw-r--r--makefiles/config_px4fmu-v2_test.mk1
-rw-r--r--src/lib/version/version.h (renamed from src/modules/sdlog2/sdlog2_version.h)8
-rw-r--r--src/modules/sdlog2/sdlog2.c2
-rw-r--r--src/systemcmds/hw_ver/hw_ver.c73
-rw-r--r--src/systemcmds/hw_ver/module.mk43
35 files changed, 755 insertions, 1455 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
index 81d4b5d57..610d482c1 100644
--- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
@@ -1,74 +1,31 @@
#!nsh
+# Maintainers: Anton Babushkin <anton.babushkin@me.com>
+
echo "[init] Team Blacksheep Discovery Quad"
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
+if [ $DO_AUTOCONFIG == yes ]
then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
-
- param set MC_ATTRATE_D 0.006
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.17
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
+ #
+ # Default parameters for this platform
+ #
param set MC_ATT_P 5.0
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.15
+ param set MC_ATT_I 0.0
+ param set MC_ATT_D 0.0
+ param set MC_ATTRATE_P 0.17
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_D 0.006
param set MC_YAWPOS_P 0.5
- param set MC_YAWRATE_D 0.0
- param set MC_YAWRATE_I 0.0
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.2
-
- param save
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 2 = quadrotor
-#
-param set MAV_TYPE 2
-
-#
-# Start and configure PX4IO or FMU interface
-#
-if px4io detect
-then
- # Start MAVLink (depends on orb)
- mavlink start
- usleep 5000
-
- sh /etc/init.d/rc.io
-else
- # Start MAVLink (on UART1 / ttyS0)
- mavlink start -d /dev/ttyS0
- usleep 5000
- fmu mode_pwm
- param set BAT_V_SCALING 0.004593
- set EXIT_ON_END yes
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_D 0.0
fi
-#
-# Load the mixer for a quad with wide arms
-#
-mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
-
-#
-# Set PWM output frequency
-#
-pwm rate -c 1234 -r 400
-
-#
-# Set disarmed, min and max PWM signals
-#
-pwm disarmed -c 1234 -p 900
-pwm min -c 1234 -p 1100
-pwm max -c 1234 -p 1900
-
-#
-# Start common for all multirotors apps
-#
-sh /etc/init.d/rc.multirotor
+set FRAME_TYPE mc
+set FRAME_GEOMETRY quad_w
+set PWM_RATE 400
+set PWM_DISARMED 900
+set PWM_MIN 1100
+set PWM_MAX 1900
diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
index b0f4eda79..de5028052 100644
--- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
@@ -1,73 +1,43 @@
#!nsh
+# Maintainers: Anton Babushkin <anton.babushkin@me.com>
+
echo "[init] 3DR Iris Quad"
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
+# Use generic wide arm quad X PWM as base
+sh /etc/init.d/10001_quad_w
- param set MC_ATTRATE_D 0.004
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.13
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
+if [ $DO_AUTOCONFIG == yes ]
+then
+ #
+ # Default parameters for this platform
+ #
param set MC_ATT_P 9.0
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.15
+ param set MC_ATT_I 0.0
+ param set MC_ATT_D 0.0
+ param set MC_ATTRATE_P 0.13
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_D 0.004
param set MC_YAWPOS_P 0.5
- param set MC_YAWRATE_D 0.0
- param set MC_YAWRATE_I 0.0
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.2
-
- param save
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 2 = quadrotor
-#
-param set MAV_TYPE 2
-
-#
-# Start and configure PX4IO or FMU interface
-#
-if px4io detect
-then
- # Start MAVLink (depends on orb)
- mavlink start
- usleep 5000
-
- sh /etc/init.d/rc.io
-else
- # Start MAVLink (on UART1 / ttyS0)
- mavlink start -d /dev/ttyS0
- usleep 5000
- fmu mode_pwm
- param set BAT_V_SCALING 0.0098
- set EXIT_ON_END yes
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_D 0.0
+
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.8
+ param set MPC_THR_MIN 0.2
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 3
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.1
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
fi
-
-#
-# Load the mixer for a quad with wide arms
-#
-mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
-
-#
-# Set PWM output frequency
-#
-pwm rate -c 1234 -r 400
-
-#
-# Set disarmed, min and max PWM signals
-#
-pwm disarmed -c 1234 -p 900
-pwm min -c 1234 -p 1050
-
-#
-# Start common for all multirotors apps
-#
-sh /etc/init.d/rc.multirotor
diff --git a/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil b/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil
index 9b664d63e..7d21176f2 100644
--- a/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil
+++ b/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil
@@ -1,105 +1,43 @@
#!nsh
-#
-# USB HIL start
-#
-echo "[HIL] HILS quadrotor starting.."
+echo "[init] PX4FMU v1, v2 with or without IO on HIL Quad"
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
+if [ $DO_AUTOCONFIG == yes ]
then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
-
- param set MC_ATTRATE_D 0.0
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.05
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
- param set MC_ATT_P 3.0
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.0
- param set MC_YAWPOS_P 2.1
- param set MC_YAWRATE_D 0.0
- param set MC_YAWRATE_I 0.0
- param set MC_YAWRATE_P 0.05
- param set NAV_TAKEOFF_ALT 3.0
- param set MPC_TILT_MAX 0.5
- param set MPC_THR_MAX 0.5
- param set MPC_THR_MIN 0.1
- param set MPC_XY_D 0
- param set MPC_XY_P 0.5
- param set MPC_XY_VEL_D 0
- param set MPC_XY_VEL_I 0
- param set MPC_XY_VEL_MAX 3
- param set MPC_XY_VEL_P 0.2
- param set MPC_Z_D 0
- param set MPC_Z_P 1
- param set MPC_Z_VEL_D 0
- param set MPC_Z_VEL_I 0.1
- param set MPC_Z_VEL_MAX 2
- param set MPC_Z_VEL_P 0.20
-
- param save
+ #
+ # Default parameters for this platform
+ #
+ param set MC_ATTRATE_P 0.12
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_D 0.004
+ param set MC_ATT_P 7.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_D 0.0
+ param set MC_YAWPOS_P 2.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWRATE_P 0.3
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_D 0.005
+
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.8
+ param set MPC_THR_MIN 0.2
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 3
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.1
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
fi
-# Allow USB some time to come up
-sleep 1
-# Tell MAVLink that this link is "fast"
-mavlink start -b 230400 -d /dev/ttyACM0
-
-# Create a fake HIL /dev/pwm_output interface
-hil mode_pwm
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
-#
-param set MAV_TYPE 2
-
-#
-# Check if we got an IO
-#
-if px4io start
-then
- echo "IO started"
-else
- fmu mode_serial
- echo "FMU started"
-fi
-
-#
-# Start the sensors (depends on orb, px4io)
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start the attitude estimator (depends on orb)
-#
-att_pos_estimator_ekf start
-
-#
-# Load mixer and start controllers (depends on px4io)
-#
-mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-
-#
-# Start position estimator
-#
-position_estimator_inav start
-
-#
-# Start attitude control
-#
-multirotor_att_control start
-
-#
-# Start position control
-#
-multirotor_pos_control start
-
-echo "[HIL] setup done, running"
+set HIL yes
+set VEHICLE_TYPE mc
+set FRAME_GEOMETRY quad_x
diff --git a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
index 97c2d7c90..9bf01c60c 100644
--- a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
+++ b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
@@ -1,13 +1,12 @@
#!nsh
-echo "[init] PX4FMU v1, v2 with or without IO on EasyStar"
+echo "[init] EasyStar"
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
+if [ $DO_AUTOCONFIG == yes ]
then
- # Set all params here, then disable autoconfig
+ #
+ # Default parameters for this platform
+ #
param set FW_P_D 0
param set FW_P_I 0
param set FW_P_IMAX 15
@@ -31,50 +30,7 @@ then
param set FW_L1_PERIOD 16
param set RC_SCALE_ROLL 1.0
param set RC_SCALE_PITCH 1.0
-
- param set SYS_AUTOCONFIG 0
- param save
fi
-#
-# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing
-#
-param set MAV_TYPE 1
-
-#
-# Start and configure PX4IO or FMU interface
-#
-if px4io detect
-then
- # Start MAVLink (depends on orb)
- mavlink start
-
- sh /etc/init.d/rc.io
- # Limit to 100 Hz updates and (implicit) 50 Hz PWM
- px4io limit 100
-else
- # Start MAVLink (on UART1 / ttyS0)
- mavlink start -d /dev/ttyS0
-
- fmu mode_pwm
- param set BAT_V_SCALING 0.004593
- set EXIT_ON_END yes
-fi
-
-#
-# Load mixer and start controllers (depends on px4io)
-#
-if [ -f /fs/microsd/etc/mixers/FMU_RET.mix ]
-then
- echo "Using /fs/microsd/etc/mixers/FMU_RET.mix"
- mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_RET.mix
-else
- echo "Using /etc/mixers/FMU_RET.mix"
- mixer load /dev/pwm_output /etc/mixers/FMU_RET.mix
-fi
-
-#
-# Start common fixedwing apps
-#
-sh /etc/init.d/rc.fixedwing
+set FRAME_TYPE fw
+set FRAME_GEOMETRY RET
diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330
index 7054210e2..0cfe68b27 100644
--- a/ROMFS/px4fmu_common/init.d/4010_dji_f330
+++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330
@@ -1,31 +1,30 @@
#!nsh
-echo "[init] PX4FMU v1, v2 with or without IO on DJI F330"
+# Maintainers: Anton Babushkin <anton.babushkin@me.com>
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
+echo "[init] DJI F330"
- param set MC_ATTRATE_D 0.004
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.12
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
+if [ $DO_AUTOCONFIG == yes ]
+then
+ #
+ # Default parameters for this platform
+ #
param set MC_ATT_P 7.0
- param set MC_YAWPOS_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_D 0.0
+ param set MC_ATTRATE_P 0.12
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_D 0.004
+ param set MC_YAWPOS_P 2.8
param set MC_YAWPOS_I 0.0
- param set MC_YAWPOS_P 2.0
- param set MC_YAWRATE_D 0.005
- param set MC_YAWRATE_I 0.2
- param set MC_YAWRATE_P 0.3
- param set NAV_TAKEOFF_ALT 3.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWRATE_P 0.2
+ param set MC_YAWRATE_I 0.05
+ param set MC_YAWRATE_D 0.0
+
param set MPC_TILT_MAX 0.5
- param set MPC_THR_MAX 0.7
- param set MPC_THR_MIN 0.3
+ param set MPC_THR_MAX 0.8
+ param set MPC_THR_MIN 0.2
param set MPC_XY_D 0
param set MPC_XY_P 0.5
param set MPC_XY_VEL_D 0
@@ -38,32 +37,14 @@ then
param set MPC_Z_VEL_I 0.1
param set MPC_Z_VEL_MAX 2
param set MPC_Z_VEL_P 0.20
-
- param save
fi
-#
-# Start and configure PX4IO or FMU interface
-#
-if px4io detect
-then
- # Start MAVLink (depends on orb)
- mavlink start
- usleep 5000
-
- sh /etc/init.d/rc.io
-else
- # Start MAVLink (on UART1 / ttyS0)
- mavlink start -d /dev/ttyS0
- usleep 5000
- fmu mode_pwm
- param set BAT_V_SCALING 0.004593
- set EXIT_ON_END yes
-fi
+set VEHICLE_TYPE mc
+set FRAME_GEOMETRY quad_x
-sh /etc/init.d/rc.mc_interface
+set PWM_RATE 400
-#
-# Start common for all multirotors apps
-#
-sh /etc/init.d/rc.multirotor
+# DJI ESC range
+set PWM_DISARMED 900
+set PWM_MIN 1200
+set PWM_MAX 1900
diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450
index a1d253191..4a0953a2e 100644
--- a/ROMFS/px4fmu_common/init.d/4011_dji_f450
+++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450
@@ -1,74 +1,36 @@
#!nsh
-echo "[init] PX4FMU v1, v2 with or without IO on DJI F450"
+# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
+echo "[init] DJI F450"
- param set MC_ATTRATE_D 0.004
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.12
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
+if [ $DO_AUTOCONFIG == yes ]
+then
+ #
+ # Default parameters for this platform
+ #
param set MC_ATT_P 7.0
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_D 0.0
+ param set MC_ATTRATE_P 0.12
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_D 0.004
param set MC_YAWPOS_P 2.0
- param set MC_YAWRATE_D 0.005
- param set MC_YAWRATE_I 0.2
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.3
-
- param save
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 2 = quadrotor
-#
-param set MAV_TYPE 2
-
-#
-# Start and configure PX4IO or FMU interface
-#
-if px4io detect
-then
- # Start MAVLink (depends on orb)
- mavlink start
- usleep 5000
-
- sh /etc/init.d/rc.io
-else
- # Start MAVLink (on UART1 / ttyS0)
- mavlink start -d /dev/ttyS0
- usleep 5000
- fmu mode_pwm
- param set BAT_V_SCALING 0.004593
- set EXIT_ON_END yes
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_D 0.005
+
+ # TODO add default MPC parameters
fi
-#
-# Load mixer
-#
-mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-
-#
-# Set PWM output frequency
-#
-pwm rate -c 1234 -r 400
+set VEHICLE_TYPE mc
+set FRAME_GEOMETRY quad_x
-#
-# Set disarmed, min and max PWM signals (for DJI ESCs)
-#
-pwm disarmed -c 1234 -p 900
-pwm min -c 1234 -p 1200
-pwm max -c 1234 -p 1800
+set PWM_RATE 400
-#
-# Start common multirotor apps
-#
-sh /etc/init.d/rc.multirotor
+# DJI ESC range
+set PWM_DISARMED 900
+set PWM_MIN 1200
+set PWM_MAX 1900
diff --git a/ROMFS/px4fmu_common/init.d/4012_hk_x550 b/ROMFS/px4fmu_common/init.d/4012_hk_x550
new file mode 100644
index 000000000..396349d9c
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/4012_hk_x550
@@ -0,0 +1,29 @@
+#!nsh
+
+# Maintainers: Todd Stellanova <tstellanova@gmail.com>
+
+echo "[init] PX4FMU v1, v2 with or without IO on HobbyKing X550"
+
+if [ $DO_AUTOCONFIG == yes ]
+then
+ #
+ # Default parameters for this platform
+ #
+ param set MC_ATT_P 5.5
+ param set MC_ATT_I 0
+ param set MC_ATT_D 0
+ param set MC_ATTRATE_P 0.14
+ param set MC_ATTRATE_I 0
+ param set MC_ATTRATE_D 0.006
+ param set MC_YAWPOS_P 0.6
+ param set MC_YAWPOS_I 0
+ param set MC_YAWPOS_D 0
+ param set MC_YAWRATE_P 0.08
+ param set MC_YAWRATE_I 0
+ param set MC_YAWRATE_D 0
+fi
+
+set VEHICLE_TYPE mc
+set FRAME_GEOMETRY quad_x
+
+set PWM_RATE 400
diff --git a/ROMFS/px4fmu_common/init.d/40_io_segway b/ROMFS/px4fmu_common/init.d/40_io_segway
deleted file mode 100644
index ad455b440..000000000
--- a/ROMFS/px4fmu_common/init.d/40_io_segway
+++ /dev/null
@@ -1,51 +0,0 @@
-#!nsh
-
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- # TODO
-
- param set SYS_AUTOCONFIG 0
- param save
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 10 = ground rover
-#
-param set MAV_TYPE 10
-
-#
-# Start MAVLink (depends on orb)
-#
-mavlink start -d /dev/ttyS1 -b 57600
-usleep 5000
-
-#
-# Start and configure PX4IO interface
-#
-sh /etc/init.d/rc.io
-
-#
-# 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
-
-#
-# Load mixer and start controllers (depends on px4io)
-#
-roboclaw start /dev/ttyS2 128 1200
-segway start
diff --git a/ROMFS/px4fmu_common/init.d/666_fmu_q_x550 b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
deleted file mode 100644
index acd8027fb..000000000
--- a/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
+++ /dev/null
@@ -1,76 +0,0 @@
-#!nsh
-
-echo "[init] 666_fmu_q_x550: PX4FMU Quad X550 with or without IO"
-
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set MC_ATTRATE_P 0.14
- param set MC_ATTRATE_I 0
- param set MC_ATTRATE_D 0.006
- param set MC_ATT_P 5.5
- param set MC_ATT_I 0
- param set MC_ATT_D 0
- param set MC_YAWPOS_D 0
- param set MC_YAWPOS_I 0
- param set MC_YAWPOS_P 0.6
- param set MC_YAWRATE_D 0
- param set MC_YAWRATE_I 0
- param set MC_YAWRATE_P 0.08
- param set RC_SCALE_PITCH 1
- param set RC_SCALE_ROLL 1
- param set RC_SCALE_YAW 3
-
- param set SYS_AUTOCONFIG 0
- param save
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 2 = quadrotor
-#
-param set MAV_TYPE 2
-
-#
-# Start and configure PX4IO or FMU interface
-#
-if px4io detect
-then
- # Start MAVLink (depends on orb)
- mavlink start
- usleep 5000
-
- sh /etc/init.d/rc.io
-else
- # Start MAVLink (on UART1 / ttyS0)
- mavlink start -d /dev/ttyS0
- usleep 5000
- fmu mode_pwm
- param set BAT_V_SCALING 0.004593
- set EXIT_ON_END yes
-fi
-
-#
-# Load mixer
-#
-mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-
-#
-# Set PWM output frequency
-#
-pwm rate -c 1234 -r 400
-
-#
-# Set disarmed, min and max PWM signals
-#
-pwm disarmed -c 1234 -p 900
-pwm min -c 1234 -p 1100
-pwm max -c 1234 -p 1900
-
-#
-# Start common for all multirotors apps
-#
-sh /etc/init.d/rc.multirotor
diff --git a/ROMFS/px4fmu_common/init.d/800_sdlogger b/ROMFS/px4fmu_common/init.d/800_sdlogger
deleted file mode 100644
index 9b90cbdd0..000000000
--- a/ROMFS/px4fmu_common/init.d/800_sdlogger
+++ /dev/null
@@ -1,51 +0,0 @@
-#!nsh
-
-echo "[init] PX4FMU v1, v2 init to log only
-
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
-
- param save
-fi
-
-#
-# Start and configure PX4IO or FMU interface
-#
-if px4io detect
-then
- # Start MAVLink (depends on orb)
- mavlink start
- usleep 5000
-
- sh /etc/init.d/rc.io
- # Set PWM values for DJI ESCs
-else
- # Start MAVLink (on UART1 / ttyS0)
- mavlink start -d /dev/ttyS0
- usleep 5000
- param set BAT_V_SCALING 0.004593
- set EXIT_ON_END yes
-fi
-
-sh /etc/init.d/rc.sensors
-
-gps start
-
-attitude_estimator_ekf start
-
-position_estimator_inav start
-
-if [ -d /fs/microsd ]
-then
- if [ $BOARD == fmuv1 ]
- then
- sdlog2 start -r 50 -e -b 16
- else
- sdlog2 start -r 200 -e -b 16
- fi
-fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart
new file mode 100644
index 000000000..9da0135b3
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -0,0 +1,141 @@
+#
+# Check if auto-setup from one of the standard scripts is wanted
+# SYS_AUTOSTART = 0 means no autostart (default)
+#
+# AUTOSTART PARTITION:
+# 0 .. 999 Reserved (historical)
+# 1000 .. 1999 Simulation setups
+# 2000 .. 2999 Standard planes
+# 3000 .. 3999 Flying wing
+# 4000 .. 4999 Quad X
+# 5000 .. 5999 Quad +
+# 6000 .. 6999 Hexa X
+# 7000 .. 7999 Hexa +
+# 8000 .. 8999 Octo X
+# 9000 .. 9999 Octo +
+# 10000 .. 10999 Wide arm / H frame
+# 11000 .. 11999 Hexa Cox
+# 12000 .. 12999 Octo Cox
+
+#
+# Simulation setups
+#
+
+if param compare SYS_AUTOSTART 1000
+then
+ #sh /etc/init.d/1000_rc_fw_easystar.hil
+fi
+
+if param compare SYS_AUTOSTART 1001
+then
+ sh /etc/init.d/1001_rc_quad.hil
+fi
+
+if param compare SYS_AUTOSTART 1002
+then
+ #sh /etc/init.d/1002_rc_fw_state.hil
+fi
+
+if param compare SYS_AUTOSTART 1003
+then
+ #sh /etc/init.d/1003_rc_quad_+.hil
+fi
+
+if param compare SYS_AUTOSTART 1004
+then
+ #sh /etc/init.d/1004_rc_fw_Rascal110.hil
+fi
+
+#
+# Standard plane
+#
+
+if param compare SYS_AUTOSTART 2100 100
+then
+ #sh /etc/init.d/2100_mpx_easystar
+ #set MODE custom
+fi
+
+if param compare SYS_AUTOSTART 2101 101
+then
+ #sh /etc/init.d/2101_hk_bixler
+ #set MODE custom
+fi
+
+if param compare SYS_AUTOSTART 2102 102
+then
+ #sh /etc/init.d/2102_3dr_skywalker
+ #set MODE custom
+fi
+
+#
+# Flying wing
+#
+
+if param compare SYS_AUTOSTART 3030
+then
+ #sh /etc/init.d/3030_io_camflyer
+fi
+
+if param compare SYS_AUTOSTART 3031 31
+then
+ #sh /etc/init.d/3031_io_phantom
+fi
+
+if param compare SYS_AUTOSTART 3032 32
+then
+ #sh /etc/init.d/3032_skywalker_x5
+fi
+
+if param compare SYS_AUTOSTART 3033 33
+then
+ #sh /etc/init.d/3033_io_wingwing
+fi
+
+if param compare SYS_AUTOSTART 3034 34
+then
+ #sh /etc/init.d/3034_io_fx79
+fi
+
+#
+# Quad X
+#
+
+if param compare SYS_AUTOSTART 4008
+then
+ #sh /etc/init.d/4008_ardrone
+fi
+
+if param compare SYS_AUTOSTART 4009
+then
+ #sh /etc/init.d/4009_ardrone_flow
+fi
+
+if param compare SYS_AUTOSTART 4010
+then
+ sh /etc/init.d/4010_dji_f330
+fi
+
+if param compare SYS_AUTOSTART 4011
+then
+ sh /etc/init.d/4011_dji_f450
+fi
+
+if param compare SYS_AUTOSTART 4012
+then
+ sh /etc/init.d/4012_hk_x550
+fi
+
+#
+# Wide arm / H frame
+#
+
+if param compare SYS_AUTOSTART 10015
+then
+ sh /etc/init.d/10015_tbs_discovery
+fi
+
+if param compare SYS_AUTOSTART 10016
+then
+ sh /etc/init.d/10016_3dr_iris
+fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl b/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
deleted file mode 100644
index 40b2ee68b..000000000
--- a/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
+++ /dev/null
@@ -1,113 +0,0 @@
-#!nsh
-
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
-
- param set MC_ATTRATE_D 0.002
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.09
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
- param set MC_ATT_P 6.8
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.0
- param set MC_YAWPOS_P 2.0
- param set MC_YAWRATE_D 0.005
- param set MC_YAWRATE_I 0.2
- param set MC_YAWRATE_P 0.3
- param set NAV_TAKEOFF_ALT 3.0
- param set MPC_TILT_MAX 0.5
- param set MPC_THR_MAX 0.7
- param set MPC_THR_MIN 0.3
- param set MPC_XY_D 0
- param set MPC_XY_P 0.5
- param set MPC_XY_VEL_D 0
- param set MPC_XY_VEL_I 0
- param set MPC_XY_VEL_MAX 3
- param set MPC_XY_VEL_P 0.2
- param set MPC_Z_D 0
- param set MPC_Z_P 1
- param set MPC_Z_VEL_D 0
- param set MPC_Z_VEL_I 0.1
- param set MPC_Z_VEL_MAX 2
- param set MPC_Z_VEL_P 0.20
-
- param save
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 2 = quadrotor
-#
-param set MAV_TYPE 2
-
-set EXIT_ON_END no
-
-#
-# Start the Mikrokopter ESC driver
-#
-if [ $MKBLCTRL_MODE == yes ]
-then
- if [ $MKBLCTRL_FRAME == x ]
- then
- echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame Mikrokopter-Addressing"
- mkblctrl -mkmode x
- else
- echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame Mikrokopter-Addressing"
- mkblctrl -mkmode +
- fi
-else
- if [ $MKBLCTRL_FRAME == x ]
- then
- echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame"
- else
- echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame"
- fi
- mkblctrl
-fi
-
-usleep 10000
-
-#
-# Start and configure PX4IO or FMU interface
-#
-if px4io detect
-then
- # Start MAVLink (depends on orb)
- mavlink start
- usleep 5000
-
- sh /etc/init.d/rc.io
-else
- # Start MAVLink (on UART1 / ttyS0)
- mavlink start -d /dev/ttyS0
- usleep 5000
- fmu mode_pwm
- param set BAT_V_SCALING 0.004593
- set EXIT_ON_END yes
-fi
-
-#
-# Load mixer
-#
-if [ $MKBLCTRL_FRAME == x ]
-then
- mixer load /dev/mkblctrl /etc/mixers/FMU_quad_x.mix
-else
- mixer load /dev/mkblctrl /etc/mixers/FMU_quad_+.mix
-fi
-
-#
-# Start common for all multirotors apps
-#
-sh /etc/init.d/rc.multirotor
-
-if [ $EXIT_ON_END == yes ]
-then
- exit
-fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.custom_io_esc b/ROMFS/px4fmu_common/init.d/rc.custom_io_esc
deleted file mode 100644
index 045e41e52..000000000
--- a/ROMFS/px4fmu_common/init.d/rc.custom_io_esc
+++ /dev/null
@@ -1,120 +0,0 @@
-#!nsh
-
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
-
- param set MC_ATTRATE_D 0.002
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.09
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
- param set MC_ATT_P 6.8
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.0
- param set MC_YAWPOS_P 2.0
- param set MC_YAWRATE_D 0.005
- param set MC_YAWRATE_I 0.2
- param set MC_YAWRATE_P 0.3
- param set NAV_TAKEOFF_ALT 3.0
- param set MPC_TILT_MAX 0.5
- param set MPC_THR_MAX 0.7
- param set MPC_THR_MIN 0.3
- param set MPC_XY_D 0
- param set MPC_XY_P 0.5
- param set MPC_XY_VEL_D 0
- param set MPC_XY_VEL_I 0
- param set MPC_XY_VEL_MAX 3
- param set MPC_XY_VEL_P 0.2
- param set MPC_Z_D 0
- param set MPC_Z_P 1
- param set MPC_Z_VEL_D 0
- param set MPC_Z_VEL_I 0.1
- param set MPC_Z_VEL_MAX 2
- param set MPC_Z_VEL_P 0.20
-
- param save
-fi
-
-echo "RC script for PX4FMU + PX4IO + PPM-ESCs running"
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 2 = quadrotor
-#
-param set MAV_TYPE 2
-
-set EXIT_ON_END no
-
-usleep 10000
-
-#
-# Start and configure PX4IO or FMU interface
-#
-if px4io detect
-then
- # Start MAVLink (depends on orb)
- mavlink start -d /dev/ttyS1 -b 57600
- usleep 5000
-
- sh /etc/init.d/rc.io
-else
- fmu mode_pwm
- # Start MAVLink (on UART1 / ttyS0)
- mavlink start -d /dev/ttyS1 -b 57600
- usleep 5000
- param set BAT_V_SCALING 0.004593
- set EXIT_ON_END yes
-fi
-
-if [ $ESC_MAKER = afro ]
-then
- # Set PWM values for Afro ESCs
- pwm disarmed -c 1234 -p 1050
- pwm min -c 1234 -p 1080
- pwm max -c 1234 -p 1860
-else
- # Set PWM values for typical ESCs
- pwm disarmed -c 1234 -p 900
- pwm min -c 1234 -p 980
- pwm max -c 1234 -p 1800
-fi
-
-#
-# Load mixer
-#
-if [ $FRAME_GEOMETRY == x ]
-then
- echo "Frame geometry X"
- mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-else
- if [ $FRAME_GEOMETRY == w ]
- then
- echo "Frame geometry W"
- mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
- else
- echo "Frame geometry +"
- mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
- fi
-fi
-
-#
-# Set PWM output frequency
-#
-pwm rate -r 400 -c 1234
-
-#
-# Start common for all multirotors apps
-#
-sh /etc/init.d/rc.multirotor
-
-if [ $EXIT_ON_END == yes ]
-then
- exit
-fi
-
-echo "Script end"
diff --git a/ROMFS/px4fmu_common/init.d/rc.fixedwing b/ROMFS/px4fmu_common/init.d/rc.fixedwing
deleted file mode 100644
index f02851006..000000000
--- a/ROMFS/px4fmu_common/init.d/rc.fixedwing
+++ /dev/null
@@ -1,34 +0,0 @@
-#!nsh
-#
-# Standard everything needed for fixedwing except mixer, actuator output and mavlink
-#
-
-#
-# Start the sensors and test them.
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start logging (depends on sensors)
-#
-sh /etc/init.d/rc.logging
-
-#
-# Start GPS interface (depends on orb)
-#
-gps start
-
-#
-# Start the attitude and position estimator
-#
-att_pos_estimator_ekf start
-
-#
-# Start attitude controller
-#
-fw_att_control start
-
-#
-# Start the position controller
-#
-fw_pos_control_l1 start
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps
new file mode 100644
index 000000000..d354fb06f
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps
@@ -0,0 +1,19 @@
+#!nsh
+#
+# Standard apps for fixed wing
+#
+
+#
+# Start the attitude and position estimator
+#
+att_pos_estimator_ekf start
+
+#
+# Start attitude controller
+#
+fw_att_control start
+
+#
+# Start the position controller
+#
+fw_pos_control_l1 start
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_interface b/ROMFS/px4fmu_common/init.d/rc.fw_interface
new file mode 100644
index 000000000..f9517f422
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_interface
@@ -0,0 +1,18 @@
+#!nsh
+#
+# Script to load fixedwing mixer and set rate/disarmed/min/max values for PWM output
+#
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing
+#
+param set MAV_TYPE 1
+
+#
+# Load mixer
+#
+echo "Frame geometry: ${FRAME_GEOMETRY}"
+set MIXER /etc/mixers/FMU_${FRAME_GEOMETRY}.mix
+echo "Loading mixer: ${MIXER}"
+mixer load /dev/pwm_output ${MIXER}
diff --git a/ROMFS/px4fmu_common/init.d/rc.hexa b/ROMFS/px4fmu_common/init.d/rc.hexa
deleted file mode 100644
index 097db28e4..000000000
--- a/ROMFS/px4fmu_common/init.d/rc.hexa
+++ /dev/null
@@ -1,94 +0,0 @@
-#!nsh
-
-echo "[init] PX4FMU v1, v2 with or without IO on Hex"
-
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
-
- param set MC_ATTRATE_D 0.004
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.12
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
- param set MC_ATT_P 7.0
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.0
- param set MC_YAWPOS_P 2.0
- param set MC_YAWRATE_D 0.005
- param set MC_YAWRATE_I 0.2
- param set MC_YAWRATE_P 0.3
- param set NAV_TAKEOFF_ALT 3.0
- param set MPC_TILT_MAX 0.5
- param set MPC_THR_MAX 0.7
- param set MPC_THR_MIN 0.3
- param set MPC_XY_D 0
- param set MPC_XY_P 0.5
- param set MPC_XY_VEL_D 0
- param set MPC_XY_VEL_I 0
- param set MPC_XY_VEL_MAX 3
- param set MPC_XY_VEL_P 0.2
- param set MPC_Z_D 0
- param set MPC_Z_P 1
- param set MPC_Z_VEL_D 0
- param set MPC_Z_VEL_I 0.1
- param set MPC_Z_VEL_MAX 2
- param set MPC_Z_VEL_P 0.20
-
- param save
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE list: https://pixhawk.ethz.ch/mavlink/
-# 13 = hexarotor
-#
-param set MAV_TYPE 13
-
-set EXIT_ON_END no
-
-#
-# Start and configure PX4IO interface
-#
-if px4io detect
-then
- # Start MAVLink (depends on orb)
- mavlink start
- usleep 5000
-
- sh /etc/init.d/rc.io
-else
- # This is not possible on a hexa
- tone_alarm error
-fi
-
-#
-# Load mixer
-#
-mixer load /dev/pwm_output $MIXER
-
-#
-# Set PWM output frequency to 400 Hz
-#
-pwm rate -a -r 400
-
-#
-# Set disarmed, min and max PWM signals
-#
-pwm disarmed -c 123456 -p 900
-pwm min -c 123456 -p 1100
-pwm max -c 123456 -p 1900
-
-#
-# Start common for all multirotors apps
-#
-sh /etc/init.d/rc.multirotor
-
-if [ $EXIT_ON_END == yes ]
-then
- exit
-fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.io b/ROMFS/px4fmu_common/init.d/rc.io
index aaf91b316..5a010cc9b 100644
--- a/ROMFS/px4fmu_common/init.d/rc.io
+++ b/ROMFS/px4fmu_common/init.d/rc.io
@@ -1,23 +1,19 @@
#
-# Start PX4IO interface (depends on orb, commander)
+# Init PX4IO interface
#
-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
+#
+# Allow PX4IO to recover from midair restarts.
+# this is very unlikely, but quite safe and robust.
+#
+px4io recovery
+
+#
+# Adjust px4io topic limiting
+#
+if hw_ver compare PX4FMU_V1
+then
+ px4io limit 200
else
- # SOS
- tone_alarm error
+ px4io limit 400
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.logging b/ROMFS/px4fmu_common/init.d/rc.logging
index dc4be8055..1791acbee 100644
--- a/ROMFS/px4fmu_common/init.d/rc.logging
+++ b/ROMFS/px4fmu_common/init.d/rc.logging
@@ -5,10 +5,12 @@
if [ -d /fs/microsd ]
then
- if [ $BOARD == fmuv1 ]
+ if hw_ver compare PX4FMU_V1
then
+ echo "Start sdlog2 at 50Hz"
sdlog2 start -r 50 -a -b 16
else
+ echo "Start sdlog2 at 200Hz"
sdlog2 start -r 200 -a -b 16
fi
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_apps b/ROMFS/px4fmu_common/init.d/rc.mc_apps
new file mode 100644
index 000000000..8b51d57e5
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_apps
@@ -0,0 +1,24 @@
+#!nsh
+#
+# Standard apps for multirotors
+#
+
+#
+# Start the attitude estimator
+#
+attitude_estimator_ekf start
+
+#
+# Start position estimator
+#
+position_estimator_inav start
+
+#
+# Start attitude control
+#
+multirotor_att_control start
+
+#
+# Start position control
+#
+multirotor_pos_control start
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_interface b/ROMFS/px4fmu_common/init.d/rc.mc_interface
index 6bb2e84ec..003aee81b 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_interface
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_interface
@@ -1,49 +1,60 @@
#!nsh
#
-# Script to set PWM min / max limits and mixer
+# Script to load multicopter mixer and set rate/disarmed/min/max values for PWM output
#
-#
-# Load mixer
-#
-if [ $FRAME_GEOMETRY == x ]
+if [ $FRAME_GEOMETRY == quad_x -o $FRAME_GEOMETRY == quad_+ ]
then
- echo "Frame geometry X"
- mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-else
- if [ $FRAME_GEOMETRY == w ]
- then
- echo "Frame geometry W"
- mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
- else
- echo "Frame geometry +"
- mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
- fi
+ set OUTPUTS 1234
+ param set MAV_TYPE 2
fi
-
-if [ $FRAME_COUNT == 4 ]
+if [ $FRAME_GEOMETRY == quad_w -o $FRAME_GEOMETRY == quad_v ]
then
set OUTPUTS 1234
param set MAV_TYPE 2
-else
- if [ $FRAME_COUNT == 6 ]
- then
+fi
+if [ $FRAME_GEOMETRY == hex_x -o $FRAME_GEOMETRY == hex_+ ]
+then
set OUTPUTS 123456
param set MAV_TYPE 13
- else
+fi
+if [ $FRAME_GEOMETRY == octo_x -o $FRAME_GEOMETRY == octo_+ ]
+then
set OUTPUTS 12345678
- fi
+ param set MAV_TYPE 14
fi
-
#
-# Set PWM output frequency
+# Load mixer
#
-pwm rate -c $OUTPUTS -r $PWM_RATE
+echo "Frame geometry: $FRAME_GEOMETRY"
+set MIXER /etc/mixers/FMU_${FRAME_GEOMETRY}.mix
+echo "Loading mixer: $MIXER"
+mixer load /dev/pwm_output $MIXER
-#
-# Set disarmed, min and max PWM signals (for DJI ESCs)
-#
-pwm disarmed -c $OUTPUTS -p $PWM_DISARMED
-pwm min -c $OUTPUTS -p $PWM_MIN
-pwm max -c $OUTPUTS -p $PWM_MAX
+if [ $OUTPUT_MODE == fmu_pwm -o $OUTPUT_MODE == io_pwm ]
+then
+ #
+ # Set PWM output frequency
+ #
+ if [ $PWM_RATE != none ]
+ then
+ pwm rate -c $OUTPUTS -r $PWM_RATE
+ fi
+
+ #
+ # Set disarmed, min and max PWM values
+ #
+ if [ $PWM_DISARMED != none ]
+ then
+ pwm disarmed -c $OUTPUTS -p $PWM_DISARMED
+ fi
+ if [ $PWM_MIN != none ]
+ then
+ pwm min -c $OUTPUTS -p $PWM_MIN
+ fi
+ if [ $PWM_MAX != none ]
+ then
+ pwm max -c $OUTPUTS -p $PWM_MAX
+ fi
+fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.multirotor b/ROMFS/px4fmu_common/init.d/rc.multirotor
deleted file mode 100644
index bc550ac5a..000000000
--- a/ROMFS/px4fmu_common/init.d/rc.multirotor
+++ /dev/null
@@ -1,39 +0,0 @@
-#!nsh
-#
-# Standard everything needed for multirotors except mixer, actuator output and mavlink
-#
-
-#
-# Start the sensors and test them.
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start logging (depends on sensors)
-#
-sh /etc/init.d/rc.logging
-
-#
-# Start GPS interface (depends on orb)
-#
-gps start
-
-#
-# Start the attitude estimator
-#
-attitude_estimator_ekf start
-
-#
-# Start position estimator
-#
-position_estimator_inav start
-
-#
-# Start attitude control
-#
-multirotor_att_control start
-
-#
-# Start position control
-#
-multirotor_pos_control start
diff --git a/ROMFS/px4fmu_common/init.d/rc.octo b/ROMFS/px4fmu_common/init.d/rc.octo
deleted file mode 100644
index ecb12e96e..000000000
--- a/ROMFS/px4fmu_common/init.d/rc.octo
+++ /dev/null
@@ -1,94 +0,0 @@
-#!nsh
-
-echo "[init] Octorotor startup"
-
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
-
- param set MC_ATTRATE_D 0.004
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.12
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
- param set MC_ATT_P 7.0
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.0
- param set MC_YAWPOS_P 2.0
- param set MC_YAWRATE_D 0.005
- param set MC_YAWRATE_I 0.2
- param set MC_YAWRATE_P 0.3
- param set NAV_TAKEOFF_ALT 3.0
- param set MPC_TILT_MAX 0.5
- param set MPC_THR_MAX 0.7
- param set MPC_THR_MIN 0.3
- param set MPC_XY_D 0
- param set MPC_XY_P 0.5
- param set MPC_XY_VEL_D 0
- param set MPC_XY_VEL_I 0
- param set MPC_XY_VEL_MAX 3
- param set MPC_XY_VEL_P 0.2
- param set MPC_Z_D 0
- param set MPC_Z_P 1
- param set MPC_Z_VEL_D 0
- param set MPC_Z_VEL_I 0.1
- param set MPC_Z_VEL_MAX 2
- param set MPC_Z_VEL_P 0.20
-
- param save
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE list: https://pixhawk.ethz.ch/mavlink/
-# 14 = octorotor
-#
-param set MAV_TYPE 14
-
-set EXIT_ON_END no
-
-#
-# Start and configure PX4IO interface
-#
-if px4io detect
-then
- # Start MAVLink (depends on orb)
- mavlink start
- usleep 5000
-
- sh /etc/init.d/rc.io
-else
- # This is not possible on an octo
- tone_alarm error
-fi
-
-#
-# Load mixer
-#
-mixer load /dev/pwm_output $MIXER
-
-#
-# Set PWM output frequency to 400 Hz
-#
-pwm rate -a -r 400
-
-#
-# Set disarmed, min and max PWM signals
-#
-pwm disarmed -c 12345678 -p 900
-pwm min -c 12345678 -p 1100
-pwm max -c 12345678 -p 1900
-
-#
-# Start common for all multirotors apps
-#
-sh /etc/init.d/rc.multirotor
-
-if [ $EXIT_ON_END == yes ]
-then
- exit
-fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors
index 070a4e7e3..a2517135f 100644
--- a/ROMFS/px4fmu_common/init.d/rc.sensors
+++ b/ROMFS/px4fmu_common/init.d/rc.sensors
@@ -28,9 +28,7 @@ fi
if lsm303d start
then
- set BOARD fmuv2
-else
- set BOARD fmuv1
+ echo "using LSM303D"
fi
# Start airspeed sensors
diff --git a/ROMFS/px4fmu_common/init.d/rc.standalone b/ROMFS/px4fmu_common/init.d/rc.standalone
deleted file mode 100644
index 67e95215b..000000000
--- a/ROMFS/px4fmu_common/init.d/rc.standalone
+++ /dev/null
@@ -1,13 +0,0 @@
-#!nsh
-#
-# Flight startup script for PX4FMU standalone configuration.
-#
-
-echo "[init] doing standalone PX4FMU startup..."
-
-#
-# Start the ORB
-#
-uorb start
-
-echo "[init] startup done"
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index ccf2cd47e..0cd8a0e04 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -36,39 +36,6 @@ then
echo "Commander started"
fi
-# Start px4io if present
-if px4io start
-then
- 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
-if attitude_estimator_ekf status
-then
- echo "multicopter att filter running"
-else
- if att_pos_estimator_ekf status
- then
- echo "fixedwing att filter running"
- else
- attitude_estimator_ekf start
- fi
-fi
-
-# Start GPS
-if gps start
-then
- echo "GPS started"
-fi
-
echo "MAVLink started, exiting shell.."
# Exit shell to make it available to MAVLink
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 66cb3f237..09d66cf41 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -52,7 +52,7 @@ then
echo "[init] USB interface connected"
fi
- echo "Running rc.APM"
+ echo "[init] Running rc.APM"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
fi
@@ -60,12 +60,9 @@ fi
if [ $MODE == autostart ]
then
#
- # Start terminal
+ # Start CDC/ACM serial driver
#
- if sercon
- then
- echo "USB connected"
- fi
+ sercon
#
# Start the ORB (first app to start)
@@ -88,9 +85,9 @@ then
then
if param load /fs/microsd/params
then
- echo "Parameters loaded"
+ echo "[init] Parameters loaded"
else
- echo "Parameter file corrupt - ignoring"
+ echo "[init] Parameter file corrupt - ignoring"
fi
fi
#fi
@@ -100,59 +97,21 @@ then
#
if rgbled start
then
- echo "Using external RGB Led"
+ echo "[init] Using external RGB Led"
else
if blinkm start
then
blinkm systemstate
fi
fi
-
- #
- # Start the Commander (needs to be this early for in-air-restarts)
- #
- commander start
- if param compare SYS_AUTOSTART 1000
- then
- sh /etc/init.d/1000_rc_fw_easystar.hil
- set MODE custom
- fi
+ # Use FMU PWM output by default
+ set OUTPUT_MODE fmu_pwm
+ set IO_PRESENT no
- if param compare SYS_AUTOSTART 1001
- then
- sh /etc/init.d/1001_rc_quad.hil
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 1002
- then
- sh /etc/init.d/1002_rc_fw_state.hil
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 1003
- then
- sh /etc/init.d/1003_rc_quad_+.hil
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 1004
- then
- sh /etc/init.d/1004_rc_fw_Rascal110.hil
- set MODE custom
- fi
-
- if [ $MODE != custom ]
- then
- # Try to get an USB console
- nshterm /dev/ttyACM0 &
- fi
-
#
# Upgrade PX4IO firmware
#
-
if [ -f /etc/extras/px4io-v2_default.bin ]
then
set io_file /etc/extras/px4io-v2_default.bin
@@ -160,18 +119,17 @@ then
set io_file /etc/extras/px4io-v1_default.bin
fi
- if px4io start
- then
- echo "PX4IO OK"
- echo "PX4IO OK" >> $logfile
- fi
-
if px4io checkcrc $io_file
then
- echo "PX4IO CRC OK"
+ echo "[init] PX4IO CRC OK"
echo "PX4IO CRC OK" >> $logfile
+
+ set IO_PRESENT yes
+
+ # If PX4IO present, use it as primary PWM output by default
+ set OUTPUT_MODE io_pwm
else
- echo "PX4IO CRC failure"
+ echo "[init] PX4IO CRC failure"
echo "PX4IO CRC failure" >> $logfile
tone_alarm MBABGP
if px4io forceupdate 14662 $io_file
@@ -179,277 +137,215 @@ then
usleep 500000
if px4io start
then
- echo "PX4IO restart OK"
+ echo "[init] PX4IO restart OK"
echo "PX4IO restart OK" >> $logfile
tone_alarm MSPAA
+
+ set IO_PRESENT yes
+
+ # If PX4IO present, use it as primary PWM output by default
+ set OUTPUT_MODE io_pwm
else
- echo "PX4IO restart failed"
+ echo "[init] PX4IO restart failed"
echo "PX4IO restart failed" >> $logfile
- tone_alarm MNGGG
- sleep 10
- reboot
+ if hw_ver compare PX4FMU_V2
+ then
+ tone_alarm MNGGG
+ sleep 10
+ reboot
+ fi
fi
else
- echo "PX4IO update failed"
+ echo "[init] PX4IO update failed"
echo "PX4IO update failed" >> $logfile
- tone_alarm MNGGG
+ if hw_ver compare PX4FMU_V2
+ then
+ tone_alarm MNGGG
+ fi
fi
fi
-
- set EXIT_ON_END no
- #
- # Check if auto-setup from one of the standard scripts is wanted
- # SYS_AUTOSTART = 0 means no autostart (default)
- #
- # AUTOSTART PARTITION:
- # 0 .. 999 Reserved (historical)
- # 1000 .. 1999 Simulation setups
- # 2000 .. 2999 Standard planes
- # 3000 .. 3999 Flying wing
- # 4000 .. 4999 Quad X
- # 5000 .. 5999 Quad +
- # 6000 .. 6999 Hexa X
- # 7000 .. 7999 Hexa +
- # 8000 .. 8999 Octo X
- # 9000 .. 9999 Octo +
- # 10000 .. 10999 Wide arm / H frame
- # 11000 .. 11999 Hexa Cox
- # 12000 .. 12999 Octo Cox
+ set HIL no
+ set FRAME_TYPE none
+ set PWM_RATE none
+ set PWM_DISARMED none
+ set PWM_MIN none
+ set PWM_MAX none
- if param compare SYS_AUTOSTART 4008 8
- then
- sh /etc/init.d/4008_ardrone
- set MODE custom
- fi
+ set EXIT_ON_END no
- if param compare SYS_AUTOSTART 4009 9
+ if param compare SYS_AUTOCONFIG 1
then
- sh /etc/init.d/4009_ardrone_flow
- set MODE custom
+ set DO_AUTOCONFIG yes
+ else
+ set DO_AUTOCONFIG no
fi
- if param compare SYS_AUTOSTART 4010 10
- then
- set FRAME_GEOMETRY x
- set FRAME_COUNT 4
- set PWM_MIN 1200
- set PWM_MAX 1900
- set PWM_DISARMED 900
- sh /etc/init.d/4010_dji_f330
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 4011 11
- then
- sh /etc/init.d/4011_dji_f450
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 4012
- then
- sh /etc/init.d/666_fmu_q_x550
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 6012 12
- then
- set MIXER /etc/mixers/FMU_hex_x.mix
- sh /etc/init.d/rc.hexa
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 7013 13
- then
- set MIXER /etc/mixers/FMU_hex_+.mix
- sh /etc/init.d/rc.hexa
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 8001
- then
- set MIXER /etc/mixers/FMU_octo_x.mix
- sh /etc/init.d/rc.octo
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 9001
- then
- set MIXER /etc/mixers/FMU_octo_+.mix
- sh /etc/init.d/rc.octo
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 12001
- then
- set MIXER /etc/mixers/FMU_octo_cox.mix
- sh /etc/init.d/rc.octo
- set MODE custom
- fi
+ #
+ # Start the Commander (needs to be this early for in-air-restarts)
+ #
+ commander start
- if param compare SYS_AUTOSTART 10015 15
- then
- sh /etc/init.d/10015_tbs_discovery
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 10016 16
- then
- sh /etc/init.d/10016_3dr_iris
- set MODE custom
- fi
-
- # PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame
- if param compare SYS_AUTOSTART 4017 17
- then
- set MKBLCTRL_MODE no
- set MKBLCTRL_FRAME x
- sh /etc/init.d/rc.custom_dji_f330_mkblctrl
- set MODE custom
- fi
-
- # PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame
- if param compare SYS_AUTOSTART 5018 18
- then
- set MKBLCTRL_MODE no
- set MKBLCTRL_FRAME +
- sh /etc/init.d/rc.custom_dji_f330_mkblctrl
- set MODE custom
- fi
-
- # PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame Mikrokopter-Addressing
- if param compare SYS_AUTOSTART 4019 19
- then
- set MKBLCTRL_MODE yes
- set MKBLCTRL_FRAME x
- sh /etc/init.d/rc.custom_dji_f330_mkblctrl
- set MODE custom
- fi
-
- # PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame Mikrokopter-Addressing
- if param compare SYS_AUTOSTART 5020 20
- then
- set MKBLCTRL_MODE yes
- set MKBLCTRL_FRAME +
- sh /etc/init.d/rc.custom_dji_f330_mkblctrl
- set MODE custom
- fi
+ #
+ # Set parameters and env variables for selected AUTOSTART
+ #
+ sh /etc/init.d/rc.autostart
- # PX4FMU v1 with IO + PPM-based ESCs on Quad X-shape frame
- if param compare SYS_AUTOSTART 4021 21
+ # Custom configuration
+ if [ -f /fs/microsd/etc/rc.conf ]
then
- set FRAME_GEOMETRY x
- set ESC_MAKER afro
- sh /etc/init.d/rc.custom_io_esc
- set MODE custom
+ sh /fs/microsd/etc/rc.conf
fi
- # PX4FMU v1 with IO + PPM-based ESCs on Quad X-shape frame
- if param compare SYS_AUTOSTART 10022 22
+ if [ $HIL == yes ]
then
- set FRAME_GEOMETRY w
- sh /etc/init.d/rc.custom_io_esc
- set MODE custom
+ set OUTPUT_MODE hil
+ else
+ # Try to get an USB console if not in HIL mode
+ nshterm /dev/ttyACM0 &
fi
- if param compare SYS_AUTOSTART 3030 30
+ #
+ # If autoconfig parameter was set, reset it and save parameters
+ #
+ if [ $DO_AUTOCONFIG == yes ]
then
- sh /etc/init.d/3030_io_camflyer
- set MODE custom
+ param set SYS_AUTOCONFIG 0
+ param save
fi
- if param compare SYS_AUTOSTART 3031 31
- then
- sh /etc/init.d/3031_io_phantom
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 3032 32
- then
- sh /etc/init.d/3032_skywalker_x5
- set MODE custom
- fi
+ if [ $MODE == autostart ]
+ then
+ #
+ # Start primary output
+ #
+ if [ $OUTPUT_MODE == io_pwm ]
+ then
+ echo "[init] Use PX4IO PWM as primary output"
+ if px4io start
+ then
+ echo "[init] PX4IO OK"
+ echo "PX4IO OK" >> $logfile
+ sh /etc/init.d/rc.io
+ else
+ echo "[init] PX4IO start error"
+ echo "PX4IO start error" >> $logfile
+ tone_alarm MNGGG
+ fi
+ fi
+ if [ $OUTPUT_MODE == fmu_pwm ]
+ then
+ echo "[init] Use PX4FMU PWM as primary output"
+ fmu mode_pwm
+ fi
+ if [ $OUTPUT_MODE == mkblctrl ]
+ then
+ echo "[init] Use MKBLCTRL as primary output"
+ mkblctrl
+ fi
+ if [ $OUTPUT_MODE == hil ]
+ then
+ echo "[init] Use HIL as primary output"
+ hil mode_pwm
+ fi
+
+ #
+ # Start PX4IO as secondary output if needed
+ #
+ if [ $IO_PRESENT == yes -a $OUTPUT_MODE != io_pwm ]
+ then
+ echo "[init] Use PX4IO PWM as secondary output"
+ if px4io start
+ then
+ echo "[init] PX4IO OK"
+ echo "PX4IO OK" >> $logfile
+ sh /etc/init.d/rc.io
+ else
+ echo "[init] PX4IO start error"
+ echo "PX4IO start error" >> $logfile
+ tone_alarm MNGGG
+ fi
+ fi
- if param compare SYS_AUTOSTART 3033 33
- then
- sh /etc/init.d/3033_io_wingwing
- set MODE custom
- fi
+ #
+ # MAVLink
+ #
+ if [ $OUTPUT_MODE == fmu_pwm -a hw_ver compare PX4FMU_V1 ]
+ then
+ # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as PWM output
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+
+ # Exit from nsh to free port for mavlink
+ set EXIT_ON_END yes
+ else
+ # Start MAVLink on default port: ttyS1
+ mavlink start
+ usleep 5000
+ fi
+
+ #
+ # Sensors, Logging, GPS
+ #
+ echo "[init] Start sensors"
+ sh /etc/init.d/rc.sensors
- if param compare SYS_AUTOSTART 3034 34
- then
- sh /etc/init.d/3034_io_fx79
- set MODE custom
- fi
+ if [ $HIL == no ]
+ then
+ echo "[init] Start logging"
+ sh /etc/init.d/rc.logging
+ fi
- if param compare SYS_AUTOSTART 40
- then
- sh /etc/init.d/40_io_segway
- set MODE custom
- fi
+ if [ $HIL == no ]
+ then
+ echo "[init] Start GPS"
+ gps start
+ fi
+
+ #
+ # Fixed wing setup
+ #
+ if [ $VEHICLE_TYPE == fw ]
+ then
+ echo "[init] Vehicle type: FIXED WING"
+
+ # Load mixer and configure outputs
+ sh /etc/init.d/rc.fw_interface
+
+ # Start standard fixedwing apps
+ sh /etc/init.d/rc.mc_apps
+ fi
- if param compare SYS_AUTOSTART 2100 100
- then
- sh /etc/init.d/2100_mpx_easystar
- set MODE custom
- fi
+ #
+ # Multicopters setup
+ #
+ if [ $VEHICLE_TYPE == mc ]
+ then
+ echo "[init] Vehicle type: MULTICOPTER"
+
+ # Load mixer and configure outputs
+ sh /etc/init.d/rc.mc_interface
+
+ # Start standard multicopter apps
+ sh /etc/init.d/rc.mc_apps
+ fi
- if param compare SYS_AUTOSTART 2101 101
- then
- sh /etc/init.d/2101_hk_bixler
- set MODE custom
+ #
+ # Generic setup (autostart ID not found)
+ #
+ if [ $VEHICLE_TYPE == none ]
+ then
+ echo "[init] Vehicle type: GENERIC"
+ attitude_estimator_ekf start
+ position_estimator_inav start
+ fi
fi
- if param compare SYS_AUTOSTART 2102 102
- then
- sh /etc/init.d/2102_3dr_skywalker
- set MODE custom
- fi
-
- if param compare SYS_AUTOSTART 800
- then
- sh /etc/init.d/800_sdlogger
- set MODE custom
- fi
-
- # Start any custom extensions that might be missing
+ # Start any custom extensions
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
- # but the AR.Drone motors can be get 'flashed'
- # if starting MAVLink on them - so do not
- # start it as default (default link: USB)
-
- # Start commander
- commander start
-
- # Start px4io if present
- if px4io detect
- then
- px4io start
- else
- if fmu mode_serial
- then
- echo "FMU driver (no PWM) 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
if [ $EXIT_ON_END == yes ]
then
diff --git a/makefiles/config_px4fmu-v1_backside.mk b/makefiles/config_px4fmu-v1_backside.mk
index c86beacca..a37aa8f96 100644
--- a/makefiles/config_px4fmu-v1_backside.mk
+++ b/makefiles/config_px4fmu-v1_backside.mk
@@ -54,6 +54,7 @@ MODULES += systemcmds/top
MODULES += systemcmds/tests
MODULES += systemcmds/config
MODULES += systemcmds/nshterm
+MODULES += systemcmds/hw_ver
#
# General system control
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index d0733ec53..33c0b99e2 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -58,6 +58,7 @@ MODULES += systemcmds/top
MODULES += systemcmds/tests
MODULES += systemcmds/config
MODULES += systemcmds/nshterm
+MODULES += systemcmds/hw_ver
#
# General system control
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index afe072b64..475cbae01 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -60,6 +60,7 @@ MODULES += systemcmds/top
MODULES += systemcmds/tests
MODULES += systemcmds/config
MODULES += systemcmds/nshterm
+MODULES += systemcmds/hw_ver
#
# General system control
diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk
index 6faef7e0a..a1bb6c92b 100644
--- a/makefiles/config_px4fmu-v2_test.mk
+++ b/makefiles/config_px4fmu-v2_test.mk
@@ -22,6 +22,7 @@ MODULES += systemcmds/perf
MODULES += systemcmds/reboot
MODULES += systemcmds/tests
MODULES += systemcmds/nshterm
+MODULES += systemcmds/hw_ver
#
# Library modules
diff --git a/src/modules/sdlog2/sdlog2_version.h b/src/lib/version/version.h
index c6a9ba638..af733aaf0 100644
--- a/src/modules/sdlog2/sdlog2_version.h
+++ b/src/lib/version/version.h
@@ -33,15 +33,15 @@
****************************************************************************/
/**
- * @file sdlog2_version.h
+ * @file version.h
*
* Tools for system version detection.
*
* @author Anton Babushkin <anton.babushkin@me.com>
*/
-#ifndef SDLOG2_VERSION_H_
-#define SDLOG2_VERSION_H_
+#ifndef VERSION_H_
+#define VERSION_H_
/*
GIT_VERSION is defined at build time via a Makefile call to the
@@ -59,4 +59,4 @@
#define HW_ARCH "PX4FMU_V2"
#endif
-#endif /* SDLOG2_VERSION_H_ */
+#endif /* VERSION_H_ */
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index e94b1e13c..658c6779c 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -85,13 +85,13 @@
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
+#include <version/version.h>
#include <mavlink/mavlink_log.h>
#include "logbuffer.h"
#include "sdlog2_format.h"
#include "sdlog2_messages.h"
-#include "sdlog2_version.h"
#define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \
log_msgs_written++; \
diff --git a/src/systemcmds/hw_ver/hw_ver.c b/src/systemcmds/hw_ver/hw_ver.c
new file mode 100644
index 000000000..4b84523cc
--- /dev/null
+++ b/src/systemcmds/hw_ver/hw_ver.c
@@ -0,0 +1,73 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 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 hw_ver.c
+ *
+ * Show and test hardware version.
+ */
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <string.h>
+#include <errno.h>
+#include <version/version.h>
+
+__EXPORT int hw_ver_main(int argc, char *argv[]);
+
+int
+hw_ver_main(int argc, char *argv[])
+{
+ if (argc >= 2) {
+ if (!strcmp(argv[1], "show")) {
+ printf(HW_ARCH "\n");
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "compare")) {
+ if (argc >= 3) {
+ int ret = strcmp(HW_ARCH, argv[2]) != 0;
+ if (ret == 0) {
+ printf("hw_ver match: %s\n", HW_ARCH);
+ }
+ exit(ret);
+
+ } else {
+ errx(1, "not enough arguments, try 'compare PX4FMU_1'");
+ }
+ }
+ }
+
+ errx(1, "expected a command, try 'show' or 'compare'");
+}
diff --git a/src/systemcmds/hw_ver/module.mk b/src/systemcmds/hw_ver/module.mk
new file mode 100644
index 000000000..3cc08b6a1
--- /dev/null
+++ b/src/systemcmds/hw_ver/module.mk
@@ -0,0 +1,43 @@
+############################################################################
+#
+# Copyright (c) 2014 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.
+#
+############################################################################
+
+#
+# Show and test hardware version
+#
+
+MODULE_COMMAND = hw_ver
+SRCS = hw_ver.c
+
+MODULE_STACKSIZE = 1024
+
+MAXOPTIMIZATION = -Os