diff --git a/.gitattributes b/.gitattributes index 353fdfa9b6..d5ff4edd8a 100644 --- a/.gitattributes +++ b/.gitattributes @@ -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 diff --git a/Makefile b/Makefile index 007d56c2ff..5d5943dde7 100644 --- a/Makefile +++ b/Makefile @@ -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 diff --git a/ROMFS/px4fmu_common/CMakeLists.txt b/ROMFS/px4fmu_common/CMakeLists.txt index 235b6c9ae9..281e5a87a0 100644 --- a/ROMFS/px4fmu_common/CMakeLists.txt +++ b/ROMFS/px4fmu_common/CMakeLists.txt @@ -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) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4001_x500 b/ROMFS/px4fmu_common/init.d-posix/airframes/4001_x500 index d58561cb2d..e7d33ca535 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4001_x500 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4001_x500 @@ -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 diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index e57de6f01f..d800a298e4 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/CMakeLists.txt index 81f99fcb65..05ec84d3ef 100644 --- a/ROMFS/px4fmu_common/init.d/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/CMakeLists.txt @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x b/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x index 69aac5a526..84f0755985 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x +++ b/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/rc.airship_apps b/ROMFS/px4fmu_common/init.d/rc.airship_apps index 4031bd4f71..837a3a2161 100644 --- a/ROMFS/px4fmu_common/init.d/rc.airship_apps +++ b/ROMFS/px4fmu_common/init.d/rc.airship_apps @@ -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. diff --git a/ROMFS/px4fmu_common/init.d/rc.airship_defaults b/ROMFS/px4fmu_common/init.d/rc.airship_defaults index 8c51643915..2b25850467 100644 --- a/ROMFS/px4fmu_common/init.d/rc.airship_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.airship_defaults @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart_ext b/ROMFS/px4fmu_common/init.d/rc.autostart_ext index 7f7916c7f9..4291a3db37 100644 --- a/ROMFS/px4fmu_common/init.d/rc.autostart_ext +++ b/ROMFS/px4fmu_common/init.d/rc.autostart_ext @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/rc.boat_defaults b/ROMFS/px4fmu_common/init.d/rc.boat_defaults index a281b8395e..93c8820883 100644 --- a/ROMFS/px4fmu_common/init.d/rc.boat_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.boat_defaults @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps index acc0fb27c5..2e2550884a 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_apps +++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps @@ -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. diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 6cae25306e..6f5d9cdf6a 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface deleted file mode 100644 index fee6ad252c..0000000000 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_apps b/ROMFS/px4fmu_common/init.d/rc.mc_apps index 60d9e65327..8158ab8b03 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_apps +++ b/ROMFS/px4fmu_common/init.d/rc.mc_apps @@ -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. diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index d057bf3050..25861aae45 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_apps b/ROMFS/px4fmu_common/init.d/rc.rover_apps index d1e389627e..4d04b53faa 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_apps +++ b/ROMFS/px4fmu_common/init.d/rc.rover_apps @@ -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. diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_defaults b/ROMFS/px4fmu_common/init.d/rc.rover_defaults index d7e826c49c..cab52039d4 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.rover_defaults @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/rc.uuv_apps b/ROMFS/px4fmu_common/init.d/rc.uuv_apps index 1855805fc2..d2eb13208c 100644 --- a/ROMFS/px4fmu_common/init.d/rc.uuv_apps +++ b/ROMFS/px4fmu_common/init.d/rc.uuv_apps @@ -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. diff --git a/ROMFS/px4fmu_common/init.d/rc.uuv_defaults b/ROMFS/px4fmu_common/init.d/rc.uuv_defaults index 01e755fc29..bb28c26222 100644 --- a/ROMFS/px4fmu_common/init.d/rc.uuv_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.uuv_defaults @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/rc.vehicle_setup b/ROMFS/px4fmu_common/init.d/rc.vehicle_setup index aac1b76fed..4f8497bc19 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vehicle_setup +++ b/ROMFS/px4fmu_common/init.d/rc.vehicle_setup @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_apps b/ROMFS/px4fmu_common/init.d/rc.vtol_apps index afcf32f45a..0bb53168d1 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_apps +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_apps @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 00c52d07a1..94a639d0ac 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -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 # diff --git a/ROMFS/px4fmu_common/mixers/AAERTWF.main.mix b/ROMFS/px4fmu_common/mixers/AAERTWF.main.mix deleted file mode 100644 index 20d4c21d93..0000000000 --- a/ROMFS/px4fmu_common/mixers/AAERTWF.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/AAVVTWFF.main.mix b/ROMFS/px4fmu_common/mixers/AAVVTWFF.main.mix deleted file mode 100644 index 9a994da0ef..0000000000 --- a/ROMFS/px4fmu_common/mixers/AAVVTWFF.main.mix +++ /dev/null @@ -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 - diff --git a/ROMFS/px4fmu_common/mixers/AAVVTWFF_vtail.main.mix b/ROMFS/px4fmu_common/mixers/AAVVTWFF_vtail.main.mix deleted file mode 100644 index ad65ca999c..0000000000 --- a/ROMFS/px4fmu_common/mixers/AAVVTWFF_vtail.main.mix +++ /dev/null @@ -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 - diff --git a/ROMFS/px4fmu_common/mixers/AERT.main.mix b/ROMFS/px4fmu_common/mixers/AERT.main.mix deleted file mode 100644 index 356ff613ae..0000000000 --- a/ROMFS/px4fmu_common/mixers/AERT.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/AETRFG.main.mix b/ROMFS/px4fmu_common/mixers/AETRFG.main.mix deleted file mode 100644 index d5cf84219b..0000000000 --- a/ROMFS/px4fmu_common/mixers/AETRFG.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/CCPM.main.mix b/ROMFS/px4fmu_common/mixers/CCPM.main.mix deleted file mode 100644 index 8f7af5aee8..0000000000 --- a/ROMFS/px4fmu_common/mixers/CCPM.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/CMakeLists.txt b/ROMFS/px4fmu_common/mixers/CMakeLists.txt deleted file mode 100644 index 5e00c9f9ab..0000000000 --- a/ROMFS/px4fmu_common/mixers/CMakeLists.txt +++ /dev/null @@ -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 -) diff --git a/ROMFS/px4fmu_common/mixers/IO_pass.main.mix b/ROMFS/px4fmu_common/mixers/IO_pass.main.mix deleted file mode 100644 index d18e1850e1..0000000000 --- a/ROMFS/px4fmu_common/mixers/IO_pass.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/cloudship.main.mix b/ROMFS/px4fmu_common/mixers/cloudship.main.mix deleted file mode 100644 index decee989ef..0000000000 --- a/ROMFS/px4fmu_common/mixers/cloudship.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/coax.main.mix b/ROMFS/px4fmu_common/mixers/coax.main.mix deleted file mode 100644 index 0a99547e20..0000000000 --- a/ROMFS/px4fmu_common/mixers/coax.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/dodeca_bottom_cox.aux.mix b/ROMFS/px4fmu_common/mixers/dodeca_bottom_cox.aux.mix deleted file mode 100644 index 8429e71cba..0000000000 --- a/ROMFS/px4fmu_common/mixers/dodeca_bottom_cox.aux.mix +++ /dev/null @@ -1,4 +0,0 @@ -# Dodeca Cox -# @board px4_fmu-v2 exclude - -R: 6a diff --git a/ROMFS/px4fmu_common/mixers/dodeca_top_cox.main.mix b/ROMFS/px4fmu_common/mixers/dodeca_top_cox.main.mix deleted file mode 100644 index 6250c3db0a..0000000000 --- a/ROMFS/px4fmu_common/mixers/dodeca_top_cox.main.mix +++ /dev/null @@ -1,4 +0,0 @@ -# Dodeca Cox -# @board px4_fmu-v2 exclude - -R: 6m diff --git a/ROMFS/px4fmu_common/mixers/fw_generic_wing.main.mix b/ROMFS/px4fmu_common/mixers/fw_generic_wing.main.mix deleted file mode 100644 index f947698d82..0000000000 --- a/ROMFS/px4fmu_common/mixers/fw_generic_wing.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/generic_diff_rover.main.mix b/ROMFS/px4fmu_common/mixers/generic_diff_rover.main.mix deleted file mode 100644 index d97aeeac0d..0000000000 --- a/ROMFS/px4fmu_common/mixers/generic_diff_rover.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/hexa_+.main.mix b/ROMFS/px4fmu_common/mixers/hexa_+.main.mix deleted file mode 100644 index 383e2d4e63..0000000000 --- a/ROMFS/px4fmu_common/mixers/hexa_+.main.mix +++ /dev/null @@ -1,4 +0,0 @@ -# @board px4_fmu-v2 exclude -# Hexa + - -R: 6+ diff --git a/ROMFS/px4fmu_common/mixers/hexa_cox.main.mix b/ROMFS/px4fmu_common/mixers/hexa_cox.main.mix deleted file mode 100644 index c8985dfee2..0000000000 --- a/ROMFS/px4fmu_common/mixers/hexa_cox.main.mix +++ /dev/null @@ -1,4 +0,0 @@ -# @board px4_fmu-v2 exclude -# Hexa coaxial - -R: 6c diff --git a/ROMFS/px4fmu_common/mixers/hexa_x.main.mix b/ROMFS/px4fmu_common/mixers/hexa_x.main.mix deleted file mode 100644 index 2a25a25580..0000000000 --- a/ROMFS/px4fmu_common/mixers/hexa_x.main.mix +++ /dev/null @@ -1,5 +0,0 @@ -# @board px4_fmu-v2 exclude -# Hexa X - -R: 6x - diff --git a/ROMFS/px4fmu_common/mixers/mount.aux.mix b/ROMFS/px4fmu_common/mixers/mount.aux.mix deleted file mode 100644 index 2b23af6e7a..0000000000 --- a/ROMFS/px4fmu_common/mixers/mount.aux.mix +++ /dev/null @@ -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 - diff --git a/ROMFS/px4fmu_common/mixers/mount_legs.aux.mix b/ROMFS/px4fmu_common/mixers/mount_legs.aux.mix deleted file mode 100644 index c9a0ce49f0..0000000000 --- a/ROMFS/px4fmu_common/mixers/mount_legs.aux.mix +++ /dev/null @@ -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 - diff --git a/ROMFS/px4fmu_common/mixers/octo_+.main.mix b/ROMFS/px4fmu_common/mixers/octo_+.main.mix deleted file mode 100644 index 9f443b33f4..0000000000 --- a/ROMFS/px4fmu_common/mixers/octo_+.main.mix +++ /dev/null @@ -1,4 +0,0 @@ -# @board px4_fmu-v2 exclude -# Octo + - -R: 8+ diff --git a/ROMFS/px4fmu_common/mixers/octo_cox.main.mix b/ROMFS/px4fmu_common/mixers/octo_cox.main.mix deleted file mode 100644 index c6730d8d86..0000000000 --- a/ROMFS/px4fmu_common/mixers/octo_cox.main.mix +++ /dev/null @@ -1,4 +0,0 @@ -# @board px4_fmu-v2 exclude -# Octo coaxial - -R: 8c diff --git a/ROMFS/px4fmu_common/mixers/octo_cox_w.main.mix b/ROMFS/px4fmu_common/mixers/octo_cox_w.main.mix deleted file mode 100644 index c6ef858590..0000000000 --- a/ROMFS/px4fmu_common/mixers/octo_cox_w.main.mix +++ /dev/null @@ -1,4 +0,0 @@ -# Octo coaxial with wide arms -# @board px4_fmu-v2 exclude - -R: 8cw diff --git a/ROMFS/px4fmu_common/mixers/octo_x.main.mix b/ROMFS/px4fmu_common/mixers/octo_x.main.mix deleted file mode 100644 index 6ebd0dee99..0000000000 --- a/ROMFS/px4fmu_common/mixers/octo_x.main.mix +++ /dev/null @@ -1,4 +0,0 @@ -# @board px4_fmu-v2 exclude -# Octo X - -R: 8x diff --git a/ROMFS/px4fmu_common/mixers/pass.aux.mix b/ROMFS/px4fmu_common/mixers/pass.aux.mix deleted file mode 100644 index 4615687def..0000000000 --- a/ROMFS/px4fmu_common/mixers/pass.aux.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/quad_+.main.mix b/ROMFS/px4fmu_common/mixers/quad_+.main.mix deleted file mode 100644 index 5dfa5a0014..0000000000 --- a/ROMFS/px4fmu_common/mixers/quad_+.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/quad_+_vtol.main.mix b/ROMFS/px4fmu_common/mixers/quad_+_vtol.main.mix deleted file mode 100644 index 34c09c73d3..0000000000 --- a/ROMFS/px4fmu_common/mixers/quad_+_vtol.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/quad_dc.main.mix b/ROMFS/px4fmu_common/mixers/quad_dc.main.mix deleted file mode 100644 index f87a8bf044..0000000000 --- a/ROMFS/px4fmu_common/mixers/quad_dc.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/quad_h.main.mix b/ROMFS/px4fmu_common/mixers/quad_h.main.mix deleted file mode 100644 index 9be41f5c09..0000000000 --- a/ROMFS/px4fmu_common/mixers/quad_h.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/quad_w.main.mix b/ROMFS/px4fmu_common/mixers/quad_w.main.mix deleted file mode 100644 index 79bba7752f..0000000000 --- a/ROMFS/px4fmu_common/mixers/quad_w.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/quad_x.main.mix b/ROMFS/px4fmu_common/mixers/quad_x.main.mix deleted file mode 100644 index ad676ff3e3..0000000000 --- a/ROMFS/px4fmu_common/mixers/quad_x.main.mix +++ /dev/null @@ -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: diff --git a/ROMFS/px4fmu_common/mixers/quad_x_cw.main.mix b/ROMFS/px4fmu_common/mixers/quad_x_cw.main.mix deleted file mode 100644 index 32bc010ba5..0000000000 --- a/ROMFS/px4fmu_common/mixers/quad_x_cw.main.mix +++ /dev/null @@ -1,4 +0,0 @@ -# @board px4_fmu-v2 exclude -# Quad X with clock-wise motor assigment - -R: 4xcw diff --git a/ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix b/ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix deleted file mode 100644 index ae88688925..0000000000 --- a/ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/quad_x_vtol_AAERT.main.mix b/ROMFS/px4fmu_common/mixers/quad_x_vtol_AAERT.main.mix deleted file mode 100644 index d0f32d9199..0000000000 --- a/ROMFS/px4fmu_common/mixers/quad_x_vtol_AAERT.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/rover_diff_and_servo.main.mix b/ROMFS/px4fmu_common/mixers/rover_diff_and_servo.main.mix deleted file mode 100644 index bf00eae8f5..0000000000 --- a/ROMFS/px4fmu_common/mixers/rover_diff_and_servo.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/rover_generic.main.mix b/ROMFS/px4fmu_common/mixers/rover_generic.main.mix deleted file mode 100644 index 687896e722..0000000000 --- a/ROMFS/px4fmu_common/mixers/rover_generic.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/standard_vtol_hitl.main.mix b/ROMFS/px4fmu_common/mixers/standard_vtol_hitl.main.mix deleted file mode 100644 index a7ce6c991a..0000000000 --- a/ROMFS/px4fmu_common/mixers/standard_vtol_hitl.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/tilt_quad.aux.mix b/ROMFS/px4fmu_common/mixers/tilt_quad.aux.mix deleted file mode 100644 index fd4d3d9068..0000000000 --- a/ROMFS/px4fmu_common/mixers/tilt_quad.aux.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/tilt_quad.main.mix b/ROMFS/px4fmu_common/mixers/tilt_quad.main.mix deleted file mode 100644 index 5d7cf9acb1..0000000000 --- a/ROMFS/px4fmu_common/mixers/tilt_quad.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/tri_y_yaw+.main.mix b/ROMFS/px4fmu_common/mixers/tri_y_yaw+.main.mix deleted file mode 100644 index 9b0a9b2708..0000000000 --- a/ROMFS/px4fmu_common/mixers/tri_y_yaw+.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/tri_y_yaw-.main.mix b/ROMFS/px4fmu_common/mixers/tri_y_yaw-.main.mix deleted file mode 100644 index d53811142b..0000000000 --- a/ROMFS/px4fmu_common/mixers/tri_y_yaw-.main.mix +++ /dev/null @@ -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 - diff --git a/ROMFS/px4fmu_common/mixers/vtol_AAERT.aux.mix b/ROMFS/px4fmu_common/mixers/vtol_AAERT.aux.mix deleted file mode 100644 index efef782992..0000000000 --- a/ROMFS/px4fmu_common/mixers/vtol_AAERT.aux.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/vtol_AAVVT.aux.mix b/ROMFS/px4fmu_common/mixers/vtol_AAVVT.aux.mix deleted file mode 100644 index e59584b213..0000000000 --- a/ROMFS/px4fmu_common/mixers/vtol_AAVVT.aux.mix +++ /dev/null @@ -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 - diff --git a/ROMFS/px4fmu_common/mixers/vtol_TTTTAAER.aux.mix b/ROMFS/px4fmu_common/mixers/vtol_TTTTAAER.aux.mix deleted file mode 100644 index fe684c70bc..0000000000 --- a/ROMFS/px4fmu_common/mixers/vtol_TTTTAAER.aux.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/vtol_delta.aux.mix b/ROMFS/px4fmu_common/mixers/vtol_delta.aux.mix deleted file mode 100644 index af248f7ce0..0000000000 --- a/ROMFS/px4fmu_common/mixers/vtol_delta.aux.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo.main.mix b/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo.main.mix deleted file mode 100644 index ba3a277224..0000000000 --- a/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo_sat.main.mix b/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo_sat.main.mix deleted file mode 100644 index 55d0f1fe4a..0000000000 --- a/ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo_sat.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/CMakeLists.txt b/ROMFS/px4fmu_test/CMakeLists.txt index be3e27cb99..4844928124 100644 --- a/ROMFS/px4fmu_test/CMakeLists.txt +++ b/ROMFS/px4fmu_test/CMakeLists.txt @@ -32,4 +32,3 @@ ############################################################################ add_subdirectory(init.d) -add_subdirectory(mixers) diff --git a/ROMFS/px4fmu_test/mixers/AAERTWF.main.mix b/ROMFS/px4fmu_test/mixers/AAERTWF.main.mix deleted file mode 100644 index 150e95d894..0000000000 --- a/ROMFS/px4fmu_test/mixers/AAERTWF.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/AAVVTWFF.main.mix b/ROMFS/px4fmu_test/mixers/AAVVTWFF.main.mix deleted file mode 100644 index 531cccaf1a..0000000000 --- a/ROMFS/px4fmu_test/mixers/AAVVTWFF.main.mix +++ /dev/null @@ -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 - diff --git a/ROMFS/px4fmu_test/mixers/AERT.main.mix b/ROMFS/px4fmu_test/mixers/AERT.main.mix deleted file mode 100644 index 975d520081..0000000000 --- a/ROMFS/px4fmu_test/mixers/AERT.main.mix +++ /dev/null @@ -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 \ No newline at end of file diff --git a/ROMFS/px4fmu_test/mixers/AETRFG.main.mix b/ROMFS/px4fmu_test/mixers/AETRFG.main.mix deleted file mode 100644 index 47de4ed3e0..0000000000 --- a/ROMFS/px4fmu_test/mixers/AETRFG.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/CMakeLists.txt b/ROMFS/px4fmu_test/mixers/CMakeLists.txt deleted file mode 100644 index 287652a9b8..0000000000 --- a/ROMFS/px4fmu_test/mixers/CMakeLists.txt +++ /dev/null @@ -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 - ) diff --git a/ROMFS/px4fmu_test/mixers/IO_pass.mix b/ROMFS/px4fmu_test/mixers/IO_pass.mix deleted file mode 100644 index 39f875ddb9..0000000000 --- a/ROMFS/px4fmu_test/mixers/IO_pass.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/complex_test.mix b/ROMFS/px4fmu_test/mixers/complex_test.mix deleted file mode 100644 index 06b5e62594..0000000000 --- a/ROMFS/px4fmu_test/mixers/complex_test.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/hexa_x.main.mix b/ROMFS/px4fmu_test/mixers/hexa_x.main.mix deleted file mode 100644 index be6a25ca57..0000000000 --- a/ROMFS/px4fmu_test/mixers/hexa_x.main.mix +++ /dev/null @@ -1,4 +0,0 @@ -# Hexa X - -R: 6x - diff --git a/ROMFS/px4fmu_test/mixers/octo_x.main.mix b/ROMFS/px4fmu_test/mixers/octo_x.main.mix deleted file mode 100644 index 1be7209411..0000000000 --- a/ROMFS/px4fmu_test/mixers/octo_x.main.mix +++ /dev/null @@ -1,3 +0,0 @@ -# Octo X - -R: 8x diff --git a/ROMFS/px4fmu_test/mixers/pass.aux.mix b/ROMFS/px4fmu_test/mixers/pass.aux.mix deleted file mode 100644 index 8e7011f0ed..0000000000 --- a/ROMFS/px4fmu_test/mixers/pass.aux.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/quad_+.main.mix b/ROMFS/px4fmu_test/mixers/quad_+.main.mix deleted file mode 100644 index c45a501961..0000000000 --- a/ROMFS/px4fmu_test/mixers/quad_+.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/quad_+_vtol.main.mix b/ROMFS/px4fmu_test/mixers/quad_+_vtol.main.mix deleted file mode 100644 index 8ab9a9fb91..0000000000 --- a/ROMFS/px4fmu_test/mixers/quad_+_vtol.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/quad_test.mix b/ROMFS/px4fmu_test/mixers/quad_test.mix deleted file mode 100644 index d3ed8a3479..0000000000 --- a/ROMFS/px4fmu_test/mixers/quad_test.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/quad_x.main.mix b/ROMFS/px4fmu_test/mixers/quad_x.main.mix deleted file mode 100644 index 85b9927002..0000000000 --- a/ROMFS/px4fmu_test/mixers/quad_x.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/rover_generic.main.mix b/ROMFS/px4fmu_test/mixers/rover_generic.main.mix deleted file mode 100644 index aacfef1f5b..0000000000 --- a/ROMFS/px4fmu_test/mixers/rover_generic.main.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/vtol1_test.mix b/ROMFS/px4fmu_test/mixers/vtol1_test.mix deleted file mode 100644 index 9df14777be..0000000000 --- a/ROMFS/px4fmu_test/mixers/vtol1_test.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/vtol2_test.mix b/ROMFS/px4fmu_test/mixers/vtol2_test.mix deleted file mode 100644 index f9ed50e6c9..0000000000 --- a/ROMFS/px4fmu_test/mixers/vtol2_test.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/vtol_AAERT.aux.mix b/ROMFS/px4fmu_test/mixers/vtol_AAERT.aux.mix deleted file mode 100644 index f3e9c42354..0000000000 --- a/ROMFS/px4fmu_test/mixers/vtol_AAERT.aux.mix +++ /dev/null @@ -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 diff --git a/ROMFS/px4fmu_test/mixers/vtol_AAVVT.aux.mix b/ROMFS/px4fmu_test/mixers/vtol_AAVVT.aux.mix deleted file mode 100644 index a9026ebd65..0000000000 --- a/ROMFS/px4fmu_test/mixers/vtol_AAVVT.aux.mix +++ /dev/null @@ -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 - diff --git a/ROMFS/px4fmu_test/mixers/vtol_convergence.main.mix b/ROMFS/px4fmu_test/mixers/vtol_convergence.main.mix deleted file mode 100644 index ed9b69360b..0000000000 --- a/ROMFS/px4fmu_test/mixers/vtol_convergence.main.mix +++ /dev/null @@ -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 diff --git a/Tools/px_romfs_pruner.py b/Tools/px_romfs_pruner.py index 46b9eff80f..20ae3109bf 100755 --- a/Tools/px_romfs_pruner.py +++ b/Tools/px_romfs_pruner.py @@ -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: diff --git a/Tools/run-shellcheck.sh b/Tools/run-shellcheck.sh index af64143761..5c745bad7a 100755 --- a/Tools/run-shellcheck.sh +++ b/Tools/run-shellcheck.sh @@ -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'." diff --git a/boards/cubepilot/cubeorange/init/rc.board_defaults b/boards/cubepilot/cubeorange/init/rc.board_defaults index 7f961cd33e..8ae2ed458b 100644 --- a/boards/cubepilot/cubeorange/init/rc.board_defaults +++ b/boards/cubepilot/cubeorange/init/rc.board_defaults @@ -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" diff --git a/boards/cubepilot/cubeyellow/init/rc.board_defaults b/boards/cubepilot/cubeyellow/init/rc.board_defaults index 6f39beb0c8..54705e650d 100644 --- a/boards/cubepilot/cubeyellow/init/rc.board_defaults +++ b/boards/cubepilot/cubeyellow/init/rc.board_defaults @@ -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" diff --git a/boards/holybro/durandal-v1/init/rc.board_defaults b/boards/holybro/durandal-v1/init/rc.board_defaults index 49254efb15..2a3b2c0a7b 100644 --- a/boards/holybro/durandal-v1/init/rc.board_defaults +++ b/boards/holybro/durandal-v1/init/rc.board_defaults @@ -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 diff --git a/boards/holybro/pix32v5/init/rc.board_defaults b/boards/holybro/pix32v5/init/rc.board_defaults index c2300a50a7..94c5828214 100644 --- a/boards/holybro/pix32v5/init/rc.board_defaults +++ b/boards/holybro/pix32v5/init/rc.board_defaults @@ -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 diff --git a/boards/mro/x21-777/init/rc.board_defaults b/boards/mro/x21-777/init/rc.board_defaults index 5d576dd747..e9fecd78a8 100644 --- a/boards/mro/x21-777/init/rc.board_defaults +++ b/boards/mro/x21-777/init/rc.board_defaults @@ -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 diff --git a/boards/mro/x21/extras/px4_io-v2_default.bin b/boards/mro/x21/extras/px4_io-v2_default.bin new file mode 100755 index 0000000000..5140391401 Binary files /dev/null and b/boards/mro/x21/extras/px4_io-v2_default.bin differ diff --git a/boards/mro/x21/init/rc.board_defaults b/boards/mro/x21/init/rc.board_defaults index 5d576dd747..e9fecd78a8 100644 --- a/boards/mro/x21/init/rc.board_defaults +++ b/boards/mro/x21/init/rc.board_defaults @@ -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 diff --git a/boards/px4/fmu-v2/init/rc.board_defaults b/boards/px4/fmu-v2/init/rc.board_defaults index 65348c4f84..e9fecd78a8 100644 --- a/boards/px4/fmu-v2/init/rc.board_defaults +++ b/boards/px4/fmu-v2/init/rc.board_defaults @@ -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 diff --git a/boards/px4/fmu-v3/init/rc.board_defaults b/boards/px4/fmu-v3/init/rc.board_defaults index 65348c4f84..e9fecd78a8 100644 --- a/boards/px4/fmu-v3/init/rc.board_defaults +++ b/boards/px4/fmu-v3/init/rc.board_defaults @@ -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 diff --git a/boards/px4/fmu-v4pro/init/rc.board_defaults b/boards/px4/fmu-v4pro/init/rc.board_defaults index 8dd9df28d5..42378a19d7 100644 --- a/boards/px4/fmu-v4pro/init/rc.board_defaults +++ b/boards/px4/fmu-v4pro/init/rc.board_defaults @@ -13,4 +13,6 @@ param set-default BAT2_A_PER_V 26.4 param set-default EKF2_MULTI_IMU 2 param set-default SENS_IMU_MODE 0 +param set-default SYS_USE_IO 1 + set LOGGER_BUF 64 diff --git a/boards/px4/fmu-v5/init/rc.board_defaults b/boards/px4/fmu-v5/init/rc.board_defaults index b88ad0245e..67829cee28 100644 --- a/boards/px4/fmu-v5/init/rc.board_defaults +++ b/boards/px4/fmu-v5/init/rc.board_defaults @@ -9,6 +9,13 @@ 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 +if ver hwtypecmp V5004000 V5006000 +then + param set-default SYS_USE_IO 0 +else + param set-default SYS_USE_IO 1 +fi + if ver hwtypecmp V5005000 V5005002 V5006000 V5006002 then # CUAV V5+ (V550/V552) and V5nano (V560/V562) have 3 IMUs diff --git a/boards/px4/fmu-v5x/init/rc.board_defaults b/boards/px4/fmu-v5x/init/rc.board_defaults index a7d844a366..ba812e4b7b 100644 --- a/boards/px4/fmu-v5x/init/rc.board_defaults +++ b/boards/px4/fmu-v5x/init/rc.board_defaults @@ -16,4 +16,6 @@ param set-default SENS_EN_INA238 0 param set-default SENS_EN_INA228 0 param set-default SENS_EN_INA226 1 +param set-default SYS_USE_IO 1 + safety_button start diff --git a/boards/px4/fmu-v6c/init/rc.board_defaults b/boards/px4/fmu-v6c/init/rc.board_defaults index f7dd269721..6418e5836d 100644 --- a/boards/px4/fmu-v6c/init/rc.board_defaults +++ b/boards/px4/fmu-v6c/init/rc.board_defaults @@ -9,3 +9,5 @@ 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 diff --git a/boards/px4/fmu-v6x/init/rc.board_defaults b/boards/px4/fmu-v6x/init/rc.board_defaults index a7d844a366..ba812e4b7b 100644 --- a/boards/px4/fmu-v6x/init/rc.board_defaults +++ b/boards/px4/fmu-v6x/init/rc.board_defaults @@ -16,4 +16,6 @@ param set-default SENS_EN_INA238 0 param set-default SENS_EN_INA228 0 param set-default SENS_EN_INA226 1 +param set-default SYS_USE_IO 1 + safety_button start diff --git a/boards/sky-drones/smartap-airlink/init/rc.board_defaults b/boards/sky-drones/smartap-airlink/init/rc.board_defaults index 14270fc9df..c581f8c741 100644 --- a/boards/sky-drones/smartap-airlink/init/rc.board_defaults +++ b/boards/sky-drones/smartap-airlink/init/rc.board_defaults @@ -25,6 +25,7 @@ param set-default BAT_V_OFFS_CURR 0.413 # Disable safety switch param set-default CBRK_IO_SAFETY 22027 +param set-default SYS_USE_IO 1 safety_button start diff --git a/boards/spracing/h7extreme/init/rc.board_defaults b/boards/spracing/h7extreme/init/rc.board_defaults index e154e34980..34177ec437 100644 --- a/boards/spracing/h7extreme/init/rc.board_defaults +++ b/boards/spracing/h7extreme/init/rc.board_defaults @@ -19,5 +19,3 @@ param set-default ATT_W_ACC 0.4000 param set-default ATT_W_GYRO_BIAS 0.0000 param set-default SYS_HAS_MAG 0 - -param set-default DSHOT_CONFIG 600 diff --git a/posix-configs/SITL/init/test/test_shutdown b/posix-configs/SITL/init/test/test_shutdown index 6cc691ebaa..7a66bb4577 100644 --- a/posix-configs/SITL/init/test/test_shutdown +++ b/posix-configs/SITL/init/test/test_shutdown @@ -33,7 +33,7 @@ fw_pos_control_l1 start vtol fw_att_control start vtol airspeed_selector start -#mixer load /dev/pwm_output0 ROMFS/sitl/mixers/standard_vtol_sitl.main.mix +control_allocator start ver all diff --git a/posix-configs/bbblue/px4.config b/posix-configs/bbblue/px4.config index 80c0b18d72..7ae7ed0f27 100644 --- a/posix-configs/bbblue/px4.config +++ b/posix-configs/bbblue/px4.config @@ -82,8 +82,8 @@ sleep 1 # RC port is mapped to /dev/ttyS4 (auto-detected) #rc_input start -d /dev/ttyS4 +control_allocator start linux_pwm_out start -mixer load /dev/pwm_out etc/mixers/quad_x.main.mix logger start -t -b 200 diff --git a/posix-configs/bbblue/px4_fw.config b/posix-configs/bbblue/px4_fw.config index 4097e7e035..7e3d6f0e74 100644 --- a/posix-configs/bbblue/px4_fw.config +++ b/posix-configs/bbblue/px4_fw.config @@ -77,8 +77,8 @@ sleep 1 # RC port is mapped to /dev/ttyS4 (auto-detected) rc_input start -d /dev/ttyS4 +control_allocator start linux_pwm_out start -mixer load /dev/pwm_out etc/mixers/AETRFG.main.mix logger start -t -b 200 diff --git a/posix-configs/rpi/pilotpi_fw.config b/posix-configs/rpi/pilotpi_fw.config index 01807d0d60..7235007931 100644 --- a/posix-configs/rpi/pilotpi_fw.config +++ b/posix-configs/rpi/pilotpi_fw.config @@ -42,7 +42,7 @@ ads1115 start -I # PWM pca9685_pwm_out start -mixer load /dev/pwm_output0 etc/mixers/AAERTWF.main.mix +control_allocator start # external GPS & compass gps start -d /dev/ttySC0 -i uart -p ubx -s diff --git a/posix-configs/rpi/pilotpi_mc.config b/posix-configs/rpi/pilotpi_mc.config index 7a4807fad5..9c037597c7 100644 --- a/posix-configs/rpi/pilotpi_mc.config +++ b/posix-configs/rpi/pilotpi_mc.config @@ -42,7 +42,7 @@ ads1115 start -I # PWM pca9685_pwm_out start -mixer load /dev/pwm_output0 etc/mixers/quad_x.main.mix +control_allocator start # external GPS & compass gps start -d /dev/ttySC0 -i uart -p ubx -s diff --git a/posix-configs/rpi/px4.config b/posix-configs/rpi/px4.config index b6663669e5..3937452583 100644 --- a/posix-configs/rpi/px4.config +++ b/posix-configs/rpi/px4.config @@ -57,7 +57,7 @@ fi navio_sysfs_rc_in start linux_pwm_out start -mixer load /dev/pwm_out etc/mixers/quad_x.main.mix +control_allocator start logger start -t -b 200 diff --git a/posix-configs/rpi/px4_fw.config b/posix-configs/rpi/px4_fw.config index 387e0a745a..7e65605bef 100644 --- a/posix-configs/rpi/px4_fw.config +++ b/posix-configs/rpi/px4_fw.config @@ -55,7 +55,7 @@ fi navio_sysfs_rc_in start linux_pwm_out start -mixer load /dev/pwm_out etc/mixers/AETRFG.main.mix +control_allocator start logger start -t -b 200 diff --git a/posix-configs/rpi/px4_hil.config b/posix-configs/rpi/px4_hil.config index 802e3c01ec..6554f52d45 100644 --- a/posix-configs/rpi/px4_hil.config +++ b/posix-configs/rpi/px4_hil.config @@ -37,7 +37,7 @@ mc_rate_control start mavlink start -x -u 14577 -r 1000000 -p navio_sysfs_rc_in start pwm_out_sim start -mixer load /dev/pwm_output0 etc/mixers/quad_x.main.mix +control_allocator start logger start -t -b 200 diff --git a/posix-configs/rpi/px4_test.config b/posix-configs/rpi/px4_test.config index 5b14f185b8..74c6643b3b 100644 --- a/posix-configs/rpi/px4_test.config +++ b/posix-configs/rpi/px4_test.config @@ -54,7 +54,7 @@ fi navio_sysfs_rc_in start linux_pwm_out start -mixer load /dev/pwm_out etc/mixers/quad_x.main.mix +control_allocator start logger start -t -f -b 200 diff --git a/src/drivers/dshot/DShot.cpp b/src/drivers/dshot/DShot.cpp index de97422716..2b4acc7cb3 100644 --- a/src/drivers/dshot/DShot.cpp +++ b/src/drivers/dshot/DShot.cpp @@ -191,41 +191,6 @@ void DShot::enable_dshot_outputs(const bool enabled) request_stop(); return; } - - } else { - DShotConfig config = (DShotConfig)_param_dshot_config.get(); - - unsigned int dshot_frequency = DSHOT600; - - switch (config) { - case DShotConfig::DShot150: - dshot_frequency = DSHOT150; - break; - - case DShotConfig::DShot300: - dshot_frequency = DSHOT300; - break; - - case DShotConfig::DShot600: - dshot_frequency = DSHOT600; - break; - - case DShotConfig::DShot1200: - dshot_frequency = DSHOT1200; - break; - - default: - break; - } - - int ret = up_dshot_init(_output_mask, dshot_frequency); - - if (ret < 0) { - PX4_ERR("up_dshot_init failed (%i)", ret); - return; - } - - _output_mask = ret; } _outputs_initialized = true; diff --git a/src/drivers/dshot/DShot.h b/src/drivers/dshot/DShot.h index 1e2169a810..3bf4e7784f 100644 --- a/src/drivers/dshot/DShot.h +++ b/src/drivers/dshot/DShot.h @@ -177,7 +177,6 @@ private: uORB::Publication _command_ack_pub{ORB_ID(vehicle_command_ack)}; DEFINE_PARAMETERS( - (ParamInt) _param_dshot_config, (ParamFloat) _param_dshot_min, (ParamBool) _param_dshot_3d_enable, (ParamInt) _param_dshot_3d_dead_h, diff --git a/src/drivers/dshot/module.yaml b/src/drivers/dshot/module.yaml index 850aaf69df..edd38edd23 100644 --- a/src/drivers/dshot/module.yaml +++ b/src/drivers/dshot/module.yaml @@ -8,24 +8,6 @@ serial_config: parameters: - group: DShot definitions: - DSHOT_CONFIG: - description: - short: Configure DShot - long: | - This enables/disables DShot. The different modes define different - speeds, for example DShot150 = 150kb/s. Not all ESCs support all modes. - - Note: this enables DShot on the FMU outputs. For boards with an IO it is the - AUX outputs. - type: enum - values: - 0: Disable (use PWM/Oneshot) - 150: DShot150 - 300: DShot300 - 600: DShot600 - 1200: DShot1200 - reboot_required: true - default: 0 DSHOT_MIN: description: short: Minimum DShot Motor Output diff --git a/src/drivers/px4io/px4io_params.c b/src/drivers/px4io/px4io_params.c index 84385e4216..ef1c1ee6ab 100644 --- a/src/drivers/px4io/px4io_params.c +++ b/src/drivers/px4io/px4io_params.c @@ -52,7 +52,7 @@ * @reboot_required true * @group System */ -PARAM_DEFINE_INT32(SYS_USE_IO, 1); +PARAM_DEFINE_INT32(SYS_USE_IO, 0); /** * S.BUS out