From aa893b3983bf863c02238977d40cf0b38b6ab7a9 Mon Sep 17 00:00:00 2001 From: Siddharth Purohit Date: Sun, 31 May 2020 17:43:03 +0530 Subject: [PATCH] AP_HAL: add available method for locked state --- libraries/AP_HAL/UARTDriver.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL/UARTDriver.h b/libraries/AP_HAL/UARTDriver.h index 4653b367aa..254e0d7229 100644 --- a/libraries/AP_HAL/UARTDriver.h +++ b/libraries/AP_HAL/UARTDriver.h @@ -41,6 +41,10 @@ public: // lock a port for exclusive use. Use a key of 0 to unlock virtual bool lock_port(uint32_t write_key, uint32_t read_key) { return false; } + // check data available on a locked port. If port is locked and key is not correct then + // 0 is returned + virtual uint32_t available_locked(uint32_t key) { return 0; } + // write to a locked port. If port is locked and key is not correct then 0 is returned // and write is discarded virtual size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) { return 0; }