ROMFS: purge old mixing system

- SYS_USE_IO is now off by default (enabled by default per board)
This commit is contained in:
Daniel Agar 2022-08-24 14:44:17 -04:00
parent ed10146e9f
commit cac9c51ac8
121 changed files with 100 additions and 2797 deletions

1
.gitattributes vendored
View File

@ -21,7 +21,6 @@
# PX4 mixers, msgs, etc
*.bin binary
*.mix text eol=lf
*.msg text eol=lf
*.config text eol=lf
*.sdf text eol=lf

View File

@ -322,6 +322,7 @@ px4io_update:
# px4_io-v2_default
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/holybro/durandal-v1/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/holybro/pix32v5/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/mro/x21/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/mro/x21-777/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v2/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v3/extras/px4_io-v2_default.bin

View File

@ -32,7 +32,6 @@
############################################################################
add_subdirectory(init.d)
add_subdirectory(mixers)
# TODO: make this configurable from the board config, or better combine
if("${PX4_BOARD}" MATCHES "sitl")
add_subdirectory(init.d-posix)

View File

@ -11,8 +11,6 @@ PX4_SIMULATOR=${PX4_SIMULATOR:=ignition}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500}
PX4_SIM_WORLD=${PX4_SIM_WORLD:=default}
param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4

View File

@ -23,16 +23,6 @@ then
fi
# initialize script variables
set IO_PRESENT no
set MIXER skip
set MIXER_AUX none
set MIXER_FILE none
set OUTPUT_MODE sim
set EXTRA_MIXER_MODE none
set PWM_OUT none
set PWM_AUX_OUT none
set SDCARD_MIXERS_PATH etc/mixers
set USE_IO no
set VEHICLE_TYPE none
set LOGGER_ARGS ""
set LOGGER_BUF 1000
@ -227,10 +217,14 @@ manual_control start
sensors start
commander start
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
if ! pwm_out_sim start -m sim
then
tune_control play error
fi
#
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for all vehicle type specific setup.
. ${R}etc/init.d/rc.vehicle_setup
navigator start

View File

