diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index d72f8b3c7e..74ebbd2a26 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -652,7 +652,7 @@ void Rover::load_parameters(void) L1_controller.set_default_period(NAVL1_PERIOD); // configure safety switch to allow stopping the motors while armed -#if AP_FEATURE_SAFETY_BUTTON +#if HAL_HAVE_SAFETY_SWITCH AP_Param::set_default_by_name("BRD_SAFETYOPTION", AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF| AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON| AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED);