AP_HAL: Added deinit() method to RCInput

Add a deinit() counterpart. This is needed for some ports that require some deinitializtion logic. The default implementation is empty. I'm not sure whether we need to inforce it for all.
This commit is contained in:
Vladislav Zakharov 2015-06-29 16:19:42 +03:00 committed by Andrew Tridgell
parent 9737c426eb
commit 97b51a4bcb

View File

@ -16,6 +16,7 @@ public:
* in the C++ type system.)
*/
virtual void init(void* implspecific) = 0;
virtual void deinit() {};
/**
* Return true if there has been new input since the last read()