diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy b/ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy index c8a8c6c16d..a212fa18d2 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy @@ -8,6 +8,63 @@ # disable circuit breaker for airspeed sensor param set-default CBRK_AIRSPD_CHK 162128 -set PWM_OUT 12345678 -set MIXER_FILE etc/mixers-sitl/vectored6dof_sitl.main.mix -set MIXER custom +param set-default SYS_CTRL_ALLOC 1 +param set-default CA_AIRFRAME 6 + +param set-default CA_ROTOR_COUNT 8 +param set-default CA_R_REV 255 +param set-default CA_ROTOR0_AX 1.0000 +param set-default CA_ROTOR0_AY -1.0000 +param set-default CA_ROTOR0_AZ 0.0000 +param set-default CA_ROTOR0_KM 0.0000 +param set-default CA_ROTOR0_PX 0.5000 +param set-default CA_ROTOR0_PY 0.3000 +param set-default CA_ROTOR0_PZ 0.2000 +param set-default CA_ROTOR1_AX 1.0000 +param set-default CA_ROTOR1_AY 1.0000 +param set-default CA_ROTOR1_AZ 0.0000 +param set-default CA_ROTOR1_KM 0.0000 +param set-default CA_ROTOR1_PX 0.5000 +param set-default CA_ROTOR1_PY -0.3000 +param set-default CA_ROTOR1_PZ 0.2000 +param set-default CA_ROTOR2_AX 1.0000 +param set-default CA_ROTOR2_AY 1.0000 +param set-default CA_ROTOR2_AZ 0.0000 +param set-default CA_ROTOR2_KM 0.0000 +param set-default CA_ROTOR2_PX -0.5000 +param set-default CA_ROTOR2_PY 0.3000 +param set-default CA_ROTOR2_PZ 0.2000 +param set-default CA_ROTOR3_AX 1.0000 +param set-default CA_ROTOR3_AY -1.0000 +param set-default CA_ROTOR3_AZ 0.0000 +param set-default CA_ROTOR3_KM 0.0000 +param set-default CA_ROTOR3_PX -0.5000 +param set-default CA_ROTOR3_PY -0.3000 +param set-default CA_ROTOR3_PZ 0.2000 +param set-default CA_ROTOR4_AZ -1.0000 +param set-default CA_ROTOR4_KM 0.0000 +param set-default CA_ROTOR4_PX 0.5000 +param set-default CA_ROTOR4_PY 0.5000 +param set-default CA_ROTOR5_AZ 1.0000 +param set-default CA_ROTOR5_KM 0.0000 +param set-default CA_ROTOR5_PX 0.5000 +param set-default CA_ROTOR5_PY -0.5000 +param set-default CA_ROTOR6_AZ 1.0000 +param set-default CA_ROTOR6_KM 0.0000 +param set-default CA_ROTOR6_PX -0.5000 +param set-default CA_ROTOR6_PY 0.5000 +param set-default CA_ROTOR7_KM 0.0000 +param set-default CA_ROTOR7_PX -0.5000 +param set-default CA_ROTOR7_PY -0.5000 + +param set-default PWM_MAIN_FUNC1 101 +param set-default PWM_MAIN_FUNC2 102 +param set-default PWM_MAIN_FUNC3 103 +param set-default PWM_MAIN_FUNC4 104 +param set-default PWM_MAIN_FUNC5 105 +param set-default PWM_MAIN_FUNC6 106 +param set-default PWM_MAIN_FUNC7 107 +param set-default PWM_MAIN_FUNC8 108 + +set MIXER skip + diff --git a/ROMFS/px4fmu_common/mixers-sitl/CMakeLists.txt b/ROMFS/px4fmu_common/mixers-sitl/CMakeLists.txt index 753c47382b..14924d8660 100644 --- a/ROMFS/px4fmu_common/mixers-sitl/CMakeLists.txt +++ b/ROMFS/px4fmu_common/mixers-sitl/CMakeLists.txt @@ -41,5 +41,4 @@ px4_add_romfs_files( standard_vtol_sitl.main.mix tiltrotor_sitl.main.mix uuv_x_sitl.main.mix - vectored6dof_sitl.main.mix ) diff --git a/ROMFS/px4fmu_common/mixers-sitl/vectored6dof_sitl.main.mix b/ROMFS/px4fmu_common/mixers-sitl/vectored6dof_sitl.main.mix deleted file mode 100644 index 1b27ef1640..0000000000 --- a/ROMFS/px4fmu_common/mixers-sitl/vectored6dof_sitl.main.mix +++ /dev/null @@ -1,40 +0,0 @@ -# Motor 1 -M: 3 -S: 0 2 -4000 -4000 0 -4000 +4000 -S: 0 3 +4000 +4000 0 -4000 +4000 -S: 0 4 -4000 -4000 0 -4000 +4000 -# Motor 2 -M: 3 -S: 0 2 +4000 +4000 0 -4000 +4000 -S: 0 3 +4000 +4000 0 -4000 +4000 -S: 0 4 +4000 +4000 0 -4000 +4000 -# Motor 3 -M: 3 -S: 0 2 -4000 -4000 0 -4000 +4000 -S: 0 3 +4000 +4000 0 -4000 +4000 -S: 0 4 +4000 +4000 0 -4000 +4000 -# Motor 4 -M: 3 -S: 0 2 +4000 +4000 0 -4000 +4000 -S: 0 3 +4000 +4000 0 -4000 +4000 -S: 0 4 -4000 -4000 0 -4000 +4000 -# Motor 5 -M: 3 -S: 0 0 -4000 -4000 0 -4000 +4000 -S: 0 1 +4000 +4000 0 -4000 +4000 -S: 0 5 -4000 -4000 0 -4000 +4000 -# Motor 6 -M: 3 -S: 0 0 -4000 -4000 0 -4000 +4000 -S: 0 1 -4000 -4000 0 -4000 +4000 -S: 0 5 +4000 +4000 0 -4000 +4000 -# Motor 7 -M: 3 -S: 0 0 +4000 +4000 0 -4000 +4000 -S: 0 1 +4000 +4000 0 -4000 +4000 -S: 0 5 +4000 +4000 0 -4000 +4000 -# Motor 8 -M: 3 -S: 0 0 +4000 +4000 0 -4000 +4000 -S: 0 1 -4000 -4000 0 -4000 +4000 -S: 0 5 -4000 -4000 0 -4000 +4000