From 720cf5a485ad7fa4887fe4eea6ca476fcd114cca Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 28 Jul 2022 10:18:06 +0200 Subject: [PATCH] config: enable dynamic control allocation by default (SYS_CTRL_ALLOC=1) --- .../px4fmu_common/init.d-posix/airframes/10017_iris_ctrlalloc | 2 -- ROMFS/px4fmu_common/init.d-posix/airframes/10019_omnicopter | 2 -- .../init.d-posix/airframes/1022_uuv_bluerov2_heavy | 1 - ROMFS/px4fmu_common/init.d-posix/airframes/1030_plane | 1 - ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol | 1 - ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter | 1 - ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor | 1 - ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover | 1 - ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover | 1 - ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat | 1 - ROMFS/px4fmu_common/init.d-posix/airframes/2507_cloudship | 1 - .../init.d-posix/airframes/6012_typhoon_h480_ctrlalloc | 2 -- .../init.d/airframes/13000_generic_vtol_standard | 1 - .../init.d/airframes/13100_generic_vtol_tiltrotor | 2 -- .../init.d/airframes/13200_generic_vtol_tailsitter | 1 - ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane | 1 - ROMFS/px4fmu_common/init.d/airframes/3000_generic_wing | 1 - src/lib/systemlib/system_params.c | 4 +--- 18 files changed, 1 insertion(+), 24 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/10017_iris_ctrlalloc b/ROMFS/px4fmu_common/init.d-posix/airframes/10017_iris_ctrlalloc index 7871be2329..9f14acc73b 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/10017_iris_ctrlalloc +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/10017_iris_ctrlalloc @@ -9,8 +9,6 @@ . ${R}etc/init.d/rc.mc_defaults -param set-default SYS_CTRL_ALLOC 1 - param set-default CA_AIRFRAME 0 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/10019_omnicopter b/ROMFS/px4fmu_common/init.d-posix/airframes/10019_omnicopter index 4e3491dd71..ad69ad0f88 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/10019_omnicopter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/10019_omnicopter @@ -9,8 +9,6 @@ . ${R}etc/init.d/rc.mc_defaults -param set-default SYS_CTRL_ALLOC 1 - param set-default CA_AIRFRAME 0 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 d224008464..9441dc8ac4 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,7 +8,6 @@ # disable circuit breaker for airspeed sensor param set-default CBRK_AIRSPD_CHK 162128 -param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 7 param set-default CA_ROTOR_COUNT 8 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1030_plane b/ROMFS/px4fmu_common/init.d-posix/airframes/1030_plane index 47e29ede25..a6af630c18 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1030_plane +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1030_plane @@ -41,7 +41,6 @@ param set-default NAV_DLL_ACT 2 param set-default RWTO_TKOFF 1 -#param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 1 param set-default CA_ROTOR_COUNT 1 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol index a2a2025a8e..fbc0dcde44 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol @@ -12,7 +12,6 @@ param set-default FD_ACT_EN 0 param set-default FD_ACT_MOT_TOUT 500 -# param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 2 param set-default CA_ROTOR_COUNT 5 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter index 3c55ebd59e..0f305728c4 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter @@ -9,7 +9,6 @@ param set-default MAV_TYPE 20 -# param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 4 param set-default CA_ROTOR_COUNT 4 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor b/ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor index 59ec3242e4..5dfaa3bff2 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor @@ -9,7 +9,6 @@ param set-default MAV_TYPE 21 -param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 3 param set-default CA_ROTOR_COUNT 4 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover b/ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover index ad1727bb33..cd8aca77f1 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover @@ -28,7 +28,6 @@ param set-default CBRK_AIRSPD_CHK 162128 param set-default GND_MAX_ANG 0.6 param set-default GND_WHEEL_BASE 2.0 -param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 5 param set-default CA_R_REV 1 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover b/ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover index 2be17c1262..8b0a91d3b4 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover @@ -28,7 +28,6 @@ param set-default CBRK_AIRSPD_CHK 162128 param set-default GND_MAX_ANG 0.6 param set-default GND_WHEEL_BASE 2.0 -param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 6 param set-default CA_R_REV 3 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat b/ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat index c45d9d78b9..1d8cb686c2 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat @@ -28,7 +28,6 @@ param set-default CBRK_AIRSPD_CHK 162128 param set-default GND_MAX_ANG 0.6 param set-default GND_WHEEL_BASE 2.0 -param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 9 param set-default CA_ROTOR_COUNT 2 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/2507_cloudship b/ROMFS/px4fmu_common/init.d-posix/airframes/2507_cloudship index 33be5fa870..e3930a1fbc 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/2507_cloudship +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/2507_cloudship @@ -11,7 +11,6 @@ . ${R}etc/init.d/rc.airship_defaults -param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 9 param set-default CA_ROTOR_COUNT 3 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/6012_typhoon_h480_ctrlalloc b/ROMFS/px4fmu_common/init.d-posix/airframes/6012_typhoon_h480_ctrlalloc index 39e360f8be..65e72db75e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/6012_typhoon_h480_ctrlalloc +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/6012_typhoon_h480_ctrlalloc @@ -9,8 +9,6 @@ param set-default MAV_TYPE 13 -param set-default SYS_CTRL_ALLOC 1 - param set-default MC_PITCHRATE_P 0.0800 param set-default MC_PITCHRATE_I 0.0400 param set-default MC_PITCHRATE_D 0.0010 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard b/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard index 9a4221f1a6..38dc721bc7 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard +++ b/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard @@ -12,7 +12,6 @@ . ${R}etc/init.d/rc.vtol_defaults -param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 2 param set-default CA_ROTOR_COUNT 5 param set-default CA_ROTOR0_PX 1 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13100_generic_vtol_tiltrotor b/ROMFS/px4fmu_common/init.d/airframes/13100_generic_vtol_tiltrotor index a457a7ce76..19f9a95eb9 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13100_generic_vtol_tiltrotor +++ b/ROMFS/px4fmu_common/init.d/airframes/13100_generic_vtol_tiltrotor @@ -11,8 +11,6 @@ . ${R}etc/init.d/rc.vtol_defaults -param set-default SYS_CTRL_ALLOC 1 - param set-default CA_AIRFRAME 3 param set-default CA_ROTOR_COUNT 4 param set-default CA_ROTOR0_PX 1 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter b/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter index 888e530050..8e0ca8e0b6 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter +++ b/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter @@ -12,7 +12,6 @@ . ${R}etc/init.d/rc.vtol_defaults -param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 4 param set-default CA_ROTOR_COUNT 2 param set-default CA_ROTOR0_KM -0.05 diff --git a/ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane b/ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane index 9ed8f7f69b..30bce6eeef 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane +++ b/ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane @@ -10,7 +10,6 @@ . ${R}etc/init.d/rc.fw_defaults -param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 1 param set-default CA_ROTOR_COUNT 1 param set-default CA_ROTOR0_PX 0.3 diff --git a/ROMFS/px4fmu_common/init.d/airframes/3000_generic_wing b/ROMFS/px4fmu_common/init.d/airframes/3000_generic_wing index 005a596103..6daab9cdac 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3000_generic_wing +++ b/ROMFS/px4fmu_common/init.d/airframes/3000_generic_wing @@ -10,7 +10,6 @@ . ${R}etc/init.d/rc.fw_defaults -param set-default SYS_CTRL_ALLOC 1 param set-default CA_AIRFRAME 1 param set-default CA_ROTOR_COUNT 1 diff --git a/src/lib/systemlib/system_params.c b/src/lib/systemlib/system_params.c index 95305d20e1..abe5ae8000 100644 --- a/src/lib/systemlib/system_params.c +++ b/src/lib/systemlib/system_params.c @@ -289,10 +289,8 @@ PARAM_DEFINE_INT32(SYS_FAILURE_EN, 0); * If enabled, dynamic control allocation with runtime configuration of the * mixing and output functions is used. * - * Note: this is work-in-progress and not all vehicle types are supported yet. - * * @boolean * @reboot_required true * @group System */ -PARAM_DEFINE_INT32(SYS_CTRL_ALLOC, 0); +PARAM_DEFINE_INT32(SYS_CTRL_ALLOC, 1);