From 3f2b0324bbbba30692ae637644916a8d5f5923ae Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 21 Nov 2024 19:04:02 +0100 Subject: [PATCH] Disable multi-ekf for SITL to see if CI failures are related --- .../init.d-posix/airframes/1041_gazebo-classic_tailsitter | 4 ---- ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator | 2 -- 2 files changed, 6 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter index a803fcee3c..e36d24110d 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter @@ -44,10 +44,6 @@ param set-default PWM_MAIN_FUNC6 201 param set-default PWM_MAIN_FUNC7 202 param set-default PWM_MAIN_REV 96 # invert both elevons -# Single-EKF (for replay) -param set-default EKF2_MULTI_IMU 0 -param set-default SENS_IMU_MODE 1 - param set-default FW_P_TC 0.6 param set-default FW_PR_FF 0.0 diff --git a/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator b/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator index 76be887e84..5b595003cd 100644 --- a/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator +++ b/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator @@ -173,8 +173,6 @@ else # EKF2 specifics param set-default EKF2_GPS_DELAY 10 - param set-default EKF2_MULTI_IMU 3 - param set-default SENS_IMU_MODE 0 simulator_tcp_port=$((4560+px4_instance))