@ -42,7 +42,6 @@ px4_add_romfs_files(
rc.fw_apps
rc.fw_defaults
rc.heli_defaults
rc.interface
rc.logging
rc.mc_apps
rc.mc_defaults

View File

@ -42,8 +42,6 @@ param set-default MC_YAW_P 4
param set-default MPC_MANTHR_MIN 0
param set-default MPC_MAN_TILT_MAX 60
param set-default DSHOT_CONFIG 600
param set-default SYS_HAS_BARO 0
param set-default SYS_HAS_MAG 0

View File

@ -48,13 +48,10 @@ fi
# End Estimator Group Selection #
###############################################################################
if param compare SYS_CTRL_ALLOC 1
then
#
# Start Control Allocator
#
control_allocator start
fi
#
# Start Control Allocator
#
control_allocator start
#
# Start Airship Attitude Controller.

View File

@ -9,9 +9,3 @@ set VEHICLE_TYPE airship
# MAV_TYPE_AIRSHIP 7
param set-default MAV_TYPE 7
#
# This is the gimbal pass mixer.
#
set MIXER_AUX pass
set PWM_AUX_OUT 1234

View File

@ -2,7 +2,6 @@
#
# External airframe startup script (on SD card)
#
set SDCARD_MIXERS_PATH ${SDCARD_EXT_PATH}/mixers
if [ -e ${SDCARD_EXT_PATH}/rc.autostart ]
then

View File

@ -20,22 +20,3 @@ param set-default NAV_ACC_RAD 2
# Temporary.
param set-default NAV_FW_ALT_RAD 1000
#
# Enable servo output on pins 3 and 4 (steering and thrust)
# but also include 1+2 as they form together one output group
# and need to be set together.
#
set PWM_OUT 1234
#
# PWM Hz - 50 Hz is the normal rate in RC cars, higher rates
# may damage analog servos.
#
set PWM_MAIN_RATE 50
#
# This is the gimbal pass mixer.
#
set MIXER_AUX pass
set PWM_AUX_OUT 1234

View File

@ -10,13 +10,10 @@
#
ekf2 start &
if param compare SYS_CTRL_ALLOC 1
then
#
# Start Control Allocator
#
control_allocator start
fi
#
# Start Control Allocator
#
control_allocator start
#
# Start attitude controller.

View File

@ -52,11 +52,3 @@ param set-default PWM_MAIN_RATE 50
# FW takeoff acceleration can easily exceed ublox GPS 2G default.
#
param set-default GPS_UBX_DYNMODEL 8
#
# This is the gimbal pass mixer.
#
set MIXER_AUX pass
set PWM_AUX_RATE 50
set PWM_AUX_OUT 1234

View File

@ -1,284 +0,0 @@
#!/bin/sh
#
# Script to configure control interfaces.
#
#
# NOTE: environment variable references:
# If the dollar sign ('$') is followed by a left bracket ('{') then the
# variable name is terminated with the right bracket character ('}').
# Otherwise, the variable name goes to the end of the argument.
#
set OUTPUT_CMD pwm_out
set MIXER_AUX_FILE none
set MIXER_EXTRA_FILE none
set OUTPUT_DEV none
set OUTPUT_AUX_DEV /dev/pwm_output1
set OUTPUT_EXTRA_DEV /dev/pwm_output0
# set these before starting the modules
if [ $PWM_AUX_OUT != none ]
then
param set PWM_AUX_OUT ${PWM_AUX_OUT}
fi
if [ $PWM_OUT != none ]
then
param set PWM_MAIN_OUT ${PWM_OUT}
fi
#
# If mount (gimbal) control is enabled and output mode is AUX, set the aux
# mixer to mount (override the airframe-specific MIXER_AUX setting).
#
if param greater -s MNT_MODE_IN -1
then
if param compare -s MNT_MODE_OUT 0
then
set MIXER_AUX mount
fi
fi
#
# Set the default output mode if none was set.
#
if [ $OUTPUT_MODE = none -a $OUTPUT_MODE != skip ]
then
if [ $USE_IO = yes ]
then
# Enable IO output only if IO is present.
if [ $IO_PRESENT = yes ]
then
set OUTPUT_MODE io
if param greater -s DSHOT_CONFIG 0
then
set OUTPUT_CMD dshot
fi
fi
else
if param greater -s DSHOT_CONFIG 0
then
set OUTPUT_MODE dshot
set OUTPUT_CMD dshot
else
set OUTPUT_MODE pwm_out
fi
fi
fi
#
# If OUTPUT_MODE = none then something is wrong with setup and we shouldn't try to enable output.
#
if [ $OUTPUT_MODE != none -a $OUTPUT_MODE != skip ]
then
if [ $OUTPUT_MODE = hil -o $OUTPUT_MODE = sim ]
then
if ! pwm_out_sim start -m $OUTPUT_MODE
then
tune_control play error
fi
fi
if [ $OUTPUT_MODE = uavcan_esc ]
then
if param compare UAVCAN_ENABLE 0
then
param set UAVCAN_ENABLE 3
fi
fi
#
# Start IO for PWM output or RC input if needed.
#
if [ $IO_PRESENT = yes ]
then
if ! px4io start
then
echo "PX4IO start failed"
tune_control play -t 18 # PROG_PX4IO_ERR
fi
fi
if [ $OUTPUT_MODE = $OUTPUT_CMD -o $OUTPUT_MODE = io ]
then
if param compare SYS_CTRL_ALLOC 1
then
pwm_out start
dshot start
else
if ! $OUTPUT_CMD start
then
echo "$OUTPUT_CMD start failed"
tune_control play error
fi
fi
fi
fi
if [ $MIXER != none -a $MIXER != skip ]
then
#
# Load main mixer.
#
if [ $MIXER_AUX = none -a $USE_IO = yes ]
then
set MIXER_AUX ${MIXER}
fi
if [ "$MIXER_FILE" = none ]
then
if [ -f ${SDCARD_MIXERS_PATH}/${MIXER}.main.mix ]
then
# Use the mixer file from the SD-card if it exists.
set MIXER_FILE ${SDCARD_MIXERS_PATH}/${MIXER}.main.mix
else
# Try out the old convention, for backward compatibility.
if [ -f ${SDCARD_MIXERS_PATH}/${MIXER}.mix ]
then
set MIXER_FILE ${SDCARD_MIXERS_PATH}/${MIXER}.mix
else
set MIXER_FILE /etc/mixers/${MIXER}.main.mix
fi
fi
fi
set OUTPUT_DEV /dev/pwm_output0
if [ $OUTPUT_MODE = uavcan_esc ]
then
set OUTPUT_DEV /dev/uavcan/esc
fi
if mixer load ${OUTPUT_DEV} ${MIXER_FILE}
then
echo "INFO [init] Mixer: ${MIXER_FILE} on ${OUTPUT_DEV}"
else
echo "ERROR [init] Failed loading mixer: ${MIXER_FILE}"
tune_control play -t 18 # tune 18 = PROG_PX4IO_ERR
fi
else
if [ $MIXER != skip ]
then
echo "ERROR [init] Mixer undefined"
tune_control play -t 18 # tune 18 = PROG_PX4IO_ERR
fi
fi
if [ $MIXER_AUX != none ]
then
#
# Load aux mixer.
#
if [ -f ${SDCARD_MIXERS_PATH}/${MIXER_AUX}.aux.mix ]
then
set MIXER_AUX_FILE ${SDCARD_MIXERS_PATH}/${MIXER_AUX}.aux.mix
else
if [ -f /etc/mixers/${MIXER_AUX}.aux.mix ]
then
set MIXER_AUX_FILE /etc/mixers/${MIXER_AUX}.aux.mix
fi
fi
if [ $MIXER_AUX_FILE != none ]
then
# Append aux mixer to main device.
if param greater SYS_HITL 0
then
if mixer append ${OUTPUT_DEV} ${MIXER_AUX_FILE}
then
echo "INFO [init] Mixer: ${MIXER_AUX_FILE} appended to ${OUTPUT_DEV}"
else
echo "ERROR [init] Failed appending mixer: ${MIXER_AUX_FILE}"
fi
fi
if [ -e $OUTPUT_AUX_DEV -a $OUTPUT_MODE != hil ]
then
if mixer load ${OUTPUT_AUX_DEV} ${MIXER_AUX_FILE}
then
echo "INFO [init] Mixer: ${MIXER_AUX_FILE} on ${OUTPUT_AUX_DEV}"
else
echo "ERROR [init] Failed loading mixer: ${MIXER_AUX_FILE}"
fi
else
echo "INFO [init] setting PWM_AUX_OUT none"
set PWM_AUX_OUT none
fi
# for DShot do not configure pwm values
if [ $OUTPUT_CMD != dshot ]
then
# Set min / max for aux out and rates.
if [ $PWM_AUX_OUT != none ]
then
# Set PWM_AUX output frequency.
if [ $PWM_AUX_RATE != none ]
then
pwm rate -c ${PWM_AUX_OUT} -r ${PWM_AUX_RATE} -d ${OUTPUT_AUX_DEV}
fi
fi
fi
fi
fi
if [ $OUTPUT_MODE = pwm_out -o $OUTPUT_MODE = io ]
then
if [ $PWM_OUT != none -a $PWM_MAIN_RATE != none ]
then
# Set PWM output frequency.
if ! param compare SYS_CTRL_ALLOC 1
then
pwm rate -c ${PWM_OUT} -r ${PWM_MAIN_RATE}
fi
fi
fi
if [ $EXTRA_MIXER_MODE != none ]
then
if [ -f ${SDCARD_MIXERS_PATH}/${MIXER_EXTRA}.aux.mix ]
then
# Use the mixer file from the SD-card if it exists.
set MIXER_EXTRA_FILE ${SDCARD_MIXERS_PATH}/${MIXER_EXTRA}.aux.mix
else
# Try out the old convention, for backward compatibility.
if [ -f ${SDCARD_MIXERS_PATH}/${MIXER_EXTRA}.mix ]
then
set MIXER_EXTRA_FILE ${SDCARD_MIXERS_PATH}/${MIXER_EXTRA}.mix
else
set MIXER_EXTRA_FILE /etc/mixers/${MIXER_EXTRA}.aux.mix
fi
fi
if mixer load ${OUTPUT_EXTRA_DEV} ${MIXER_EXTRA_FILE}
then
echo "INFO [init] Mixer: ${MIXER_EXTRA_FILE} on ${OUTPUT_EXTRA_DEV}"
else
echo "ERROR [init] Failed loading mixer: ${MIXER_EXTRA_FILE}"
tune_control play -t 20
fi
if [ $PWM_EXTRA_OUT != none ]
then
# Set PWM output frequency.
if [ $PWM_EXTRA_RATE != none ]
then
pwm rate -c ${PWM_EXTRA_OUT} -r ${PWM_EXTRA_RATE}
fi
fi
fi
unset OUTPUT_CMD
unset MIXER_AUX_FILE
unset MIXER_EXTRA_FILE
unset OUTPUT_DEV
unset OUTPUT_AUX_DEV
unset OUTPUT_EXTRA_DEV

View File

@ -48,13 +48,10 @@ fi
# End Estimator Group Selection #
###############################################################################
if param compare SYS_CTRL_ALLOC 1
then
#
# Start Control Allocator
#
control_allocator start
fi
#
# Start Control Allocator
#
control_allocator start
#
# Start Multicopter Rate Controller.

View File

@ -25,14 +25,3 @@ param set-default PWM_MAIN_MIN 1075
param set-default PWM_MAIN_RATE 400
param set-default GPS_UBX_DYNMODEL 6
#
# This is the gimbal pass mixer.
#
set MIXER_AUX pass
set MIXER quad_x
set PWM_OUT 1234
set PWM_AUX_OUT 1234

View File

@ -12,13 +12,10 @@ ekf2 start &
#attitude_estimator_q start
#local_position_estimator start
if param compare SYS_CTRL_ALLOC 1
then
#
# Start Control Allocator
#
control_allocator start
fi
#
# Start Control Allocator
#
control_allocator start
#
# Start attitude controllers.

View File

@ -21,22 +21,3 @@ param set-default NAV_LOITER_RAD 2
# Temporary.
param set-default NAV_FW_ALT_RAD 1000
#
# Enable servo output on pins 3 and 4 (steering and thrust)
# but also include 1+2 as they form together one output group
# and need to be set together.
#
set PWM_OUT 1234
#
# PWM Hz - 50 Hz is the normal rate in RC cars, higher rates
# may damage analog servos.
#
set PWM_MAIN_RATE 50
#
# This is the gimbal pass mixer.
#
set MIXER_AUX pass
set PWM_AUX_OUT 1234

View File

@ -15,13 +15,10 @@ ekf2 start &
# End Estimator Group Selection #
###############################################################################
if param compare SYS_CTRL_ALLOC 1
then
#
# Start Control Allocator
#
control_allocator start
fi
#
# Start Control Allocator
#
control_allocator start
#
# Start UUV Attitude Controller.

View File

@ -13,20 +13,3 @@ param set-default MAV_TYPE 12
param set-default PWM_MAIN_MAX 1950
param set-default PWM_MAIN_MIN 1050
param set-default PWM_MAIN_DISARM 1500
#
# PWM Hz - 50 Hz is the normal rate in RC cars, boats etc,
# higher rates may damage analog servos.
#
set PWM_MAIN_RATE 50
#
# Enable servo output on pins 1-4
set PWM_OUT 1234
#
# This is the gimbal pass mixer.
#
set MIXER_AUX pass
set PWM_AUX_OUT 1234
set PWM_AUX_RATE 50

View File

@ -10,14 +10,6 @@
#
if [ $VEHICLE_TYPE = fw ]
then
if [ $MIXER = none ]
then
echo "FW mixer undefined"
fi
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
# Start standard fixedwing apps.
. ${R}etc/init.d/rc.fw_apps
fi
@ -27,14 +19,6 @@ fi
#
if [ $VEHICLE_TYPE = mc ]
then
if [ $MIXER = none ]
then
echo "MC mixer undefined"
fi
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
# Start standard multicopter apps.
. ${R}etc/init.d/rc.mc_apps
fi
@ -44,14 +28,6 @@ fi
#
if [ $VEHICLE_TYPE = rover ]
then
if [ $MIXER = none ]
then
echo "rover mixer undefined"
fi
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
# Start standard UGV apps.
. ${R}etc/init.d/rc.rover_apps
fi
@ -61,14 +37,6 @@ fi
#
if [ $VEHICLE_TYPE = vtol ]
then
if [ $MIXER = none ]
then
echo "VTOL mixer undefined"
fi
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
# Start standard vtol apps.
. ${R}etc/init.d/rc.vtol_apps
fi
@ -78,14 +46,6 @@ fi
#
if [ $VEHICLE_TYPE = airship ]
then
if [ $MIXER = none ]
then
echo "Airship mixer undefined"
fi
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
# Start airship apps.
. ${R}etc/init.d/rc.airship_apps
fi
@ -95,14 +55,6 @@ fi
#
if [ $VEHICLE_TYPE = uuv ]
then
if [ $MIXER = none ]
then
echo "UUV mixer undefined"
fi
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
# Start standard vtol apps.
. ${R}etc/init.d/rc.uuv_apps
fi

View File

@ -15,13 +15,10 @@ ekf2 start &
# End Estimator group selection #
###############################################################################
if param compare SYS_CTRL_ALLOC 1
then
#
# Start Control Allocator
#
control_allocator start
fi
#
# Start Control Allocator
#
control_allocator start
airspeed_selector start

View File

@ -25,29 +25,14 @@ set FCONFIG /fs/microsd/etc/config.txt
set FEXTRAS /fs/microsd/etc/extras.txt
set FRC /fs/microsd/etc/rc.txt
set IOFW "/etc/extras/px4_io-v2_default.bin"
set IO_PRESENT no
set LOGGER_ARGS ""
set LOGGER_BUF 8
set MIXER skip
set MIXER_AUX none
set MIXER_FILE none
set MIXER_EXTRA none
set OUTPUT_MODE none
set PARAM_FILE ""
set PWM_OUT none
set PWM_MAIN_RATE p:PWM_MAIN_RATE
set PWM_AUX_OUT none
set PWM_AUX_RATE p:PWM_AUX_RATE
set PWM_EXTRA_OUT none
set PWM_EXTRA_RATE p:PWM_EXTRA_RATE
set EXTRA_MIXER_MODE none
set RC_INPUT_ARGS ""
set SDCARD_AVAILABLE no
set SDCARD_EXT_PATH /fs/microsd/ext_autostart
set SDCARD_FORMAT no
set SDCARD_MIXERS_PATH /fs/microsd/etc/mixers
set STARTUP_TUNE 1
set USE_IO no
set VEHICLE_TYPE none
#
@ -236,7 +221,7 @@ else
# Waypoint storage.
# REBOOTWORK this needs to start in parallel.
#
if param compare SYS_DM_BACKEND 1
if param compare -s SYS_DM_BACKEND 1
then
dataman start -r
else
@ -278,13 +263,8 @@ else
if param greater -s UAVCAN_ENABLE 0
then
# Start core UAVCAN module.
if uavcan start
if ! uavcan start
then
if param greater UAVCAN_ENABLE 2
then
set OUTPUT_MODE uavcan_esc
fi
else
tune_control play error
fi
else
@ -295,22 +275,15 @@ else
fi
#
# Check if PX4IO present and update firmware if needed.
# Assumption IOFW set to firmware file and IO_PRESENT = no
# Start IO for PWM output or RC input if enabled
#
if [ -f $IOFW ]
if param compare -s SYS_USE_IO 1
then
# Check for the mini using build with px4io fw file
# but not a px4IO
if ver hwtypecmp V5004000 V5006000
# Check if PX4IO present and update firmware if needed.
if [ -f $IOFW ]
then
param set SYS_USE_IO 0
else
if px4io checkcrc ${IOFW}
if ! px4io checkcrc ${IOFW}
then
set IO_PRESENT yes
else
# tune Program PX4IO
tune_control play -t 16 # tune 16 = PROG_PX4IO
@ -321,7 +294,6 @@ else
if px4io checkcrc ${IOFW}
then
tune_control play -t 17 # tune 17 = PROG_PX4IO_OK
set IO_PRESENT yes
else
tune_control play -t 18 # tune 18 = PROG_PX4IO_ERR
fi
@ -330,20 +302,12 @@ else
fi
fi
fi
fi
#
# Set USE_IO flag.
#
if param compare -s SYS_USE_IO 1
then
set USE_IO yes
fi
if [ $USE_IO = yes -a $IO_PRESENT = no ]
then
echo "PX4IO not found"
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
if ! px4io start
then
echo "PX4IO start failed"
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
fi
fi
#
@ -359,7 +323,11 @@ else
#
if param greater SYS_HITL 0
then
set OUTPUT_MODE hil
if ! pwm_out_sim start -m hil
then
tune_control play error
fi
sensors start -h
commander start -h
# disable GPS
@ -397,13 +365,14 @@ else
sensors start
commander start
dshot start
pwm_out start
fi
#
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
#
# Note: rc.vehicle_setup is the entry point for all vehicle type specific setup.
. ${R}etc/init.d/rc.vehicle_setup
# Pre-takeoff continuous magnetometer calibration
@ -435,11 +404,8 @@ else
#
. ${R}etc/init.d/rc.serial
if [ $IO_PRESENT = no ]
then
# Must be started after the serial config is read
rc_input start $RC_INPUT_ARGS
fi
# Must be started after the serial config is read
rc_input start $RC_INPUT_ARGS
# PPS capture driver (before pwm_out)
if param greater -s PPS_CAP_ENABLE 0
@ -564,28 +530,15 @@ unset R
unset FCONFIG
unset FEXTRAS
unset FRC
unset IO_PRESENT
unset IOFW
unset LOGGER_ARGS
unset LOGGER_BUF
unset MIXER
unset MIXER_AUX
unset MIXER_FILE
unset OUTPUT_MODE
unset PARAM_FILE
unset PWM_AUX_OUT
unset PWM_AUX_RATE
unset PWM_MAIN_RATE
unset PWM_OUT
unset PWM_EXTRA_OUT
unset PWM_EXTRA_RATE
unset RC_INPUT_ARGS
unset SDCARD_AVAILABLE
unset SDCARD_EXT_PATH
unset SDCARD_FORMAT
unset SDCARD_MIXERS_PATH
unset STARTUP_TUNE
unset USE_IO
unset VEHICLE_TYPE
#

View File

@ -1,88 +0,0 @@
# @board px4_fmu-v2 exclude
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 + spoiler)
---------------------------------
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
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
M: 2
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 -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
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
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
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
S: 0 2 10000 10000 0 -10000 10000
Flaps / gimbal / payload mixer for last three channels,
using the payload control group
-----------------------------------------------------
M: 1
S: 0 4 10000 10000 0 -10000 10000
M: 1
S: 2 0 10000 10000 0 -10000 10000
M: 1
S: 2 2 10000 10000 0 -10000 10000

