From 9b7f0f7957c0bf4652587dbf03dec573d07e913e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 8 Jan 2017 12:26:54 +1100 Subject: [PATCH] AP_HAL: make new_input() API clearer in comments --- libraries/AP_HAL/RCInput.h | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/libraries/AP_HAL/RCInput.h b/libraries/AP_HAL/RCInput.h index d1db3b02aa..4017e4a734 100644 --- a/libraries/AP_HAL/RCInput.h +++ b/libraries/AP_HAL/RCInput.h @@ -17,12 +17,9 @@ public: virtual void teardown() {}; /** - * 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. + * Return true if there has been new input since the last call to new_input() */ - virtual bool new_input() = 0; + virtual bool new_input(void) = 0; /** * Return the number of valid channels in the last read