aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-02-07 22:28:42 +0100
committerJulian Oes <julian@oes.ch>2014-02-07 22:28:42 +0100
commit70e1bfa4d69e967b309d177060804e7567f148b2 (patch)
tree4af8a9f2fe15e11586669f0e538ba25e871cc718 /ROMFS/px4fmu_common
parentce83f450b8ef96fef095ed28cf3ae8ed8b8c8373 (diff)
downloadpx4-firmware-70e1bfa4d69e967b309d177060804e7567f148b2.tar.gz
px4-firmware-70e1bfa4d69e967b309d177060804e7567f148b2.tar.bz2
px4-firmware-70e1bfa4d69e967b309d177060804e7567f148b2.zip
Startup scripts: use rc.mc_defaults for default MC parameters
Diffstat (limited to 'ROMFS/px4fmu_common')
-rw-r--r--ROMFS/px4fmu_common/init.d/10015_tbs_discovery41
-rw-r--r--ROMFS/px4fmu_common/init.d/10016_3dr_iris38
-rw-r--r--ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil4
-rw-r--r--ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil4
-rw-r--r--ROMFS/px4fmu_common/init.d/12001_octo_cox4
-rw-r--r--ROMFS/px4fmu_common/init.d/4001_quad_x44
-rw-r--r--ROMFS/px4fmu_common/init.d/4010_dji_f33047
-rw-r--r--ROMFS/px4fmu_common/init.d/4011_dji_f45047
-rw-r--r--ROMFS/px4fmu_common/init.d/4012_hk_x5506
-rw-r--r--ROMFS/px4fmu_common/init.d/5001_quad_+4
-rw-r--r--ROMFS/px4fmu_common/init.d/6001_hexa_x4
-rw-r--r--ROMFS/px4fmu_common/init.d/7001_hexa_+6
-rw-r--r--ROMFS/px4fmu_common/init.d/8001_octo_x4
-rw-r--r--ROMFS/px4fmu_common/init.d/9001_octo_+4
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_defaults45
15 files changed, 79 insertions, 223 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
index a3d7c3d97..b09765e8e 100644
--- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
@@ -5,45 +5,8 @@
# Simon Wilks <sjwilks@gmail.com>
#
-if [ $DO_AUTOCONFIG == yes ]
-then
- #
- # Default parameters for this platform
- #
- param set MC_ROLL_P 5.0
- param set MC_ROLLRATE_P 0.17
- param set MC_ROLLRATE_I 0.0
- param set MC_ROLLRATE_D 0.006
- param set MC_PITCH_P 5.0
- param set MC_PITCHRATE_P 0.17
- param set MC_PITCHRATE_I 0.0
- param set MC_PITCHRATE_D 0.006
- param set MC_YAW_P 0.5
- param set MC_YAWRATE_P 0.2
- param set MC_YAWRATE_I 0.0
- param set MC_YAWRATE_D 0.0
+sh /etc/init.d/rc.mc_defaults
- param set MPC_THR_MAX 1.0
- param set MPC_THR_MIN 0.1
- param set MPC_XY_P 1.0
- param set MPC_XY_VEL_P 0.1
- param set MPC_XY_VEL_I 0.02
- param set MPC_XY_VEL_D 0.01
- param set MPC_XY_VEL_MAX 5
- param set MPC_XY_FF 0.5
- param set MPC_Z_P 1.0
- param set MPC_Z_VEL_P 0.1
- param set MPC_Z_VEL_I 0.02
- param set MPC_Z_VEL_D 0.0
- param set MPC_Z_VEL_MAX 3
- param set MPC_Z_FF 0.5
- param set MPC_TILT_MAX 1.0
- param set MPC_LAND_SPEED 1.0
- param set MPC_LAND_TILT 0.3
-fi
-
-set VEHICLE_TYPE mc
set MIXER FMU_quad_w
-set PWM_OUTPUTS 1234
-set PWM_RATE 400
+set PWM_OUTPUTS 1234 \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
index 1c7ecb712..42d516993 100644
--- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
@@ -5,51 +5,17 @@
# Anton Babushkin <anton.babushkin@me.com>
#
+sh /etc/init.d/rc.mc_defaults
+
if [ $DO_AUTOCONFIG == yes ]
then
#
# Default parameters for this platform
#
- param set MC_ROLL_P 9.0
- param set MC_ROLLRATE_P 0.13
- param set MC_ROLLRATE_I 0.0
- param set MC_ROLLRATE_D 0.004
- param set MC_PITCH_P 9.0
- param set MC_PITCHRATE_P 0.13
- param set MC_PITCHRATE_I 0.0
- param set MC_PITCHRATE_D 0.004
- param set MC_YAW_P 0.5
- param set MC_YAWRATE_P 0.2
- param set MC_YAWRATE_I 0.0
- param set MC_YAWRATE_D 0.0
-
- param set MPC_THR_MAX 1.0
- param set MPC_THR_MIN 0.1
- param set MPC_XY_P 1.0
- param set MPC_XY_VEL_P 0.1
- param set MPC_XY_VEL_I 0.02
- param set MPC_XY_VEL_D 0.01
- param set MPC_XY_VEL_MAX 5
- param set MPC_XY_FF 0.5
- param set MPC_Z_P 1.0
- param set MPC_Z_VEL_P 0.1
- param set MPC_Z_VEL_I 0.02
- param set MPC_Z_VEL_D 0.0
- param set MPC_Z_VEL_MAX 3
- param set MPC_Z_FF 0.5
- param set MPC_TILT_MAX 1.0
- param set MPC_LAND_SPEED 1.0
- param set MPC_LAND_TILT 0.3
-
param set BAT_V_SCALING 0.00989
param set BAT_C_SCALING 0.0124
fi
-set VEHICLE_TYPE mc
set MIXER FMU_quad_w
set PWM_OUTPUTS 1234
-set PWM_RATE 400
-set PWM_DISARMED 900
-set PWM_MIN 1000
-set PWM_MAX 2000
diff --git a/ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil b/ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil
index 45880f44b..7a7a9542c 100644
--- a/ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil
+++ b/ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil
@@ -5,6 +5,8 @@
# Anton Babushkin <anton.babushkin@me.com>
#
-sh /etc/init.d/4001_quad_x
+sh /etc/init.d/rc.mc_defaults
+
+set MIXER FMU_quad_x
set HIL yes
diff --git a/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
index 2b26810e7..c47500c7a 100644
--- a/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
+++ b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
@@ -5,6 +5,8 @@
# Anton Babushkin <anton.babushkin@me.com>
#
-sh /etc/init.d/1001_rc_quad_x.hil
+sh /etc/init.d/rc.mc_defaults
set MIXER FMU_quad_+
+
+set HIL yes \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/12001_octo_cox b/ROMFS/px4fmu_common/init.d/12001_octo_cox
index 8a813595e..c5d3e7807 100644
--- a/ROMFS/px4fmu_common/init.d/12001_octo_cox
+++ b/ROMFS/px4fmu_common/init.d/12001_octo_cox
@@ -5,6 +5,8 @@
# Lorenz Meier <lm@inf.ethz.ch>, Anton Babushkin <anton.babushkin@me.com>
#
-sh /etc/init.d/8001_octo_x
+sh /etc/init.d/rc.mc_defaults
set MIXER FMU_octo_cox
+
+set PWM_OUTPUTS 12345678 \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/4001_quad_x b/ROMFS/px4fmu_common/init.d/4001_quad_x
index 0f1288dec..fa751f1e3 100644
--- a/ROMFS/px4fmu_common/init.d/4001_quad_x
+++ b/ROMFS/px4fmu_common/init.d/4001_quad_x
@@ -5,48 +5,8 @@
# Lorenz Meier <lm@inf.ethz.ch>
#
-if [ $DO_AUTOCONFIG == yes ]
-then
- #
- # Default parameters for this platform
- #
- param set MC_ROLL_P 7.0
- param set MC_ROLLRATE_P 0.12
- param set MC_ROLLRATE_I 0.0
- param set MC_ROLLRATE_D 0.004
- param set MC_PITCH_P 7.0
- param set MC_PITCHRATE_P 0.12
- param set MC_PITCHRATE_I 0.0
- param set MC_PITCHRATE_D 0.004
- param set MC_YAW_P 2.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_THR_MAX 1.0
- param set MPC_THR_MIN 0.1
- param set MPC_XY_P 1.0
- param set MPC_XY_VEL_P 0.1
- param set MPC_XY_VEL_I 0.02
- param set MPC_XY_VEL_D 0.01
- param set MPC_XY_VEL_MAX 5
- param set MPC_XY_FF 0.5
- param set MPC_Z_P 1.0
- param set MPC_Z_VEL_P 0.1
- param set MPC_Z_VEL_I 0.02
- param set MPC_Z_VEL_D 0.0
- param set MPC_Z_VEL_MAX 3
- param set MPC_Z_FF 0.5
- param set MPC_TILT_MAX 1.0
- param set MPC_LAND_SPEED 1.0
- param set MPC_LAND_TILT 0.3
-fi
+sh /etc/init.d/rc.mc_defaults
-set VEHICLE_TYPE mc
set MIXER FMU_quad_x
-set PWM_OUTPUTS 1234
-set PWM_RATE 400
-set PWM_DISARMED 900
-set PWM_MIN 1100
-set PWM_MAX 2000
+set PWM_OUTPUTS 1234 \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330
index 782946033..232af57b4 100644
--- a/ROMFS/px4fmu_common/init.d/4010_dji_f330
+++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330
@@ -5,49 +5,6 @@
# Anton Babushkin <anton.babushkin@me.com>
#
-if [ $DO_AUTOCONFIG == yes ]
-then
- #
- # Default parameters for this platform
- #
- param set MC_ROLL_P 7.0
- param set MC_ROLLRATE_P 0.12
- param set MC_ROLLRATE_I 0.0
- param set MC_ROLLRATE_D 0.004
- param set MC_PITCH_P 7.0
- param set MC_PITCHRATE_P 0.12
- param set MC_PITCHRATE_I 0.0
- param set MC_PITCHRATE_D 0.004
- param set MC_YAW_P 2.8
- param set MC_YAWRATE_P 0.2
- param set MC_YAWRATE_I 0.05
- param set MC_YAWRATE_D 0.0
-
- param set MPC_THR_MAX 1.0
- param set MPC_THR_MIN 0.1
- param set MPC_XY_P 1.0
- param set MPC_XY_VEL_P 0.1
- param set MPC_XY_VEL_I 0.02
- param set MPC_XY_VEL_D 0.01
- param set MPC_XY_VEL_MAX 5
- param set MPC_XY_FF 0.5
- param set MPC_Z_P 1.0
- param set MPC_Z_VEL_P 0.1
- param set MPC_Z_VEL_I 0.02
- param set MPC_Z_VEL_D 0.0
- param set MPC_Z_VEL_MAX 3
- param set MPC_Z_FF 0.5
- param set MPC_TILT_MAX 1.0
- param set MPC_LAND_SPEED 1.0
- param set MPC_LAND_TILT 0.3
-fi
+sh /etc/init.d/4001_quad_x
-set VEHICLE_TYPE mc
-set MIXER FMU_quad_x
-
-set PWM_OUTPUTS 1234
-set PWM_RATE 400
-# DJI ESC range
-set PWM_DISARMED 900
-set PWM_MIN 1200
-set PWM_MAX 1900
+set PWM_MIN 1175 \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450
index 8eb53d172..259636acc 100644
--- a/ROMFS/px4fmu_common/init.d/4011_dji_f450
+++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450
@@ -5,49 +5,6 @@
# Lorenz Meier <lm@inf.ethz.ch>
#
-if [ $DO_AUTOCONFIG == yes ]
-then
- #
- # Default parameters for this platform
- #
- param set MC_ROLL_P 7.0
- param set MC_ROLLRATE_P 0.12
- param set MC_ROLLRATE_I 0.0
- param set MC_ROLLRATE_D 0.004
- param set MC_PITCH_P 7.0
- param set MC_PITCHRATE_P 0.12
- param set MC_PITCHRATE_I 0.0
- param set MC_PITCHRATE_D 0.004
- param set MC_YAW_P 2.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_THR_MAX 1.0
- param set MPC_THR_MIN 0.1
- param set MPC_XY_P 1.0
- param set MPC_XY_VEL_P 0.1
- param set MPC_XY_VEL_I 0.02
- param set MPC_XY_VEL_D 0.01
- param set MPC_XY_VEL_MAX 5
- param set MPC_XY_FF 0.5
- param set MPC_Z_P 1.0
- param set MPC_Z_VEL_P 0.1
- param set MPC_Z_VEL_I 0.02
- param set MPC_Z_VEL_D 0.0
- param set MPC_Z_VEL_MAX 3
- param set MPC_Z_FF 0.5
- param set MPC_TILT_MAX 1.0
- param set MPC_LAND_SPEED 1.0
- param set MPC_LAND_TILT 0.3
-fi
+sh /etc/init.d/4001_quad_x
-set VEHICLE_TYPE mc
-set MIXER FMU_quad_x
-
-set PWM_OUTPUTS 1234
-set PWM_RATE 400
-# DJI ESC range
-set PWM_DISARMED 900
-set PWM_MIN 1200
-set PWM_MAX 1900
+set PWM_MIN 1175 \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/4012_hk_x550 b/ROMFS/px4fmu_common/init.d/4012_hk_x550
index 3d8e9fcf7..a5c4a8690 100644
--- a/ROMFS/px4fmu_common/init.d/4012_hk_x550
+++ b/ROMFS/px4fmu_common/init.d/4012_hk_x550
@@ -6,9 +6,3 @@
#
sh /etc/init.d/4001_quad_x
-
-set PWM_OUTPUTS 1234
-set PWM_RATE 400
-set PWM_DISARMED 900
-set PWM_MIN 1000
-set PWM_MAX 2000
diff --git a/ROMFS/px4fmu_common/init.d/5001_quad_+ b/ROMFS/px4fmu_common/init.d/5001_quad_+
index ff11bccfe..2f5ab44d7 100644
--- a/ROMFS/px4fmu_common/init.d/5001_quad_+
+++ b/ROMFS/px4fmu_common/init.d/5001_quad_+
@@ -5,6 +5,8 @@
# Anton Babushkin <anton.babushkin@me.com>
#
-sh /etc/init.d/4001_quad_x
+sh /etc/init.d/rc.mc_defaults
set MIXER FMU_quad_+
+
+set PWM_OUTPUTS 1234 \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/6001_hexa_x b/ROMFS/px4fmu_common/init.d/6001_hexa_x
index fd5756586..73ef12569 100644
--- a/ROMFS/px4fmu_common/init.d/6001_hexa_x
+++ b/ROMFS/px4fmu_common/init.d/6001_hexa_x
@@ -5,10 +5,10 @@
# Anton Babushkin <anton.babushkin@me.com>
#
-sh /etc/init.d/4001_quad_x
+sh /etc/init.d/rc.mc_defaults
set MIXER FMU_hexa_x
# We only can run one channel group with one rate,
# so all 8 at 400 Hz
-set PWM_OUTPUTS 12345678
+set PWM_OUTPUTS 12345678 \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/7001_hexa_+ b/ROMFS/px4fmu_common/init.d/7001_hexa_+
index 45279ec39..ef4b6297d 100644
--- a/ROMFS/px4fmu_common/init.d/7001_hexa_+
+++ b/ROMFS/px4fmu_common/init.d/7001_hexa_+
@@ -5,6 +5,10 @@
# Anton Babushkin <anton.babushkin@me.com>
#
-sh /etc/init.d/6001_hexa_x
+sh /etc/init.d/rc.mc_defaults
set MIXER FMU_hexa_+
+
+# We only can run one channel group with one rate,
+# so all 8 at 400 Hz
+set PWM_OUTPUTS 12345678 \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/8001_octo_x b/ROMFS/px4fmu_common/init.d/8001_octo_x
index 6fa962668..bb87f89fe 100644
--- a/ROMFS/px4fmu_common/init.d/8001_octo_x
+++ b/ROMFS/px4fmu_common/init.d/8001_octo_x
@@ -5,8 +5,8 @@
# Anton Babushkin <anton.babushkin@me.com>
#
-sh /etc/init.d/4001_quad_x
+sh /etc/init.d/rc.mc_defaults
set MIXER FMU_octo_x
-set PWM_OUTPUTS 12345678
+set PWM_OUTPUTS 12345678 \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/9001_octo_+ b/ROMFS/px4fmu_common/init.d/9001_octo_+
index fa3869f9f..81132fd3e 100644
--- a/ROMFS/px4fmu_common/init.d/9001_octo_+
+++ b/ROMFS/px4fmu_common/init.d/9001_octo_+
@@ -5,6 +5,8 @@
# Anton Babushkin <anton.babushkin@me.com>
#
-sh /etc/init.d/8001_octo_x
+sh /etc/init.d/rc.mc_defaults
set MIXER FMU_octo_+
+
+set PWM_OUTPUTS 12345678 \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
new file mode 100644
index 000000000..14b6fe12c
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
@@ -0,0 +1,45 @@
+#!nsh
+
+set VEHICLE_TYPE mc
+
+if [ $DO_AUTOCONFIG == yes ]
+then
+ #
+ # Default parameters for this platform
+ #
+ param set MC_ROLL_P 7.0
+ param set MC_ROLLRATE_P 0.12
+ param set MC_ROLLRATE_I 0.0
+ param set MC_ROLLRATE_D 0.004
+ param set MC_PITCH_P 7.0
+ param set MC_PITCHRATE_P 0.12
+ param set MC_PITCHRATE_I 0.0
+ param set MC_PITCHRATE_D 0.004
+ param set MC_YAW_P 2.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_THR_MAX 1.0
+ param set MPC_THR_MIN 0.1
+ param set MPC_XY_P 1.0
+ param set MPC_XY_VEL_P 0.1
+ param set MPC_XY_VEL_I 0.02
+ param set MPC_XY_VEL_D 0.01
+ param set MPC_XY_VEL_MAX 5
+ param set MPC_XY_FF 0.5
+ param set MPC_Z_P 1.0
+ param set MPC_Z_VEL_P 0.1
+ param set MPC_Z_VEL_I 0.02
+ param set MPC_Z_VEL_D 0.0
+ param set MPC_Z_VEL_MAX 3
+ param set MPC_Z_FF 0.5
+ param set MPC_TILT_MAX 1.0
+ param set MPC_LAND_SPEED 1.0
+ param set MPC_LAND_TILT 0.3
+fi
+
+set PWM_RATE 400
+set PWM_DISARMED 900
+set PWM_MIN 1075
+set PWM_MAX 2000 \ No newline at end of file