View File

@ -1,77 +0,0 @@
# @board px4_fmu-v2 exclude
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 + spoiler)
---------------------------------
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
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
M: 2
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 -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
S: 0 2 -7000 -7000 0 -10000 10000
S: 0 1 -8000 -8000 0 -10000 10000
M: 2
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
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
S: 0 2 -10000 -10000 0 -10000 10000
Flaps mixer
------------
Flap servos are physically reversed.
M: 1
S: 0 4 0 5000 -10000 -10000 10000
M: 1
S: 0 4 0 -5000 10000 -10000 10000

View File

@ -1,71 +0,0 @@
# @board px4_fmu-v2 exclude
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), 3 (thrust) 4 (flaps), 5 (spoiler).
Aileron mixer (roll + spoiler)
---------------------------------
This mixer assumes that the aileron servos are set up mechanically reversed.
M: 2
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
M: 2
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 5 -10000 -10000 0 -10000 10000
V-tail mixers
-------------
Three scalers total (output, roll, pitch).
M: 2
S: 0 2 7000 7000 0 -10000 10000
S: 0 1 -8000 -8000 0 -10000 10000
M: 2
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
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
S: 0 2 -10000 -10000 0 -10000 10000
Flaps mixer
------------
Flap servos are physically reversed.
M: 1
S: 0 4 0 5000 -10000 -10000 10000
M: 1
S: 0 4 0 -5000 10000 -10000 10000

