Browse Source

AP_BoardConfig: more changes for 32 bit servo mask

apm_2208
Andrew Tridgell 3 years ago
parent
commit
7ed8e8d3b6
  1. 2
      libraries/AP_BoardConfig/AP_BoardConfig.cpp
  2. 4
      libraries/AP_BoardConfig/AP_BoardConfig.h

2
libraries/AP_BoardConfig/AP_BoardConfig.cpp

@ -373,7 +373,7 @@ void AP_BoardConfig::init() @@ -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);

4
libraries/AP_BoardConfig/AP_BoardConfig.h

@ -100,7 +100,7 @@ public: @@ -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: @@ -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…
Cancel
Save