AP_HAL_AVR: remove unused write method

This commit is contained in:
Lucas De Marchi 2015-08-21 18:38:12 -03:00 committed by Randy Mackay
parent 666dc3e440
commit f1e53a9bdd
3 changed files with 0 additions and 16 deletions

View File

@ -21,7 +21,6 @@ public:
/* Output, either single channel or bulk array of channels */
void write(uint8_t ch, uint16_t period_ms);
void write(uint8_t ch, uint16_t* period_ms, uint8_t len);
/* Read back current output state, as either single channel or
* array of channels. */
@ -48,7 +47,6 @@ public:
/* Output, either single channel or bulk array of channels */
void write(uint8_t ch, uint16_t period_us);
void write(uint8_t ch, uint16_t* period_us, uint8_t len);
/* Read back current output state, as either single channel or
* array of channels starting at 0. */

View File

@ -174,13 +174,6 @@ void APM1RCOutput::write(uint8_t ch, uint16_t period_us) {
}
}
void APM1RCOutput::write(uint8_t ch, uint16_t* period_us, uint8_t len) {
for (int i = 0; i < len; i++) {
write(i + ch, period_us[i]);
}
}
/* Read back current output state, as either single channel or
* array of channels. */
uint16_t APM1RCOutput::read(uint8_t ch) {

View File

@ -165,13 +165,6 @@ void APM2RCOutput::write(uint8_t ch, uint16_t period_us) {
}
}
void APM2RCOutput::write(uint8_t ch, uint16_t* period_us, uint8_t len) {
for (int i = 0; i < len; i++) {
write(i + ch, period_us[i]);
}
}
/* Read back current output state, as either single channel or
* array of channels. */
uint16_t APM2RCOutput::read(uint8_t ch) {