diff --git a/ROMFS/px4fmu_common/mixers/AAERTWF.main.mix b/ROMFS/px4fmu_common/mixers/AAERTWF.main.mix index 2d6cf285f0..18d8ed802f 100644 --- a/ROMFS/px4fmu_common/mixers/AAERTWF.main.mix +++ b/ROMFS/px4fmu_common/mixers/AAERTWF.main.mix @@ -19,12 +19,10 @@ factors (to reverse the servo movement) and adjust the offset, scaling and endpoints to suit. M: 2 -O: 10000 10000 0 -10000 10000 S: 0 0 10000 10000 0 -10000 10000 S: 0 6 10000 10000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 0 0 10000 10000 0 -10000 10000 S: 0 6 -10000 -10000 0 -10000 10000 @@ -38,7 +36,6 @@ factors (to reverse the servo movement) and adjust the offset, scaling and endpoints to suit. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 1 -10000 -10000 0 -10000 10000 Rudder mixer @@ -51,7 +48,6 @@ factors (to reverse the servo movement) and adjust the offset, scaling and endpoints to suit. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 10000 10000 0 -10000 10000 Motor speed mixer @@ -62,7 +58,6 @@ 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 Wheel mixer @@ -75,7 +70,6 @@ factors (to reverse the servo movement) and adjust the offset, scaling and endpoints to suit. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 10000 10000 0 -10000 10000 @@ -84,13 +78,10 @@ using the payload control group ----------------------------------------------------- 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: 2 0 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 2 2 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/AAVVTWFF.main.mix b/ROMFS/px4fmu_common/mixers/AAVVTWFF.main.mix index e6520862d7..17a2c0bbd6 100644 --- a/ROMFS/px4fmu_common/mixers/AAVVTWFF.main.mix +++ b/ROMFS/px4fmu_common/mixers/AAVVTWFF.main.mix @@ -20,12 +20,10 @@ factors (to reverse the servo movement) and adjust the offset, scaling and endpoints to suit. M: 2 -O: 10000 10000 0 -10000 10000 S: 0 0 10000 10000 0 -10000 10000 S: 0 6 10000 10000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 0 0 10000 10000 0 -10000 10000 S: 0 6 -10000 -10000 0 -10000 10000 @@ -37,12 +35,10 @@ On the assumption that the two tail servos are physically reversed, the pitch input is inverted between the two servos. M: 2 -O: 10000 10000 0 -10000 10000 S: 0 2 -7000 -7000 0 -10000 10000 S: 0 1 -8000 -8000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 0 2 -7000 -7000 0 -10000 10000 S: 0 1 8000 8000 0 -10000 10000 @@ -54,7 +50,6 @@ 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 Wheel mixer @@ -67,7 +62,6 @@ factors (to reverse the servo movement) and adjust the offset, scaling and endpoints to suit. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 -10000 -10000 0 -10000 10000 Flaps mixer @@ -75,10 +69,8 @@ Flaps mixer Flap servos are physically reversed. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 4 0 5000 -10000 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 0 4 0 -5000 10000 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/AERT.main.mix b/ROMFS/px4fmu_common/mixers/AERT.main.mix index 975d520081..9b636cd9ee 100644 --- a/ROMFS/px4fmu_common/mixers/AERT.main.mix +++ b/ROMFS/px4fmu_common/mixers/AERT.main.mix @@ -23,7 +23,6 @@ differences between the servos must be made mechanically. To obtain the correct motion using a Y cable, the servos can be positioned reversed from one another. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 0 10000 10000 0 -10000 10000 CH2: Elevator mixer @@ -36,7 +35,6 @@ factors (to reverse the servo movement) and adjust the offset, scaling and endpoints to suit. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 1 -10000 -10000 0 -10000 10000 CH3: Rudder mixer @@ -49,7 +47,6 @@ factors (to reverse the servo movement) and adjust the offset, scaling and endpoints to suit. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 10000 10000 0 -10000 10000 CH4: Motor speed mixer @@ -60,7 +57,6 @@ 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 CH5: Flaps mixer @@ -77,5 +73,4 @@ Ch6: Landing gear mixer By default pass-through of gear switch M: 1 -O: 10000 10000 0 -10000 10000 S: 3 5 10000 10000 0 -10000 10000 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/mixers/AETRFG.main.mix b/ROMFS/px4fmu_common/mixers/AETRFG.main.mix index 47de4ed3e0..4ebf75fdd0 100644 --- a/ROMFS/px4fmu_common/mixers/AETRFG.main.mix +++ b/ROMFS/px4fmu_common/mixers/AETRFG.main.mix @@ -23,7 +23,6 @@ differences between the servos must be made mechanically. To obtain the correct motion using a Y cable, the servos can be positioned reversed from one another. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 0 10000 10000 0 -10000 10000 CH2: Elevator mixer @@ -36,7 +35,6 @@ factors (to reverse the servo movement) and adjust the offset, scaling and endpoints to suit. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 1 -10000 -10000 0 -10000 10000 CH3: Motor speed mixer @@ -47,7 +45,6 @@ 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 CH4: Rudder mixer @@ -60,7 +57,6 @@ factors (to reverse the servo movement) and adjust the offset, scaling and endpoints to suit. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 10000 10000 0 -10000 10000 CH5: Flaps mixer @@ -77,5 +73,4 @@ CH6: Landing gear mixer By default pass-through of gear switch M: 1 -O: 10000 10000 0 -10000 10000 S: 3 5 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/CCPM.main.mix b/ROMFS/px4fmu_common/mixers/CCPM.main.mix index 1c45b3e59f..311a57285c 100644 --- a/ROMFS/px4fmu_common/mixers/CCPM.main.mix +++ b/ROMFS/px4fmu_common/mixers/CCPM.main.mix @@ -8,7 +8,6 @@ Output 0 - Rear Servo Mixer Rear Servo = Collective (Thrust - 3) + Elevator (Pitch - 1) M: 2 -O: 10000 10000 0 -10000 10000 S: 0 3 10000 10000 0 -10000 10000 S: 0 1 10000 10000 0 -10000 10000 @@ -18,7 +17,6 @@ Output 1 - Left Servo Mixer Left Servo = Collective (Thurst - 3) - 0.5 * Elevator (Pitch - 1) + 0.866 * Aileron (Roll - 0) M: 3 -O: 10000 10000 0 -10000 10000 S: 0 3 -10000 -10000 0 -10000 10000 S: 0 1 -5000 -5000 0 -10000 10000 S: 0 0 8660 8660 0 -10000 10000 @@ -30,7 +28,6 @@ Right Servo = Collective (Thurst - 3) - 0.5 * Elevator (Pitch - 1) - 0.866 * Ail M: 3 -O: 10000 10000 0 -10000 10000 S: 0 3 -10000 -10000 0 -10000 10000 S: 0 1 -5000 -5000 0 -10000 10000 S: 0 0 -8660 -8660 0 -10000 10000 @@ -40,7 +37,6 @@ Output 3 - Tail Servo Mixer Tail Servo = Yaw (control index = 2) M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 10000 10000 0 -10000 10000 @@ -49,5 +45,4 @@ Output 4 - Motor speed mixer This would be the motor speed control output from governor power demand- not sure what index to use here? M: 1 -O: 10000 10000 0 -10000 10000 S: 0 4 0 20000 -10000 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/FMU_pass.mix b/ROMFS/px4fmu_common/mixers/FMU_pass.mix index e9a81f2bb2..2f01459d60 100644 --- a/ROMFS/px4fmu_common/mixers/FMU_pass.mix +++ b/ROMFS/px4fmu_common/mixers/FMU_pass.mix @@ -6,18 +6,14 @@ This file defines passthrough mixers suitable for testing. Channel group 0, channels 0-3 are passed directly through to the outputs. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 0 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 0 1 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 0 3 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/FX79.main.mix b/ROMFS/px4fmu_common/mixers/FX79.main.mix index 3223eff133..a1e0e345cc 100644 --- a/ROMFS/px4fmu_common/mixers/FX79.main.mix +++ b/ROMFS/px4fmu_common/mixers/FX79.main.mix @@ -26,12 +26,10 @@ 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 8500 8500 0 -10000 10000 S: 0 1 9500 9500 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 0 0 8500 8500 0 -10000 10000 S: 0 1 -9500 -9500 0 -10000 10000 @@ -49,5 +47,4 @@ 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 diff --git a/ROMFS/px4fmu_common/mixers/IO_pass.main.mix b/ROMFS/px4fmu_common/mixers/IO_pass.main.mix index 39f875ddb9..fc5877fbba 100644 --- a/ROMFS/px4fmu_common/mixers/IO_pass.main.mix +++ b/ROMFS/px4fmu_common/mixers/IO_pass.main.mix @@ -6,33 +6,25 @@ This file defines passthrough mixers suitable for testing. Channel group 0, channels 0-7 are passed directly through to the outputs. M: 1 -O: 10000 10000 0 -10000 10000 S: 0 0 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 0 1 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 0 3 10000 10000 0 -10000 10000 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/Viper.main.mix b/ROMFS/px4fmu_common/mixers/Viper.main.mix index 5aa3828f29..adc0e96696 100644 --- a/ROMFS/px4fmu_common/mixers/Viper.main.mix +++ b/ROMFS/px4fmu_common/mixers/Viper.main.mix @@ -26,12 +26,10 @@ 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 7500 7500 0 -10000 10000 S: 0 1 8000 8000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 0 0 7500 7500 0 -10000 10000 S: 0 1 -8000 -8000 0 -10000 10000 @@ -49,7 +47,6 @@ 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 Inputs to the mixer come from channel group 2 (payload), channels 0 @@ -57,15 +54,12 @@ Inputs to the mixer come from channel group 2 (payload), channels 0 ----------------------------------------------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 2 0 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 2 1 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 2 2 -8000 -8000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/blade130.main.mix b/ROMFS/px4fmu_common/mixers/blade130.main.mix index d03f19faf5..3cbf49f510 100644 --- a/ROMFS/px4fmu_common/mixers/blade130.main.mix +++ b/ROMFS/px4fmu_common/mixers/blade130.main.mix @@ -12,5 +12,4 @@ S: 220 13054 10000 0 -8000 8000 # Tail servo: M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/caipi.main.mix b/ROMFS/px4fmu_common/mixers/caipi.main.mix index cd06d66914..68eea39b51 100644 --- a/ROMFS/px4fmu_common/mixers/caipi.main.mix +++ b/ROMFS/px4fmu_common/mixers/caipi.main.mix @@ -24,12 +24,10 @@ 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 8000 8000 0 -10000 10000 S: 0 1 9000 9000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 0 0 8000 8000 0 -10000 10000 S: 0 1 -9000 -9000 0 -10000 10000 @@ -47,5 +45,4 @@ 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 diff --git a/ROMFS/px4fmu_common/mixers/claire.aux.mix b/ROMFS/px4fmu_common/mixers/claire.aux.mix index 410db07e64..cdc27fd8ae 100644 --- a/ROMFS/px4fmu_common/mixers/claire.aux.mix +++ b/ROMFS/px4fmu_common/mixers/claire.aux.mix @@ -9,7 +9,6 @@ Tilt mechanism servo mixer M: 1 -O: 10000 10000 0 -10000 10000 S: 1 4 10000 10000 0 -10000 10000 @@ -21,11 +20,9 @@ Elevon mixers M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 -7500 -7500 0 -10000 10000 S: 1 1 7500 7500 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 -7500 -7500 0 -10000 10000 S: 1 1 -7500 -7500 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/coax.main.mix b/ROMFS/px4fmu_common/mixers/coax.main.mix index bcd161cc72..0c99dd3b0b 100644 --- a/ROMFS/px4fmu_common/mixers/coax.main.mix +++ b/ROMFS/px4fmu_common/mixers/coax.main.mix @@ -7,20 +7,17 @@ Coaxial helicopter mixer Left swashplate servomotor, pitch axis ------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 0 1 -10000 -10000 0 -10000 10000 Right swashplate servomotor, roll axis ------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 0 0 10000 10000 0 -10000 10000 Upper rotor (CCW) Mixing between yaw and thrust ------------- M: 2 -O: 10000 10000 0 -10000 10000 S: 0 2 10000 10000 0 -10000 10000 S: 0 3 0 20000 -10000 -10000 10000 @@ -28,6 +25,5 @@ Lower rotor (CW) Mixing between yaw and thrust ------------- M: 2 -O: 10000 10000 0 -10000 10000 S: 0 2 -10000 -10000 0 -10000 10000 S: 0 3 0 20000 -10000 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/delta.main.mix b/ROMFS/px4fmu_common/mixers/delta.main.mix index cb22b74ae5..6188948ee7 100644 --- a/ROMFS/px4fmu_common/mixers/delta.main.mix +++ b/ROMFS/px4fmu_common/mixers/delta.main.mix @@ -22,12 +22,10 @@ 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 3000 5000 0 -10000 10000 S: 0 1 5000 5000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 0 0 5000 3000 0 -10000 10000 S: 0 1 -5000 -5000 0 -10000 10000 @@ -45,5 +43,4 @@ 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 diff --git a/ROMFS/px4fmu_common/mixers/deltaquad.main.mix b/ROMFS/px4fmu_common/mixers/deltaquad.main.mix index e9a9ef1bd6..f615b24c66 100644 --- a/ROMFS/px4fmu_common/mixers/deltaquad.main.mix +++ b/ROMFS/px4fmu_common/mixers/deltaquad.main.mix @@ -18,7 +18,6 @@ input is inverted between the two servos. ------------- M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 -8000 -8000 0 -10000 10000 S: 1 1 8000 8000 0 -10000 10000 @@ -26,7 +25,6 @@ S: 1 1 8000 8000 0 -10000 10000 ------------- M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 -8000 -8000 0 -10000 10000 S: 1 1 -8000 -8000 0 -10000 10000 @@ -39,12 +37,10 @@ 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: 1 3 0 20000 -10000 -10000 10000 8: Reverse thrust (brake) mixer ----------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 1 6 0 20000 -9000 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/firefly6.aux.mix b/ROMFS/px4fmu_common/mixers/firefly6.aux.mix index 8e31007ff1..ddc150984a 100644 --- a/ROMFS/px4fmu_common/mixers/firefly6.aux.mix +++ b/ROMFS/px4fmu_common/mixers/firefly6.aux.mix @@ -4,23 +4,19 @@ Tilt mechanism servo mixer --------------------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 1 4 0 20000 -10000 -10000 10000 Elevon mixers ------------- M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 -7500 -7500 0 -10000 10000 S: 1 1 8000 8000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 -7500 -7500 0 -10000 10000 S: 1 1 -8000 -8000 0 -10000 10000 Landing gear mixer ------------------ M: 1 -O: 10000 10000 0 -10000 10000 S: 3 6 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/fw_generic_wing.main.mix b/ROMFS/px4fmu_common/mixers/fw_generic_wing.main.mix index b33afc15fe..eedf427f57 100644 --- a/ROMFS/px4fmu_common/mixers/fw_generic_wing.main.mix +++ b/ROMFS/px4fmu_common/mixers/fw_generic_wing.main.mix @@ -22,12 +22,10 @@ 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 -8000 -8000 0 -10000 10000 S: 0 1 6000 6000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 0 0 -8000 -8000 0 -10000 10000 S: 0 1 -6000 -6000 0 -10000 10000 @@ -45,5 +43,4 @@ 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 diff --git a/ROMFS/px4fmu_common/mixers/mount.aux.mix b/ROMFS/px4fmu_common/mixers/mount.aux.mix index 0edaa07811..e2c817ee0a 100644 --- a/ROMFS/px4fmu_common/mixers/mount.aux.mix +++ b/ROMFS/px4fmu_common/mixers/mount.aux.mix @@ -3,21 +3,17 @@ # pitch M: 1 -O: 10000 10000 0 -10000 10000 S: 2 1 10000 10000 0 -10000 10000 # roll M: 1 -O: 10000 10000 0 -10000 10000 S: 2 0 10000 10000 0 -10000 10000 # yaw M: 1 -O: 10000 10000 0 -10000 10000 S: 2 2 10000 10000 0 -10000 10000 # Shutter/retract M: 1 -O: 10000 10000 0 -10000 10000 S: 2 3 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/mount_legs.aux.mix b/ROMFS/px4fmu_common/mixers/mount_legs.aux.mix index 14bae025e6..4bfa035d41 100644 --- a/ROMFS/px4fmu_common/mixers/mount_legs.aux.mix +++ b/ROMFS/px4fmu_common/mixers/mount_legs.aux.mix @@ -1,27 +1,22 @@ # Roll channel for mount M: 1 -O: 10000 10000 0 -10000 10000 S: 2 0 10000 10000 0 -10000 10000 # Pitch channel for mount M: 1 -O: 10000 10000 0 -10000 10000 S: 2 1 10000 10000 0 -10000 10000 # Yaw channel for mount M: 1 -O: 10000 10000 0 -10000 10000 S: 2 2 10000 10000 0 -10000 10000 # mixer for left leg M: 1 -O: 10000 10000 0 -10000 10000 S: 0 7 0 20000 -10000 -10000 10000 # mixer for right leg M: 1 -O: 10000 10000 0 -10000 10000 S: 0 7 0 20000 -10000 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/pass.aux.mix b/ROMFS/px4fmu_common/mixers/pass.aux.mix index 8e7011f0ed..26e991f032 100644 --- a/ROMFS/px4fmu_common/mixers/pass.aux.mix +++ b/ROMFS/px4fmu_common/mixers/pass.aux.mix @@ -2,20 +2,16 @@ # AUX1 channel (select RC channel with RC_MAP_AUX1 param) M: 1 -O: 10000 10000 0 -10000 10000 S: 3 5 10000 10000 0 -10000 10000 # AUX2 channel (select RC channel with RC_MAP_AUX2 param) M: 1 -O: 10000 10000 0 -10000 10000 S: 3 6 10000 10000 0 -10000 10000 # AUX3 channel (select RC channel with RC_MAP_AUX3 param) M: 1 -O: 10000 10000 0 -10000 10000 S: 3 7 10000 10000 0 -10000 10000 # FLAPS channel (select RC channel with RC_MAP_FLAPS param) M: 1 -O: 10000 10000 0 -10000 10000 S: 3 4 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/phantom.main.mix b/ROMFS/px4fmu_common/mixers/phantom.main.mix index 328073054a..0e5c2df55c 100644 --- a/ROMFS/px4fmu_common/mixers/phantom.main.mix +++ b/ROMFS/px4fmu_common/mixers/phantom.main.mix @@ -21,12 +21,10 @@ 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 @@ -44,5 +42,4 @@ 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 diff --git a/ROMFS/px4fmu_common/mixers/quad_+.main.mix b/ROMFS/px4fmu_common/mixers/quad_+.main.mix index 0c582e8772..e21ce44c71 100644 --- a/ROMFS/px4fmu_common/mixers/quad_+.main.mix +++ b/ROMFS/px4fmu_common/mixers/quad_+.main.mix @@ -10,9 +10,7 @@ Gimbal / payload mixer for last two channels ----------------------------------------------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 3 5 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 3 6 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/quad_+_vtol.main.mix b/ROMFS/px4fmu_common/mixers/quad_+_vtol.main.mix index 3021221d80..258b6af168 100644 --- a/ROMFS/px4fmu_common/mixers/quad_+_vtol.main.mix +++ b/ROMFS/px4fmu_common/mixers/quad_+_vtol.main.mix @@ -8,21 +8,17 @@ R: 4+ 10000 10000 10000 0 # mixer for the elevons M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 10000 10000 0 -10000 10000 S: 1 1 10000 10000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 10000 10000 0 -10000 10000 S: 1 1 -10000 -10000 0 -10000 10000 # mixer for canard surface M: 1 -O: 10000 10000 0 -10000 10000 S: 1 1 -10000 -10000 0 -10000 10000 # mixer for rudder M: 1 -O: 10000 10000 0 -10000 10000 S: 1 2 -10000 -10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/quad_h.main.mix b/ROMFS/px4fmu_common/mixers/quad_h.main.mix index e0b0193e3d..8048b44317 100644 --- a/ROMFS/px4fmu_common/mixers/quad_h.main.mix +++ b/ROMFS/px4fmu_common/mixers/quad_h.main.mix @@ -10,9 +10,7 @@ Gimbal / payload mixer for last two channels ----------------------------------------------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 3 5 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 3 6 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/quad_s250aq.main.mix b/ROMFS/px4fmu_common/mixers/quad_s250aq.main.mix index 549ff3a41c..1fb38039dc 100644 --- a/ROMFS/px4fmu_common/mixers/quad_s250aq.main.mix +++ b/ROMFS/px4fmu_common/mixers/quad_s250aq.main.mix @@ -1,7 +1,5 @@ R: 4s 10000 10000 10000 0 M: 1 -O: 10000 10000 0 -10000 10000 S: 3 5 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 3 6 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/quad_w.main.mix b/ROMFS/px4fmu_common/mixers/quad_w.main.mix index b93238c32a..9ec4e6c8b9 100644 --- a/ROMFS/px4fmu_common/mixers/quad_w.main.mix +++ b/ROMFS/px4fmu_common/mixers/quad_w.main.mix @@ -9,9 +9,7 @@ Gimbal / payload mixer for last two channels ----------------------------------------------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 3 5 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 3 6 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/quad_x.main.mix b/ROMFS/px4fmu_common/mixers/quad_x.main.mix index bf034e7c1f..94514e76b4 100644 --- a/ROMFS/px4fmu_common/mixers/quad_x.main.mix +++ b/ROMFS/px4fmu_common/mixers/quad_x.main.mix @@ -1,7 +1,5 @@ R: 4x 10000 10000 10000 0 M: 1 -O: 10000 10000 0 -10000 10000 S: 3 5 10000 10000 0 -10000 10000 M: 1 -O: 10000 10000 0 -10000 10000 S: 3 6 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix b/ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix index 12bd885dce..689d677109 100644 --- a/ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix +++ b/ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix @@ -10,17 +10,14 @@ Z: # left elevon M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 5000 5000 0 -10000 10000 S: 1 1 5000 5000 0 -10000 10000 # right elevon M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 5000 5000 0 -10000 10000 S: 1 1 -5000 -5000 0 -10000 10000 # mixer for the virtual elevator M: 1 -O: 10000 10000 0 -10000 10000 S: 1 1 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/quad_x_vtol_sim.main.mix b/ROMFS/px4fmu_common/mixers/quad_x_vtol_sim.main.mix index bfe0b5f654..fd6f11cf26 100644 --- a/ROMFS/px4fmu_common/mixers/quad_x_vtol_sim.main.mix +++ b/ROMFS/px4fmu_common/mixers/quad_x_vtol_sim.main.mix @@ -7,15 +7,12 @@ Z: # left elevon M: 1 -O: 10000 10000 0 -10000 10000 S: 1 0 10000 10000 0 -10000 10000 # right elevon M: 1 -O: 10000 10000 0 -10000 10000 S: 1 0 -10000 -10000 0 -10000 10000 # mixer for the virtual elevator M: 1 -O: 10000 10000 0 -10000 10000 S: 1 1 -10000 -10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/stampede.main.mix b/ROMFS/px4fmu_common/mixers/stampede.main.mix index 6ab22d8300..e9ed0fc024 100644 --- a/ROMFS/px4fmu_common/mixers/stampede.main.mix +++ b/ROMFS/px4fmu_common/mixers/stampede.main.mix @@ -20,7 +20,6 @@ Z: Steering mixer using roll on output 1 --------------------------------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 10000 10000 0 -10000 10000 @@ -33,5 +32,4 @@ Z: Output 3 --------------------------------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 0 3 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/tri_y_yaw+.main.mix b/ROMFS/px4fmu_common/mixers/tri_y_yaw+.main.mix index 6cf826cd45..0cbb082dac 100644 --- a/ROMFS/px4fmu_common/mixers/tri_y_yaw+.main.mix +++ b/ROMFS/px4fmu_common/mixers/tri_y_yaw+.main.mix @@ -8,5 +8,4 @@ R: 3y 10000 10000 10000 0 # Yaw Servo M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/tri_y_yaw-.main.mix b/ROMFS/px4fmu_common/mixers/tri_y_yaw-.main.mix index 3342a5f1de..c2c7fad6a6 100644 --- a/ROMFS/px4fmu_common/mixers/tri_y_yaw-.main.mix +++ b/ROMFS/px4fmu_common/mixers/tri_y_yaw-.main.mix @@ -8,6 +8,5 @@ R: 3y 10000 10000 10000 0 # Yaw Servo M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 -10000 -10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/ugv_generic.main.mix b/ROMFS/px4fmu_common/mixers/ugv_generic.main.mix index aacfef1f5b..9605ee3edd 100644 --- a/ROMFS/px4fmu_common/mixers/ugv_generic.main.mix +++ b/ROMFS/px4fmu_common/mixers/ugv_generic.main.mix @@ -20,7 +20,6 @@ Z: Steering mixer using roll on output 1 --------------------------------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 0 2 10000 10000 0 -10000 10000 @@ -33,5 +32,4 @@ Z: Output 3 --------------------------------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 0 3 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/vtol_AAERT.aux.mix b/ROMFS/px4fmu_common/mixers/vtol_AAERT.aux.mix index f3e9c42354..b6d4756e9d 100644 --- a/ROMFS/px4fmu_common/mixers/vtol_AAERT.aux.mix +++ b/ROMFS/px4fmu_common/mixers/vtol_AAERT.aux.mix @@ -4,29 +4,24 @@ Mixer for an AAERT VTOL Aileron 1 mixer --------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 1 0 -7500 -7500 0 -10000 10000 Aileron 2 mixer --------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 1 0 -7500 -7500 0 -10000 10000 Elevator mixer -------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 1 1 10000 10000 0 -10000 10000 Rudder mixer ------------ M: 1 -O: 10000 10000 0 -10000 10000 S: 1 2 -10000 -10000 0 -10000 10000 Throttle mixer -------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 1 3 0 20000 -10000 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/vtol_AAVVT.aux.mix b/ROMFS/px4fmu_common/mixers/vtol_AAVVT.aux.mix index 86581585c2..70ec007c53 100644 --- a/ROMFS/px4fmu_common/mixers/vtol_AAVVT.aux.mix +++ b/ROMFS/px4fmu_common/mixers/vtol_AAVVT.aux.mix @@ -19,12 +19,10 @@ factors (to reverse the servo movement) and adjust the offset, scaling and endpoints to suit. M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 10000 10000 0 -10000 10000 S: 1 6 10000 10000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 10000 10000 0 -10000 10000 S: 1 6 -10000 -10000 0 -10000 10000 @@ -37,12 +35,10 @@ On the assumption that the two tail servos are physically reversed, the pitch input is inverted between the two servos. M: 2 -O: 10000 10000 0 -10000 10000 S: 1 2 -7000 -7000 0 -10000 10000 S: 1 1 -8000 -8000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 1 2 -7000 -7000 0 -10000 10000 S: 1 1 8000 8000 0 -10000 10000 @@ -54,6 +50,5 @@ 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: 1 3 0 20000 -10000 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/vtol_convergence.main.mix b/ROMFS/px4fmu_common/mixers/vtol_convergence.main.mix index 38afd90189..80db1600b9 100644 --- a/ROMFS/px4fmu_common/mixers/vtol_convergence.main.mix +++ b/ROMFS/px4fmu_common/mixers/vtol_convergence.main.mix @@ -9,24 +9,20 @@ Tilt mechanism servo mixer --------------------------- #RIGHT up:2000 down:1000 M: 2 -O: 10000 10000 0 -10000 10000 S: 1 4 0 -20000 10000 -10000 10000 S: 0 2 8000 8000 0 -10000 10000 #LEFT up:1000 down:2000 M: 2 -O: 10000 10000 0 -10000 10000 S: 1 4 0 20000 -10000 -10000 10000 S: 0 2 8000 8000 0 -10000 10000 Elevon mixers ------------- M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 -7500 -7500 0 -10000 10000 S: 1 1 8000 8000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 -7500 -7500 0 -10000 10000 S: 1 1 -8000 -8000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/vtol_delta.aux.mix b/ROMFS/px4fmu_common/mixers/vtol_delta.aux.mix index 20a9149ae6..26bb2045d0 100644 --- a/ROMFS/px4fmu_common/mixers/vtol_delta.aux.mix +++ b/ROMFS/px4fmu_common/mixers/vtol_delta.aux.mix @@ -18,12 +18,10 @@ On the assumption that the two elevon servos are physically reversed, the pitch input is inverted between the two servos. M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 -8000 -8000 0 -10000 10000 S: 1 1 8000 8000 0 -10000 10000 M: 2 -O: 10000 10000 0 -10000 10000 S: 1 0 -8000 -8000 0 -10000 10000 S: 1 1 -8000 -8000 0 -10000 10000 @@ -35,7 +33,6 @@ 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: 1 3 0 20000 -10000 -10000 10000 @@ -43,7 +40,6 @@ Reverse thrust (brake) mixer ----------------- M: 1 -O: 10000 10000 0 -10000 10000 S: 1 6 0 20000 -10000 -10000 10000 @@ -52,5 +48,4 @@ Aux1 mixer This is actuated on the AUX5 port M: 1 -O: 10000 10000 0 -10000 10000 S: 3 5 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/wingwing.main.mix b/ROMFS/px4fmu_common/mixers/wingwing.main.mix index 08333ba5cf..8b937599a2 100644 --- a/ROMFS/px4fmu_common/mixers/wingwing.main.mix +++ b/ROMFS/px4fmu_common/mixers/wingwing.main.mix @@ -24,12 +24,10 @@ 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 @@ -47,5 +45,4 @@ 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 diff --git a/ROMFS/px4fmu_common/mixers/zmr250.main.mix b/ROMFS/px4fmu_common/mixers/zmr250.main.mix index 5d3fb0ddb0..c94b1670ed 100644 --- a/ROMFS/px4fmu_common/mixers/zmr250.main.mix +++ b/ROMFS/px4fmu_common/mixers/zmr250.main.mix @@ -5,9 +5,7 @@ R: 4x 7654 10000 10000 0 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 diff --git a/src/lib/mixer/mixer.cpp b/src/lib/mixer/mixer.cpp index 54ed4d4c46..6dda03776d 100644 --- a/src/lib/mixer/mixer.cpp +++ b/src/lib/mixer/mixer.cpp @@ -40,6 +40,7 @@ #include "mixer.h" #include +#include #define debug(fmt, args...) do { } while(0) //#define debug(fmt, args...) do { printf("[mixer] " fmt "\n", ##args); } while(0) @@ -125,6 +126,21 @@ Mixer::findtag(const char *buf, unsigned &buflen, char tag) return nullptr; } +char +Mixer::findnexttag(const char *buf, unsigned buflen) +{ + while (buflen >= 2) { + if (isupper(buf[0]) && buf[1] == ':') { + return buf[0]; + } + + buf++; + buflen--; + } + + return 0; +} + const char * Mixer::skipline(const char *buf, unsigned &buflen) { diff --git a/src/lib/mixer/mixer.h b/src/lib/mixer/mixer.h index 6fed7a6831..04f7a29ec1 100644 --- a/src/lib/mixer/mixer.h +++ b/src/lib/mixer/mixer.h @@ -265,6 +265,14 @@ protected: */ static const char *findtag(const char *buf, unsigned &buflen, char tag); + /** + * Find next tag and return it (0 is returned if no tag is found) + * + * @param buf The buffer to operate on. + * @param buflen length of the buffer. + */ + static char findnexttag(const char *buf, unsigned buflen); + /** * Skip a line * @@ -340,6 +348,7 @@ public: * M: * O: <-ve scale> <+ve scale> * + * The second line O: can be omitted. In that case 'O: 10000 10000 0 -10000 10000' is used. * The definition continues with entries describing the control * inputs and their scaling, in the form: * diff --git a/src/lib/mixer/mixer_simple.cpp b/src/lib/mixer/mixer_simple.cpp index ce9693dc5e..94cc725713 100644 --- a/src/lib/mixer/mixer_simple.cpp +++ b/src/lib/mixer/mixer_simple.cpp @@ -151,6 +151,7 @@ SimpleMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handle, c unsigned inputs; int used; const char *end = buf + buflen; + char next_tag; /* enforce that the mixer ends with a new line */ if (!string_well_formed(buf, buflen)) { @@ -163,6 +164,12 @@ SimpleMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handle, c goto out; } + /* at least 1 input is required */ + if (inputs == 0) { + debug("simple parse got 0 inputs"); + goto out; + } + buf = skipline(buf, buflen); if (buf == nullptr) { @@ -179,9 +186,27 @@ SimpleMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handle, c mixinfo->control_count = inputs; - if (parse_output_scaler(end - buflen, buflen, mixinfo->output_scaler)) { - debug("simple mixer parser failed parsing out scaler tag, ret: '%s'", buf); - goto out; + /* find the next tag */ + next_tag = findnexttag(end - buflen, buflen); + + if (next_tag == 'S') { + + /* No output scalers specified. Use default values. + * Corresponds to: + * O: 10000 10000 0 -10000 10000 + */ + mixinfo->output_scaler.negative_scale = 1.0f; + mixinfo->output_scaler.positive_scale = 1.0f; + mixinfo->output_scaler.offset = 0.f; + mixinfo->output_scaler.min_output = -1.0f; + mixinfo->output_scaler.max_output = 1.0f; + + } else { + + if (parse_output_scaler(end - buflen, buflen, mixinfo->output_scaler)) { + debug("simple mixer parser failed parsing out scaler tag, ret: '%s'", buf); + goto out; + } } for (unsigned i = 0; i < inputs; i++) {