mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
More example mixers; three different fixed-wing configurations for FMU.
This commit is contained in:
parent
6976fe4b19
commit
5c30722e77
@ -21,7 +21,10 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \
|
||||
$(SRCROOT)/scripts/rc.standalone~init.d/rc.standalone \
|
||||
$(SRCROOT)/scripts/rc.PX4IO~init.d/rc.PX4IO \
|
||||
$(SRCROOT)/scripts/rc.PX4IOAR~init.d/rc.PX4IOAR \
|
||||
$(SRCROOT)/mixers/FMU_delta.mix~mixers/FMU_delta.mix
|
||||
$(SRCROOT)/mixers/FMU_delta.mix~mixers/FMU_delta.mix \
|
||||
$(SRCROOT)/mixers/FMU_AERT.mix~mixers/FMU_AERT.mix \
|
||||
$(SRCROOT)/mixers/FMU_AET.mix~mixers/FMU_AET.mix \
|
||||
$(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.mix
|
||||
|
||||
#
|
||||
# Add the PX4IO firmware to the spec if someone has dropped it into the
|
||||
|
||||
64
ROMFS/mixers/FMU_AERT.mix
Normal file
64
ROMFS/mixers/FMU_AERT.mix
Normal file
@ -0,0 +1,64 @@
|
||||
Aileron/rudder/elevator/throttle mixer for PX4FMU
|
||||
==================================================
|
||||
|
||||
This file defines mixers suirable 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).
|
||||
|
||||
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: 2
|
||||
S: 0 0 10000 10000 0 -10000 10000
|
||||
S: 0 0 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: 2
|
||||
S: 0 0 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: 2
|
||||
S: 0 0 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: 2
|
||||
S: 0 0 10000 10000 0 -10000 10000
|
||||
S: 0 3 0 20000 -10000 -10000 10000
|
||||
60
ROMFS/mixers/FMU_AET.mix
Normal file
60
ROMFS/mixers/FMU_AET.mix
Normal file
@ -0,0 +1,60 @@
|
||||
Aileron/elevator/throttle mixer for PX4FMU
|
||||
==================================================
|
||||
|
||||
This file defines mixers suirable for controlling a fixed wing aircraft with
|
||||
aileron, 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 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).
|
||||
|
||||
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.
|
||||
|
||||
Alternatively, output 2 could be used as a second aileron servo output with
|
||||
separate mixing.
|
||||
|
||||
M: 2
|
||||
S: 0 0 10000 10000 0 -10000 10000
|
||||
S: 0 0 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: 2
|
||||
S: 0 0 10000 10000 0 -10000 10000
|
||||
S: 0 1 10000 10000 0 -10000 10000
|
||||
|
||||
Output 2
|
||||
--------
|
||||
This mixer is empty.
|
||||
|
||||
M: 0
|
||||
|
||||
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: 2
|
||||
S: 0 0 10000 10000 0 -10000 10000
|
||||
S: 0 3 0 20000 -10000 -10000 10000
|
||||
53
ROMFS/mixers/FMU_RET.mix
Normal file
53
ROMFS/mixers/FMU_RET.mix
Normal file
@ -0,0 +1,53 @@
|
||||
Rudder/elevator/throttle mixer for PX4FMU
|
||||
=========================================
|
||||
|
||||
This file defines mixers suirable for controlling a fixed wing aircraft with
|
||||
rudder, elevator and throttle controls using PX4FMU. The configuration assumes
|
||||
the rudder servo is connected to PX4FMU servo output 0, the elevator to output 1
|
||||
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).
|
||||
|
||||
Rudder mixer
|
||||
------------
|
||||
Two scalers total (output, roll).
|
||||
|
||||
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: 2
|
||||
S: 0 0 10000 10000 0 -10000 10000
|
||||
S: 0 0 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: 2
|
||||
S: 0 0 10000 10000 0 -10000 10000
|
||||
S: 0 1 10000 10000 0 -10000 10000
|
||||
|
||||
Output 2
|
||||
--------
|
||||
This mixer is empty.
|
||||
|
||||
M: 0
|
||||
|
||||
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: 2
|
||||
S: 0 0 10000 10000 0 -10000 10000
|
||||
S: 0 3 0 20000 -10000 -10000 10000
|
||||
@ -1,12 +1,10 @@
|
||||
Delta-wing mixer for PX4FMU
|
||||
===========================
|
||||
|
||||
Lines in this file that begin with a capital letter and a colon are interpreted
|
||||
as mixer commands. All other lines are ignored.
|
||||
|
||||
This delta-wing mixer assumes the elevon servos are connected to PX4FMU servo
|
||||
outputs 0 and 1 and the motor speed control to output 2. Output 3 is assumed to
|
||||
be unused.
|
||||
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).
|
||||
@ -33,6 +31,11 @@ S: 0 0 10000 10000 0 -10000 10000
|
||||
S: 0 0 5000 3000 0 -10000 10000
|
||||
S: 0 1 -5000 -5000 0 -10000 10000
|
||||
|
||||
Output 2
|
||||
--------
|
||||
This mixer is empty.
|
||||
|
||||
M: 0
|
||||
|
||||
Motor speed mixer
|
||||
-----------------
|
||||
@ -43,9 +46,4 @@ range. Inputs below zero are treated as zero.
|
||||
|
||||
M: 2
|
||||
S: 0 0 10000 10000 0 -10000 10000
|
||||
S: 0 2 0 20000 -10000 -10000 10000
|
||||
|
||||
|
||||
We leave the fourth mixer empty.
|
||||
|
||||
M: 0
|
||||
S: 0 3 0 20000 -10000 -10000 10000
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user