View File

@ -1,77 +0,0 @@
# @board px4_fmu-v2 exclude
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
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
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
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
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
S: 3 5 10000 10000 0 -10000 10000

View File

@ -1,77 +0,0 @@
# @board px4_fmu-v2 exclude
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
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
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
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
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
S: 3 5 10000 10000 0 -10000 10000

View File

@ -1,49 +0,0 @@
# @board px4_fmu-v2 exclude
Helicopter 120 degree Cyclic-Collective-Pitch Mixing (CCPM) for PX4FMU
==================================================
Output 0 - Rear Servo Mixer
----------------
Rear Servo = Collective (Thrust - 3) + Elevator (Pitch - 1)
M: 2
S: 0 3 10000 10000 0 -10000 10000
S: 0 1 10000 10000 0 -10000 10000
Output 1 - Left Servo Mixer
-----------------
Left Servo = Collective (Thurst - 3) - 0.5 * Elevator (Pitch - 1) + 0.866 * Aileron (Roll - 0)
M: 3
S: 0 3 -10000 -10000 0 -10000 10000
S: 0 1 -5000 -5000 0 -10000 10000
S: 0 0 8660 8660 0 -10000 10000
Output 2 - Right Servo Mixer
----------------
Right Servo = Collective (Thurst - 3) - 0.5 * Elevator (Pitch - 1) - 0.866 * Aileron (Roll - 0)
M: 3
S: 0 3 -10000 -10000 0 -10000 10000
S: 0 1 -5000 -5000 0 -10000 10000
S: 0 0 -8660 -8660 0 -10000 10000
Output 3 - Tail Servo Mixer
----------------
Tail Servo = Yaw (control index = 2)
M: 1
S: 0 2 10000 10000 0 -10000 10000
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
S: 0 4 0 20000 -10000 -10000 10000

View File

@ -1,80 +0,0 @@
############################################################################
#
# Copyright (c) 2018 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_romfs_files(
AAERTWF.main.mix
AAVVTWFF.main.mix
AAVVTWFF_vtail.main.mix
AERT.main.mix
AETRFG.main.mix
CCPM.main.mix
cloudship.main.mix
coax.main.mix
dodeca_bottom_cox.aux.mix
dodeca_top_cox.main.mix
fw_generic_wing.main.mix
generic_diff_rover.main.mix
hexa_cox.main.mix
hexa_+.main.mix
hexa_x.main.mix
IO_pass.main.mix
mount.aux.mix
mount_legs.aux.mix
octo_cox.main.mix
octo_cox_w.main.mix
octo_+.main.mix
octo_x.main.mix
pass.aux.mix
quad_dc.main.mix
quad_h.main.mix
quad_+.main.mix
quad_+_vtol.main.mix
quad_w.main.mix
quad_x_cw.main.mix
quad_x.main.mix
quad_x_vtol.main.mix
quad_x_vtol_AAERT.main.mix
rover_diff_and_servo.main.mix
rover_generic.main.mix
standard_vtol_hitl.main.mix
tilt_quad.aux.mix
tilt_quad.main.mix
tri_y_yaw+.main.mix
tri_y_yaw-.main.mix
vtol_AAERT.aux.mix
vtol_AAVVT.aux.mix
vtol_TTTTAAER.aux.mix
vtol_delta.aux.mix
vtol_tailsitter_duo.main.mix
vtol_tailsitter_duo_sat.main.mix
)

