Browse Source

AP_HAL_FLYMAPLE: remove unused write method

master
Lucas De Marchi 10 years ago committed by Randy Mackay
parent
commit
9b4be3bf74
  1. 8
      libraries/AP_HAL_FLYMAPLE/RCOutput.cpp
  2. 1
      libraries/AP_HAL_FLYMAPLE/RCOutput.h

8
libraries/AP_HAL_FLYMAPLE/RCOutput.cpp

@ -95,13 +95,7 @@ void FLYMAPLERCOutput::write(uint8_t ch, uint16_t period_us) @@ -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;

1
libraries/AP_HAL_FLYMAPLE/RCOutput.h

@ -30,7 +30,6 @@ class AP_HAL_FLYMAPLE_NS::FLYMAPLERCOutput : public AP_HAL::RCOutput { @@ -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);

Loading…
Cancel
Save