mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_Empty: remove unused write method
This commit is contained in:
parent
f1e53a9bdd
commit
302252d096
@ -20,9 +20,6 @@ void EmptyRCOutput::disable_ch(uint8_t ch)
|
|||||||
void EmptyRCOutput::write(uint8_t ch, uint16_t period_us)
|
void EmptyRCOutput::write(uint8_t ch, uint16_t period_us)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
void EmptyRCOutput::write(uint8_t ch, uint16_t* period_us, uint8_t len)
|
|
||||||
{}
|
|
||||||
|
|
||||||
uint16_t EmptyRCOutput::read(uint8_t ch) {
|
uint16_t EmptyRCOutput::read(uint8_t ch) {
|
||||||
return 900;
|
return 900;
|
||||||
}
|
}
|
||||||
|
@ -11,7 +11,6 @@ class Empty::EmptyRCOutput : public AP_HAL::RCOutput {
|
|||||||
void enable_ch(uint8_t ch);
|
void enable_ch(uint8_t ch);
|
||||||
void disable_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);
|
||||||
void write(uint8_t ch, uint16_t* period_us, uint8_t len);
|
|
||||||
uint16_t read(uint8_t ch);
|
uint16_t read(uint8_t ch);
|
||||||
void read(uint16_t* period_us, uint8_t len);
|
void read(uint16_t* period_us, uint8_t len);
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user