diff --git a/Tools/Replay/LR_MsgHandler.cpp b/Tools/Replay/LR_MsgHandler.cpp index 3fb24fb4ab..227099c6ba 100644 --- a/Tools/Replay/LR_MsgHandler.cpp +++ b/Tools/Replay/LR_MsgHandler.cpp @@ -381,7 +381,7 @@ void LR_MsgHandler_NTUN_Copter::process_message(uint8_t *msg) bool LR_MsgHandler::set_parameter(const char *name, float value) { - const char *ignore_parms[] = { "GPS_TYPE", "AHRS_EKF_TYPE", "EK2_ENABLE", "EKF_ENABLE", + const char *ignore_parms[] = { "GPS_TYPE", "AHRS_EKF_TYPE", "EK2_ENABLE", "COMPASS_ORIENT", "COMPASS_ORIENT2", "COMPASS_ORIENT3", "LOG_FILE_BUFSIZE"}; for (uint8_t i=0; i < ARRAY_SIZE(ignore_parms); i++) { diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index d865c43735..152de2d349 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -90,7 +90,6 @@ void ReplayVehicle::load_parameters(void) if (!AP_Param::check_var_info()) { AP_HAL::panic("Bad parameter table"); } - AP_Param::set_default_by_name("EKF_ENABLE", 1); AP_Param::set_default_by_name("EK2_ENABLE", 1); AP_Param::set_default_by_name("EK2_IMU_MASK", 1); AP_Param::set_default_by_name("EK3_ENABLE", 1);