From 6663d307280d7ac0cfc5e1e268a78ba586407ada Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 10 Mar 2016 13:55:42 -0800 Subject: [PATCH] AP_HAL: add RCOutput::read_last_sent definition --- libraries/AP_HAL/RCOutput.h | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h index 440380cc2c..fafeab47a8 100644 --- a/libraries/AP_HAL/RCOutput.h +++ b/libraries/AP_HAL/RCOutput.h @@ -67,10 +67,16 @@ public: virtual void push() { } /* 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 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 in the safe state