AP_HAL_ChibiOS: move is_dshot_protocol up to AP_HAL

This commit is contained in:
Iampete1 2021-09-22 23:55:32 +01:00 committed by Andrew Tridgell
parent 9b02baa5f0
commit 9751cb5b24
2 changed files with 0 additions and 17 deletions

View File

@ -2017,22 +2017,6 @@ void RCOutput::set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
#endif
}
/*
true when the output mode is of type dshot
*/
bool RCOutput::is_dshot_protocol(const enum output_mode mode)
{
switch (mode) {
case MODE_PWM_DSHOT150:
case MODE_PWM_DSHOT300:
case MODE_PWM_DSHOT600:
case MODE_PWM_DSHOT1200:
return true;
default:
return false;
}
}
/*
returns the bitrate in Hz of the given output_mode
*/

View File

@ -600,7 +600,6 @@ private:
const uint16_t buffer_length, bool choose_high, uint32_t pulse_time_us);
void send_pulses_DMAR(pwm_group &group, uint32_t buffer_length);
void set_group_mode(pwm_group &group);
static bool is_dshot_protocol(const enum output_mode mode);
static uint32_t protocol_bitrate(const enum output_mode mode);
void print_group_setup_error(pwm_group &group, const char* error_string);