AP_HAL: changed semantics of RCInput.new_input()

this makes calling new_input() in RCInput clear the new input
flag. This fixes an issue with calls to read() for auxillary channels
clearing the new_input flag, which could cause brief failsafe
conditions.
This commit is contained in:
Andrew Tridgell 2015-02-09 09:55:35 +11:00
parent a118ac69c6
commit 3075cb058d

View File

@ -18,7 +18,10 @@ public:
virtual void init(void* implspecific) = 0;
/**
* Return true if there has been new input since the last read() call
* Return true if there has been new input since the last read()
* call. This call also clears the new_input flag, so once it
* returns true it won't return true again until another frame is
* received.
*/
virtual bool new_input() = 0;