From 9751cb5b24eab54939fde2a9d065f90c2377471d Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 22 Sep 2021 23:55:32 +0100 Subject: [PATCH] AP_HAL_ChibiOS: move is_dshot_protocol up to AP_HAL --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 16 ---------------- libraries/AP_HAL_ChibiOS/RCOutput.h | 1 - 2 files changed, 17 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index be9d437bbf..05797a01a5 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -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 */ diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index 4df5473ef3..0cd5b4feae 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -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);