aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-02-11 08:09:51 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-02-11 08:09:51 +0100
commit0388d9adefb33c98f1e4350e3f2ed59a7fdd5359 (patch)
tree0f9a6f8378e70a0ce728f6fbd8721b5f3227c276 /ROMFS/px4fmu_common
parent80100dcf198049e456e663870252622ad3da2b40 (diff)
downloadpx4-firmware-0388d9adefb33c98f1e4350e3f2ed59a7fdd5359.tar.gz
px4-firmware-0388d9adefb33c98f1e4350e3f2ed59a7fdd5359.tar.bz2
px4-firmware-0388d9adefb33c98f1e4350e3f2ed59a7fdd5359.zip
Hotfix and cleanup for system mixers
Diffstat (limited to 'ROMFS/px4fmu_common')
-rw-r--r--ROMFS/px4fmu_common/init.d/11001_hexa_cox39
-rw-r--r--ROMFS/px4fmu_common/init.d/12001_octo_cox (renamed from ROMFS/px4fmu_common/init.d/12001_octo_cox_pwm)4
-rw-r--r--ROMFS/px4fmu_common/init.d/6001_hexa_x_pwm2
-rw-r--r--ROMFS/px4fmu_common/init.d/7001_hexa_+_pwm2
-rw-r--r--ROMFS/px4fmu_common/init.d/8001_octo_x_pwm2
-rw-r--r--ROMFS/px4fmu_common/init.d/9001_octo_+_pwm2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.autostart11
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS12
-rw-r--r--ROMFS/px4fmu_common/mixers/FMU_hex_+.mix17
-rw-r--r--ROMFS/px4fmu_common/mixers/FMU_hex_x.mix17
-rw-r--r--ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix6
-rw-r--r--ROMFS/px4fmu_common/mixers/FMU_octo_x.mix6
-rw-r--r--ROMFS/px4fmu_common/mixers/README154
-rw-r--r--ROMFS/px4fmu_common/mixers/hexa_cox.mix3
14 files changed, 70 insertions, 207 deletions
diff --git a/ROMFS/px4fmu_common/init.d/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
new file mode 100644
index 000000000..2dc83a517
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
@@ -0,0 +1,39 @@
+#!nsh
+#
+# UNTESTED UNTESTED!
+#
+# Generic 10” Hexa coaxial geometry
+#
+# 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
+
+set VEHICLE_TYPE mc
+set MIXER hexa_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/12001_octo_cox_pwm b/ROMFS/px4fmu_common/init.d/12001_octo_cox
index 5f3cec4e0..a55fc5a30 100644
--- a/ROMFS/px4fmu_common/init.d/12001_octo_cox_pwm
+++ b/ROMFS/px4fmu_common/init.d/12001_octo_cox
@@ -2,7 +2,7 @@
#
# Generic 10” Octo coaxial geometry
#
-# Maintainers: Lorenz Meier <lm@inf.ethz.ch>
+# Lorenz Meier <lm@inf.ethz.ch>
#
if [ $DO_AUTOCONFIG == yes ]
@@ -29,7 +29,7 @@ fi
set VEHICLE_TYPE mc
set MIXER FMU_octo_cox
-set PWM_OUTPUTS 1234
+set PWM_OUTPUTS 12345678
set PWM_RATE 400
# DJI ESC range
set PWM_DISARMED 900
diff --git a/ROMFS/px4fmu_common/init.d/6001_hexa_x_pwm b/ROMFS/px4fmu_common/init.d/6001_hexa_x_pwm
index ddec8f36e..447796709 100644
--- a/ROMFS/px4fmu_common/init.d/6001_hexa_x_pwm
+++ b/ROMFS/px4fmu_common/init.d/6001_hexa_x_pwm
@@ -29,7 +29,7 @@ fi
set VEHICLE_TYPE mc
set MIXER FMU_hexa_x
-set PWM_OUTPUTS 1234
+set PWM_OUTPUTS 12345678
set PWM_RATE 400
# DJI ESC range
set PWM_DISARMED 900
diff --git a/ROMFS/px4fmu_common/init.d/7001_hexa_+_pwm b/ROMFS/px4fmu_common/init.d/7001_hexa_+_pwm
index 106e0fb54..c4e9560d1 100644
--- a/ROMFS/px4fmu_common/init.d/7001_hexa_+_pwm
+++ b/ROMFS/px4fmu_common/init.d/7001_hexa_+_pwm
@@ -29,7 +29,7 @@ fi
set VEHICLE_TYPE mc
set MIXER FMU_hexa_+
-set PWM_OUTPUTS 1234
+set PWM_OUTPUTS 12345678
set PWM_RATE 400
# DJI ESC range
set PWM_DISARMED 900
diff --git a/ROMFS/px4fmu_common/init.d/8001_octo_x_pwm b/ROMFS/px4fmu_common/init.d/8001_octo_x_pwm
index f0eea339b..ea56195d4 100644
--- a/ROMFS/px4fmu_common/init.d/8001_octo_x_pwm
+++ b/ROMFS/px4fmu_common/init.d/8001_octo_x_pwm
@@ -29,7 +29,7 @@ fi
set VEHICLE_TYPE mc
set MIXER FMU_octo_x
-set PWM_OUTPUTS 1234
+set PWM_OUTPUTS 12345678
set PWM_RATE 400
# DJI ESC range
set PWM_DISARMED 900
diff --git a/ROMFS/px4fmu_common/init.d/9001_octo_+_pwm b/ROMFS/px4fmu_common/init.d/9001_octo_+_pwm
index 992a7aeba..f7693875c 100644
--- a/ROMFS/px4fmu_common/init.d/9001_octo_+_pwm
+++ b/ROMFS/px4fmu_common/init.d/9001_octo_+_pwm
@@ -29,7 +29,7 @@ fi
set VEHICLE_TYPE mc
set MIXER FMU_octo_+
-set PWM_OUTPUTS 1234
+set PWM_OUTPUTS 12345678
set PWM_RATE 400
# DJI ESC range
set PWM_DISARMED 900
diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart
index 00baed646..38b1cb57e 100644
--- a/ROMFS/px4fmu_common/init.d/rc.autostart
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -186,10 +186,19 @@ then
fi
#
+# Hexa Coaxial
+#
+
+if param compare SYS_AUTOSTART 11001
+then
+ sh /etc/init.d/11001_hexa_cox
+fi
+
+#
# Octo Coaxial
#
if param compare SYS_AUTOSTART 12001
then
- sh /etc/init.d/12001_octo_cox_pwm
+ sh /etc/init.d/12001_octo_cox
fi
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 6f4e1f3b5..50ac9759a 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -467,19 +467,23 @@ then
# Use mixer to detect vehicle type
if [ $MIXER == FMU_hex_x -o $MIXER == FMU_hex_+ ]
then
- param set MAV_TYPE 13
+ set MAV_TYPE 13
+ fi
+ if [ $MIXER == hexa_cox ]
+ then
+ set MAV_TYPE 13
fi
if [ $MIXER == FMU_octo_x -o $MIXER == FMU_octo_+ ]
then
- param set MAV_TYPE 14
+ set MAV_TYPE 14
fi
if [ $MIXER == FMU_octo_cox ]
then
- param set MAV_TYPE 14
+ set MAV_TYPE 14
fi
fi
- param set MAV_TYPE $MAV_TYPE
+ param set MAV_TYPE $MAV_TYPE
# Load mixer and configure outputs
sh /etc/init.d/rc.interface
diff --git a/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix b/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix
index f8f9f0e4d..e608b459f 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix
@@ -1,18 +1,3 @@
-Multirotor mixer for PX4FMU
-===========================
-
-This file defines a single mixer for a hexacopter in the + configuration. All controls
-are mixed 100%.
+# Hexa +
R: 6+ 10000 10000 10000 0
-
-Gimbal / payload mixer for last two channels
------------------------------------------------------
-
-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/FMU_hex_x.mix b/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix
index 26b40b9e9..16e6e22f9 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix
@@ -1,18 +1,3 @@
-Multirotor mixer for PX4FMU
-===========================
-
-This file defines a single mixer for a hexacopter in the X configuration. All controls
-are mixed 100%.
+# Hexa X
R: 6x 10000 10000 10000 0
-
-Gimbal / payload mixer for last two channels
------------------------------------------------------
-
-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/FMU_octo_cox.mix b/ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix
index 51cebb785..f7845450d 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix
@@ -1,7 +1,3 @@
-Multirotor mixer for PX4FMU
-===========================
-
-This file defines a single mixer for a Coaxial Octocopter in the X configuration. All controls
-are mixed 100%.
+# Octo coaxial
R: 8c 10000 10000 10000 0
diff --git a/ROMFS/px4fmu_common/mixers/FMU_octo_x.mix b/ROMFS/px4fmu_common/mixers/FMU_octo_x.mix
index edc71f013..c9a348aa4 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_octo_x.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_octo_x.mix
@@ -1,7 +1,3 @@
-Multirotor mixer for PX4FMU
-===========================
-
-This file defines a single mixer for a octocopter in the X configuration. All controls
-are mixed 100%.
+# Octo X
R: 8x 10000 10000 10000 0
diff --git a/ROMFS/px4fmu_common/mixers/README b/ROMFS/px4fmu_common/mixers/README
deleted file mode 100644
index 6649c53c2..000000000
--- a/ROMFS/px4fmu_common/mixers/README
+++ /dev/null
@@ -1,154 +0,0 @@
-PX4 mixer definitions
-=====================
-
-Files in this directory implement example mixers that can be used as a basis
-for customisation, or for general testing purposes.
-
-Mixer basics
-------------
-
-Mixers combine control values from various sources (control tasks, user inputs,
-etc.) and produce output values suitable for controlling actuators; servos,
-motors, switches and so on.
-
-An actuator derives its value from the combination of one or more control
-values. Each of the control values is scaled according to the actuator's
-configuration and then combined to produce the actuator value, which may then be
-further scaled to suit the specific output type.
-
-Internally, all scaling is performed using floating point values. Inputs and
-outputs are clamped to the range -1.0 to 1.0.
-
-control control control
- | | |
- v v v
- scale scale scale
- | | |
- | v |
- +-------> mix <------+
- |
- scale
- |
- v
- out
-
-Scaling
--------
-
-Basic scalers provide linear scaling of the input to the output.
-
-Each scaler allows the input value to be scaled independently for inputs
-greater/less than zero. An offset can be applied to the output, and lower and
-upper boundary constraints can be applied. Negative scaling factors cause the
-output to be inverted (negative input produces positive output).
-
-Scaler pseudocode:
-
-if (input < 0)
- output = (input * NEGATIVE_SCALE) + OFFSET
-else
- output = (input * POSITIVE_SCALE) + OFFSET
-
-if (output < LOWER_LIMIT)
- output = LOWER_LIMIT
-if (output > UPPER_LIMIT)
- output = UPPER_LIMIT
-
-Syntax
-------
-
-Mixer definitions are text files; lines beginning with a single capital letter
-followed by a colon are significant. All other lines are ignored, meaning that
-explanatory text can be freely mixed with the definitions.
-
-Each file may define more than one mixer; the allocation of mixers to actuators
-is specific to the device reading the mixer definition, and the number of
-actuator outputs generated by a mixer is specific to the mixer.
-
-A mixer begins with a line of the form
-
- <tag>: <mixer arguments>
-
-The tag selects the mixer type; 'M' for a simple summing mixer, 'R' for a
-multirotor mixer, etc.
-
-Null Mixer
-..........
-
-A null mixer consumes no controls and generates a single actuator output whose
-value is always zero. Typically a null mixer is used as a placeholder in a
-collection of mixers in order to achieve a specific pattern of actuator outputs.
-
-The null mixer definition has the form:
-
- Z:
-
-Simple Mixer
-............
-
-A simple mixer combines zero or more control inputs into a single actuator
-output. Inputs are scaled, and the mixing function sums the result before
-applying an output scaler.
-
-A simple mixer definition begins with:
-
- M: <control count>
- O: <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
-
-If <control count> is zero, the sum is effectively zero and the mixer will
-output a fixed value that is <offset> constrained by <lower limit> and <upper
-limit>.
-
-The second line defines the output scaler with scaler parameters as discussed
-above. Whilst the calculations are performed as floating-point operations, the
-values stored in the definition file are scaled by a factor of 10000; i.e. an
-offset of -0.5 is encoded as -5000.
-
-The definition continues with <control count> entries describing the control
-inputs and their scaling, in the form:
-
- S: <group> <index> <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
-
-The <group> value identifies the control group from which the scaler will read,
-and the <index> value an offset within that group. These values are specific to
-the device reading the mixer definition.
-
-When used to mix vehicle controls, mixer group zero is the vehicle attitude
-control group, and index values zero through three are normally roll, pitch,
-yaw and thrust respectively.
-
-The remaining fields on the line configure the control scaler with parameters as
-discussed above. Whilst the calculations are performed as floating-point
-operations, the values stored in the definition file are scaled by a factor of
-10000; i.e. an offset of -0.5 is encoded as -5000.
-
-Multirotor Mixer
-................
-
-The multirotor mixer combines four control inputs (roll, pitch, yaw, thrust)
-into a set of actuator outputs intended to drive motor speed controllers.
-
-The mixer definition is a single line of the form:
-
-R: <geometry> <roll scale> <pitch scale> <yaw scale> <deadband>
-
-The supported geometries include:
-
- 4x - quadrotor in X configuration
- 4+ - quadrotor in + configuration
- 6x - hexcopter in X configuration
- 6+ - hexcopter in + configuration
- 8x - octocopter in X configuration
- 8+ - octocopter in + configuration
-
-Each of the roll, pitch and yaw scale values determine scaling of the roll,
-pitch and yaw controls relative to the thrust control. Whilst the calculations
-are performed as floating-point operations, the values stored in the definition
-file are scaled by a factor of 10000; i.e. an factor of 0.5 is encoded as 5000.
-
-Roll, pitch and yaw inputs are expected to range from -1.0 to 1.0, whilst the
-thrust input ranges from 0.0 to 1.0. Output for each actuator is in the
-range -1.0 to 1.0.
-
-In the case where an actuator saturates, all actuator values are rescaled so that
-the saturating actuator is limited to 1.0.
diff --git a/ROMFS/px4fmu_common/mixers/hexa_cox.mix b/ROMFS/px4fmu_common/mixers/hexa_cox.mix
new file mode 100644
index 000000000..497786feb
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/hexa_cox.mix
@@ -0,0 +1,3 @@
+# Hexa coaxial
+
+R: 6c 10000 10000 10000 0