diff --git a/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp b/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp index bc09b5f899..cbf97c9b8c 100644 --- a/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp +++ b/libraries/AP_HAL_FLYMAPLE/RCOutput.cpp @@ -95,13 +95,7 @@ void FLYMAPLERCOutput::write(uint8_t ch, uint16_t period_us) pwmWrite(pin, (period_us * _clocks_per_msecond[ch]) / 1000); } -void FLYMAPLERCOutput::write(uint8_t ch, uint16_t* period_us, uint8_t len) -{ - for (int i = 0; i < len; i++) - write(i + ch, period_us[i]); -} - -uint16_t FLYMAPLERCOutput::read(uint8_t ch) +uint16_t FLYMAPLERCOutput::read(uint8_t ch) { if (ch >= FLYMAPLE_RC_OUTPUT_NUM_CHANNELS) return 0; diff --git a/libraries/AP_HAL_FLYMAPLE/RCOutput.h b/libraries/AP_HAL_FLYMAPLE/RCOutput.h index 51035ebdc0..50a8e5a12e 100644 --- a/libraries/AP_HAL_FLYMAPLE/RCOutput.h +++ b/libraries/AP_HAL_FLYMAPLE/RCOutput.h @@ -30,7 +30,6 @@ class AP_HAL_FLYMAPLE_NS::FLYMAPLERCOutput : public AP_HAL::RCOutput { void enable_ch(uint8_t ch); void disable_ch(uint8_t ch); void write(uint8_t ch, uint16_t period_us); - void write(uint8_t ch, uint16_t* period_us, uint8_t len); uint16_t read(uint8_t ch); void read(uint16_t* period_us, uint8_t len);