AP_HAL_PX4: remove unused write method
This commit is contained in:
parent
191ec10554
commit
ce674f6926
@ -235,13 +235,6 @@ void PX4RCOutput::write(uint8_t ch, uint16_t period_us)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void PX4RCOutput::write(uint8_t ch, uint16_t* period_us, uint8_t len)
|
|
||||||
{
|
|
||||||
for (uint8_t i=0; i<len; i++) {
|
|
||||||
write(i, period_us[i]);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
uint16_t PX4RCOutput::read(uint8_t ch)
|
uint16_t PX4RCOutput::read(uint8_t ch)
|
||||||
{
|
{
|
||||||
if (ch >= PX4_NUM_OUTPUT_CHANNELS) {
|
if (ch >= PX4_NUM_OUTPUT_CHANNELS) {
|
||||||
|
@ -18,7 +18,6 @@ public:
|
|||||||
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);
|
||||||
void set_safety_pwm(uint32_t chmask, uint16_t period_us);
|
void set_safety_pwm(uint32_t chmask, uint16_t period_us);
|
||||||
|
Loading…
Reference in New Issue
Block a user