View File

@ -1,31 +0,0 @@
# @board px4_fmu-v2 exclude
Passthrough mixer for PX4IO
============================
This file defines passthrough mixers suitable for testing.
Channel group 0, channels 0-7 are passed directly through to the outputs.
M: 1
S: 0 0 10000 10000 0 -10000 10000
M: 1
S: 0 1 10000 10000 0 -10000 10000
M: 1
S: 0 2 10000 10000 0 -10000 10000
M: 1
S: 0 3 10000 10000 0 -10000 10000
M: 1
S: 0 4 10000 10000 0 -10000 10000
M: 1
S: 0 5 10000 10000 0 -10000 10000
M: 1
S: 0 6 10000 10000 0 -10000 10000
M: 1
S: 0 7 10000 10000 0 -10000 10000

View File

@ -1,49 +0,0 @@
Thrust tilt/ Starboard Thrust / Port Thrust / Tail Thrust mixer for PX4FMU
=======================================================
# @board px4_fmu-v2 exclude
This file defines mixers suitable for controlling an airship with
a thrust tilt, starboard and port thruster and a tail thruster using PX4FMU.
The configuration assumes the starboard thruster is connected to PX4FMU
output 1, port thruster to output 2, tilt servo to output 3, and the
tail thruster to output 4.
Inputs to the mixer come from channel group 0 (vehicle attitude),
channels 0 (roll), 1 (pitch), 2 (yaw) and 3 (thrust).
Starboard and port thruster mixer
-----------------
Two scalers total (output, thrust).
By default mixer output is normalized. The input is in the (0 - 1) range.
M: 1
S: 0 3 0 20000 -10000 -10000 10000
M: 1
S: 0 3 0 20000 -10000 -10000 10000
Servo controlling tilt mixer
------------
Two scalers total (output, tilt angle).
This mixer assumes that the tilt 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
S: 0 1 10000 10000 0 -10000 10000
Tail thruster mixer
------------
Two scalers total (output, yaw).
This mixer assumes that the tail thruster is set up correctly mechanically;
depending on the actual configuration it may be necessary to reverse the scaling
factors (to reverse the motor movement) and adjust the offset, scaling and
endpoints to suit.
M: 1
S: 0 2 10000 10000 0 -10000 10000

View File

@ -1,30 +0,0 @@
# @board px4_fmu-v2 exclude
Coaxial helicopter mixer
- Two servomotors act on the swashplate (90 degree angle on the swashplate, decoupled effect on roll and pitch).
- No collective pitch.
- One motor per rotor.
===========================
Left swashplate servomotor, pitch axis
-------------
M: 1
S: 0 1 -10000 -10000 0 -10000 10000
Right swashplate servomotor, roll axis
-------------
M: 1
S: 0 0 10000 10000 0 -10000 10000
Upper rotor (CCW)
Mixing between yaw and thrust
-------------
M: 2
S: 0 2 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
Lower rotor (CW)
Mixing between yaw and thrust
-------------
M: 2
S: 0 2 -10000 -10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000

View File

@ -1,4 +0,0 @@
# Dodeca Cox
# @board px4_fmu-v2 exclude
R: 6a

View File

@ -1,4 +0,0 @@
# Dodeca Cox
# @board px4_fmu-v2 exclude
R: 6m

View File

@ -1,47 +0,0 @@
# @board px4_fmu-v2 exclude
Generic wing mixer
===========================
This file defines mixers suitable for controlling a delta wing aircraft.
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 for roll inputs is adjusted to implement differential travel
for the elevons.
M: 2
S: 0 0 -8000 -8000 0 -10000 10000
S: 0 1 6000 6000 0 -10000 10000
M: 2
S: 0 0 -8000 -8000 0 -10000 10000
S: 0 1 -6000 -6000 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
S: 0 3 0 20000 -10000 -10000 10000

View File

@ -1,26 +0,0 @@
# @board px4_fmu-v2 exclude
Generic differential-drive rover
===========================
This mixer is suitable for controlling any differential-drive rover. That is,
a rover where the left wheels and right wheels are driven independently,
allowing turning in place. It outputs to channels 0 (left wheels) and
1 (right wheels)
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.
Throttle of left wheels of rover on Output 0
---------------------------------------
M: 2
S: 0 2 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
Throttle of right wheels of rover on Output 1
---------------------------------------
M: 2
S: 0 2 -10000 -10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000

View File

@ -1,4 +0,0 @@
# @board px4_fmu-v2 exclude
# Hexa +
R: 6+

View File

@ -1,4 +0,0 @@
# @board px4_fmu-v2 exclude
# Hexa coaxial
R: 6c

View File

@ -1,5 +0,0 @@
# @board px4_fmu-v2 exclude
# Hexa X
R: 6x

View File

@ -1,20 +0,0 @@
# @board px4_fmu-v2 exclude
# Mount Mixer (e.g. Gimbal, servo-controlled gimbal, etc...)
# pitch
M: 1
S: 2 1 10000 10000 0 -10000 10000
# roll
M: 1
S: 2 0 10000 10000 0 -10000 10000
# yaw
M: 1
S: 2 2 10000 10000 0 -10000 10000
# Shutter/retract
M: 1
S: 2 3 10000 10000 0 -10000 10000

View File

@ -1,23 +0,0 @@
# @board px4_fmu-v2 exclude
# Roll channel for mount
M: 1
S: 2 0 10000 10000 0 -10000 10000
# Pitch channel for mount
M: 1
S: 2 1 10000 10000 0 -10000 10000
# Yaw channel for mount
M: 1
S: 2 2 10000 10000 0 -10000 10000
# mixer for left leg
M: 1
S: 0 7 0 20000 -10000 -10000 10000
# mixer for right leg
M: 1
S: 0 7 0 20000 -10000 -10000 10000

View File

@ -1,4 +0,0 @@
# @board px4_fmu-v2 exclude
# Octo +
R: 8+

View File

@ -1,4 +0,0 @@
# @board px4_fmu-v2 exclude
# Octo coaxial
R: 8c

View File

@ -1,4 +0,0 @@
# Octo coaxial with wide arms
# @board px4_fmu-v2 exclude
R: 8cw

View File

