diff --git a/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator b/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator index 0a0a21cbf5..8121f3914c 100644 --- a/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator +++ b/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator @@ -167,6 +167,12 @@ elif [ "$PX4_SIM_MODEL" = "jmavsim_iris" ] || [ "$(param show -q SYS_AUTOSTART)" else # otherwise start simulator (mavlink) module + + # 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)) # Check if PX4_SIM_HOSTNAME environment variable is empty diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index e7a6ae984d..0084a6701e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -164,10 +164,6 @@ param set-default COM_RC_IN_MODE 1 # Speedup SITL startup param set-default EKF2_REQ_GPS_H 0.5 -# Multi-EKF -param set-default EKF2_MULTI_IMU 3 -param set-default SENS_IMU_MODE 0 - param set-default IMU_GYRO_FFT_EN 1 param set-default MAV_PROTO_VER 2 # Ensures QGC does not drop the first few packets after a SITL restart due to MAVLINK 1 packets