SRV_Channel: allow motor mask and motor output type to be passed in for AP_Periph

This commit is contained in:
Andy Piper 2022-09-05 18:06:42 +01:00 committed by Peter Barker
parent 25ef429cf7
commit cea9f639fc
2 changed files with 5 additions and 3 deletions

View File

@ -517,6 +517,8 @@ public:
// return the ESC type for dshot commands
static AP_HAL::RCOutput::DshotEscType get_dshot_esc_type() { return AP_HAL::RCOutput::DshotEscType(_singleton->dshot_esc_type.get()); }
static uint8_t get_dshot_rate() { return _singleton->dshot_rate.get(); }
static SRV_Channel *srv_channel(uint8_t i) {
#if NUM_SERVO_CHANNELS > 0
return i<NUM_SERVO_CHANNELS?&channels[i]:nullptr;
@ -567,7 +569,7 @@ public:
static void zero_rc_outputs();
// initialize before any call to push
static void init();
static void init(uint32_t motor_mask = 0, AP_HAL::RCOutput::output_mode mode = AP_HAL::RCOutput::MODE_PWM_NONE);
// return true if a channel is set to type GPIO
static bool is_GPIO(uint8_t channel);

View File

@ -395,11 +395,11 @@ SRV_Channels::SRV_Channels(void)
}
// SRV_Channels initialization
void SRV_Channels::init(void)
void SRV_Channels::init(uint32_t motor_mask, AP_HAL::RCOutput::output_mode mode)
{
// initialize BLHeli late so that all of the masks it might setup don't get trodden on by motor initialization
#if HAL_SUPPORT_RCOUT_SERIAL
blheli_ptr->init();
blheli_ptr->init(motor_mask, mode);
#endif
#ifndef HAL_BUILD_AP_PERIPH
hal.rcout->set_dshot_rate(_singleton->dshot_rate, AP::scheduler().get_loop_rate_hz());