@ -1,4 +0,0 @@
# @board px4_fmu-v2 exclude
# Octo X
R: 8x

View File

@ -1,18 +0,0 @@
# @board px4_fmu-v2 exclude
# Manual pass through mixer for servo outputs 1-4
# AUX1 channel (select RC channel with RC_MAP_AUX1 param)
M: 1
S: 3 5 10000 10000 0 -10000 10000
# AUX2 channel (select RC channel with RC_MAP_AUX2 param)
M: 1
S: 3 6 10000 10000 0 -10000 10000
# AUX3 channel (select RC channel with RC_MAP_AUX3 param)
M: 1
S: 3 7 10000 10000 0 -10000 10000
# FLAPS channel (select RC channel with RC_MAP_FLAPS param)
M: 1
S: 3 4 10000 10000 0 -10000 10000

View File

@ -1,17 +0,0 @@
# @board px4_fmu-v2 exclude
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a quadrotor in the + configuration. All controls
are mixed 100%.
R: 4+
Gimbal / payload mixer for last two channels
-----------------------------------------------------
M: 1
S: 3 5 10000 10000 0 -10000 10000
M: 1
S: 3 6 10000 10000 0 -10000 10000

View File

@ -1,25 +0,0 @@
# @board px4_fmu-v2 exclude
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+
# mixer for the elevons
M: 2
S: 1 0 10000 10000 0 -10000 10000
S: 1 1 10000 10000 0 -10000 10000
M: 2
S: 1 0 10000 10000 0 -10000 10000
S: 1 1 -10000 -10000 0 -10000 10000
# mixer for canard surface
M: 1
S: 1 1 -10000 -10000 0 -10000 10000
# mixer for rudder
M: 1
S: 1 2 -10000 -10000 0 -10000 10000

View File

@ -1,7 +0,0 @@
# @board px4_fmu-v2 exclude
Multirotor mixer
===========================
This file defines a single mixer for a quadrotor in DC wide arms configuration. All controls are mixed 100%.
R: 4dc

View File

@ -1,17 +0,0 @@
# @board px4_fmu-v2 exclude
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a quadrotor in the H configuration. All controls
are mixed 100%.
R: 4h
Gimbal / payload mixer for last two channels
-----------------------------------------------------
M: 1
S: 3 5 10000 10000 0 -10000 10000
M: 1
S: 3 6 10000 10000 0 -10000 10000

View File

@ -1,16 +0,0 @@
# @board px4_fmu-v2 exclude
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a quadrotor with a wide configuration. All controls are mixed 100%.
R: 4w
Gimbal / payload mixer for last two channels
-----------------------------------------------------
M: 1
S: 3 5 10000 10000 0 -10000 10000
M: 1
S: 3 6 10000 10000 0 -10000 10000

View File

@ -1,17 +0,0 @@
# @board px4_fmu-v2 exclude
R: 4x
AUX1 Passthrough
M: 1
S: 3 5 10000 10000 0 -10000 10000
AUX2 Passthrough
M: 1
S: 3 6 10000 10000 0 -10000 10000
Failsafe outputs
The following outputs are set to their disarmed value
during normal operation and to their failsafe falue in case
of flight termination.
Z:
Z:

View File

@ -1,4 +0,0 @@
# @board px4_fmu-v2 exclude
# Quad X with clock-wise motor assigment
R: 4xcw

View File

@ -1,19 +0,0 @@
Mixer for Tailsitter with x motor configuration and elevons
===========================================================
# @board px4_fmu-v2 exclude
# @board omnibus_f4sd exclude
This file defines a single mixer for tailsitter with motors in X configuration. All controls
are mixed 100%.
R: 4x
# left elevon
M: 2
S: 1 0 -5000 -5000 0 -10000 10000
S: 1 1 5000 5000 0 -10000 10000
# right elevon
M: 2
S: 1 0 -5000 -5000 0 -10000 10000
S: 1 1 -5000 -5000 0 -10000 10000

View File

@ -1,30 +0,0 @@
# @board px4_fmu-v2 exclude
Mixer for an AAERT VTOL
=======================
R: 4x
Aileron 1 mixer
---------------
M: 1
S: 1 0 7500 7500 0 -10000 10000
Aileron 2 mixer
---------------
M: 1
S: 1 0 7500 7500 0 -10000 10000
Elevator mixer
--------------
M: 1
S: 1 1 10000 10000 0 -10000 10000
Rudder mixer
------------
M: 1
S: 1 2 -10000 -10000 0 -10000 10000
Throttle mixer
--------------
M: 1
S: 1 3 0 20000 -10000 -10000 10000

View File

@ -1,41 +0,0 @@
# @board px4_fmu-v2 exclude
Generic car mixer (eg DF Robot GPX:Asurada RC Car)
===========================
Designed for DF Robot GPX:Asurada
This file defines mixers suitable for controlling a DF Robot GPX:Asurada rover using
PX4FMU. The configuration assumes the steering is connected to PX4FMU
servo outputs 1 and the motor speed controls to output 2 and 3. Output 0 is
assumed to be unused.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0 (roll), and 3 (thrust).
See the README for more information on the scaler format.
Output 1 - Empty
-----------------------------------------
Z:
Output 2 - Steering mixer using yaw
------------------------------------------
M: 1
O: 10000 10000 0 -10000 10000 5000
S: 0 2 10000 10000 0 -10000 10000
Output 3 - Left row of wheels using yaw and throttle (1s rise time)
------------------------------------------
M: 2
O: 10000 10000 0 -10000 10000 10000
S: 0 2 -500 -500 0 0 10000
S: 0 3 10000 10000 0 -10000 10000
Output 4 - Right row of wheels using yaw and throttle (1s rise time)
------------------------------------------
M: 2
O: 10000 10000 0 -10000 10000 10000
S: 0 2 500 500 0 0 10000
S: 0 3 10000 10000 0 -10000 10000

View File

@ -1,38 +0,0 @@
# @board px4_fmu-v2 exclude
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 1: Empty
---------------------------------------
Z:
Output 2: Steering mixer using yaw, with 0.5s rise time
---------------------------------------
M: 1
O: 10000 10000 0 -10000 10000 5000
S: 0 2 10000 10000 0 -10000 10000
Output 3: Empty
---------------------------------------
This mixer is empty.
Z:
Output 4: Throttle with 2s rise time
---------------------------------------
M: 1
O: 10000 10000 0 -10000 10000 20000
S: 0 3 10000 10000 0 -10000 10000

View File

@ -1,22 +0,0 @@
Mixer for Standard VTOL (QuadPlane) with motor x configuration (Gazebo HITL)
=============================================================================
# @board px4_fmu-v2 exclude
R: 4x
# mixer for the pusher/puller throttle
M: 1
S: 1 3 0 20000 -10000 -10000 10000
# mixer for the left aileron
M: 1
S: 1 0 -10000 -10000 0 -10000 10000
# mixer for the right aileron
M: 1
S: 1 0 10000 10000 0 -10000 10000
# mixer for the elevator
M: 1
S: 1 1 10000 10000 0 -10000 10000

