Skip to content
Snippets Groups Projects
Commit 95f17d56 authored by Daniel Agar's avatar Daniel Agar
Browse files

px4fmu_test update mixers

parent 45eb9cb5
No related branches found
No related tags found
No related merge requests found
Showing
with 589 additions and 25 deletions
Aileron/rudder/elevator/throttle/wheel/flaps mixer for PX4FMU
=======================================================
This file defines mixers suitable for controlling a fixed wing aircraft with
aileron, rudder, elevator, throttle and steerable wheel controls using PX4FMU.
The configuration assumes the aileron servo(s) are connected to PX4FMU servo
output 0 and 1, the elevator to output 2, the rudder to output 3, the throttle
to output 4 and the wheel to output 5.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps).
Aileron mixer (roll + flaperon)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
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
Elevator mixer
------------
Two scalers total (output, roll).
This mixer assumes that the elevator servo is set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
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
------------
Two scalers total (output, yaw).
This mixer assumes that the rudder servo is set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
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
-----------------
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
Wheel mixer
------------
Two scalers total (output, yaw).
This mixer assumes that the wheel servo is set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
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 / gimbal / payload mixer for last three channels,
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
Aileron/v-tail/throttle/wheel/flaps mixer for PX4FMU
=======================================================
This file defines mixers suitable for controlling a fixed wing aircraft with
aileron, v-tail (rudder, elevator), throttle, steerable wheel and flaps
using PX4FMU.
The configuration assumes the aileron servos are connected to PX4FMU servo
output 0 and 1, the tail servos to output 2 and 3, the throttle
to output 4, the wheel to output 5 and the flaps to output 6 and 7.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 6 (flaperon).
Aileron mixer (roll + flaperon)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
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
V-tail mixers
-------------
Three scalers total (output, roll, pitch).
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
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
Wheel mixer
------------
Two scalers total (output, yaw).
This mixer assumes that the wheel servo is set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
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
------------
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
Aileron/rudder/elevator/throttle mixer for PX4FMU
==================================================
This file defines mixers suitable for controlling a fixed wing aircraft with
aileron, rudder, elevator and throttle controls using PX4FMU. The configuration
assumes the aileron servo(s) are connected to PX4FMU servo output 0, the
elevator to output 1, the rudder to output 2 and the throttle to output 3.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch) and 3 (thrust).
CH1: Aileron mixer
-------------
Two scalers total (output, roll).
This mixer assumes that the aileron servos are set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
factors (to reverse the servo movement) and adjust the offset, scaling and
endpoints to suit.
As there is only one output, if using two servos adjustments to compensate for
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
------------
Two scalers total (output, roll).
This mixer assumes that the elevator servo is set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
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
------------
Two scalers total (output, yaw).
This mixer assumes that the rudder servo is set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
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
-----------------
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
CH5: Flaps mixer
------------
Flaps are controlled automatically in position control and auto
but can also be controlled manually
M: 1
O: 5000 10000 0 -10000 10000
S: 0 4 10000 10000 0 -10000 10000
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
Aileron/Elevator/Throttle/Rudder/Gear/Flaps mixer
==================================================
This file defines mixers suitable for controlling a fixed wing aircraft with
aileron, rudder, elevator, throttle, gear, flaps controls. The configuration
assumes the aileron servo(s) are connected to output 0, the elevator to
output 1, the throttle to output 2 and the rudder to output 3.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (thrust), 3 (yaw), 4 (flaps), 7 (landing gear)
CH1: Aileron mixer
-------------
Two scalers total (output, roll).
This mixer assumes that the aileron servos are set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
factors (to reverse the servo movement) and adjust the offset, scaling and
endpoints to suit.
As there is only one output, if using two servos adjustments to compensate for
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
------------
Two scalers total (output, roll).
This mixer assumes that the elevator servo is set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
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
-----------------
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
CH4: Rudder mixer
------------
Two scalers total (output, yaw).
This mixer assumes that the rudder servo is set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
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
------------
Flaps are controlled automatically in position control and auto
but can also be controlled manually
M: 1
O: 5000 10000 0 -10000 10000
S: 0 4 10000 10000 0 -10000 10000
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
...@@ -32,10 +32,22 @@ ...@@ -32,10 +32,22 @@
############################################################################ ############################################################################
px4_add_romfs_files( px4_add_romfs_files(
AAERTWF.main.mix
AAVVTWFF.main.mix
AERT.main.mix
AETRFG.main.mix
complex_test.mix complex_test.mix
hexa_x.main.mix
IO_pass.mix IO_pass.mix
octo_x.main.mix
pass.aux.mix
quad_+.main.mix
quad_test.mix quad_test.mix
uuv_quad_x.mix quad_+_vtol.main.mix
ugv_generic.main.mix
vtol1_test.mix vtol1_test.mix
vtol2_test.mix vtol2_test.mix
vtol_AAERT.aux.mix
vtol_AAVVT.aux.mix
vtol_convergence.main.mix
) )
# Hexa X
R: 6x 10000 10000 10000 0
# Octo X
R: 8x 10000 10000 10000 0
# Manual pass through mixer for servo outputs 1-4
# 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
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a quadrotor in the + configuration. All controls
are mixed 100%.
R: 4+ 10000 10000 10000 0
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
Mixer for Tailsitter with + motor configuration and elevons
===========================================================
This file defines a single mixer for tailsitter with motors in X configuration. All controls
are mixed 100%.
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
Generic car mixer (eg Traxxas Stampede RC Car)
===========================
Designed for Traxxas Stampede
This file defines mixers suitable for controlling a Traxxas Stampede rover using
PX4FMU. The configuration assumes the steering is connected to PX4FMU
servo outputs 1 and the motor speed control to output 3. Output 0 and 2 is
assumed to be unused.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 2 (yaw), and 3 (thrust).
See the README for more information on the scaler format.
Output 0
---------------------------------------
Z:
Steering mixer using roll on output 1
---------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
S: 0 2 10000 10000 0 -10000 10000
Output 2
---------------------------------------
This mixer is empty.
Z:
Output 3
---------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
M: 4
O: 10000 10000 0 -10000 10000
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 1 -10000 -10000 0 -10000 10000
S: 0 2 +10000 +10000 0 -10000 10000
S: 0 3 +10000 +10000 0 -10000 10000
M: 4
O: 10000 10000 0 -10000 10000
S: 0 0 +10000 +10000 0 -10000 10000
S: 0 1 -10000 -10000 0 -10000 10000
S: 0 2 -10000 -10000 0 -10000 10000
S: 0 3 +10000 +10000 0 -10000 10000
M: 4
O: 10000 10000 0 -10000 10000
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 1 +10000 +10000 0 -10000 10000
S: 0 2 -10000 -10000 0 -10000 10000
S: 0 3 +10000 +10000 0 -10000 10000
M: 4
O: 10000 10000 0 -10000 10000
S: 0 0 +10000 +10000 0 -10000 10000
S: 0 1 +10000 +10000 0 -10000 10000
S: 0 2 +10000 +10000 0 -10000 10000
S: 0 3 +10000 +10000 0 -10000 10000
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
Aileron/v-tail/throttle VTOL mixer for PX4FMU
=======================================================
This file defines mixers suitable for controlling a fixed wing aircraft with
aileron, v-tail (rudder, elevator) and throttle using PX4FMU.
The configuration assumes the aileron servos are connected to PX4FMU
AUX servo output 0 and 1, the tail servos to output 2 and 3, the throttle
to output 4.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 6 (flaperon).
Aileron mixer (roll + flaperon)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
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
V-tail mixers
-------------
Three scalers total (output, roll, pitch).
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
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: 1 3 0 20000 -10000 -10000 10000
# E-flite Convergence Tricopter Y-Configuration Mixer
# Motors
R: 3y 10000 10000 10000 0
Z:
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
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment