diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 68386b56f8..76cdeba1f5 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -641,6 +641,14 @@ void Rover::load_parameters(void) const uint16_t old_aux_chan_mask = 0x3FFA; SRV_Channels::upgrade_parameters(old_rc_keys, old_aux_chan_mask, &rcmap); hal.console->printf("load_all took %uus\n", unsigned(micros() - before)); + // set a more reasonable default NAVL1_PERIOD for rovers L1_controller.set_default_period(NAVL1_PERIOD); + + // configure safety switch to allow stopping the motors while armed +#if AP_FEATURE_SAFETY_BUTTON + 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); +#endif }