mirror of https://github.com/ArduPilot/ardupilot
AP_BoardConfig: more changes for 32 bit servo mask
This commit is contained in:
parent
f3ce44ef2c
commit
7ed8e8d3b6
|
@ -373,7 +373,7 @@ void AP_BoardConfig::init()
|
|||
}
|
||||
|
||||
// set default value for BRD_SAFETY_MASK
|
||||
void AP_BoardConfig::set_default_safety_ignore_mask(uint16_t mask)
|
||||
void AP_BoardConfig::set_default_safety_ignore_mask(uint32_t mask)
|
||||
{
|
||||
#if HAL_HAVE_SAFETY_SWITCH
|
||||
state.ignore_safety_channels.set_default(mask);
|
||||
|
|
|
@ -100,7 +100,7 @@ public:
|
|||
};
|
||||
|
||||
// set default value for BRD_SAFETY_MASK
|
||||
void set_default_safety_ignore_mask(uint16_t mask);
|
||||
void set_default_safety_ignore_mask(uint32_t mask);
|
||||
|
||||
static enum px4_board_type get_board_type(void) {
|
||||
#if AP_FEATURE_BOARD_DETECT
|
||||
|
@ -141,7 +141,7 @@ public:
|
|||
// return the value of BRD_SAFETY_MASK
|
||||
uint16_t get_safety_mask(void) const {
|
||||
#if AP_FEATURE_BOARD_DETECT || defined(AP_FEATURE_BRD_PWM_COUNT_PARAM)
|
||||
return uint16_t(state.ignore_safety_channels.get());
|
||||
return uint32_t(state.ignore_safety_channels.get());
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue