mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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:
parent
a118ac69c6
commit
3075cb058d
@ -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…
Reference in New Issue
Block a user