aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-02-11 23:24:49 +0100
committerAnton Babushkin <anton.babushkin@me.com>2014-02-11 23:24:49 +0100
commit16908f9aff0e7ad0f967613adf2be9a00c1c6cce (patch)
tree978c791e7480375d6dd3b3aa5129fc659d9518b4
parent6f506874eb77312501596780829b158bc167f82b (diff)
downloadpx4-firmware-16908f9aff0e7ad0f967613adf2be9a00c1c6cce.tar.gz
px4-firmware-16908f9aff0e7ad0f967613adf2be9a00c1c6cce.tar.bz2
px4-firmware-16908f9aff0e7ad0f967613adf2be9a00c1c6cce.zip
autostart for multicopters: frame-specific default parameters reverted and cleaned up
-rw-r--r--ROMFS/px4fmu_common/init.d/10015_tbs_discovery21
-rw-r--r--ROMFS/px4fmu_common/init.d/10016_3dr_iris17
-rw-r--r--ROMFS/px4fmu_common/init.d/11001_hexa_cox28
-rw-r--r--ROMFS/px4fmu_common/init.d/12001_octo_cox29
-rw-r--r--ROMFS/px4fmu_common/init.d/4001_quad_x2
-rw-r--r--ROMFS/px4fmu_common/init.d/4010_dji_f33019
-rw-r--r--ROMFS/px4fmu_common/init.d/4011_dji_f45020
-rw-r--r--ROMFS/px4fmu_common/init.d/4012_hk_x5508
-rw-r--r--ROMFS/px4fmu_common/init.d/5001_quad_+2
-rw-r--r--ROMFS/px4fmu_common/init.d/6001_hexa_x5
-rw-r--r--ROMFS/px4fmu_common/init.d/7001_hexa_+5
-rw-r--r--ROMFS/px4fmu_common/init.d/8001_octo_x2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.autostart5
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_defaults24
14 files changed, 92 insertions, 95 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
index b09765e8e..880e4899b 100644
--- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
@@ -2,11 +2,28 @@
#
# Team Blacksheep Discovery Quadcopter
#
-# Simon Wilks <sjwilks@gmail.com>
+# Anton Babushkin <anton.babushkin@me.com>, Simon Wilks <sjwilks@gmail.com>
#
sh /etc/init.d/rc.mc_defaults
+if [ $DO_AUTOCONFIG == yes ]
+then
+ # TODO review MC_YAWRATE_I
+ param set MC_ROLL_P 8.0
+ param set MC_ROLLRATE_P 0.07
+ param set MC_ROLLRATE_I 0.05
+ param set MC_ROLLRATE_D 0.0017
+ param set MC_PITCH_P 8.0
+ param set MC_PITCHRATE_P 0.14
+ param set MC_PITCHRATE_I 0.1
+ param set MC_PITCHRATE_D 0.0025
+ param set MC_YAW_P 2.8
+ param set MC_YAWRATE_P 0.28
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_D 0.0
+fi
+
set MIXER FMU_quad_w
-set PWM_OUTPUTS 1234 \ No newline at end of file
+set PWM_OUTPUTS 1234
diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
index 42d516993..d691a6f2e 100644
--- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
@@ -9,9 +9,20 @@ sh /etc/init.d/rc.mc_defaults
if [ $DO_AUTOCONFIG == yes ]
then
- #
- # Default parameters for this platform
- #
+ # TODO tune roll/pitch separately
+ 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 BAT_V_SCALING 0.00989
param set BAT_C_SCALING 0.0124
fi
diff --git a/ROMFS/px4fmu_common/init.d/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
index 2dc83a517..b98ab4774 100644
--- a/ROMFS/px4fmu_common/init.d/11001_hexa_cox
+++ b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
@@ -7,33 +7,9 @@
# Lorenz Meier <lm@inf.ethz.ch>
#
-if [ $DO_AUTOCONFIG == yes ]
-then
- #
- # Default parameters for this platform
- #
- 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
-
- # TODO add default MPC parameters
-fi
+sh /etc/init.d/rc.mc_defaults
-set VEHICLE_TYPE mc
set MIXER hexa_cox
+# We only can run one channel group with one rate, so set all 8 channels
set PWM_OUTPUTS 12345678
-set PWM_RATE 400
-# DJI ESC range
-set PWM_DISARMED 900
-set PWM_MIN 1200
-set PWM_MAX 1900
diff --git a/ROMFS/px4fmu_common/init.d/12001_octo_cox b/ROMFS/px4fmu_common/init.d/12001_octo_cox
index a55fc5a30..655cb6226 100644
--- a/ROMFS/px4fmu_common/init.d/12001_octo_cox
+++ b/ROMFS/px4fmu_common/init.d/12001_octo_cox
@@ -5,33 +5,8 @@
# Lorenz Meier <lm@inf.ethz.ch>
#
-if [ $DO_AUTOCONFIG == yes ]
-then
- #
- # Default parameters for this platform
- #
- 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
-
- # TODO add default MPC parameters
-fi
+sh /etc/init.d/rc.mc_defaults
-set VEHICLE_TYPE mc
-set MIXER FMU_octo_cox
+set MIXER octo_cox
set PWM_OUTPUTS 12345678
-set PWM_RATE 400
-# DJI ESC range
-set PWM_DISARMED 900
-set PWM_MIN 1200
-set PWM_MAX 1900
diff --git a/ROMFS/px4fmu_common/init.d/4001_quad_x b/ROMFS/px4fmu_common/init.d/4001_quad_x
index fa751f1e3..345b0e3e4 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 \ No newline at end of file
+set PWM_OUTPUTS 1234
diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330
index 232af57b4..cd4480c3e 100644
--- a/ROMFS/px4fmu_common/init.d/4010_dji_f330
+++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330
@@ -7,4 +7,21 @@
sh /etc/init.d/4001_quad_x
-set PWM_MIN 1175 \ No newline at end of file
+if [ $DO_AUTOCONFIG == yes ]
+then
+ param set MC_ROLL_P 7.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 7.0
+ param set MC_PITCHRATE_P 0.1
+ param set MC_PITCHRATE_I 0.0
+ param set MC_PITCHRATE_D 0.003
+ param set MC_YAW_P 2.8
+ param set MC_YAWRATE_P 0.2
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_D 0.0
+fi
+
+set PWM_MIN 1175
+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 259636acc..ac2ecc70a 100644
--- a/ROMFS/px4fmu_common/init.d/4011_dji_f450
+++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450
@@ -7,4 +7,22 @@
sh /etc/init.d/4001_quad_x
-set PWM_MIN 1175 \ No newline at end of file
+if [ $DO_AUTOCONFIG == yes ]
+then
+ # TODO REVIEW
+ param set MC_ROLL_P 7.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 7.0
+ param set MC_PITCHRATE_P 0.1
+ param set MC_PITCHRATE_I 0.0
+ param set MC_PITCHRATE_D 0.003
+ param set MC_YAW_P 2.8
+ param set MC_YAWRATE_P 0.2
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_D 0.0
+fi
+
+set PWM_MIN 1175
+set PWM_MAX 1900
diff --git a/ROMFS/px4fmu_common/init.d/4012_hk_x550 b/ROMFS/px4fmu_common/init.d/4012_hk_x550
deleted file mode 100644
index a5c4a8690..000000000
--- a/ROMFS/px4fmu_common/init.d/4012_hk_x550
+++ /dev/null
@@ -1,8 +0,0 @@
-#!nsh
-#
-# HobbyKing X550 Quadcopter
-#
-# Todd Stellanova <tstellanova@gmail.com>
-#
-
-sh /etc/init.d/4001_quad_x
diff --git a/ROMFS/px4fmu_common/init.d/5001_quad_+ b/ROMFS/px4fmu_common/init.d/5001_quad_+
index 2f5ab44d7..55b31067d 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 \ No newline at end of file
+set PWM_OUTPUTS 1234
diff --git a/ROMFS/px4fmu_common/init.d/6001_hexa_x b/ROMFS/px4fmu_common/init.d/6001_hexa_x
index 73ef12569..7714a508c 100644
--- a/ROMFS/px4fmu_common/init.d/6001_hexa_x
+++ b/ROMFS/px4fmu_common/init.d/6001_hexa_x
@@ -9,6 +9,5 @@ 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 \ No newline at end of file
+# We only can run one channel group with one rate, so set all 8 channels
+set PWM_OUTPUTS 12345678
diff --git a/ROMFS/px4fmu_common/init.d/7001_hexa_+ b/ROMFS/px4fmu_common/init.d/7001_hexa_+
index ef4b6297d..60db8c069 100644
--- a/ROMFS/px4fmu_common/init.d/7001_hexa_+
+++ b/ROMFS/px4fmu_common/init.d/7001_hexa_+
@@ -9,6 +9,5 @@ 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
+# We only can run one channel group with one rate, so set all 8 channels
+set PWM_OUTPUTS 12345678
diff --git a/ROMFS/px4fmu_common/init.d/8001_octo_x b/ROMFS/px4fmu_common/init.d/8001_octo_x
index bb87f89fe..411aee114 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 \ No newline at end of file
+set PWM_OUTPUTS 12345678
diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart
index 48c26aacd..3968af58e 100644
--- a/ROMFS/px4fmu_common/init.d/rc.autostart
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -116,11 +116,6 @@ then
sh /etc/init.d/4011_dji_f450
fi
-if param compare SYS_AUTOSTART 4012 12
-then
- sh /etc/init.d/4012_hk_x550
-fi
-
#
# Quad +
#
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
index 52584677b..4db62607a 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
@@ -4,22 +4,20 @@ set VEHICLE_TYPE mc
if [ $DO_AUTOCONFIG == yes ]
then
- #
- # Default parameters for MC
- #
param set MC_ROLL_P 7.0
- param set MC_ROLLRATE_P 0.12
+ param set MC_ROLLRATE_P 0.1
param set MC_ROLLRATE_I 0.0
- param set MC_ROLLRATE_D 0.004
+ param set MC_ROLLRATE_D 0.003
param set MC_PITCH_P 7.0
- param set MC_PITCHRATE_P 0.12
+ param set MC_PITCHRATE_P 0.1
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 MC_PITCHRATE_D 0.003
+ param set MC_YAW_P 2.8
+ 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.5
+
param set MPC_THR_MAX 1.0
param set MPC_THR_MIN 0.1
param set MPC_XY_P 1.0
@@ -42,4 +40,4 @@ fi
set PWM_RATE 400
set PWM_DISARMED 900
set PWM_MIN 1075
-set PWM_MAX 2000 \ No newline at end of file
+set PWM_MAX 2000