mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_BoardConfig: kill AP_FEATURE_SAFETY_BUTTON
This is redundant and can be just HAL_HAVE_SAFETY_SWITCH.
This commit is contained in:
parent
00f03360bc
commit
73f8dd98f2
@ -87,7 +87,7 @@
|
||||
#define HAL_IMU_TEMP_DEFAULT -1 // disabled
|
||||
#endif
|
||||
|
||||
#if AP_FEATURE_SAFETY_BUTTON
|
||||
#if HAL_HAVE_SAFETY_SWITCH
|
||||
# ifndef BOARD_SAFETY_OPTION_DEFAULT
|
||||
# define BOARD_SAFETY_OPTION_DEFAULT (BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)
|
||||
# endif
|
||||
@ -131,7 +131,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
||||
AP_GROUPINFO("SER2_RTSCTS", 2, AP_BoardConfig, state.ser2_rtscts, 2),
|
||||
#endif
|
||||
|
||||
#if AP_FEATURE_SAFETY_BUTTON
|
||||
#if HAL_HAVE_SAFETY_SWITCH
|
||||
// @Param: SAFETYENABLE
|
||||
// @DisplayName: Enable use of safety arming switch
|
||||
// @Description: This controls the default state of the safety switch at startup. When set to 1 the safety switch will start in the safe state (flashing) at boot. When set to zero the safety switch will start in the unsafe state (solid) at startup. Note that if a safety switch is fitted the user can still control the safety state after startup using the switch. The safety state can also be controlled in software using a MAVLink message.
|
||||
@ -158,7 +158,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SERIAL_NUM", 5, AP_BoardConfig, vehicleSerialNumber, 0),
|
||||
|
||||
#if AP_FEATURE_SAFETY_BUTTON
|
||||
#if HAL_HAVE_SAFETY_SWITCH
|
||||
// @Param: SAFETY_MASK
|
||||
// @DisplayName: Channels to which ignore the safety switch state
|
||||
// @Description: A bitmask which controls what channels can move while the safety switch has not been pressed
|
||||
@ -213,7 +213,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
||||
AP_SUBGROUPINFO(param_helper, "", 12, AP_BoardConfig, AP_Param_Helper),
|
||||
#endif
|
||||
|
||||
#if AP_FEATURE_SAFETY_BUTTON
|
||||
#if HAL_HAVE_SAFETY_SWITCH
|
||||
// @Param: SAFETYOPTION
|
||||
// @DisplayName: Options for safety button behavior
|
||||
// @Description: This controls the activation of the safety button. It allows you to control if the safety button can be used for safety enable and/or disable, and whether the button is only active when disarmed
|
||||
@ -246,7 +246,7 @@ void AP_BoardConfig::init()
|
||||
// set default value for BRD_SAFETY_MASK
|
||||
void AP_BoardConfig::set_default_safety_ignore_mask(uint16_t mask)
|
||||
{
|
||||
#if AP_FEATURE_SAFETY_BUTTON
|
||||
#if HAL_HAVE_SAFETY_SWITCH
|
||||
state.ignore_safety_channels.set_default(mask);
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
px4_setup_safety_mask();
|
||||
@ -256,9 +256,7 @@ void AP_BoardConfig::set_default_safety_ignore_mask(uint16_t mask)
|
||||
|
||||
void AP_BoardConfig::init_safety()
|
||||
{
|
||||
#if AP_FEATURE_SAFETY_BUTTON
|
||||
board_init_safety();
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -15,12 +15,6 @@
|
||||
#define AP_FEATURE_BOARD_DETECT 0
|
||||
#endif
|
||||
|
||||
#if HAL_HAVE_SAFETY_SWITCH
|
||||
#define AP_FEATURE_SAFETY_BUTTON 1
|
||||
#else
|
||||
#define AP_FEATURE_SAFETY_BUTTON 0
|
||||
#endif
|
||||
|
||||
#ifndef AP_FEATURE_RTSCTS
|
||||
#define AP_FEATURE_RTSCTS 0
|
||||
#endif
|
||||
@ -127,7 +121,7 @@ public:
|
||||
return instance?instance->pwm_count.get():4;
|
||||
}
|
||||
|
||||
#if AP_FEATURE_SAFETY_BUTTON
|
||||
#if HAL_HAVE_SAFETY_SWITCH
|
||||
enum board_safety_button_option {
|
||||
BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF=1,
|
||||
BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON=2,
|
||||
@ -156,7 +150,7 @@ private:
|
||||
AP_Int16 vehicleSerialNumber;
|
||||
AP_Int8 pwm_count;
|
||||
|
||||
#if AP_FEATURE_BOARD_DETECT || defined(AP_FEATURE_BRD_PWM_COUNT_PARAM) || AP_FEATURE_SAFETY_BUTTON
|
||||
#if AP_FEATURE_BOARD_DETECT || defined(AP_FEATURE_BRD_PWM_COUNT_PARAM) || HAL_HAVE_SAFETY_SWITCH
|
||||
struct {
|
||||
AP_Int8 safety_enable;
|
||||
AP_Int16 safety_option;
|
||||
@ -190,11 +184,8 @@ private:
|
||||
|
||||
#endif // AP_FEATURE_BOARD_DETECT
|
||||
|
||||
#if AP_FEATURE_SAFETY_BUTTON
|
||||
void board_init_safety(void);
|
||||
void board_setup_safety_mask(void);
|
||||
#endif
|
||||
|
||||
|
||||
void board_setup_uart(void);
|
||||
void board_setup_sbus(void);
|
||||
void board_setup(void);
|
||||
|
@ -22,12 +22,12 @@
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#if AP_FEATURE_SAFETY_BUTTON
|
||||
/*
|
||||
init safety state
|
||||
*/
|
||||
void AP_BoardConfig::board_init_safety()
|
||||
{
|
||||
#if HAL_HAVE_SAFETY_SWITCH
|
||||
if (state.safety_enable.get() == 0) {
|
||||
hal.rcout->force_safety_off();
|
||||
hal.rcout->force_safety_no_wait();
|
||||
@ -37,8 +37,8 @@ void AP_BoardConfig::board_init_safety()
|
||||
hal.scheduler->delay(20);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
#if AP_FEATURE_BOARD_DETECT
|
||||
|
Loading…
Reference in New Issue
Block a user