View File

@ -1,33 +0,0 @@
Tilt-Quadrotor mixer for PX4FMU (2/2) V2
===========================
# @board px4_fmu-v2 exclude
This file defines the aux outputs mixer for a Tilt-quadrotor in the + configuration.
# @output AUX1 Outer servo motor for rotor 2 arm
# @output AUX2 Outer servo motor for rotor 4 arm
# @output AUX3 Inner servo motor for rotor 2 arm
# @output AUX4 Inner servo motor for rotor 4 arm
Servo 1
M: 1
S: 0 1 -1000 -1000 0 -10000 10000
Servo 2
M: 1
S: 0 1 1000 1000 0 -10000 10000
Servo 3
M: 2
S: 0 2 -10000 -10000 0 -10000 10000
S: 3 5 10000 10000 0 -10000 10000
Servo 4
M: 2
S: 0 2 10000 10000 0 -10000 10000
S: 3 5 10000 10000 0 -10000 10000

View File

@ -1,35 +0,0 @@
Tilt-Quadrotor mixer for PX4FMU (1/2) V2
===========================
# @board px4_fmu-v2 exclude
This file defines the main outputs mixer for a Tilt-quadrotor in the + configuration.
# @output MAIN1 motor 1
# @output MAIN2 motor 2
# @output MAIN3 motor 3
# @output MAIN4 motor 4
Motor 1
M: 2
S: 0 1 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
Motor 2
M: 2
S: 0 0 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
Motor 3
M: 2
S: 0 1 -10000 -10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
Motor 4
M: 2
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000

View File

@ -1,12 +0,0 @@
# @board px4_fmu-v2 exclude
# Tricopter Y-Configuration Mixer
# Yaw Servo +Output ==> +Yaw Vehicle Rotation
# Motors
R: 3y
# Yaw Servo
M: 1
S: 0 2 10000 10000 0 -10000 10000

View File

@ -1,13 +0,0 @@
# @board px4_fmu-v2 exclude
# Tricopter Y-Configuration Mixer
# Yaw Servo +Output ==> -Yaw Vehicle Rotation
# Motors
R: 3y
# Yaw Servo
M: 1
S: 0 2 -10000 -10000 0 -10000 10000

View File

@ -1,29 +0,0 @@
Mixer for an AAERT VTOL
=======================
# @board px4_fmu-v2 exclude
Aileron 1 mixer
---------------
M: 1
S: 1 0 7500 7500 0 -10000 10000
Aileron 2 mixer
---------------
M: 1
S: 1 0 7500 7500 0 -10000 10000
Elevator mixer
--------------
M: 1
S: 1 1 10000 10000 0 -10000 10000
Rudder mixer
------------
M: 1
S: 1 2 -10000 -10000 0 -10000 10000
Throttle mixer
--------------
M: 1
S: 1 3 0 20000 -10000 -10000 10000

View File

@ -1,56 +0,0 @@
Aileron/v-tail/throttle VTOL mixer for PX4FMU
=======================================================
# @board px4_fmu-v2 exclude
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 + spoiler)
---------------------------------
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
S: 1 0 -10000 -10000 0 -10000 10000
S: 1 5 10000 10000 0 -10000 10000
M: 2
S: 1 0 -10000 -10000 0 -10000 10000
S: 1 5 -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
S: 1 2 -7000 -7000 0 -10000 10000
S: 1 1 -8000 -8000 0 -10000 10000
M: 2
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
S: 1 3 0 20000 -10000 -10000 10000

View File

@ -1,41 +0,0 @@
# Generic quadplane tiltrotor servo mixer
# @board px4_fmu-v2 exclude
# Tilt mechanism servo mixer
---------------------------
# front left up:2000 down:1000
M: 1
S: 1 8 0 -20000 10000 -10000 10000
# front right up:1000 down:2000
M: 1
S: 1 8 0 20000 -10000 -10000 10000
# rear left up:2000 down:1000
M: 1
S: 1 8 0 -20000 10000 -10000 10000
# rear right up:1000 down:2000
M: 1
S: 1 8 0 20000 -10000 -10000 10000
# Aileron mixer
# ---------------------------------
M: 1
S: 1 0 10000 10000 0 -10000 10000
M: 1
S: 1 0 10000 10000 0 -10000 10000
# Elevator mixer
# ------------
M: 1
S: 1 1 -10000 -10000 0 -10000 10000
# Rudder mixer
# ------------
M: 1
S: 1 2 10000 10000 0 -10000 10000

View File

@ -1,52 +0,0 @@
Delta-wing VTOL mixer
=====================
# @board px4_fmu-v2 exclude
This file defines mixers suitable for controlling a delta wing VTOL aircraft using
PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
AUX servo outputs 0 and 1 and the motor speed control to output 2.
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.
M: 2
S: 1 0 8000 8000 0 -10000 10000
S: 1 1 8000 8000 0 -10000 10000
M: 2
S: 1 0 8000 8000 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
S: 1 3 0 20000 -10000 -10000 10000
Reverse thrust (brake) mixer
-----------------
M: 1
S: 1 6 0 20000 -10000 -10000 10000
Aux1 mixer
-----------------
This is actuated on the AUX5 port
M: 1
S: 3 5 10000 10000 0 -10000 10000

View File

@ -1,38 +0,0 @@
Tailsitter duo mixer
============================
# @board px4_fmu-v2 exclude
This file defines a mixer for a generic duo tailsitter VTOL (eg TBS Caipirinha tailsitter edition). This vehicle
has two motors in total, one attached to each wing. It also has two elevons which
are located in the slipstream of the propellers. This mixer generates 4 PWM outputs
on the main PWM output port, two at 400Hz for the motors, and two at 50Hz for the
elevon servos. Channels 1-4 are configured to run at 400Hz, while channels 5-8 run
at the default rate of 50Hz. Note that channels 3 and 4 are assigned but not used.
Motor mixer
------------
Channel 1 connects to the right (starboard) motor.
Channel 2 connects to the left (port) motor.
R: 2-
Zero mixer (2x)
---------------
Channels 3,4 are unused.
Z:
Z:
Elevons mixer
--------------
Channel 5 connects to the right (starboard) elevon.
Channel 6 connects to the left (port) elevon.
M: 2
S: 1 0 10000 10000 0 -10000 10000
S: 1 1 10000 10000 0 -10000 10000
M: 2
S: 1 0 10000 10000 0 -10000 10000
S: 1 1 -10000 -10000 0 -10000 10000

View File

