Browse Source

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.
master
Andrew Tridgell 10 years ago
parent
commit
3075cb058d
  1. 7
      libraries/AP_HAL/RCInput.h

7
libraries/AP_HAL/RCInput.h

@ -18,9 +18,12 @@ public: @@ -18,9 +18,12 @@ 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;
virtual bool new_input() = 0;
/**
* Return the number of valid channels in the last read

Loading…
Cancel
Save