Browse Source

AP_BoardConfig: added BRD_OPTIONS

used to enable STM32 watchdog
mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
288569e156
  1. 15
      libraries/AP_BoardConfig/AP_BoardConfig.cpp
  2. 15
      libraries/AP_BoardConfig/AP_BoardConfig.h

15
libraries/AP_BoardConfig/AP_BoardConfig.cpp

@ -68,6 +68,14 @@ @@ -68,6 +68,14 @@
#define BOARD_CONFIG_BOARD_VOLTAGE_MIN 4.3f
#endif
#ifndef HAL_BRD_OPTIONS_DEFAULT
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#define HAL_BRD_OPTIONS_DEFAULT BOARD_OPTION_WATCHDOG
#else
#define HAL_BRD_OPTIONS_DEFAULT 0
#endif
#endif
extern const AP_HAL::HAL& hal;
AP_BoardConfig *AP_BoardConfig::_singleton;
@ -230,6 +238,13 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { @@ -230,6 +238,13 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
AP_GROUPINFO("PWM_VOLT_SEL", 18, AP_BoardConfig, _pwm_volt_sel, 0),
#endif
// @Param: OPTIONS
// @DisplayName: Board options
// @Description: Board specific option flags
// @Bitmask: 0:Enable hardware watchdog
// @User: Advanced
AP_GROUPINFO("OPTIONS", 19, AP_BoardConfig, _options, HAL_BRD_OPTIONS_DEFAULT),
AP_GROUPEND
};

15
libraries/AP_BoardConfig/AP_BoardConfig.h

@ -157,13 +157,22 @@ public: @@ -157,13 +157,22 @@ public:
return _singleton?_singleton->_sdcard_slowdown.get():0;
}
#endif
enum board_options {
BOARD_OPTION_WATCHDOG = (1 << 0),
};
// return true if watchdog enabled
static bool watchdog_enabled(void) {
return _singleton?(_singleton->_options & BOARD_OPTION_WATCHDOG)!=0:false;
}
private:
static AP_BoardConfig *_singleton;
AP_Int16 vehicleSerialNumber;
AP_Int8 pwm_count;
#if AP_FEATURE_BOARD_DETECT || defined(AP_FEATURE_BRD_PWM_COUNT_PARAM) || HAL_HAVE_SAFETY_SWITCH
struct {
AP_Int8 safety_enable;
@ -223,4 +232,6 @@ private: @@ -223,4 +232,6 @@ private:
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
AP_Int8 _sdcard_slowdown;
#endif
AP_Int32 _options;
};

Loading…
Cancel
Save