@ -1,40 +0,0 @@
# @board px4_fmu-v2 exclude
Tailsitter duo mixer
============================
This file defines a mixer for a generic duo tailsitter VTOL (eg TBS Caipirinha tailsitter edition). This vehicle
has two motors in total, one attached to each wing. It also has two elevons which
are located in the slipstream of the propellers. This mixer generates 4 PWM outputs
on the main PWM output port, two at 400Hz for the motors, and two at 50Hz for the
elevon servos. Channels 1-4 are configured to run at 400Hz, while channels 5-8 run
at the default rate of 50Hz. Note that channels 3 and 4 are assigned but not used.
Motor mixer
------------
Channel 1 connects to the right (starboard) motor.
Channel 2 connects to the left (port) motor.
R: 2-
Zero mixer (2x)
---------------
Channels 3,4 are unused.
Z:
Z:
Elevons mixer
--------------
Channel 5 connects to the right (starboard) elevon.
Channel 6 connects to the left (port) elevon.
Here we saturate the elevons before their full range
to avoid roll-pitch-yaw coupling during faster maneuvers
M: 2
S: 1 0 10000 10000 0 -6000 6000
S: 1 1 10000 10000 0 -6000 6000
M: 2
S: 1 0 10000 10000 0 -6000 6000
S: 1 1 -10000 -10000 0 -6000 6000

View File

@ -32,4 +32,3 @@
############################################################################
add_subdirectory(init.d)
add_subdirectory(mixers)

View File

@ -1,96 +0,0 @@
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 + spoiler)
---------------------------------
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 5 10000 10000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 -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

View File

@ -1,84 +0,0 @@
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) 5 (spoiler).
Aileron mixer (roll + spoiler)
---------------------------------
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 5 10000 10000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 -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

View File

@ -1,81 +0,0 @@
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

View File

@ -1,81 +0,0 @@
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

View File

@ -1,53 +0,0 @@
############################################################################
#
# Copyright (c) 2018 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_romfs_files(
AAERTWF.main.mix
AAVVTWFF.main.mix
AERT.main.mix
AETRFG.main.mix
complex_test.mix
hexa_x.main.mix
IO_pass.mix
octo_x.main.mix
pass.aux.mix
quad_+.main.mix
quad_test.mix
quad_+_vtol.main.mix
rover_generic.main.mix
vtol1_test.mix
vtol2_test.mix
vtol_AAERT.aux.mix
vtol_AAVVT.aux.mix
vtol_convergence.main.mix
)

View File

@ -1,38 +0,0 @@
Passthrough mixer for PX4IO
============================
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

View File

@ -1,27 +0,0 @@
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: 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

View File

@ -1,4 +0,0 @@
# Hexa X
R: 6x

View File

@ -1,3 +0,0 @@
# Octo X
R: 8x

View File

@ -1,21 +0,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

View File

@ -1,18 +0,0 @@
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a quadrotor in the + configuration. All controls
are mixed 100%.
R: 4+
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

View File

@ -1,28 +0,0 @@
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+
# 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

View File

@ -1,25 +0,0 @@
Multirotor mixer for TEST
===========================
This file defines a single mixer for a quadrotor with a wide configuration. All controls are mixed 100%.
R: 4w
Gimbal / 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

View File

@ -1,7 +0,0 @@
R: 4x
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

View File

@ -1,37 +0,0 @@
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

View File

@ -1,12 +0,0 @@
# VTOL test mixer
R: 2-
Z:
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

View File

@ -1,32 +0,0 @@
# E-flite Convergence Tricopter Y-Configuration Mixer
# Motors
R: 3y
Z:
Tilt mechanism servo mixer
---------------------------
#RIGHT up:2000 down:1000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 8 0 -20000 9000 -10000 10000
S: 0 2 4000 4000 0 -10000 10000
#LEFT up:1000 down:2000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 0 2 4000 4000 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

View File

@ -1,32 +0,0 @@
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

View File

@ -1,59 +0,0 @@
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) 5 (spoiler).
Aileron mixer (roll + spoiler)
---------------------------------
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 5 10000 10000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 0 10000 10000 0 -10000 10000
S: 1 5 -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

View File

@ -1,32 +0,0 @@
# E-flite Convergence Tricopter Y-Configuration Mixer
# Motors
R: 3y
Z:
Tilt mechanism servo mixer
---------------------------
#RIGHT up:2000 down:1000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 8 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 8 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

View File

@ -105,18 +105,10 @@ def main():
# find excluded boards
if re.search(r'\b{0} exclude\b'.format(args.board), line):
board_excluded = True
# handle mixer files differently than startup files
if file_path.endswith(".mix"):
if line.startswith(("Z:", "M:", "R: ", "O:", "S:",
"H:", "T:", "P:", "A:")):
# reduce multiple consecutive spaces into a
# single space
line_reduced = re.sub(' +', ' ', line)
pruned_content += line_reduced
else:
if not line.isspace() \
and not line.strip().startswith("#"):
pruned_content += line.strip() + "\n"
if not line.isspace() \
and not line.strip().startswith("#"):
pruned_content += line.strip() + "\n"
# delete the file if it doesn't contain the architecture
# write out the pruned content else
if not board_excluded:

View File

@ -14,7 +14,7 @@ search_directory="$1"
command -v shellcheck >/dev/null 2>&1 || { echo -e >&2 \
"Error: shellcheck required but it's not installed. On Ubuntu use:\n sudo apt-get install shellcheck\n\nAborting."; exit 1; }
scripts="$(find "$search_directory" -type f ! -name '*.txt' ! -name '*.mix' ! -name '*.bin')"
scripts="$(find "$search_directory" -type f ! -name '*.txt' ! -name '*.bin')"
echo "Running shellcheck in '$search_directory'."

View File

@ -14,4 +14,6 @@ param set-default SENS_EN_THERMAL 0
param set-default -s SENS_TEMP_ID 2621474
param set-default SYS_USE_IO 1
set IOFW "/etc/extras/cubepilot_io-v2_default.bin"

View File

@ -13,4 +13,6 @@ param set-default BAT2_A_PER_V 17
# Disable IMU thermal control
param set-default SENS_EN_THERMAL 0
param set-default SYS_USE_IO 1
set IOFW "/etc/extras/cubepilot_io-v2_default.bin"

View File

@ -11,3 +11,5 @@ param set-default BAT2_A_PER_V 36.367515152
# Enable IMU thermal control
param set-default SENS_EN_THERMAL 1
param set-default SYS_USE_IO 1

View File

@ -9,5 +9,7 @@ param set-default BAT2_V_DIV 18.1
param set-default BAT1_A_PER_V 36.367515152
param set-default BAT2_A_PER_V 36.367515152
param set-default SYS_USE_IO 1
rgbled_pwm start
safety_button start

View File

@ -5,3 +5,5 @@
param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303
param set-default SYS_USE_IO 1

Binary file not shown.

View File

@ -5,3 +5,5 @@
param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303
param set-default SYS_USE_IO 1

View File

@ -6,3 +6,4 @@
param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303
param set-default SYS_USE_IO 1

Some files were not shown because too many files have changed in this diff Show More