mirror of https://github.com/ArduPilot/ardupilot
AP_BoardConfig: moved BRD_PWM_COUNT to common code
this allows all boards to configure some PWM outputs as GPIOs
This commit is contained in:
parent
7e897c16c0
commit
99ca0ea913
|
@ -88,20 +88,22 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef BOARD_PWM_COUNT_DEFAULT
|
||||
#define BOARD_PWM_COUNT_DEFAULT 8
|
||||
#endif
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
AP_BoardConfig *AP_BoardConfig::instance;
|
||||
|
||||
// table of user settable parameters
|
||||
const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
||||
#if AP_FEATURE_BOARD_DETECT || defined(AP_FEATURE_BRD_PWM_COUNT_PARAM)
|
||||
// @Param: PWM_COUNT
|
||||
// @DisplayName: Auxiliary pin config
|
||||
// @Description: Control assigning of FMU pins to PWM output, timer capture and GPIO. All unassigned pins can be used for GPIO
|
||||
// @Values: 0:No PWMs,2:Two PWMs,4:Four PWMs,6:Six PWMs,7:Three PWMs and One Capture
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("PWM_COUNT", 0, AP_BoardConfig, state.pwm_count, BOARD_PWM_COUNT_DEFAULT),
|
||||
#endif
|
||||
AP_GROUPINFO("PWM_COUNT", 0, AP_BoardConfig, pwm_count, BOARD_PWM_COUNT_DEFAULT),
|
||||
|
||||
#if AP_FEATURE_RTSCTS
|
||||
// @Param: SER1_RTSCTS
|
||||
|
|
|
@ -122,12 +122,7 @@ public:
|
|||
|
||||
// get number of PWM outputs enabled on FMU
|
||||
static uint8_t get_pwm_count(void) {
|
||||
#if AP_FEATURE_BOARD_DETECT || defined(AP_FEATURE_BRD_PWM_COUNT_PARAM)
|
||||
return instance?instance->state.pwm_count.get():4;
|
||||
#else
|
||||
// default to 16, which means all PWM channels available
|
||||
return 16;
|
||||
#endif
|
||||
return instance?instance->pwm_count.get():4;
|
||||
}
|
||||
|
||||
#if AP_FEATURE_SAFETY_BUTTON
|
||||
|
@ -157,10 +152,10 @@ private:
|
|||
static AP_BoardConfig *instance;
|
||||
|
||||
AP_Int16 vehicleSerialNumber;
|
||||
|
||||
AP_Int8 pwm_count;
|
||||
|
||||
#if AP_FEATURE_BOARD_DETECT || defined(AP_FEATURE_BRD_PWM_COUNT_PARAM) || AP_FEATURE_SAFETY_BUTTON
|
||||
struct {
|
||||
AP_Int8 pwm_count;
|
||||
AP_Int8 safety_enable;
|
||||
AP_Int16 safety_option;
|
||||
AP_Int32 ignore_safety_channels;
|
||||
|
|
|
@ -62,7 +62,7 @@ void AP_BoardConfig::px4_setup_pwm()
|
|||
{ 8, PWM_SERVO_MODE_12PWM, 0 },
|
||||
#endif
|
||||
};
|
||||
uint8_t mode_parm = (uint8_t)state.pwm_count.get();
|
||||
uint8_t mode_parm = (uint8_t)pwm_count.get();
|
||||
uint8_t i;
|
||||
for (i=0; i<ARRAY_SIZE(mode_table); i++) {
|
||||
if (mode_table[i].mode_parm == mode_parm) {
|
||||
|
|
Loading…
Reference in New Issue