Skip to content

Commit

Permalink
ROMFS: purge old mixing system
Browse files Browse the repository at this point in the history
 - SYS_USE_IO is now off by default (enabled by default per board)
  • Loading branch information
dagar committed Sep 9, 2022
1 parent ed10146 commit cac9c51
Show file tree
Hide file tree
Showing 121 changed files with 100 additions and 2,797 deletions.
1 change: 0 additions & 1 deletion .gitattributes
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
1 change: 1 addition & 0 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 0 additions & 2 deletions ROMFS/px4fmu_common/init.d-posix/airframes/4001_x500
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
20 changes: 7 additions & 13 deletions ROMFS/px4fmu_common/init.d-posix/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 0 additions & 2 deletions ROMFS/px4fmu_common/init.d/airframes/4041_beta75x
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
11 changes: 4 additions & 7 deletions ROMFS/px4fmu_common/init.d/rc.airship_apps
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
6 changes: 0 additions & 6 deletions ROMFS/px4fmu_common/init.d/rc.airship_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -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
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/rc.autostart_ext
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
19 changes: 0 additions & 19 deletions ROMFS/px4fmu_common/init.d/rc.boat_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -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
11 changes: 4 additions & 7 deletions ROMFS/px4fmu_common/init.d/rc.fw_apps
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
8 changes: 0 additions & 8 deletions ROMFS/px4fmu_common/init.d/rc.fw_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -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
Loading

0 comments on commit cac9c51

Please sign in to comment.