From cac9c51ac87741e214df55747ec445d00fe8fd9f Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 24 Aug 2022 14:44:17 -0400 Subject: [PATCH] ROMFS: purge old mixing system - SYS_USE_IO is now off by default (enabled by default per board) --- .gitattributes | 1 - Makefile | 1 + ROMFS/px4fmu_common/CMakeLists.txt | 1 - .../init.d-posix/airframes/4001_x500 | 2 - ROMFS/px4fmu_common/init.d-posix/rcS | 20 +- ROMFS/px4fmu_common/init.d/CMakeLists.txt | 1 - .../init.d/airframes/4041_beta75x | 2 - ROMFS/px4fmu_common/init.d/rc.airship_apps | 11 +- .../px4fmu_common/init.d/rc.airship_defaults | 6 - ROMFS/px4fmu_common/init.d/rc.autostart_ext | 1 - ROMFS/px4fmu_common/init.d/rc.boat_defaults | 19 -- ROMFS/px4fmu_common/init.d/rc.fw_apps | 11 +- ROMFS/px4fmu_common/init.d/rc.fw_defaults | 8 - ROMFS/px4fmu_common/init.d/rc.interface | 284 ------------------ ROMFS/px4fmu_common/init.d/rc.mc_apps | 11 +- ROMFS/px4fmu_common/init.d/rc.mc_defaults | 11 - ROMFS/px4fmu_common/init.d/rc.rover_apps | 11 +- ROMFS/px4fmu_common/init.d/rc.rover_defaults | 19 -- ROMFS/px4fmu_common/init.d/rc.uuv_apps | 11 +- ROMFS/px4fmu_common/init.d/rc.uuv_defaults | 17 -- ROMFS/px4fmu_common/init.d/rc.vehicle_setup | 48 --- ROMFS/px4fmu_common/init.d/rc.vtol_apps | 11 +- ROMFS/px4fmu_common/init.d/rcS | 93 ++---- ROMFS/px4fmu_common/mixers/AAERTWF.main.mix | 88 ------ ROMFS/px4fmu_common/mixers/AAVVTWFF.main.mix | 77 ----- .../mixers/AAVVTWFF_vtail.main.mix | 71 ----- ROMFS/px4fmu_common/mixers/AERT.main.mix | 77 ----- ROMFS/px4fmu_common/mixers/AETRFG.main.mix | 77 ----- ROMFS/px4fmu_common/mixers/CCPM.main.mix | 49 --- ROMFS/px4fmu_common/mixers/CMakeLists.txt | 80 ----- ROMFS/px4fmu_common/mixers/IO_pass.main.mix | 31 -- ROMFS/px4fmu_common/mixers/cloudship.main.mix | 49 --- ROMFS/px4fmu_common/mixers/coax.main.mix | 30 -- .../mixers/dodeca_bottom_cox.aux.mix | 4 - .../mixers/dodeca_top_cox.main.mix | 4 - .../mixers/fw_generic_wing.main.mix | 47 --- .../mixers/generic_diff_rover.main.mix | 26 -- ROMFS/px4fmu_common/mixers/hexa_+.main.mix | 4 - ROMFS/px4fmu_common/mixers/hexa_cox.main.mix | 4 - ROMFS/px4fmu_common/mixers/hexa_x.main.mix | 5 - ROMFS/px4fmu_common/mixers/mount.aux.mix | 20 -- ROMFS/px4fmu_common/mixers/mount_legs.aux.mix | 23 -- ROMFS/px4fmu_common/mixers/octo_+.main.mix | 4 - ROMFS/px4fmu_common/mixers/octo_cox.main.mix | 4 - .../px4fmu_common/mixers/octo_cox_w.main.mix | 4 - ROMFS/px4fmu_common/mixers/octo_x.main.mix | 4 - ROMFS/px4fmu_common/mixers/pass.aux.mix | 18 -- ROMFS/px4fmu_common/mixers/quad_+.main.mix | 17 -- .../px4fmu_common/mixers/quad_+_vtol.main.mix | 25 -- ROMFS/px4fmu_common/mixers/quad_dc.main.mix | 7 - ROMFS/px4fmu_common/mixers/quad_h.main.mix | 17 -- ROMFS/px4fmu_common/mixers/quad_w.main.mix | 16 - ROMFS/px4fmu_common/mixers/quad_x.main.mix | 17 -- ROMFS/px4fmu_common/mixers/quad_x_cw.main.mix | 4 - .../px4fmu_common/mixers/quad_x_vtol.main.mix | 19 -- .../mixers/quad_x_vtol_AAERT.main.mix | 30 -- .../mixers/rover_diff_and_servo.main.mix | 41 --- .../mixers/rover_generic.main.mix | 38 --- .../mixers/standard_vtol_hitl.main.mix | 22 -- ROMFS/px4fmu_common/mixers/tilt_quad.aux.mix | 33 -- ROMFS/px4fmu_common/mixers/tilt_quad.main.mix | 35 --- .../px4fmu_common/mixers/tri_y_yaw+.main.mix | 12 - .../px4fmu_common/mixers/tri_y_yaw-.main.mix | 13 - ROMFS/px4fmu_common/mixers/vtol_AAERT.aux.mix | 29 -- ROMFS/px4fmu_common/mixers/vtol_AAVVT.aux.mix | 56 ---- .../mixers/vtol_TTTTAAER.aux.mix | 41 --- ROMFS/px4fmu_common/mixers/vtol_delta.aux.mix | 52 ---- .../mixers/vtol_tailsitter_duo.main.mix | 38 --- .../mixers/vtol_tailsitter_duo_sat.main.mix | 40 --- ROMFS/px4fmu_test/CMakeLists.txt | 1 - ROMFS/px4fmu_test/mixers/AAERTWF.main.mix | 96 ------ ROMFS/px4fmu_test/mixers/AAVVTWFF.main.mix | 84 ------ ROMFS/px4fmu_test/mixers/AERT.main.mix | 81 ----- ROMFS/px4fmu_test/mixers/AETRFG.main.mix | 81 ----- ROMFS/px4fmu_test/mixers/CMakeLists.txt | 53 ---- ROMFS/px4fmu_test/mixers/IO_pass.mix | 38 --- ROMFS/px4fmu_test/mixers/complex_test.mix | 27 -- ROMFS/px4fmu_test/mixers/hexa_x.main.mix | 4 - ROMFS/px4fmu_test/mixers/octo_x.main.mix | 3 - ROMFS/px4fmu_test/mixers/pass.aux.mix | 21 -- ROMFS/px4fmu_test/mixers/quad_+.main.mix | 18 -- ROMFS/px4fmu_test/mixers/quad_+_vtol.main.mix | 28 -- ROMFS/px4fmu_test/mixers/quad_test.mix | 25 -- ROMFS/px4fmu_test/mixers/quad_x.main.mix | 7 - .../px4fmu_test/mixers/rover_generic.main.mix | 37 --- ROMFS/px4fmu_test/mixers/vtol1_test.mix | 12 - ROMFS/px4fmu_test/mixers/vtol2_test.mix | 32 -- ROMFS/px4fmu_test/mixers/vtol_AAERT.aux.mix | 32 -- ROMFS/px4fmu_test/mixers/vtol_AAVVT.aux.mix | 59 ---- .../mixers/vtol_convergence.main.mix | 32 -- Tools/px_romfs_pruner.py | 16 +- Tools/run-shellcheck.sh | 2 +- .../cubeorange/init/rc.board_defaults | 2 + .../cubeyellow/init/rc.board_defaults | 2 + .../durandal-v1/init/rc.board_defaults | 2 + boards/holybro/pix32v5/init/rc.board_defaults | 2 + boards/mro/x21-777/init/rc.board_defaults | 2 + boards/mro/x21/extras/px4_io-v2_default.bin | Bin 0 -> 39924 bytes boards/mro/x21/init/rc.board_defaults | 2 + boards/px4/fmu-v2/init/rc.board_defaults | 1 + boards/px4/fmu-v3/init/rc.board_defaults | 1 + boards/px4/fmu-v4pro/init/rc.board_defaults | 2 + boards/px4/fmu-v5/init/rc.board_defaults | 7 + boards/px4/fmu-v5x/init/rc.board_defaults | 2 + boards/px4/fmu-v6c/init/rc.board_defaults | 2 + boards/px4/fmu-v6x/init/rc.board_defaults | 2 + .../smartap-airlink/init/rc.board_defaults | 1 + .../spracing/h7extreme/init/rc.board_defaults | 2 - posix-configs/SITL/init/test/test_shutdown | 2 +- posix-configs/bbblue/px4.config | 2 +- posix-configs/bbblue/px4_fw.config | 2 +- posix-configs/rpi/pilotpi_fw.config | 2 +- posix-configs/rpi/pilotpi_mc.config | 2 +- posix-configs/rpi/px4.config | 2 +- posix-configs/rpi/px4_fw.config | 2 +- posix-configs/rpi/px4_hil.config | 2 +- posix-configs/rpi/px4_test.config | 2 +- src/drivers/dshot/DShot.cpp | 35 --- src/drivers/dshot/DShot.h | 1 - src/drivers/dshot/module.yaml | 18 -- src/drivers/px4io/px4io_params.c | 2 +- 121 files changed, 100 insertions(+), 2797 deletions(-) delete mode 100644 ROMFS/px4fmu_common/init.d/rc.interface delete mode 100644 ROMFS/px4fmu_common/mixers/AAERTWF.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/AAVVTWFF.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/AAVVTWFF_vtail.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/AERT.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/AETRFG.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/CCPM.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/CMakeLists.txt delete mode 100644 ROMFS/px4fmu_common/mixers/IO_pass.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/cloudship.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/coax.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/dodeca_bottom_cox.aux.mix delete mode 100644 ROMFS/px4fmu_common/mixers/dodeca_top_cox.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/fw_generic_wing.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/generic_diff_rover.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/hexa_+.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/hexa_cox.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/hexa_x.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/mount.aux.mix delete mode 100644 ROMFS/px4fmu_common/mixers/mount_legs.aux.mix delete mode 100644 ROMFS/px4fmu_common/mixers/octo_+.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/octo_cox.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/octo_cox_w.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/octo_x.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/pass.aux.mix delete mode 100644 ROMFS/px4fmu_common/mixers/quad_+.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/quad_+_vtol.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/quad_dc.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/quad_h.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/quad_w.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/quad_x.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/quad_x_cw.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/quad_x_vtol_AAERT.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/rover_diff_and_servo.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/rover_generic.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/standard_vtol_hitl.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/tilt_quad.aux.mix delete mode 100644 ROMFS/px4fmu_common/mixers/tilt_quad.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/tri_y_yaw+.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/tri_y_yaw-.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/vtol_AAERT.aux.mix delete mode 100644 ROMFS/px4fmu_common/mixers/vtol_AAVVT.aux.mix delete mode 100644 ROMFS/px4fmu_common/mixers/vtol_TTTTAAER.aux.mix delete mode 100644 ROMFS/px4fmu_common/mixers/vtol_delta.aux.mix delete mode 100644 ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo.main.mix delete mode 100644 ROMFS/px4fmu_common/mixers/vtol_tailsitter_duo_sat.main.mix delete mode 100644 ROMFS/px4fmu_test/mixers/AAERTWF.main.mix delete mode 100644 ROMFS/px4fmu_test/mixers/AAVVTWFF.main.mix delete mode 100644 ROMFS/px4fmu_test/mixers/AERT.main.mix delete mode 100644 ROMFS/px4fmu_test/mixers/AETRFG.main.mix delete mode 100644 ROMFS/px4fmu_test/mixers/CMakeLists.txt delete mode 100644 ROMFS/px4fmu_test/mixers/IO_pass.mix delete mode 100644 ROMFS/px4fmu_test/mixers/complex_test.mix delete mode 100644 ROMFS/px4fmu_test/mixers/hexa_x.main.mix delete mode 100644 ROMFS/px4fmu_test/mixers/octo_x.main.mix delete mode 100644 ROMFS/px4fmu_test/mixers/pass.aux.mix delete mode 100644 ROMFS/px4fmu_test/mixers/quad_+.main.mix delete mode 100644 ROMFS/px4fmu_test/mixers/quad_+_vtol.main.mix delete mode 100644 ROMFS/px4fmu_test/mixers/quad_test.mix delete mode 100644 ROMFS/px4fmu_test/mixers/quad_x.main.mix delete mode 100644 ROMFS/px4fmu_test/mixers/rover_generic.main.mix delete mode 100644 ROMFS/px4fmu_test/mixers/vtol1_test.mix delete mode 100644 ROMFS/px4fmu_test/mixers/vtol2_test.mix delete mode 100644 ROMFS/px4fmu_test/mixers/vtol_AAERT.aux.mix delete mode 100644 ROMFS/px4fmu_test/mixers/vtol_AAVVT.aux.mix delete mode 100644 ROMFS/px4fmu_test/mixers/vtol_convergence.main.mix create mode 100755 boards/mro/x21/extras/px4_io-v2_default.bin 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 0000000000000000000000000000000000000000..51403914013d2f9cecc849dfda750db977a95303 GIT binary patch literal 39924 zcmeFZiGNhp{Xcxpy?2&O1~OTIY``o5k_<~Api!_6Gs(>|!Jx4%0=5@}_9AGasEu7@ zAXrDx7Kyb;T+nD;ur)IfOVBt`v~{WN3`@U2q(rffBwFu4VD4m_=Y3{ErN8gXN9o8x@k5FaJh)Wgnz75}?3aNNX{WeSjJ2+w%CJ-|r#Ju(uqJI>> zqn)H+u6y2f`O<1B%Qm-aZuPvHQb~}EQl>m-nM%$Oui#r+qPrb-3NW=mOe!Jwz0e9*HnOS06`#}|t9X)lC^NY`rE&SjV8{Kg)19ZJ}!dGNaBisyB?Qg0#E7`ayND7N==m{AQ0-{Q|6piT$zfH z(sQ26x-n#T6D3VkuNIhi-A#eH;v*uB2*wv9dMz0w&Tr4B|Jq|~IiK$RR3#;buAcMn z6s662gXo5|s;ytIKV;w)Bk$@@;rBUQ{d)edsP*HaU!PylRVm~hW9^8!`zxhI)TA9d ztyc9A%<+%p2G!W7RgBs{Ip+53bo(7kTu#;KAcH+l{{>IonGmO~15RoKrukX(_42C@ z&Sj8}hZ~hi%1k?|ui+IPe}if>lOpuMX9Y}_ zEDPpG_#vWrmopr&_W!GX39GYPrZ!g3=%FrDd2^$<%u z`pIRrw`{1tGplih{>Yu5$@_+t^D9z#WjaqwKa*DJUHv4})Yu|f20Q9^s%uQNC_e-m zZP=;aLQ)F3puUg`rTAQfp8E90kEQg+ooWL~U1u9~)a&t<)Tge=XavlIj*azzm@Co; zP`BZ9xMf3b<8pbQ`XjTWpK}@{V(sy_<5yFqsnfIJyLok}t4pr(xfC;vM<4nR%(lTD zcUgdqLG+W?m@W65cbJ+gTQ;<)TNC%Z#+$Hum&$tZuB=lK6a7Az#24%LCiLr}5BuZM zm2tC3l`ZNw{s)1E6&{5S}(i1V07N;?IRDHxe z-5y-cM<{0q5ZimI*Nm&g)J@DI;j&I%Y?FN#HgCFlok@Ic!}o%|3%fRHgN}1F^GRoJ zuu;h-7^(4H-OcM78dHt|tDx{1V-<>CV{5#54KaTkw&9&)(1Z6mV>9snT$mJJ6?|M> zQ?l1b?RA5myN!XmL9&t9GF^|W4Q5iD6>wOIH52@#gm017+)0!#hfjoa#eawUeXTOD zlyD`**`Z9d%m`)3fr%Nz#LAx1#qO_64yrUBB&4kK!42B#V)3_lPnFw-1TnjdJrl(|Y!=J9Cru&x zvd%0KaNlcf%#_>wPikLKe^iolY(J>otDSVrEE45noZ9w-64JFg_THSK$sZ8Ya1NAbog)dv7vDl>*%FfLWP_wCfr@FPogi&2S6K2#OH~Y*9n2GXE z04rrF>(q!_H<-n(s$_~s*NpAmkX4h{*y_v=au=GM?Ed_PdvMo;fa&=YtB92-e~VeM zt8Ace8+P##NotHoUmM-i*!@)**6O8h%+MlKoekr@l&|_1WD=<&3BJwvH>0O`^xgQG z#(H0puAT$bjJ`I+7!`RyL1n08tFbj|#8&6kSyXSM`_h<#V{Q^HB4H8}fW#HI{Vo9VOlI=;?X+-z$;|@4qRqR%$qthsxzvHa@DA*Ivw{# zqZ85Y)wnFCq4$+Tq=4EcEc-t6g=*hN%~yB*C|?#!N*`5IK=IQ@OGUbnpZ#q}=xFLr z_PYo2;19SC;Cc_&<@{D(a~P1Dd<>$$jcG6Y^_Q_re3-$;;K~H=nGn&^6hJe7)G(V1 zO)$r!AC2^Z^ZaF`Th*F)lw@OGTn8vJF(;?o3Q3d3w@O@dD@n8NcDS&Hn>N}Mo?i*x zmRZx(No-l-_03+VHb_f#b}nM#qM!_7j_T&@gcQIm}FG|f+@u+MiI^%Sa)C~N_ zbaRA=N$3wXb+dLi=MufvZR+F)NEYT$LKSC>6uuU~ZpQvg_RZcd>niE2kYAGv6e_$X zmCKejOXZq1PWgzmROZ{ZCFW}#j5}8eR;7tsWz2MKmrA;O&T<(`Wv}dj^zvwRM~OW< zV6^E22JpP?Oh)7PMBBx1JbG)uB_EfW1o=*W@UpF+QiF?=&iI**0(eMCXNo(eDhHe+ zSJc<0EPLm?&hn&_3+bRcm2~rxRidTE(uMGjZ%E%RTzhamh3j!#-=5carYS-i7yR~o z%H~JK+eI#7<}hB%oU%S1*1c2}?4M&y&u64BALHtA5fjmqFGydB zK+KO$CHi}DWp;XO>qPph02uLD#H~zLQhzDm7DO;ZTXse}UBT zhco<~hv}0{i*2gZcmDT#eK%1Y>SP-)u{DW?Df*zwq#;wMYnq|_F((O`y3KbYl%G;!VIk?ofF+h&XOA+ai)acU(*7v;DHoMgHE^^lu^?C3Ml!VH5M@v zrVFMQ^ASBC#&6Kc^ljo-;nb`WefRWEVy3UKd6B~X0b=HMX*zCJh2bW~ zwZsNU#=P~rDoJ51*s!5UWW2Y@(RO=w<(#u>UB&i}*tC*4e!55yz2alyUgz-unE?ti zKqpUa-=62+%XWadVY~JAJpUX&r}Ca#Te`nef72BKQ^Ouge`p&hKUp(7)UaWzN;{~f z_ja?mt5S$$5TcwLYuKO_nJnnNeOG1N{}Aevxxtf-3Qtai$;=DTO$_8{c+S~qU5l(0 zkEmIm38FqykWwYmokTf2CQO^wOA0PQMcbZo<{rVw4|=Ry(AROb+dM*Z+2RO$JN;;x`SjJBil4q$Y-!2TM9+ksbQX^VXGI!(l+cK{p3z-LbH z+-7>kWF@Yh7o>CT35b(>ZlF2tU*ENUL!p=_V+E(_PO{!vyX$~O;BYf5YfF@^-@u+q`EQ+G&vySU z_b+y2x*G0s`}$=13a2y<(>7w~KJAl`W%Tn$Y>#I6^H7!@D80W*%n$Ie)~32(IgC#AvE37o z?v68T{AIKZ*ic(&sbCL;h^C!S=G{cN<5t1G!&0MGitCX;mhkAP~ULWDYDXMM}=vo-jqoEsvuepCR);v z!SZd`DJI+h8Z|DS^i|NqzaK~uZr{Fl9JfL+Nu>-r2Ki?rk0*A?$ITkiDB67=%Py?? z$CAdjU1GWvXom;<>@}|y9`=wz+9(JNBl9T38HhUcBbfwRL>%DQoxk-2O zjSJg0{Semdq|9fW>w`_*rFc$3d5m#`%}L7qjvlW**}nZ2$b$@jTP|Ik20iLh9qXfK z9!b)y;nOpZSRYN+`N+?BvmFvG6t+Iv_sITOaY=@s_%m{q@ON#W-`+63Cj6%j+n-1O zec|V~OKi6$YKOzOY~O<##GiPR+r!%aDhb;nh2!;sGmmH@@kRQ8?Lj(6INq?`EVj4A zqj$zH`hSJ-1L35+bDlHZ6^|}{n-p#fG5h@)rvX^lys0I0ug@+wNbBWxX+SVp|jY{laiUd$%-fur#%;V=~hY@0D;Adv^`vHJ^`S zzT+MbwtIWQYtJ<2btQH(o|E#9)%+K@b3D2?ek82I3J}D3;&*HJN53ib-7f)B`VtSh zn6RZ)M?8A$?e8>&uY&E{Ew|sYAi~8?7i17VHpVeYym{86i8-vh)=yvARr$K} ztKgYOK8KDGywUDIvz1W`U6kyLUU3||^ZZgBc;^mrDzIi(g=rbROR?YRtKfI|l>+^M zww-+V&{^SDtCE)R)1KT+loHrI$?;5`x>{;AV-@4k)Zw~|@r?~0Vr%y#SE}~FLh!*d z=v1~*L#;;KALB||oC5q5?Os~i?kVd=OXW{Pr0{w8TW z7HBLjWbn-^o)U^j--+|hZ~D$W%tN#0?ODN@V!KQVQv0kZ=Yo${XpVe-f)ubmt>Tez zgFH*j7e5Yj;wQL>?IX+}mH#W72mfK1;d}%5GQ&Gnlr9cFW(unf+I)b?PuO+^wb!+D zmNwPa)w-8RzmQmz!tHi1OWrLayVtmTtc8guP8p2xw!Qa>?#i0?&kChl+uoK6_f?Pv zht86M*EYYe_5d3{8(Zp@#i?%r?H--hk6Ppz2o1SwB0s(Q*(vJ3K<&4b0ohmoS3UFukoh|XcK28Vl>mnGU>5pHqb%y5KeJAF~Gb4z2=R zOK{Z!m*u#da1|93{oTNMIo_4wcRsG!xUzBGT1xaEUPJVgQ0M)tnEgo#9Or7CYb}DC zJT729yWojR`eHu0ndtYUpW4DE_z8_-*75HoNKRKg`kZPNb+!7ci++c?$Uz3)Cr*h; z4#t-m?;i%7%VwiJ#;q;XcN&kU)ZCz!l&tb`13lag;K5pVu8fQAPOHX!5x!d1hSg_t zW3aRKm)o_auxsHzRJ#(gUgOS}X9L3rW2UY%+iB^U7G~2X+IFU+>?xGJ7V~s{CkdD= zB=(d~iS0~FiaSrP?@G!6=2fMO+x+Okej)U2m;w(Gz;X%40_xg)*>cB_M{%SyRZ`fv z$#K%$Mscd#g!Qf--s9W5orjl-v+IJd$}RG4Cl6n@k?8sgMb~ITS5wm&iB@aEZnb&Gy6WX>?6g^y9cNO?wh_sIGMi2@4z^A$aR~(bQSB594o5 zT7{Jt<99I#w!!b4)La{tZ3GbvFHJy`gf8XNlp2#<;^Q{#cIu(U^J^Kdll6%?942zo zbN+dl(dVV{H5mWeOXDvzi%jEUv;`kv{5$Hhdvk@9qjqneF!5MY8;M6J#}o2?_W4tV zB3%-Xz7Q|)_lIYD{vFnJ%07J!v2+ZdJI@Vg!s`khVB-oG-64Z-e?7t{YqjW)UHgtHZoK?LEDO1?D0A+?qHia#P zHT?GE-u3*x`HA{#)I3-P)vzi}HM~?PrnZqMl5kIelsE2XM7}KXH}1 zXgQg)DD*d#IGFA8D*Ak?{5ALwF8ZI}%s2_x_Ox1NwyoiD7fcOn+P8CvB-@lje5R|t zMTnGhmiyM+$D5gN>KtbB;(bK{Fw09>s9>{dbP2i<4{(j8F<%-x3g&po5#s80jQ27gT;gWF8d8)M z*e324J>qh45_;b`Cgv}CbGFDW)DCQ=%n}`lzeM2qDJ&0?0bNRuN_H$qy$8kw@p`dJ z9E;vHwhumg{k65_!ZlZxzgdwFeXCj(j31~yQqo_;_&S~PeHFTO;o%@vq_N}b!V+4d zEq}&2`7mAhmQx8eDq0c_yH%kMk%8%Ykv>M1+OaJnebNkiqlU5QHDfoH{~dI`k{n^w zPJ-Zxp#<+u@QZ}MlPDekiB7`PXvVl%6TmNzs6FNzRI{nNYxTOealWVzrHgwiiIS(% zl0D9EL)5H>DL55XJ|9B-B*AYr?rgct*YW^w=RzGZBm9Vs3WvXpR|=xOQ*eLb&z1>d zDMVR{=o(^2W2}tvycIr=Yz8krqV9nw~XY|96UWIK`}Lrlp3cg)09uRw#0~ zA4zzK%D`91oAeY_CIFtvq^z68Vc5Kq?IWP;t+FN)QdZ6eoaG zAc0GILlcuF``Ai!FyF>_Ph{pqtTF3nLX}3YP)j8ulYv7#_Epm^PqL@>^_j4eh%zx@ zVM$mGcwQ5H{8HZ~J|0}29z{-q2mBo?&HTnpTATx?)0`ZO7LJZftAw;rJEw?~-C9VD zsd79zHk{^LzhSZT0)wk1DZRM4=|O&O7JPGAq1!iDWP^(o+`hIqF*Bm1tBCA^X4Gzr zeESA#Kjpp+Tjg&++mnQ^$La6N&M9uz``?E*zz;)|(?egl1P6V*06NbRv}G|r`Z7^& zR$cjmXbMu1zD$+B$1LE;M9EMEvBXEGvS%-BD3;H|d~^STX1#xynop0*{FcikJ~6Le zcaP6{|2C&K#7DAdNf-8_GO7xFX0bqqH(Q~xOZI9RWI6xyRZOSZI=-ghboeLd;&Ij)0cg}7dpw|gde5US1hlTZkKmU zUxxFblMtnSA^%+)tk)XX^0njx)d+UJl}@T5Cn17925h;jV#7U{g) z25$wm6*X^%C$~ki%ZD&Nzveqkz&i_x|L1Xk44H{I@DNJ9$yJ|J&1h@mNc#g?yFT=P zVkkWF<00?)L}t=FeUKtzFbQ51<~;zP)1C;oKcKN+3<=O8iE>_zgfG!W_mxD?B$OZ` zW}pWR@U)dgZq#Ai7B9x$ujcRh@lZ=FcaZ!{2tJHANohlO5#_}=lURen=eJ)aItR(! z&$kfeC-I|dc}J)0?$>B;UCZj8?ujx{dYPjuyx$*x26Eu%Se}+0oLU z%1?DX*q@3vL}`fscxc-Yi}5H0V~O@QR>Q&Uf#2F1XA>IjydR z{s#}Phbj}*Vt6lPw45F@MN-oQ5i}M`&``m6e52(zKKcsVvs>fL>q~dF59qla&PM`0 zxx{>x=nXi^i6X~Yn|~#^#pmJphr1Uu8`jj>vRx4KG?R{A-Q|%BeJ)4`E>r;O_6#xn zrY0iDpTSEIkKQoWz8x6{4ec#SUnG2CC{6Cp`~wB>J7gbB@_VAZI!0_(cr&xHlZr>J zBC%;L)J&CvQTASI;qW{SlFHN#JdRU;3)WQ|q8n1-d&%=7-wAqok{2`Sg?i&U{+0(c z#VH}phT?=yU+f`Px|IX2KORo<5$sw5Z&*R0yXZPt*5!q6$;|Gv+<(Sj_B7MY{u0GH zq7kcnBqHf%-&+V>H+vD2$FDo1p&smt%n>G&xmnrQkw}kb*1cv{Vi%fT7_TzD{)$3-D+kJEwquq|IEhUYwEtVevoay{BPNYNcDIdSfKw8vh5!SFZID>j1l(Tt^{vb5Ztzp z6wSLVX5^BYcV?|Rz4}gRqWr#U^w5RVy4c<~jn3{X5n=t=9+OvP(_`uK{H}Iq)~D%m zQCC*=7r9@DO`<_m!d{s#Pd*ii6KgP!QBxn&Tr&C|lb>+54^aMv0bY1+K%kFF--KX$ zfEvFZc}*IR;IdrN%_Q(CXtSv^t=1~9M1C4wOzf?a_R|?6nQ4T*X~RUCEGriXuHB^ z04yg*h*^>@`4h4cuRI%OzMuC-&N1FbB9N5vf3m(o`D~wCnZJ(x=FuxJ9g3K3sS1}>Xwz^L}5j+dC@7^HZQTIkc@eID=>3F^Cf zcfx)c_jxgUfYCw5G99Axb7iXhXm}~87=CZ1dzfjidGHNAGAy{h@YniMYqgPkARy+0 zE;3ZRd{3zj@F|;%Wc*!v&wQfnM0|<$$^30B_hGYBA4F~}vpZ*>-;vz z{PFGU5&H~%k;qv=#v{?z>N{1Jy+*LP*WvZ@<=X5*d<&osSvb|Ps2B!<{(*gTBND&uF?-?Bcl zyx}LdM5gU~>VXny0UO^#cd!)s_td9K6kGdGAR7|v4!^og%2=i$Y%`44)S0?$HZc9! zP?ay`Isq7+FBgGptcx>@mP$?C44+L7hR^;3Nqn+)33<2P>}%iNE6`)$_iFogmf6wX zf{ehk6H6N!AS?Gf?=*^}cy1`WCIgmwc4&$_M^5juiKe%*D{s8by@A7ct+%=5Be!ke zkogmn+r8FfbHmH!*|>eJ>8*HlW+12@FfYAr%WYd4-@PrUzGdcqqO0k_JJ=0BLA|?s z@XqvB(#~XXedr+ilFkhGZ#(kk(dZXrm=V>;jISg4d_2>~EH>Pk&|}8eXEYid(@5=i z(w8$@&)mti+8Q%kiLK!_$V8Q`S6OGv`cI|`3EKF%kFEQ}6NlCpBf>$z!+$l#i=VGA zF8{pYmi0H}-O`W^{z`1apo1pl;}{dzy?dwxG<+oX-#Gr$*#E|H*=0CJG;KYTT3Mpa zM>kQ0r}3yOKD!(lTf&;WLh;XMCw~7fPy-JiOcVC;p?sEYcfC(vZbq(2PcHi_)MS^p zAj77qQWh_SapJ%p4S)OgAO1;2#NY`z-Bf81*)x}TCd2?+or*m8$_n*T4CW+!2Va1X zaBeDsdXz(e@$%o<*k{S#tS?sMp03Nwd&kRF?6b)%#-jXCeKkiDN#oZfbLbGk3g*)C z_s-HxVMY$}ZAqmC84kaf^<_Wx?DCkVFZ1+CR#jNt=KWl5?02~u`|Dk1vEDOi)@0g4`3W>Hh;^N|;XZ1DxFv7A_@ieKdNkr%W?@s0A>Q~4Z;?4c{yJRdO<~@#yZcs25S8SnpW$ZzIcL zDv8p@MZ%-ey`wyMn{dhuf6sJS7Z-Y|`Cs9&=uHVvhTe<)piEYcwiPad{Kw*Q zP5JtDHeZf6-DmcCoton}O2EPb-uDzd6uHPXQNkU_(b65}QxJEtljHDWm#osq!l~H5 zNiXdE*sZU}WoBEBThqtXJ?37&ReE3D<4EM`buU!8C6?)j&QIhE@U#$F{2yieV_5UT z$-N(}Jbad3VJhD!rTU(bpOG@WtUR;4&0m1K)5|g(t;!~3;&YQ6c+t&LhQ9Uz%td+nEV@u zm{@~=wb$PR$P@O@?8*?C=L+f~nVK0m1M<4_8t6rcXvaH&4aZ^D-^RGn#t##zeBHu* zR&Rs+s`H8?&&&1Dlu~`q!*aBG>+@3WrV}sw+x%;C8tSd(RUY$Yknyg159_lu-ryA$ zUZN_7ANF=;yukM=w5{UlIMV|wK<%C(TM{`AqKRa3 zEPDJ{1$Tn!p_!@!5WWJx&r@OIiN~2-j7N*$dCT@OTMW7uFj3a6>^FK-#R)l`G0p_* zu_(Xy*jYLyd)56?VR?%05AvhZRB!&O-}%4Edop`=`BOL4d8T{Hy=^NC2IJsen}mE< zIWVt)zu)^d2b=N{r}4-W{wK3v$b0IB>pasuZ7VOW#(K{{SOIs3htdkZVJRpXjlMq2 zB+TSemJfR7mNN}!)+Vj8f|9XlH>|HSx9+)vAlA&w?YG9GFOEjTu&1O{IkQVIRYCu8 z%h}RUI29TZ-&G~)@rD=mko*~PhOY+EABt7@61kk5#7@+t%AB~}=kc|`H<2qFBvvB@ zkrOw{>^`Q2wK|7Fuon-oeh4f{PDTc3*Gh?v3hpYiw>S8z(DxQ+okF-t0V=zt90|2h zPHZl~#!H!9@0^9is9ceND0r4ESkRR!m3GyjA4I21kwGm*!z*zSf=J2TI}kTXl@K}M zxhj{7m>E1w|8MF<#+9X9=474wUsKKua~06wZE$7RR18pfM*gCfNC{~H8{v}8V5*&S z)>}12w8Bq1QC!(|T3zVDwFB24Tpb@&z&f?rq^m&xFISF5r;M&pg~jz1=Z>tZP!8{^ zgugWK739NeoLyrV%b8{OLZ1bmLV`Rrrgt(O6?vTEd|%Zxu5e+XQTZWBzMEe3EV2yv zAsXT3RM+kR4+#Hv$@c#$0andyeWn*Z9U$@t;Qw^Iw~71tPX1NcZFwx4QiD7~WQPv$ z9Zi)APE|}0w|D47?qybX4Pv21cqWRd3eV6h*uMWQEL+J(VNYoAK3gpk>2CJ4NL?bO zB0G=ezz&65WNuxnQ+N1XIdmhjw8-xwKHegQZfvU5xarlrq;Yd=T#1$A=BG9>o!eeb z^bg{KO^ceK6*uV5&FZjUByj6^Io1aDssdlm4&)*{)bW@~_8f$biQT#7U}Q#`E=VKD z%3O3kY*ZWUiO>2TV_9<%E|ry@3zAs|>-WSiu`65G?wC@EEMr>(I zgRe$P_+EdC{f6T?$mz@oaKpMQxnb=U)ru!Y*LN^7Cv7%rmZbHEsuh|7pZ{Jq{y#zn zP$Q3S0$^B0hgPlc+=R6!ujs zTuL?0_5Dw{TG6K*#a~lODBN{{Z2HrYgOQ)5&B2KGq!r`u?P&#}qCwBP=|d04st3va zZ-);?iqlLX)-R(vE@Dy}F9%kv}=TI!07nR>68j!hVlXHVrlr8c z#sM$u(tZ$H+{NG)f|yUEF+ltdKQL8K3T=vsf190Ct8eo=oF_HhvE}``l+>WXN?HM1 zN;TF2K8ChE11Tv#23}8UK7ky#>ljYv8M-Q_!%uhT$?|h1n&U7P4f*+yO-VPfx4DWb zZGBL?*Ik~ePFPZ6zd2Mq*i%!in8r)>X&Xbi3Qf}n{Z7xhM?C&qZXiW>&VNJRVgH)G z|AyA%@9`JG9yu6Uk=Ew7feIVBkUynp=JAx`g5#&Z;*_FH8~$l*wn+wSkusTY^W)Ul zCNB8Hev~Yl%3U~i2JY#$nxJ7q-skfdA z*MKH>S}IoR-h+=hJovk<%OqL&rUhE4hkv=dMb+n=Y!) z>Gkh(4)*4Xe&=feGV_gGh7)VBWPB9XXL^V(Iw*crQTXXg11Wr0#RpjDspZTsG&4ln zrk1CM>%`L-o%}c}u)@-8vB}&bmihL@e;_y=%vHFwtbpBOwxGu!X9wn>7F~p_fbnq* zk@(f0gc)UN_p%k_2U0jjFBz&ae^=!P|Dip4?XfQrElxyDNr1(G^kT*!xhp?FEmnAU z_Ya@Dzzt7wrPybRvqjCPC8d5RLB9UE6HVPIzAH2(xw_J~ESWy<6AMK&%bX z0JQ}Au>IjSo$eS-Se|%%p)Hvy_uGh zqM?u}x2cjt-U2P(=FAjnC_C5GosSGDGW%jkP2?P!#nI?i=+;BMrtZ;bAVA<#5MZ%p z`*@bSA(`kjJK}8bwYdEVpiCnWc_I zpBO!lH7-QE(dgZ8shur|Wo&n*iRQx&`C&qoB_mo<_PyBbF(XGICaN%CrNJorGs5Yf>mRj%Yi({|@}G3C=Lk;MG5f1k0^?;?Tm-SWG|B+Cy z7MC1Kj#R>)lcTVwBWfK9;SPFhj*wKVS^IFvT+@M!d&G0n6|y*3f& z4gzPU-X-7Stm{7m4~~s+IJqPwW_Y8M30T=(OAbO(z3d6FlUIBeL2hV_E$LLRnymc!t3s^o5m9mYqSA z50Sev8a0eTUiOmN6EG^9XUfU-^5^K+3RLO@HkWp}6yD9zXzCc+6Ad&En|LR(_f5J5 zu&{5E^`-o~Z#pN7(U1u?D)U!6G4Ijn`B538Q1xHf#lM0+_keHVx_sYS+34F-DL{V% zj5xE2yuwoC6_%Q@rxzlBOM#}Z6(8*I?0ZQ5>ArRQyw0K^%b&C&vn8{)R3@z(Wn`9I z37xie@w)ZCb27g(Pj>rccIpKfVs+<%+8Lb8HhU+&UKC!-75R^zcNR+Pq)bs0(Q7V- zNWs?$e4Gt`qywio#;w~4-8dcIhm>I6x?Wh$Svb+dvaguF$o?{apa!}Saz2Z`7bG)T z#wT~%CufD*=wsR^ko74c){Bgvf?n>~;Y9W$wa*GIUT5FO@@13xQ|Y~!@2^-M<>GaD zz^iuGt}cQYQZoOOo#GIt4W1;nGI1|@`&iZPB8A@u$8di8Ygq1E<6i-0jgZLH63&E6 zu*WBe4|PE2AGU}%2@2oRYoK~#?OWStIg(dyb6P1ZtgKvzhlNJlX)y^k88xT zeJPOwoNE}3?!>tUcFtuis*Cr9PvG47&wW#+<>H6x>gA)+LnC)eFRFUa?|h`-8fiS+ z_@NKg70bT~rwnK(6)s|U(hG<1H&y5fFA={^#F>}F)A^T}29UKsj11$=qtTPGLfDcT zP#=qHk46uG)(qHrqtSK9v3f3WyWEPJt*H4vD2qkV1@Qy)@&e9k4)^Yl8B5$0lO`U0O#0KSkI735<4X1J+;2+qH^CZj*U!)@Y)!crc3Hc)|LSRujo7u-( zpTEy4x88R?+A*taSoWY8O@Vk^*jud_= zr4v57nf$Eu+Kg(eoGRzRf^k&!#&UaqcX%uyCjaaYFH}M1S@psLU|-M z6#fNtCyjf{1E$V;bpd?W@#xctYB4;K04t-A;>^xr{!}K@ndkdRjCsDtqCb3-1agqu zIuYLC11w@N9v4NH30CsM0Pkfd=J-e)(b4w;yocqyd=SvDP58Ddla?aumt~-w8s9tN z;mb2nn2wNEJ40r?X?8D2Q|C7&sGfcZ?B9>6?F6GclG`&NNkHx`xO&gdG8>c_JCxJV}RaHg)T zAmgI5O)HnV(HMUS$@vlq{#cxCXQlb#^+ZVK&odX(*+ zr*kvK&{^8k1MPxkpmRa5{8v>^b~{=0?79;MZ=3&ct{dJ%gU9C4drzxh_c-8{k~{}h z&g>Amej_}IuR?nmi{3XXM1<7&;tJ-C;zpwX7&3dw9B0rj{zyEDJVsbb#_OeY-$_+( z-X=ZmFV5cSf7WUB%ybu>*pwIWzjVWM*;bs@tMR;rzB3)uU9YKJ(^#}-bW@njyLRxG zuM_*VgFk!yS?B*8zDDfLdp>OQuJKN(V$e~S&9f!}6NgL=2G4;odTCnh$Ys5le-!?a zxH`IBsx zBen(~kQ=!p203Hg`;;vWd^r<1j%E`~W?(QN*Z$s)qk6Nnj(+5alK71o&Df2WC zrK{@?5xwz_v%=p<5l(&Bb9>?GR!}4t?{9E647m8F z%H$nV`hV5%T{VC&2^F*HlTh9H9aPA*xf~ki3DrNtV$Z)8348-Bo^8%4 zV&w_{(3bOV-=T<^YKHhRGkiVII+pfNocNTZu766^+r#R}^r44h`r-V~jl(I5#kdq- zS=r$z`E$;c6H9Uk zvadY~zxg@TCY!mkCFN^#i3JqsnC2taPaVjFaKab+5Z4v|CxeOD>q3v_QcGQb#&y$& zwy2%MVdF$fQ_00xa7`%-ym-%v}06uCoto!pTv z=)23aHTTv5o~Pz#L^Ai)AZlLsQutX1@WzE0rmpj0TwqGY*y#mB+_|S6WLQ5^?3!e( z=%*F0RR}};U<%*`9)PvqcwVb;z%u8`t|@&KK>f=c zirL+B_?3#gPjFYUnkky4{bXr#_??JZx7}eK(v8&i^TruNy1}~s{Ok4)kHw}BJpveV z%FRQ%^C`pnp+_B4U3R0ZUnqaRf*Yde$PhiBaw2~~5MZ^IR2_c4LOk(GgiBdl{=$Gk zKo1Oi<$!(Y4}gQU(kE&I?nQG@+kS#8TU+kvPjT!S<{oBkYAgOME)#Q(Ob-6Yw{Kt~ zw{}1y2t&H46(db|{gtgO!oduy^P%S&!;gpqUz)`Dm#&I04<8udCa%N$X<1(wUl$3d zi;sjii(O&8xDi)%m{HX=<(XkdF9l&Hr+6<1PPWsZ>S}eSvUA`6kx6a-92XtWm4ub+ zg>HeGFZl7@2EN_di0s5f{T7d9GdMl<_WB?88yuX6Nh=d{z|zhM?p52`{JWg#pBih8 zRWq8kdo{bw7BWy_qOH8rG-7KeHeHRaDS7IKo#!e^XnrNIUlquR*?MCB8h57EQ00m^ zm$MW$A6E@Mz{cdQnvf$(UEKU+2UTVdF$>|DD&%3QoZ?f7^{LvYm)!_onqbL5#FJOj zM_zMs;)T$z+7|zrEyTtdtu1`(6K>{b<`4;eyy_G5%qhoIt$AlPue9L&pX=hYWH`EG zsP^3JxW6!@5o^!Q#nZDxj{XWl3xy!7^9ogeXI!$mhc47&X33m4{+!ZCZ1i-|k7zV-ruL0Dj&ID@DN^S;kPV;7bw0<`# zgVG{Cv@|he%}|54O*i!@Rpc@EbsF&>(BBT_Y5^I?>k^P@-x6yYD)fPs6^6qZFQ+1d zJ2Tb|O*{3;SCGfHNV-e9%{y7)wB`gB8J>D$iSZuECojV(ARet(ogK$#a+8TWC98r>r&R$a7@lFuiCT)?BDl?lZnItX%9I z9=SlTpo{+Kd^|ubY?auU&&8(K{Lz^%!{bcTrMHjg?0=oGhnu;X!aYZ^}99pRzeis?^n)r?ep?XHcp&aC&;GOU+(a%O) zb29Ebf;?G)cM>l1b2`FkcsZVHam_}X8*wkFnSq()$X=WlXZH*|LOxLIfB z2b>wxK_R8XcI+T~6IEUw?HJJWdYlf)tyu%Unv%f2o+dFD7(D&QTeoGr+@%WAewFj= zS8+B%xlWzbHhsve{=xr-fBMk&;bM`RVf*e&tu7VeH}%A$Q$cG#AN7ca$KL*u?ZZOA zhNwqkUzT7lEDo~}cP0xp$Yhx!Lbj)zR-5+ZUdQZCs=TN6`8556XI?@>XrFJFGb@-` za|C?Eg;Tyqa7t5osNHu^)tk)X!+xslP|d#c1dM3uDBHg{Xip|c!q^~SO9T#AEl^-yIUats($zjZq(@E&Ay=6kX|{U}K%`mSsb*LPDPe|(yU&gV+sM)`#k`5ra= zadzB(M_to(-oQJNxc+%a8g>Tv1$fREq+O+Qb-8%jgeb}zo`VsJ)8XA7Zcb{DpCg1~ z-iQ5`enA-V&_&<)^^thlXW=)!+1lvQw{Yrp@*HyRCC}-vG>Xx>;OeRuZ+r2@AN=UW z7hk+%<1Zh3YzzL8EQQB+aj1oi^D(WOrBGfM%EC$tp<8sd0l@~Z4qxi|TX>^aK>U*j zPV-$Gy{oj&z(y~xnDOfc|2>|!!x8U-haZO2VP9J68+#+X|H22GknfFerhRZ%PElDP z$I^isJN+L2zr#y>tTa(}PtI(V6?AwbUMuM3+weVG?%oDlqIxI#`SZxmuw39(!lcuPD(aXqS2JCgHTI?zpbdh)4lZ?#@WP_ou0g zR$W>6v!M3)g2KB%(;I_KGp*^nqi`s6m0Ri)%*bhE9DL(0XMVtW?zM&$uG8wECqK}0 zKCR?sL~S&vv17c(^nl~y7p@hqWZ6XWKK8lZmf3e&ec6NW(^;4u0KW)Y{B-DLl_c8U zjVCTq(~Q{YRQI%|sqX1bHu+g+*I{C|%ltqkZSnaW&(53)d~cTRw2O4bN=vGyF1~GW?o4YtBs~L(#vFnQP58vaj8HlVCW?G>jB` zrldPjhcCaGr^cf#!?X`lMr!vW`qDVXof}-`1s3nhM1-Q^+;V(@AVc| z#@BiY?y2r4z3GFVyZ8{JlcDIXZ?}0f6*Jlpi^eSk5;B?QG(j>`oLva8`E137F9E?H zsdMXUn3keTXemr*AvUUP8cBW?=+v!AT9W=>>i=ZC{{6QRebrZ#I8c9MXJ&2Yb;#>n zW>b22o0I{+K`H*H!w}NfSW|8rj{Xb&oz&`Fycv$hVm5qR z!-2LOzS5ReP8KOy>SaTb!rr@y!Cv`XHw%MW(2G3}D6`G?Ke zUHmio*EewkqV@@=_C$tC2R8Rlr1>f}T@3%msR=r4wx+nPz3EKTgg#_h5=Y_G(43mj zn)fv0yv>No=RrB?GdCf=9mg50=7K7!TuZt6Gp=)!TbcyekDHydPMB2s^Pf5VtJU!F zF4mUY%fA|rE`hK5pS@fg|D+kKYqlXju9@4-1EyAIS%7Qhp2?`X8`?s2XlB#j!j~W! zvmFTE(zL@mp_c5#CdYShhodWi8MB;=)0V^04KbYEP&}9+^BI!>!vn+5!?@oKI%c?G zxGL++fz~0EW+)TW@?>3ba&>CrYbB`?wPd+-nvQ6-$1>bgo9Do~%fLmB%W!cD%rP)wF|w^cGN&RtWC6XXGPGu`AH_VvO4ClJi_Xs3G~?#lIuhoz0Vt%f@8$hfS2A5k2m|mDxG6yjp{q zeXoq79XtPGlMQC}y%zRM#4n0p`oynm@heZq9b=r()NPa3qC`lPEKtp|NfAgSq<5#( zAoC=0{DzehXmgOD9B22W71A#03*bRtKpjS0y>Hw>X5-GjMnr6kcV*Uo2;CGhM|Va| zHoij4V8{dv7geU?u=5vfx>V@A|5nAkH3NDbnWqojI``ZWaE~SdJjE=t_8vd`iV)7a zq3?yb*m(Gsg#)?h1;j$kdYs7Dv+QN6$CRqXudrX5^-kx|;0tn*FU`<__%p*cmUCk-~9@8Lyf=BkC zh+p9`3O^aAJRRp@Pe2lsJ0Lg8B+0cF=abK$ce}oa?>X-Z>>D0Dzoh2zK&B_%v$%Fi zT?4q3i5CJ_)?|8I=k(m0-dyL(P=;+`4Q*XimA03(5_#fYmf=K|*7z3jfX`$p1CI@< zPpeCCqW$XN0&9bp;SnchO{AzS$h5x(PpNm6jvlqTb3NaA8u5)n^|bnU&!?~@ItF+> z*(Dh^p*3wUk8FjxJl8sLFKunDN!{C8#V|M_GKXh4u3UJRO^BUTfDKFU80L&$OIU&nDoO z*qrC|nm^!t?VH}Ijyr>72C*$Yr`P^Ly#jBhIiNpy$SkHs@|ub6G}1gU5zghix-*%;QOGQJ=6DFWD>KAGc#O4!h3fQ#V>4igT7~+ym%^T37~1 z17=iPW%Gdac{| zD$B2!M2SY|3&3T2jcuS*t#TB0dt-pcIW23!J{#4IPF zWk7UZK$-7E?JXZYjHa~-}# zpE)B7ydp0qNfL_@!;7zF2lzLFyEONG8#CY#JrnI>27A=TYNuxA{71@U%(PBna`g_3 z_0%P=-U%K2->M355}pn*4(4i$%z<{9P++BT+;O_D9x^^ki}Q_8W*B59cuAb2R%zY^DU}#) zRAzz>Dbj*63Fg3_??Od84_N9p3_)dl7TQT;^{sT?1g1ARC%vA@PM z!;ovTByJ%7+mPpFvG8IaJRRbC^5+gEcswUBN+Nn?o&*1XuQeKT2(jCECR{|nWI~st z<$-_ZPPDCq`>H3_m*Xfx1BkUHKR+vQirLgJx{*~^zZ6|Cy!l+Kc ziyL-r1Kl09@nirv5)y$Xz#2IstDlE0gJ990(DH+ zZrJVH*B?V|q_a^T^bq*ec@1J{tnq}fgSi*4VG#l(9? z@!(N8akB1C)v#Kv%D8j8c@fN0rFSWZ_L569L=L?4^;L=z5W+r5G|{y3mdCCL&6( zlKx=>BPmu2YWZH zr0Xf}3b09ivuNHgxi!Ue>|qi~r;r~op3#cH!z?#UGjuqbI-cSs@ex^J`ZDz_{agC0 z`mp@B@~-C1DtN2lYC%{be1&45uao>Tpct`tO_R!?`-2f)J)SdbY=`)n84QgkR}P(c**XZCXdhw zh-vAH%Mxhq7E&RvrYXz1-sS}psGLBzp8IQ&SNeivR9FP4Ct*81I|8$Cf|)dl_mt%{<@)%vhy`+k0lCYyS+p1C!Ln1hZv_&dS;Rh+oiP!usDoE{uWBrCINmEhfm46W9 zNY7Y6_gxeZ>Yd8o&^;)Q;PyUnbas%qfEwtP(VdD!G>Ehw0T)$Z7YOuvf#4akb^r~Z ziV-A0Mutqm7(t|%C%lyXu2fy;vu|AIQ@1i@ewNR`7t460Uy#UsTJFP$dHIL@<|_@f zuS4HQBhR-QZWw3_c-O#aYV~0e^ED}%lXzx#N~@p0TqUl+|Q10g~}W!Hl& z?cj}OKziahB$t?{VI9sy|YwPK}*vO1j^RrgHM7%o09h3OtRq0Kho-YwK zU;Lra6=I+vVl{7A#SRpA5Twy}hv-*L;tN-yZaUm43Rf++FoRetQ_jYC)N?>>>ARmx zWr6+s195NDERp^RObt6`r%H|^2{DjT>M_0?hPsb^pTeO2i>TVpC85!;?UiW#q5>ccUKylY)l1{ z#FVw!X!uvL%(cRiKXr%QbA`zf<~j1(V__Iot}!DoJq(i_p(kGLjvqVe$y~eRhi-co zv^d-`Q}3&qQVA0!t)XXg^n|b7ajrAV_0(6ehrs_uC*?b~J8EFR4f{CkS73jN_(0f) zI#cc)g#9sce+~8lgiB%nqcfvb2zw7~0ql1W9tyhx=|f<@+37ypYMdOSi7_JKlq4peChzPE82%+}V zt`IR?rx8N!$*vF?T-6Anw$2se2UjIRsIBg%+bN(nxaoGh6LiCwrqG2#LuuFU*m<1F zm|>3UM$46gGbaTvbcqtIp@Og*&T#XC~*VNAM-^J z##adp4|%Qco!PAu64wWz|Fhn@lx9{KYACUshir?iB~gTPZSgzUFTJ7mtUCbvJvFHd z&V?6bDNY#0P4=04CHN}4Y zqUJ3~_r=n;bjRPTV=%|@D!rD;y6st$}0P+2U_Q3 z^`iSPLs9lRa4h8dLZBF_>~EM<_W*HeK3H`iq@rq_`q_r-{QIBpG2o^vMVb0(>#WRK z8J^HQ%dtXgTFL3bchNISWl5x|M67BlH$9~rZ4Nb0$*c<@%57D2FZTkZOV*htWkPOR z!6c^O9~1}bJ@Fbp&glqn4gwNAB%}weuwKA7?gZ7gs7uaM1n~Qg)%Ov$anC$_-vKX6 zBM@#c;B0*Y#hnzj?037XCaN9c1OAy{%02>$P7eAHqqOSN$II zz|8X@`6e&ZdnQ)-lFc37-awQQS;`W*-UQB8k*OIJ+jBQ#Y1Q427q`^EXOPFdQ!_E_ zU439?IPV|NDHqu2zIIL9vX6bTBoP`()DWd`XYv_YA%F8q}a$H=a5s@0qyn9&Y7J`p(A z0a<|=0eXs)x)U`g&y?ypeX5>QNc6oGoAS+i$~FC3kJAjJIWJa`!b_i!>(TGKs7z~W zs~Nq~P)*-IeKnELJ9>a#ry?*xFtps1pKIAqTx-g3|A_6|CS!gffxP;N87K(Be=6LD2|pdMtgHbR1L%^QAYQOuxc7DtK@BWNjGhoDm(VDoCoR( zR(Q5>o{yLC$bDM2RA6;5Km^Bm;D0IMJFc{YU1@(t+UEQ2uVJO;U{oN+kEHv`4r8HKSc$(V*SDH40t8m`UG zxQZ5=WV~cs*SBwMdwmMpYzkrzSk&WiE`et@;F&SVkG5QjRy^GG>`7|`qnzP` z-_TOjz0C6}iQSGIV=~xL7j2Oba}z`)LOR%Nr3lJ??dxs9x^*}Z>V*;{SwesZ5n@(k z_nGsf3=q#ad)EU1@LRVCTikjW!A5(g-*vpujC4@%bU< zCV#_r8uk1&%vFr9wBA=?@B9V)U%{M#`4XlBaedz-k`$P^Fq>dLf%y@}XAhCg(9O&Y zDm808OJ|I`&Tp|m5-f^93UvdYs*15Zg?bGsor3or;B$4`d5tW@yq!;t=b9O1xq3A? z5U-#gP~N57G7hPL?_5rO{-q>lrM1M8iLlK)4bfQAb?F(wrOYU%xpwI!^wSr3%1h+R znWT-d3zc%?g3?jhds^1Ax$4{$|MKg+WGi^IrGoNY=m>7$+1=QYcpfN~oA$40Mqg)@ zS7gbin3W4wy4}y4Vpc5Z4nJ<%zp}YId>}6xd!RHoZFmDM2SxnMwM0B$@O*|A&xN0r zftT(_M}g5i4P}SAa|0K1>`hykZUe6c9YRV$2YgEu-y2lWDnd)w*eZ}4i8a-_zg~{m zV5%S1NMg5H{W4wvCyKUGw{9V)pgc5MKeWDRUD5g(1^RD;*#$%E?ccCzofX0sy^nf= zP3!VD?D!*szTVo6mHn^GLs{qY{+R~sTz~0gE9Pr8ZM#bdmvoH}kZ9A4w z9$;k`P6;C=x<25X9P1FfRt`YYg5LxBHQ4J8rE(EecH|el#|l#qLvai=;rAWcUD1$B zrrJpa`vJq=K$Py)=j=LP>?4U6 zc;V7O$Z|lBylfU$Nb5Tp+-b6E`gOi?cYRuV!*TF3Q>`QTP$F!;Al%(LKc2BibkJI{ z@N}#+v@`Za9hfJVnyR*_qiST@8I7OyA??cumhoX>SE?Y-dq1T~$`JS@ z`wU@{RD^%~MT>+n7#YLnA9&?WJHkS$A?M1k^~xt56gyzp4Zi?Ber00c9?zW z2VEZSlcAbM(8YxM``5SMj&(ZzRzvw47%5HXgVKSfOqAQRWkbLfW?s(-)QSvm0qX{( z9Efk6xixcZwgiQh_CeD zs_ui^B%N#SHc*VVt>8`Jgmvjw^>4K?rM@vLd%cNKMi>$2_ZIX;duf?rRvV*4nk8=m zS?gCDZq+@tG%P4az>7|)T0bx;OMQWHZ-guWlLScs<&9as(Nxx)gwM~o6tY>Js8zLA znoiGR5}@50d(Wo)TR`j+^-MU^!QEk6WPZUa5`EKJjl4fq4{MM{5XCb(vISc3iQ9PA zrPttNm6y)Q+{QDFGiNC~eC}-Hxkf2uprsu?*ik}1q(YF$Byq8%>}N>L#kWsH>-@qw z9d)}B5~-$kX$3*8E5VmyhJS10?0<0mWB1qo6I>cU-+%_$5PzW6{kuffdMok9>Kwbj zhaY5Q=-sX|Ewtgl2bXK5yW-cEtoN?i!;>vHS7YX4IdCz2%H>93BksuM+O0knAx1{& zTMoK~%i)4#FY0MF*0<&AvG8Gt8Q0hCFt(AjDPCxKmq*@yr)6p=X zlp7pk4Sh&cO8q|`d5#SJ(b_xa7ShQFLmE#TOKS*keoG4tXXHX6B5YJ6gt3aVdI3vD ztP3{DDnen)%0mruy$dt%HQFa>-&~KjN5>7?KLao}9EY3WXc_B1&Gt&F%`4s)9I*pb zy?4K|g?L0?L%-z%v+B?s1%5vwk_;UaU!`a9;0EJ zu*_2@-Y+N%tAOs{Ivx7Bxhs(NgLRlsFkU=bCR(1#yKlJU>fSIWMvbgV1nv=TnYFub z*rmKc+HX$X`9cYF8A$BN>QCMABwj|wo`6vd(l=eiUfv~xYdP)=c%E07DFFkc9MfqWkG)b1kHkrteHs4sBlf-bBol4{ZEiQ`gPHI+<4IE2O<)u=*V6QA` zhFmYrav9SjHrz~7K&%4Xc6zeU15cW+#VbKeJ^q=W6#~?c;FPdMqa0*5_)u! zN?A85#x&%uf+5QIBf)r@M0%ji-Nppl=;12wY1E0|TKD~r@z^8N@(qQFhZzZDM;*}n zG?h4k;4agVdvT`%BmQ~ZWJhH>B-M~+alNzCW=36%Jkm$!jU7FS9ePC&mFSWYtPDkn&}uRCH2* zSr>hh`hz-|q0KgWkMd31$P@J4jPe@^13h4hUb1eM7w%_f6tos7Pjq7?P8gIYvP4?i zYR~kvT48mTdp7aa9?dq{H=F2ps_bSHz4MLnJgmFUH@*;BdYvbSUgd-05Awk(db`O% zzK;s>$Gb_y4xW|m;JGcYN^+tFEsP+uiHSbQ_fovd2TtI&N7tXd<3WJd*7Y9R;0j36 z=RSBBuEA)RL!HrDq$HxfPRDzY1mh|Qc2S#6$$TKV0}Q)V3ZXyFGRiVlATJpt z*9d`@o`D-dd$HavfzXOx+tp}!8}D+)1>w|FjJ#H1MlA+5wmB=24~(aBCV}yi16=b( zP6#|brbBpF&I`i4H5@R!#DgR)tfayv8!-h42_)7~`+Sz%%p_G*`NYai&(#x!dzNxK zOpqz0x>ZX*_OB?hEY+2@yVfYJerx3|CSPC38ZOG3sXjl;AEP4aUj)kST}vrv2Il>y zcVR3&lmpGMuEPy{IGI&7acHBS;PEnoSNUF`Y*4()E?T?JQyxqGs@9vP>D_mp9JOuJ zny@}6W$)Qs^&^>_HF+E@t=tr@rF87-QUI+O=aqNlnpizEG+lCwTUiqb;1Tp#c*8X^wjAXrc@8M1HL_+N^!w zof2p!%Nn2L*@|kUoYFvf$Bk+Cpdr9WX^bHGBu^Sk(sWnJpv+o9bb13F+f%Jx5kVN& zJ;4X)aFpFuP3#1Zj8pXxChN zxLcNN0c6QiTFr@W>6P1cxZ}7q*_fnH0QclaTcQCgu*Tf5!I{3XNqUB78|xeV!Sy6% zF}ms6P_wMu>39(c$4Pn;b*^@#@vO}cGk<@bpKInf9}3rz$i8OE=_N`<=0|E-1Jf)F zgDl%BTPXYHf@Z0hdlUMMr5ebx9aHx^&kXz3c7o52_bm^Ijj9Py9>N+qNh>#@kBlqB z>FnT*gDpNg!Ozn(iLznPqSkiUTyv66=w9Et=5;zB(fNe7CEDI7{b+lm^rQTx7b|ya zUjT2(7t-Bj_x+%$Bh@N!gD}M{I?i)_1F!j%M``6o-|}#6FZ~HV19~8&RJcu6F4!i@ z!dhZmBGwX5I7RfGFS*web=~jafxbX-0(u+B;1p}pJWcfntzHR&=qE8dF?Q(~Mbr>7 z6SqIzv5p4*0KKv9cPoE_#jaZP z3$S0<-swmLntDOe4sO{C31lxuK%1P|7YG?(0Zvi{$Q$>!An!&eMRle++`o6fMfk{DD4M9i@IK^v z)`2>q$o8KgC)1Fsk|Z2f9kL$F2NX3A&v zcWe=`J8YcccbmU~Gq83mtF&7=xrWmdASfG{7>aB{YT9n zd!%Nu;|6MlEW#Uz6(k(`YryhjK_vz??B&9)5LN)Y0(D*u1PF>;(doE`yDKPi1tFZ4 z0eW)$5mELlK=+A10Y2``(^d0Tllch63r#Y`9Xdwg+kFq?_HZf{p~EiH?t}XknDPMV zF^BL}k5Q(g8q4umHTMA~^GlTzfwacpJ%y0QMoPHWw$t}f*P`||U~SNyz=ldjOHoZi zfe0TC7mX7lmAkH@v^PLeJ?w0p;5l`)_ zyqM7T=iLH+csRwMLkqr2`5IIbApV5sppM!DD`$!wE)1qlhqjYMwOsz)=84mVmywI& zB;AovL;*e8$0qczlQnx*Qu)X|OR=+vfCe>6<$dxYUH8&=0L26dxt)$LcuH08Xg6KO zuDgZ;F%EK9dgv-hYO{7i&y0HvyH32Lhn@mRjr_Y)GHzsbyF=BXsE#tIEF93DxyC3L zhSN-7XzoaNA&`T9ZrqLjF4-VAF2t!jU*)bz?iI^ueZY@owX!Q-89^zGT4>E_Gcmy_ zeyQP*ACYJ!Crq)OKwUh;OHKe=3fl5*wJG+$O>D6_oofi_B@Jt`PU>3|)>NCj4eO;c zn8ntRRPc?ZDmJKQc2i1tUuX=G0!`BdnWkx?-|kK(L24%|%U$C8WKAYXX*$1TCQ&sp zB)?@1`yi%I{h<~hk2as4AgRG9ON{AT?8FyOWJ_u?+3cnX3RTlY#hTHlYwB8@oT};c z1Zd{B0jm)^Rc7?lSN$=$tY3Oy64)*@+rUasDAtbjc8yYr> zrmIF{`ZnZ`^x15Uih$Sc%ZzTfQqDse!Wmb1Ch?=;$?aCk2YSsW?fzQGv*3F@t?@_| zRFi=J`dWNB_5}3pwA{UG@Sh{mZiO2rC%{Un#MG);-&*=CSE~b+K<9_gsq9@U`aSq6 zmrDhg3Hh;&q-HJXuO|H{Rk>|IR9n*&QM{%}Sv=ngt@`}BW_iKqHFZHLsti?%>S)bO zbui@9F$12d4$! zpTomM{SSe!P}M9&JxJ~QYY1w1k~&E9S&dZ{q;c26T9isuV?tS(L?-!&EeGF8zcHwW zeq}gl$N37Zw7w*u87SPu_=Z7}(U|UUUy~!KRgtI~m5cWNEoA8vHRLX(BmD}^L#iUb z{9bq(ITkQlH7lajRMMPOZ6>6q?FhWs8c+>dwkq}PCL)!9iW>VH8j9acNLV9IWLX+U z(|RIpj~|o;y;Lroh}q}?Y|VO%5Re(Mf1;7p>}dgN_g%t$*0HHoGI~$*>0H?r25qt+ zm9|XULb3ACQ2=W|)69~d*3TlGrlRo^nzCtY?umD`UN!Nlt7_@W@j9Pl-^Cqj_RsgY zkkdqz8k9xZ!P;G=#CQ3(s)zJ?LO3_@Zt>}g0$Us{Po*x3{4)(}tFdU(8GpYkUJ97$q| zB*YsweSr_Pk)bcOZ{WQ$*ryr7QhPl|IBFv!0c{DOH5pURybB7Th*u-ND@rC^rYEUzPNEY`alG_n( zx>ffll9$4XB(h{kWC_VEEG|+^&MR4fhulAku|sJ@=L1TM9$N-KP4Pr`d}_CU-lBQS z$h@UXhQQ2TzNo0wSX8jAsBm7%QV{-$MT-~ZEi8JHOj%g8ki^U>UYxfqhD0q|UR)fF zye#91gc_P}b+_#~VcO8loY9JsWqC`N&093rlZ;CnH(D`gX;G0Pa`_-dao*CoMJ3DN z_9T%do}_Sej)`1ON{W^#3XAfW&viY3+GSDWD!fuc{An8y z`*?(f`Uj32J3OJkGA7RW+}~CdFUT*-$kC=u&YkgeqwV+G_kr11fBjPJnJ>Qi*OoVT z?cDUr3mf)+{P%YcA3Ap8t5awHedX%KIw#+9@8(axHGNuHee%GEAH4UPdF_j3ufJVB zP!T;i`H5kP{et{@aRP78sS~C@qsvZHFE-@ODOt99<;Kk~nYM4Mc+2uh&C!GV_q^ZU z<*@(!WAm?{fBD_l*DjyG00QWjFMWR1#HVIY8<(X?4er}pCS<*&;RA+5jTxOZbbO{N zebSU!GoM{jx@P{u!h$D9#gB-H926^JB)%bi0^}d<+x?HKBcC0AW9yE0UVe4`x*r;> z-=F^Hx94u%_~nm|2W@vAcH%^mGC?tEnqt|!g++^(FC$MXCQKctC|Z=4UtCn!?L(!y zy$K~mvJd7Uj0NThOf}5AFdx96I#ppZRz=$p8NP@aMD3oR#2rWb8;t{x@Xw#X9Y^~n zjf?v;#^s{nG*4>x7}|fSo90Iijd$fe4UXM3fMthL3x0=X*c z%*fKG|37IH|EIK|RL1PdY1wJx(k4%u{$C4=BFua|)Bje2k+W&mE<$w|7pakjB2JN` zqhw28yiDyE}hx z}ha_*#wIpfFavNF@Psp^!mW0FUW7@9aFE@q%o5f&u(c6~DajQ{!@(jEIo zy!g36c|N}%o9MAK_{>7_Yi;w5!#*guy=Qyju0-<{pZAYmUD5aU#YS^O-J7x5pLm>D zW%-*p?x<~RpPDU&vQPW8Dk|q^EUCWpL(0kZt1ny*Y5wWj!ih&Nw0*VV{JN)h6w6QT zT~N5PJ^#V4XNz9WnZ*P&6pIQ9#`t#J^_IN)wPI27GqQQvKc(m|E?qMBz1p9+C(&x)2@VLnsT?TC?G{A1$=%aVRaJ`sKJQ_VX`7moh&-dSeGZmv%*eErG!3%&Qwn7`8NJD;E4c6yWz{D^p3c8OP~migN2_DEhbv@(6W zPK)L}JvHBPZf=oj$?)P}n`ptJXG1S^HO8LbIAi5y*|%BO<}SWo-QNDk$<3ORpZ31E zxl;ejo=cbhR#yA&nbY+nC$(PBX_A{(en#WUOv@RmSC5@A~Xe&yVkAal`d1 z1u0+rp}#)m`rN&LY+jVG;^aK-rbBt>Le|asYn zaLUQ#WB-iuI#IQ4#^G4O{6n+;;r#w|!gtmquk30V)aRogW>%gqtQgQ*@atQ9<}ddw zTgdJcdAv1txKHzjx#FersYLifR?YT+l}CU4DAw})$k0!u6`Sj}d7r%a^QV7YT@`-) zir0m@^DnA@ywJiQx@K6k?sC6>^*XtB=78#ZH=e6p{9O8{LAPc|%*Oe?&To=Mb7pyg z_p+<#wRs=q^XHul^3uL5?p6Au=kDL@yuY8kPB8xTA#POOfVuy0^wL|$rO(T}^4y{) zv*y=+balq1hB;o>Rrcii5xF0Iw(p<2j{mUcyQ=it&Li<*ttU>reEQfo@nwf{|GwvN zf8lWJu`<#3|B9aa!{nN|4a&hQ=Nvkkm3M{>H9Y-#?BbXaC%q28yIJ~0=ylaji!%#sBqSp}^I8MB$ECK_H>W{rD4-w_R(T?sSjGVNvf|=MSU7Si_K!jLHLR z1JB*v>yk&3TmK^eKa;4)1g@tH*oHlH|CxfitkA>XLVD6Y9@kTz;WU_*Clx#cl!x2> zpXvS=zY3Qf^}Gl4dFX!pSxO%T_J5Cu_W0cN89}|YJQ+k4g7Sp!#+=rZq}#UA{6ndS zRpHO|W5NjL8CK=;;E(M?AYjI-;B@`CzSyG>R^{^GPtcE$34~R_>G}y3n2-poBHcex zI3cBkRdsuDB`L~|dSMXoER1U+#TxEwA{*F~=21I?IGvCBoezJHhPvG}PZcV{iA|v^ H8T|hTn0)s@ literal 0 HcmV?d00001 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