AP_HAL: RCOutput: remove unused write method

This method is not used anymore since the introduction of channel map and
allowing motors to be enabled/disabled in AP_Motors.

Later we may introduce a method to write multiple values with a default
implementation that supports the channel and enable maps rather than
requiring all subclasses to implement this method.
This commit is contained in:
Lucas De Marchi 2015-08-21 18:30:24 -03:00 committed by Randy Mackay
parent a5cc0be531
commit 666dc3e440

View File

@ -43,9 +43,8 @@ public:
virtual void enable_ch(uint8_t ch) = 0;
virtual void disable_ch(uint8_t ch) = 0;
/* Output, either single channel or bulk array of channels */
/* Output a single channel */
virtual void write(uint8_t ch, uint16_t period_us) = 0;
virtual void write(uint8_t ch, uint16_t* period_us, uint8_t len) = 0;
/* Read back current output state, as either single channel or
* array of channels. */