aboutsummaryrefslogtreecommitdiff
path: root/ROMFS
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS')
-rw-r--r--ROMFS/px4fmu_common/init.d/10015_tbs_discovery2
-rw-r--r--ROMFS/px4fmu_common/init.d/3031_phantom6
-rw-r--r--ROMFS/px4fmu_common/init.d/3033_wingwing30
-rw-r--r--ROMFS/px4fmu_common/init.d/4010_dji_f3302
-rw-r--r--ROMFS/px4fmu_common/init.d/4011_dji_f4502
-rw-r--r--ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb28
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.autostart5
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_defaults2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.sensors1
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.usb2
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS23
-rw-r--r--ROMFS/px4fmu_common/mixers/phantom.mix67
-rw-r--r--ROMFS/px4fmu_common/mixers/wingwing.mix51
13 files changed, 195 insertions, 26 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
index fe85f7d35..c4be16943 100644
--- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
@@ -20,7 +20,7 @@ then
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_I 0.1
param set MC_YAWRATE_D 0.0
fi
diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom
index 24372bddc..654b0bdab 100644
--- a/ROMFS/px4fmu_common/init.d/3031_phantom
+++ b/ROMFS/px4fmu_common/init.d/3031_phantom
@@ -36,4 +36,8 @@ then
param set FW_T_TIME_CONST 5
fi
-set MIXER FMU_Q
+set MIXER phantom
+
+# Provide ESC a constant 1000 us pulse
+set PWM_OUTPUTS 4
+set PWM_DISARMED 1000
diff --git a/ROMFS/px4fmu_common/init.d/3033_wingwing b/ROMFS/px4fmu_common/init.d/3033_wingwing
index fff4b58df..f4dedef15 100644
--- a/ROMFS/px4fmu_common/init.d/3033_wingwing
+++ b/ROMFS/px4fmu_common/init.d/3033_wingwing
@@ -11,28 +11,38 @@ if [ $DO_AUTOCONFIG == yes ]
then
param set BAT_N_CELLS 2
param set FW_AIRSPD_MAX 15
- param set FW_AIRSPD_MIN 7
- param set FW_AIRSPD_TRIM 11
+ param set FW_AIRSPD_MIN 10
+ param set FW_AIRSPD_TRIM 13
param set FW_ATT_TC 0.3
param set FW_L1_DAMPING 0.74
- param set FW_L1_PERIOD 12
+ param set FW_L1_PERIOD 16
param set FW_LND_ANG 15
param set FW_LND_FLALT 5
param set FW_LND_HHDIST 15
param set FW_LND_HVIRT 13
param set FW_LND_TLALT 5
param set FW_THR_LND_MAX 0
- param set FW_P_ROLLFF 2
- param set FW_PR_FF 0.6
- param set FW_PR_IMAX 0.2
- param set FW_PR_P 0.06
+ param set FW_PR_FF 0.35
+ param set FW_PR_I 0.005
+ param set FW_PR_IMAX 0.4
+ param set FW_PR_P 0.08
param set FW_RR_FF 0.6
+ param set FW_RR_I 0.005
param set FW_RR_IMAX 0.2
- param set FW_RR_P 0.09
- param set FW_THR_CRUISE 0.65
+ param set FW_RR_P 0.04
+ param set MT_TKF_PIT_MAX 30.0
+ param set MT_ACC_D 0.2
+ param set MT_ACC_P 0.6
+ param set MT_A_LP 0.5
+ param set MT_PIT_OFF 0.1
+ param set MT_PIT_I 0.1
+ param set MT_THR_OFF 0.65
+ param set MT_THR_I 0.35
+ param set MT_THR_P 0.2
+ param set MT_THR_FF 1.5
fi
-set MIXER FMU_Q
+set MIXER wingwing
# Provide ESC a constant 1000 us pulse
set PWM_OUTPUTS 4
set PWM_DISARMED 1000
diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330
index cd4480c3e..e6e2e19dc 100644
--- a/ROMFS/px4fmu_common/init.d/4010_dji_f330
+++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330
@@ -19,7 +19,7 @@ then
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_I 0.1
param set MC_YAWRATE_D 0.0
fi
diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450
index ac2ecc70a..3465b59cf 100644
--- a/ROMFS/px4fmu_common/init.d/4011_dji_f450
+++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450
@@ -20,7 +20,7 @@ then
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_I 0.1
param set MC_YAWRATE_D 0.0
fi
diff --git a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb
new file mode 100644
index 000000000..99ffd73a5
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb
@@ -0,0 +1,28 @@
+#!nsh
+#
+# Hobbyking Micro Integrated PCB Quadcopter
+# with SimonK ESC firmware and Mystery A1510 motors
+#
+# Thomas Gubler <thomasgubler@gmail.com>
+#
+echo "HK Micro PCB Quad"
+
+sh /etc/init.d/4001_quad_x
+
+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 1200
diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart
index b365bd642..5d9e9502c 100644
--- a/ROMFS/px4fmu_common/init.d/rc.autostart
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -136,6 +136,11 @@ then
sh /etc/init.d/4011_dji_f450
fi
+if param compare SYS_AUTOSTART 4020
+then
+ sh /etc/init.d/4020_hk_micro_pcb
+fi
+
#
# Quad +
#
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
index 127e42164..0df320f49 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
@@ -14,7 +14,7 @@ then
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_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAW_FF 0.5
diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors
index 1e14930fe..be54ea98b 100644
--- a/ROMFS/px4fmu_common/init.d/rc.sensors
+++ b/ROMFS/px4fmu_common/init.d/rc.sensors
@@ -24,6 +24,7 @@ fi
if ver hwcmp PX4FMU_V2
then
+ # IMPORTANT: EXTERNAL BUSES SHOULD BE SCANNED FIRST
if lsm303d start
then
echo "[init] Using LSM303D"
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index d6e638c0a..1f8d8b862 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -3,7 +3,7 @@
# USB MAVLink start
#
-mavlink start -r 10000 -d /dev/ttyACM0
+mavlink start -r 10000 -d /dev/ttyACM0 -x
# Enable a number of interesting streams we want via USB
mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10
usleep 100000
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 6d06f897a..8855539fe 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -132,6 +132,10 @@ then
#
if param compare SYS_AUTOCONFIG 1
then
+ # We can't be sure the defaults haven't changed, so
+ # if someone requests a re-configuration, we do it
+ # cleanly from scratch (except autostart / autoconfig)
+ param reset_nostart
set DO_AUTOCONFIG yes
else
set DO_AUTOCONFIG no
@@ -276,6 +280,11 @@ then
nshterm /dev/ttyACM0 &
#
+ # Start the datamanager
+ #
+ dataman start
+
+ #
# Start the Commander (needs to be this early for in-air-restarts)
#
commander start
@@ -428,11 +437,10 @@ then
#
sh /etc/init.d/rc.sensors
- if [ $HIL == no ]
- then
- echo "[init] Start logging"
- sh /etc/init.d/rc.logging
- fi
+ #
+ # Start logging in all modes, including HIL
+ #
+ sh /etc/init.d/rc.logging
if [ $GPS == yes ]
then
@@ -545,11 +553,6 @@ then
fi
#
- # Start the datamanager
- #
- dataman start
-
- #
# Start the navigator
#
navigator start
diff --git a/ROMFS/px4fmu_common/mixers/phantom.mix b/ROMFS/px4fmu_common/mixers/phantom.mix
new file mode 100644
index 000000000..00c37a16c
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/phantom.mix
@@ -0,0 +1,67 @@
+Phantom FX-61 mixer
+===================
+
+This file defines mixers suitable for controlling a delta wing aircraft using
+PX4/Pixhawk. The configuration assumes the elevon servos are connected to
+servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
+assumed to be unused.
+
+Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
+(roll), 1 (pitch) and 3 (thrust).
+
+See the README for more information on the scaler format.
+
+Elevon mixers
+-------------
+Three scalers total (output, roll, pitch).
+
+On the assumption that the two elevon servos are physically reversed, the pitch
+input is inverted between the two servos.
+
+The scaling factor are set so that pitch will have more travel than roll.
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 -6000 -6000 0 -10000 10000
+S: 0 1 6500 6500 0 -10000 10000
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 -6000 -6000 0 -10000 10000
+S: 0 1 -6500 -6500 0 -10000 10000
+
+Output 2
+--------
+This mixer is empty.
+
+Z:
+
+Motor speed mixer
+-----------------
+Two scalers total (output, thrust).
+
+This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
+range. Inputs below zero are treated as zero.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000
+
+Gimbal / flaps / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/wingwing.mix b/ROMFS/px4fmu_common/mixers/wingwing.mix
new file mode 100644
index 000000000..08333ba5c
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/wingwing.mix
@@ -0,0 +1,51 @@
+Delta-wing mixer for PX4FMU
+===========================
+
+Designed for Wing Wing Z-84
+
+This file defines mixers suitable for controlling a delta wing aircraft using
+PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
+servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
+assumed to be unused.
+
+Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
+(roll), 1 (pitch) and 3 (thrust).
+
+See the README for more information on the scaler format.
+
+Elevon mixers
+-------------
+Three scalers total (output, roll, pitch).
+
+On the assumption that the two elevon servos are physically reversed, the pitch
+input is inverted between the two servos.
+
+The scaling factor for roll inputs is adjusted to implement differential travel
+for the elevons.
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 -6000 -6000 0 -10000 10000
+S: 0 1 6500 6500 0 -10000 10000
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 -6000 -6000 0 -10000 10000
+S: 0 1 -6500 -6500 0 -10000 10000
+
+Output 2
+--------
+This mixer is empty.
+
+Z:
+
+Motor speed mixer
+-----------------
+Two scalers total (output, thrust).
+
+This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
+range. Inputs below zero are treated as zero.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000