AP_HAL: add RCOutput::read_last_sent definition

This commit is contained in:
Jonathan Challinger 2016-03-10 13:55:42 -08:00
parent 7b4a4f6232
commit 6663d30728
1 changed files with 7 additions and 1 deletions

View File

@ -67,10 +67,16 @@ public:
virtual void push() { } virtual void push() { }
/* Read back current output state, as either single channel or /* Read back current output state, as either single channel or
* array of channels. */ * array of channels. On boards that have a separate IO controller,
* this returns the latest output value that the IO controller has
* reported */
virtual uint16_t read(uint8_t ch) = 0; virtual uint16_t read(uint8_t ch) = 0;
virtual void read(uint16_t* period_us, uint8_t len) = 0; virtual void read(uint16_t* period_us, uint8_t len) = 0;
/* Read the current input state. This returns the last value that was written. */
virtual uint16_t read_last_sent(uint8_t ch) { return read(ch); }
virtual void read_last_sent(uint16_t* period_us, uint8_t len) { read(period_us, len); };
/* /*
set PWM to send to a set of channels when the safety switch is set PWM to send to a set of channels when the safety switch is
in the safe state in the safe state