mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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:
parent
9737c426eb
commit
97b51a4bcb
@ -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()
|
||||
|
Loading…
Reference in New Issue
Block a user