diff --git a/libraries/AP_HAL/utility/Stream.h b/libraries/AP_HAL/utility/Stream.h
index 749dddfe3060cb969ad32190927672ee35042bb2..7416ce0be25d8a9e96116ab7f29f87863ba5e92a 100644
--- a/libraries/AP_HAL/utility/Stream.h
+++ b/libraries/AP_HAL/utility/Stream.h
@@ -8,10 +8,10 @@
 
 class AP_HAL::Stream : public AP_HAL::Print {
 public:
-    virtual int16_t available() = 0;
+    virtual uint32_t available() = 0;
     /* NB txspace was traditionally a member of BetterStream in the
      * FastSerial library. As far as concerns go, it belongs with available() */
-    virtual int16_t txspace() = 0;
+    virtual uint32_t txspace() = 0;
 
     /* return value for read():
      * -1 if nothing available, uint8_t value otherwise. */
diff --git a/libraries/AP_HAL_Empty/UARTDriver.cpp b/libraries/AP_HAL_Empty/UARTDriver.cpp
index 7689a2386e1be506afd5970b1dc91c8738c4b56c..73943d7536ddd678b68648a0f4e3bf7f59560ee8 100644
--- a/libraries/AP_HAL_Empty/UARTDriver.cpp
+++ b/libraries/AP_HAL_Empty/UARTDriver.cpp
@@ -14,8 +14,8 @@ void UARTDriver::set_blocking_writes(bool blocking) {}
 bool UARTDriver::tx_pending() { return false; }
 
 /* Empty implementations of Stream virtual methods */
-int16_t UARTDriver::available() { return 0; }
-int16_t UARTDriver::txspace() { return 1; }
+uint32_t UARTDriver::available() { return 0; }
+uint32_t UARTDriver::txspace() { return 1; }
 int16_t UARTDriver::read() { return -1; }
 
 /* Empty implementations of Print virtual methods */
diff --git a/libraries/AP_HAL_Empty/UARTDriver.h b/libraries/AP_HAL_Empty/UARTDriver.h
index 22d5a7a04f830a7189967cd61aba177c5d293c40..987472ab86fad5d108c13a5d32d82e760d7bff93 100644
--- a/libraries/AP_HAL_Empty/UARTDriver.h
+++ b/libraries/AP_HAL_Empty/UARTDriver.h
@@ -15,9 +15,9 @@ public:
     bool tx_pending();
 
     /* Empty implementations of Stream virtual methods */
-    int16_t available();
-    int16_t txspace();
-    int16_t read();
+    uint32_t available() override;
+    uint32_t txspace() override;
+    int16_t read() override;
 
     /* Empty implementations of Print virtual methods */
     size_t write(uint8_t c);
diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp
index 4312634fae26b099f604a511b593ce5b1f927e7e..a355fbfb99f625a528479ab553c99f0827e4f72b 100644
--- a/libraries/AP_HAL_Linux/UARTDriver.cpp
+++ b/libraries/AP_HAL_Linux/UARTDriver.cpp
@@ -290,7 +290,7 @@ bool UARTDriver::tx_pending()
 /*
   return the number of bytes available to be read
  */
-int16_t UARTDriver::available()
+uint32_t UARTDriver::available()
 {
     if (!_initialised) {
         return 0;
@@ -302,7 +302,7 @@ int16_t UARTDriver::available()
 /*
   how many bytes are available in the output buffer?
  */
-int16_t UARTDriver::txspace()
+uint32_t UARTDriver::txspace()
 {
     if (!_initialised) {
         return 0;
diff --git a/libraries/AP_HAL_Linux/UARTDriver.h b/libraries/AP_HAL_Linux/UARTDriver.h
index 4f42f8853802a36f0b6ff4d9669a1a35933833d1..0cdd83383dad953da54ad1f63d473f033a973d50 100644
--- a/libraries/AP_HAL_Linux/UARTDriver.h
+++ b/libraries/AP_HAL_Linux/UARTDriver.h
@@ -25,9 +25,9 @@ public:
     bool tx_pending();
 
     /* Linux implementations of Stream virtual methods */
-    int16_t available();
-    int16_t txspace();
-    int16_t read();
+    uint32_t available() override;
+    uint32_t txspace() override;
+    int16_t read() override;
 
     /* Linux implementations of Print virtual methods */
     size_t write(uint8_t c);
diff --git a/libraries/AP_HAL_PX4/NSHShellStream.cpp b/libraries/AP_HAL_PX4/NSHShellStream.cpp
index 262c470c50e5495fc41d22cb61bdcd41c8608e21..90314a8a0c3e44c4ef62bcb9544f6b5c30111981 100644
--- a/libraries/AP_HAL_PX4/NSHShellStream.cpp
+++ b/libraries/AP_HAL_PX4/NSHShellStream.cpp
@@ -122,18 +122,18 @@ int16_t NSHShellStream::read()
     return -1;
 }
 
-int16_t NSHShellStream::available()
+uint32_t NSHShellStream::available()
 {
-    int ret = 0;
+    uint32_t ret = 0;
     if (ioctl(shell_stdin, FIONREAD, (unsigned long)&ret) == OK) {
         return ret;
     }
     return 0;
 }
 
-int16_t NSHShellStream::txspace()
+uint32_t NSHShellStream::txspace()
 {
-    int ret = 0;
+    uint32_t ret = 0;
     if (ioctl(shell_stdout, FIONWRITE, (unsigned long)&ret) == OK) {
         return ret;
     }
diff --git a/libraries/AP_HAL_PX4/UARTDriver.cpp b/libraries/AP_HAL_PX4/UARTDriver.cpp
index 17aad7fa7e035c00bebd63c8bbb7c1ea21a9a868..f907fa9cca07becc3623953dcc639f94eb5b36b5 100644
--- a/libraries/AP_HAL_PX4/UARTDriver.cpp
+++ b/libraries/AP_HAL_PX4/UARTDriver.cpp
@@ -236,7 +236,7 @@ bool PX4UARTDriver::tx_pending() { return false; }
 /*
   return number of bytes available to be read from the buffer
  */
-int16_t PX4UARTDriver::available() 
+uint32_t PX4UARTDriver::available()
 { 
 	if (!_initialised) {
         try_initialise();
@@ -249,7 +249,7 @@ int16_t PX4UARTDriver::available()
 /*
   return number of bytes that can be added to the write buffer
  */
-int16_t PX4UARTDriver::txspace() 
+uint32_t PX4UARTDriver::txspace()
 { 
 	if (!_initialised) {
         try_initialise();
diff --git a/libraries/AP_HAL_PX4/UARTDriver.h b/libraries/AP_HAL_PX4/UARTDriver.h
index 73924ad203c5550c582d3bcd571115f4233a318f..a0055485ae23141efaf9f402aeecba45b9d27393 100644
--- a/libraries/AP_HAL_PX4/UARTDriver.h
+++ b/libraries/AP_HAL_PX4/UARTDriver.h
@@ -16,9 +16,9 @@ public:
     bool tx_pending();
 
     /* PX4 implementations of Stream virtual methods */
-    int16_t available();
-    int16_t txspace();
-    int16_t read();
+    uint32_t available() override;
+    uint32_t txspace() override;
+    int16_t read() override;
 
     /* PX4 implementations of Print virtual methods */
     size_t write(uint8_t c);
diff --git a/libraries/AP_HAL_PX4/Util.h b/libraries/AP_HAL_PX4/Util.h
index ae29fff8b768a3d61ff745528a4f7ac97451089e..f2ac3a3aa94c791c102976b03e204434f18c07bd 100644
--- a/libraries/AP_HAL_PX4/Util.h
+++ b/libraries/AP_HAL_PX4/Util.h
@@ -8,9 +8,9 @@ class PX4::NSHShellStream : public AP_HAL::Stream {
 public:
     size_t write(uint8_t);
     size_t write(const uint8_t *buffer, size_t size);
-    int16_t read();
-    int16_t available();
-    int16_t txspace();
+    int16_t read() override;
+    uint32_t available() override;
+    uint32_t txspace() override;
 private:
     int shell_stdin = -1;
     int shell_stdout = -1;
diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp
index a03d92c7e06e4ec98f6d01b29f2131b0fe15a1e3..0b64b446f3a8891032eb8b516cdeb08b233c6324 100644
--- a/libraries/AP_HAL_SITL/UARTDriver.cpp
+++ b/libraries/AP_HAL_SITL/UARTDriver.cpp
@@ -100,7 +100,7 @@ void UARTDriver::end()
 {
 }
 
-int16_t UARTDriver::available(void)
+uint32_t UARTDriver::available(void)
 {
     _check_connection();
 
@@ -111,9 +111,7 @@ int16_t UARTDriver::available(void)
     return _readbuffer.available();
 }
 
-
-
-int16_t UARTDriver::txspace(void)
+uint32_t UARTDriver::txspace(void)
 {
     _check_connection();
     if (!_connected) {
diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h
index 97e251a6238e65beac53c987ddc79fdaa404e6ff..a438e23dd1a55e7db4b2517648a94a5397b6549d 100644
--- a/libraries/AP_HAL_SITL/UARTDriver.h
+++ b/libraries/AP_HAL_SITL/UARTDriver.h
@@ -47,9 +47,9 @@ public:
     }
 
     /* Implementations of Stream virtual methods */
-    int16_t available();
-    int16_t txspace();
-    int16_t read();
+    uint32_t available() override;
+    uint32_t txspace() override;
+    int16_t read() override;
 
     /* Implementations of Print virtual methods */
     size_t write(uint8_t c);
diff --git a/libraries/AP_HAL_VRBRAIN/UARTDriver.cpp b/libraries/AP_HAL_VRBRAIN/UARTDriver.cpp
index 2d8c0959cc0201cc2b64047d4d8db13baeb6de16..bb9b33713cce672e96f14393f883d6d30165d068 100644
--- a/libraries/AP_HAL_VRBRAIN/UARTDriver.cpp
+++ b/libraries/AP_HAL_VRBRAIN/UARTDriver.cpp
@@ -230,7 +230,7 @@ bool VRBRAINUARTDriver::tx_pending() { return false; }
 /*
   return number of bytes available to be read from the buffer
  */
-int16_t VRBRAINUARTDriver::available()
+uint32_t VRBRAINUARTDriver::available()
 { 
 	if (!_initialised) {
         try_initialise();
@@ -243,7 +243,7 @@ int16_t VRBRAINUARTDriver::available()
 /*
   return number of bytes that can be added to the write buffer
  */
-int16_t VRBRAINUARTDriver::txspace()
+uint32_t VRBRAINUARTDriver::txspace()
 { 
 	if (!_initialised) {
         try_initialise();
diff --git a/libraries/AP_HAL_VRBRAIN/UARTDriver.h b/libraries/AP_HAL_VRBRAIN/UARTDriver.h
index e644cdcae35b1bf1fc4b2fb00b48008f582122bc..27c00d738f4bb26157cb145fdd65ca2481527974 100644
--- a/libraries/AP_HAL_VRBRAIN/UARTDriver.h
+++ b/libraries/AP_HAL_VRBRAIN/UARTDriver.h
@@ -16,9 +16,9 @@ public:
     bool tx_pending();
 
     /* VRBRAIN implementations of Stream virtual methods */
-    int16_t available();
-    int16_t txspace();
-    int16_t read();
+    uint32_t available() override;
+    uint32_t txspace() override;
+    int16_t read() override;
 
     /* VRBRAIN implementations of Print virtual methods */
     size_t write(uint8_t c);
diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.cpp b/libraries/AP_Mount/AP_Mount_Alexmos.cpp
index 4b5568b9b15eaccc2c81caee91c57beb4721050d..c679430d309f5a62c8a0c853055801b731bff49c 100644
--- a/libraries/AP_Mount/AP_Mount_Alexmos.cpp
+++ b/libraries/AP_Mount/AP_Mount_Alexmos.cpp
@@ -165,7 +165,7 @@ void AP_Mount_Alexmos::write_params()
 */
 void AP_Mount_Alexmos::send_command(uint8_t cmd, uint8_t* data, uint8_t size)
 {
-    if (_port->txspace() < (size + 5)) {
+    if (_port->txspace() < (size + 5U)) {
         return;
     }
     uint8_t checksum = 0;