mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_HAL_AVR: remove unused write method
This commit is contained in:
parent
666dc3e440
commit
f1e53a9bdd
@ -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. */
|
||||
|
@ -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) {
|
||||
|
@ -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) {
|
||||
|
Loading…
Reference in New Issue
Block a user