mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 23:18:28 -04:00
Rover: default BRD_SAFETYOPTION to to allow disarming with safety switch
This commit is contained in:
parent
57b46f5a49
commit
17d16133d7
@ -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", 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
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user