aboutsummaryrefslogtreecommitdiff
path: root/ROMFS
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-01-18 16:42:49 +0100
committerAnton Babushkin <anton.babushkin@me.com>2014-01-18 16:42:49 +0100
commit524a502a56e7a5db5d05502ba26e9e7d18872e53 (patch)
treec35a98c101da770df15e948df06773507a423da5 /ROMFS
parent5b2f3b0b585bce29910560090fdfaa3d54e26ff3 (diff)
downloadpx4-firmware-524a502a56e7a5db5d05502ba26e9e7d18872e53.tar.gz
px4-firmware-524a502a56e7a5db5d05502ba26e9e7d18872e53.tar.bz2
px4-firmware-524a502a56e7a5db5d05502ba26e9e7d18872e53.zip
autostart fixes
Diffstat (limited to 'ROMFS')
-rw-r--r--ROMFS/px4fmu_common/init.d/10015_tbs_discovery2
-rw-r--r--ROMFS/px4fmu_common/init.d/10016_3dr_iris30
-rw-r--r--ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil30
-rw-r--r--ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil38
-rw-r--r--ROMFS/px4fmu_common/init.d/4010_dji_f33030
-rw-r--r--ROMFS/px4fmu_common/init.d/4011_dji_f4502
-rw-r--r--ROMFS/px4fmu_common/init.d/4012_hk_x5502
7 files changed, 40 insertions, 94 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
index 63798bb3c..5740e863c 100644
--- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
@@ -12,13 +12,11 @@ then
#
param set MC_ATT_P 5.0
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_YAWPOS_I 0.15
- param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
index 67c24fab3..62a794299 100644
--- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
@@ -12,32 +12,28 @@ then
#
param set MC_ATT_P 9.0
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_YAWPOS_I 0.15
- param set MC_YAWPOS_D 0.0
param set MC_YAWRATE_P 0.2
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
+ param set MPC_TILT_MAX 1.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_D 0.01
+ param set MPC_XY_VEL_I 0.02
+ param set MPC_XY_VEL_MAX 5
+ param set MPC_XY_VEL_P 0.1
+ param set MPC_Z_P 1.0
+ param set MPC_Z_VEL_D 0.0
+ param set MPC_Z_VEL_I 0.02
+ param set MPC_Z_VEL_MAX 3
+ param set MPC_Z_VEL_P 0.1
param set BAT_V_SCALING 0.00989
param set BAT_C_SCALING 0.0124
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 8c0797d7c..9e098093e 100644
--- a/ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil
+++ b/ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil
@@ -15,29 +15,25 @@ then
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
+ param set MPC_TILT_MAX 1.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_D 0.01
+ param set MPC_XY_VEL_I 0.02
+ param set MPC_XY_VEL_MAX 5
+ param set MPC_XY_VEL_P 0.1
+ param set MPC_Z_P 1.0
+ param set MPC_Z_VEL_D 0.0
+ param set MPC_Z_VEL_I 0.02
+ param set MPC_Z_VEL_MAX 3
+ param set MPC_Z_VEL_P 0.1
fi
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 bce3015fc..297082b79 100644
--- a/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
+++ b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
@@ -5,42 +5,6 @@
# Maintainers: Anton Babushkin <anton.babushkin@me.com>
#
-if [ $DO_AUTOCONFIG == yes ]
-then
- #
- # 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
+sh /etc/ini.d/1001_rc_quad_x.hil
-set HIL yes
-
-set VEHICLE_TYPE mc
set MIXER FMU_quad_+
diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330
index ab1db94d0..5ce86f593 100644
--- a/ROMFS/px4fmu_common/init.d/4010_dji_f330
+++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330
@@ -12,32 +12,28 @@ then
#
param set MC_ATT_P 7.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_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.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
+ param set MPC_TILT_MAX 1.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_D 0.01
+ param set MPC_XY_VEL_I 0.02
+ param set MPC_XY_VEL_MAX 5
+ param set MPC_XY_VEL_P 0.1
+ param set MPC_Z_P 1.0
+ param set MPC_Z_VEL_D 0.0
+ param set MPC_Z_VEL_I 0.02
+ param set MPC_Z_VEL_MAX 3
+ param set MPC_Z_VEL_P 0.1
fi
set VEHICLE_TYPE mc
diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450
index 299771c1d..1ff5c796a 100644
--- a/ROMFS/px4fmu_common/init.d/4011_dji_f450
+++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450
@@ -12,13 +12,11 @@ then
#
param set MC_ATT_P 7.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_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
diff --git a/ROMFS/px4fmu_common/init.d/4012_hk_x550 b/ROMFS/px4fmu_common/init.d/4012_hk_x550
index 7e020cf59..673043c14 100644
--- a/ROMFS/px4fmu_common/init.d/4012_hk_x550
+++ b/ROMFS/px4fmu_common/init.d/4012_hk_x550
@@ -12,13 +12,11 @@ then
#
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