mbed library sources. Supersedes mbed-src.

Dependents:   Nucleo_Hello_Encoder BLE_iBeaconScan AM1805_DEMO DISCO-F429ZI_ExportTemplate1 ... more

Revision:
189:f392fc9709a3
Parent:
188:bcfe06ba3d64
--- a/targets/TARGET_Cypress/TARGET_PSOC6/serial_api.c	Thu Nov 08 11:46:34 2018 +0000
+++ b/targets/TARGET_Cypress/TARGET_PSOC6/serial_api.c	Wed Feb 20 22:31:08 2019 +0000
@@ -1,6 +1,8 @@
 /*
  * mbed Microcontroller Library
  * Copyright (c) 2017-2018 Future Electronics
+ * Copyright (c) 2018-2019 Cypress Semiconductor Corporation
+ * SPDX-License-Identifier: Apache-2.0
  *
  * Licensed under the Apache License, Version 2.0 (the "License");
  * you may not use this file except in compliance with the License.
@@ -27,16 +29,19 @@
 #include "serial_api.h"
 #include "psoc6_utils.h"
 
-#include "drivers/peripheral/sysclk/cy_sysclk.h"
-#include "drivers/peripheral/gpio/cy_gpio.h"
-#include "drivers/peripheral/scb/cy_scb_uart.h"
-#include "drivers/peripheral/sysint/cy_sysint.h"
+#include "cy_sysclk.h"
+#include "cy_gpio.h"
+#include "cy_scb_uart.h"
+#include "cy_sysint.h"
 
 #define UART_OVERSAMPLE                 12
 #define UART_DEFAULT_BAUDRATE           115200
 #define NUM_SERIAL_PORTS                8
 #define SERIAL_DEFAULT_IRQ_PRIORITY     3
 
+#define UART_RX_INTR_MASK   (CY_SCB_UART_RX_TRIGGER   | CY_SCB_UART_RX_OVERFLOW  | \
+                             CY_SCB_UART_RX_ERR_FRAME | CY_SCB_UART_RX_ERR_PARITY)
+
 typedef struct serial_s serial_obj_t;
 #if DEVICE_SERIAL_ASYNCH
 #define OBJ_P(in)     (&(in->serial))
@@ -50,7 +55,7 @@
  * For this reason only low level PDL API is used here.
  */
 
-
+/* Default UART configuration */
 static const cy_stc_scb_uart_config_t default_uart_config = {
     .uartMode                   = CY_SCB_UART_STANDARD,
     .enableMutliProcessorMode   = false,
@@ -78,16 +83,20 @@
     .rtsRxFifoLevel             = 20UL,
     .rtsPolarity                = CY_SCB_UART_ACTIVE_LOW,
 
-    .rxFifoTriggerLevel         = 0UL,
+    .rxFifoTriggerLevel         = 0UL,  /* Level triggers when at least one element is in FIFO */
     .rxFifoIntEnableMask        = 0x0UL,
 
-    .txFifoTriggerLevel         = 0UL,
+    .txFifoTriggerLevel         = 63UL, /* Level triggers when half-fifo is half empty */
     .txFifoIntEnableMask        = 0x0UL
 };
 
-int stdio_uart_inited = false;
+/* STDIO serial information  */
+bool stdio_uart_inited = false;
 serial_t stdio_uart;
 
+int bt_uart_inited = false;
+serial_t bt_uart;
+
 typedef struct irq_info_s {
     serial_obj_t        *serial_obj;
     uart_irq_handler    handler;
@@ -98,6 +107,8 @@
 #endif
 } irq_info_t;
 
+
+/* Allocate interrupt information table */
 static irq_info_t irq_info[NUM_SERIAL_PORTS] = {
     {NULL, NULL, 0, unconnected_IRQn},
     {NULL, NULL, 0, unconnected_IRQn},
@@ -110,9 +121,14 @@
 };
 
 
+/** Routes interrupt to proper SCB block.
+ *
+ * @param serial_id     The ID of serial object
+ */
 static void serial_irq_dispatcher(uint32_t serial_id)
 {
     MBED_ASSERT(serial_id < NUM_SERIAL_PORTS);
+
     irq_info_t *info = &irq_info[serial_id];
     serial_obj_t *obj = info->serial_obj;
     MBED_ASSERT(obj);
@@ -123,13 +139,15 @@
         return;
     }
 #endif
+
     if (Cy_SCB_GetRxInterruptStatusMasked(obj->base) & CY_SCB_RX_INTR_NOT_EMPTY) {
         info->handler(info->id_arg, RxIrq);
         Cy_SCB_ClearRxInterrupt(obj->base, CY_SCB_RX_INTR_NOT_EMPTY);
     }
 
-    if (Cy_SCB_GetTxInterruptStatusMasked(obj->base) & (CY_SCB_TX_INTR_LEVEL | CY_SCB_UART_TX_DONE)) {
+    if (Cy_SCB_GetTxInterruptStatusMasked(obj->base) & CY_SCB_UART_TX_EMPTY) {
         info->handler(info->id_arg, TxIrq);
+        Cy_SCB_ClearTxInterrupt(obj->base, CY_SCB_UART_TX_EMPTY);
     }
 }
 
@@ -173,7 +191,7 @@
     serial_irq_dispatcher(7);
 }
 
-
+/* Interrupts table */
 static void (*irq_dispatcher_table[])(void) = {
     serial_irq_dispatcher_uart0,
     serial_irq_dispatcher_uart1,
@@ -193,15 +211,9 @@
     return cy_m0_nvic_allocate_channel(CY_SERIAL_IRQN_ID + obj->serial_id);
 #else
     return (IRQn_Type)(scb_0_interrupt_IRQn + obj->serial_id);
-#endif // M0
+#endif /* (TARGET_MCU_PSOC6_M0) */
 }
 
-static void serial_irq_release_channel(IRQn_Type channel, uint32_t serial_id)
-{
-#if defined (TARGET_MCU_PSOC6_M0)
-    cy_m0_nvic_release_channel(channel, CY_SERIAL_IRQN_ID + serial_id);
-#endif //M0
-}
 
 static int serial_irq_setup_channel(serial_obj_t *obj)
 {
@@ -213,32 +225,50 @@
         if (irqn < 0) {
             return (-1);
         }
-        // Configure NVIC
+
+        /* Configure NVIC */
         irq_config.intrPriority = SERIAL_DEFAULT_IRQ_PRIORITY;
         irq_config.intrSrc = irqn;
 #if defined (TARGET_MCU_PSOC6_M0)
         irq_config.cm0pSrc = info->cm0p_irq_src;
 #endif
         if (Cy_SysInt_Init(&irq_config, irq_dispatcher_table[obj->serial_id]) != CY_SYSINT_SUCCESS) {
-            return(-1);
+            return (-1);
         }
 
         info->irqn = irqn;
         info->serial_obj = obj;
-        NVIC_EnableIRQ(irqn);
     }
+
+    /* Enable interrupt after successful setup */
+    NVIC_EnableIRQ(info->irqn);
+
     return 0;
 }
 
-/*
- * Calculates fractional divider value.
+
+/** Calculates fractional divider value.
+ *
+ * @param frequency The desired frequency of UART clock
+ * @param frac_bits The number of fractional bits in the divider
+ * @return The divider value
  */
 static uint32_t divider_value(uint32_t frequency, uint32_t frac_bits)
 {
     /* UARTs use peripheral clock */
-    return ((CY_CLK_PERICLK_FREQ_HZ * (1 << frac_bits)) + (frequency / 2)) / frequency;
+    return ((cy_PeriClkFreqHz * (1 << frac_bits)) + (frequency / 2)) / frequency;
 }
 
+
+#define FRACT_DIV_INT(divider)      (((divider) >> 5U) - 1U)
+#define FRACT_DIV_FARCT(divider)    ((divider) & 0x1FU)
+
+/** Finds clock divider, configures it and connects to SCB block.
+ *
+ * @param obj      The serial object
+ * @param baudrate The desired UART baud rate
+ * @return CY_SYSCLK_SUCCESS if operation successful and CY_SYSCLK_BAD_PARAM otherwise
+ */
 static cy_en_sysclk_status_t serial_init_clock(serial_obj_t *obj, uint32_t baudrate)
 {
     cy_en_sysclk_status_t status = CY_SYSCLK_BAD_PARAM;
@@ -247,21 +277,21 @@
         uint32_t divider_num = cy_clk_allocate_divider(CY_SYSCLK_DIV_16_5_BIT);
 
         if (divider_num < PERI_DIV_16_5_NR) {
-            /* Assign fractional divider. */
+            /* Assign fractional divider */
             status = Cy_SysClk_PeriphAssignDivider(obj->clock, CY_SYSCLK_DIV_16_5_BIT, divider_num);
             if (status == CY_SYSCLK_SUCCESS) {
                 obj->div_type = CY_SYSCLK_DIV_16_5_BIT;
-                obj->div_num = divider_num;
+                obj->div_num  = divider_num;
             }
         } else {
             // Try 16-bit divider.
             divider_num = cy_clk_allocate_divider(CY_SYSCLK_DIV_16_BIT);
             if (divider_num < PERI_DIV_16_NR) {
-                /* Assign 16-bit divider. */
+                /* Assign 16-bit divider */
                 status = Cy_SysClk_PeriphAssignDivider(obj->clock, CY_SYSCLK_DIV_16_BIT, divider_num);
                 if (status == CY_SYSCLK_SUCCESS) {
                     obj->div_type = CY_SYSCLK_DIV_16_BIT;
-                    obj->div_num = divider_num;
+                    obj->div_num  = divider_num;
                 }
             } else {
                 error("Serial: cannot assign clock divider.");
@@ -272,80 +302,88 @@
     }
 
     if (status == CY_SYSCLK_SUCCESS) {
+        Cy_SysClk_PeriphDisableDivider(obj->div_type, obj->div_num);
+
         /* Set baud rate */
         if (obj->div_type == CY_SYSCLK_DIV_16_5_BIT) {
-            Cy_SysClk_PeriphDisableDivider(CY_SYSCLK_DIV_16_5_BIT, obj->div_num);
-            uint32_t divider = divider_value(baudrate * UART_OVERSAMPLE, 5);
+            /* Get fractional divider */
+            uint32_t divider = divider_value(baudrate * UART_OVERSAMPLE, 5U);
+
             status = Cy_SysClk_PeriphSetFracDivider(CY_SYSCLK_DIV_16_5_BIT,
                                                     obj->div_num,
-                                                    (divider >> 5) - 1, // integral part
-                                                    divider & 0x1F);    // fractional part
-            Cy_SysClk_PeriphEnableDivider(CY_SYSCLK_DIV_16_5_BIT, obj->div_num);
-        } else if (obj->div_type == CY_SYSCLK_DIV_16_BIT) {
-            Cy_SysClk_PeriphDisableDivider(CY_SYSCLK_DIV_16_BIT, obj->div_num);
+                                                    FRACT_DIV_INT(divider),
+                                                    FRACT_DIV_FARCT(divider));
+        } else {
+            /* Get integer divider */
             status = Cy_SysClk_PeriphSetDivider(CY_SYSCLK_DIV_16_BIT,
                                                 obj->div_num,
                                                 divider_value(baudrate * UART_OVERSAMPLE, 0));
-            Cy_SysClk_PeriphEnableDivider(CY_SYSCLK_DIV_16_BIT, obj->div_num);
         }
+
+        Cy_SysClk_PeriphEnableDivider(obj->div_type, obj->div_num);
     }
+
     return status;
 }
 
-/*
- * Initializes i/o pins for UART tx/rx.
+
+/** Initializes i/o pins for UART tx/rx.
+ *
+ * @param obj The serial object
  */
 static void serial_init_pins(serial_obj_t *obj)
 {
-    int tx_function = pinmap_function(obj->pin_tx, PinMap_UART_TX);
-    int rx_function = pinmap_function(obj->pin_rx, PinMap_UART_RX);
-    if (cy_reserve_io_pin(obj->pin_tx) || cy_reserve_io_pin(obj->pin_rx)) {
+    if ((cy_reserve_io_pin(obj->pin_tx) || cy_reserve_io_pin(obj->pin_rx))
+            && !obj->already_reserved) {
         error("Serial TX/RX pin reservation conflict.");
     }
-    pin_function(obj->pin_tx, tx_function);
-    pin_function(obj->pin_rx, rx_function);
+
+    pin_function(obj->pin_tx, pinmap_function(obj->pin_tx, PinMap_UART_TX));
+    pin_function(obj->pin_rx, pinmap_function(obj->pin_rx, PinMap_UART_RX));
 }
 
-/*
- * Initializes i/o pins for UART flow control.
+
+/** Initializes i/o pins for UART flow control
+ *
+ * @param obj The serial object
  */
 static void serial_init_flow_pins(serial_obj_t *obj)
 {
     if (obj->pin_rts != NC) {
-        int rts_function = pinmap_function(obj->pin_rts, PinMap_UART_RTS);
-        if (cy_reserve_io_pin(obj->pin_rts)) {
+        if ((0 != cy_reserve_io_pin(obj->pin_rts)) && !obj->already_reserved) {
             error("Serial RTS pin reservation conflict.");
         }
-        pin_function(obj->pin_rts, rts_function);
+        pin_function(obj->pin_rts, pinmap_function(obj->pin_rts, PinMap_UART_RTS));
     }
 
     if (obj->pin_cts != NC) {
-        int cts_function = pinmap_function(obj->pin_cts, PinMap_UART_CTS);
-        if (cy_reserve_io_pin(obj->pin_cts)) {
+        if ((0 != cy_reserve_io_pin(obj->pin_cts)) && !obj->already_reserved) {
             error("Serial CTS pin reservation conflict.");
         }
-        pin_function(obj->pin_cts, cts_function);
+        pin_function(obj->pin_cts, pinmap_function(obj->pin_cts, PinMap_UART_CTS));
     }
 }
 
 
-/*
- * Initializes and enables UART/SCB.
+/** Initializes and enables UART/SCB.
+ *
+ * @param obj The serial object
  */
 static void serial_init_peripheral(serial_obj_t *obj)
 {
     cy_stc_scb_uart_config_t uart_config = default_uart_config;
 
-    uart_config.dataWidth   = obj->data_width;
-    uart_config.parity      = obj->parity;
-    uart_config.stopBits    = obj->stop_bits;
-    uart_config.enableCts   = (obj->pin_cts != NC);
+    uart_config.dataWidth = obj->data_width;
+    uart_config.parity    = obj->parity;
+    uart_config.stopBits  = obj->stop_bits;
+    uart_config.enableCts = (obj->pin_cts != NC);
 
     Cy_SCB_UART_Init(obj->base, &uart_config, NULL);
     Cy_SCB_UART_Enable(obj->base);
 }
 
-#if DEVICE_SLEEP && DEVICE_LOWPOWERTIMER
+
+#if DEVICE_SLEEP && DEVICE_LPTICKER && SERIAL_PM_CALLBACK_ENABLED
 static cy_en_syspm_status_t serial_pm_callback(cy_stc_syspm_callback_params_t *params)
 {
     serial_obj_t *obj = (serial_obj_t *)params->context;
@@ -358,7 +396,7 @@
             * Deep Sleep mode.
             */
             if (Cy_SCB_UART_IsTxComplete(obj->base)) {
-                if (0UL == Cy_SCB_UART_GetNumInRxFifo(obj->base)) {
+                if (0 == Cy_SCB_UART_GetNumInRxFifo(obj->base)) {
                     /* Disable the UART. The transmitter stops driving the
                     * lines and the receiver stops receiving data until
                     * the UART is enabled.
@@ -391,54 +429,92 @@
         default:
             break;
     }
+
     return status;
 }
-#endif // DEVICE_SLEEP && DEVICE_LOWPOWERTIMER
+#endif /* (DEVICE_SLEEP && DEVICE_LPTICKER && SERIAL_PM_CALLBACK_ENABLED) */
+
 
 void serial_init(serial_t *obj_in, PinName tx, PinName rx)
 {
     serial_obj_t *obj = OBJ_P(obj_in);
     bool is_stdio = (tx == CY_STDIO_UART_TX) || (rx == CY_STDIO_UART_RX);
+#if !defined(TARGET_CY8CKIT_062_BLE)
+    bool is_bt = (tx == CY_BT_UART_TX) || (rx == CY_BT_UART_RX);
+#else
+    bool is_bt = false;
+#endif
 
     if (is_stdio && stdio_uart_inited) {
         memcpy(obj_in, &stdio_uart, sizeof(serial_t));
         return;
-    }
-    {
+    } else if (is_bt && bt_uart_inited) {
+        memcpy(obj_in, &bt_uart, sizeof(serial_t));
+        return;
+    } else {
         uint32_t uart = pinmap_peripheral(tx, PinMap_UART_TX);
         uart = pinmap_merge(uart, pinmap_peripheral(rx, PinMap_UART_RX));
+
         if (uart != (uint32_t)NC) {
-            obj->base = (CySCB_Type*)uart;
-            obj->serial_id = ((UARTName)uart - UART_0) / (UART_1 - UART_0);
-            obj->pin_tx = tx;
-            obj->pin_rx = rx;
-            obj->clock = CY_PIN_CLOCK(pinmap_function(tx, PinMap_UART_TX));
-            obj->div_num = CY_INVALID_DIVIDER;
+            uint32_t  serial_id = ((UARTName)uart - UART_0) / (UART_1 - UART_0);
+
+            /* Initialize configuration */
+            obj->base      = (CySCB_Type *)uart;
+            obj->serial_id = serial_id;
+            obj->clock     = CY_PIN_CLOCK(pinmap_function(tx, PinMap_UART_TX));
+            obj->div_num   = CY_INVALID_DIVIDER;
+            obj->already_reserved = (0 != cy_reserve_scb(obj->serial_id));
+
+            obj->pin_tx    = tx;
+            obj->pin_rx    = rx;
+            obj->pin_rts   = NC;
+            obj->pin_cts   = NC;
+
             obj->data_width = 8;
-            obj->stop_bits = CY_SCB_UART_STOP_BITS_1;
-            obj->parity = CY_SCB_UART_PARITY_NONE;
-            obj->pin_rts = NC;
-            obj->pin_cts = NC;
+            obj->stop_bits  = CY_SCB_UART_STOP_BITS_1;
+            obj->parity     = CY_SCB_UART_PARITY_NONE;
+
+            /* Check if resource severed */
+            if (obj->already_reserved) {
+                uint32_t map;
+
+                /* SCB pins and clocks are connected */
+
+                /* Disable block and get it into the default state */
+                Cy_SCB_UART_Disable(obj->base, NULL);
+                Cy_SCB_UART_DeInit(obj->base);
 
+                /* Get connected clock */
+                map = Cy_SysClk_PeriphGetAssignedDivider(obj->clock);
+                obj->div_num  = _FLD2VAL(CY_PERI_CLOCK_CTL_DIV_SEL,  map);
+                obj->div_type = (cy_en_divider_types_t) _FLD2VAL(CY_PERI_CLOCK_CTL_TYPE_SEL, map);
+            } else {
+#if DEVICE_SLEEP && DEVICE_LPTICKER && SERIAL_PM_CALLBACK_ENABLED
+                /* Register callback once */
+                obj->pm_callback_handler.callback = serial_pm_callback;
+                obj->pm_callback_handler.type = CY_SYSPM_DEEPSLEEP;
+                obj->pm_callback_handler.skipMode = 0;
+                obj->pm_callback_handler.callbackParams = &obj->pm_callback_params;
+                obj->pm_callback_params.base = obj->base;
+                obj->pm_callback_params.context = obj;
+
+                if (!Cy_SysPm_RegisterCallback(&obj->pm_callback_handler)) {
+                    error("PM callback registration failed!");
+                }
+#endif /* (DEVICE_SLEEP && DEVICE_LPTICKER && SERIAL_PM_CALLBACK_ENABLED) */
+            }
+
+            /* Configure hardware resources */
             serial_init_clock(obj, UART_DEFAULT_BAUDRATE);
+            serial_init_pins(obj);
             serial_init_peripheral(obj);
-            //Cy_GPIO_Write(Cy_GPIO_PortToAddr(CY_PORT(P13_6)), CY_PIN(P13_6), 1);
-            serial_init_pins(obj);
-            //Cy_GPIO_Write(Cy_GPIO_PortToAddr(CY_PORT(P13_6)), CY_PIN(P13_6), 0);
-#if DEVICE_SLEEP && DEVICE_LOWPOWERTIMER
-            obj->pm_callback_handler.callback = serial_pm_callback;
-            obj->pm_callback_handler.type = CY_SYSPM_DEEPSLEEP;
-            obj->pm_callback_handler.skipMode = 0;
-            obj->pm_callback_handler.callbackParams = &obj->pm_callback_params;
-            obj->pm_callback_params.base = obj->base;
-            obj->pm_callback_params.context = obj;
-            if (!Cy_SysPm_RegisterCallback(&obj->pm_callback_handler)) {
-                error("PM callback registration failed!");
-            }
-#endif // DEVICE_SLEEP && DEVICE_LOWPOWERTIMER
+
             if (is_stdio) {
                 memcpy(&stdio_uart, obj_in, sizeof(serial_t));
                 stdio_uart_inited = true;
+            } else if (is_bt) {
+                memcpy(&bt_uart, obj_in, sizeof(serial_t));
+                bt_uart_inited = true;
             }
         } else {
             error("Serial pinout mismatch. Requested pins Rx and Tx can't be used for the same Serial communication.");
@@ -446,6 +522,13 @@
     }
 }
 
+
+void serial_free(serial_t *obj)
+{
+    error("This function is not supported.");
+}
+
+
 void serial_baud(serial_t *obj_in, int baudrate)
 {
     serial_obj_t *obj = OBJ_P(obj_in);
@@ -455,6 +538,7 @@
     Cy_SCB_UART_Enable(obj->base);
 }
 
+
 void serial_format(serial_t *obj_in, int data_bits, SerialParity parity, int stop_bits)
 {
     serial_obj_t *obj = OBJ_P(obj_in);
@@ -475,7 +559,7 @@
             break;
         case ParityForced1:
         case ParityForced0:
-            MBED_ASSERT("Serial parity mode not supported!");
+            error("Serial parity mode not supported!");
             break;
     }
 
@@ -496,48 +580,58 @@
 
     Cy_SCB_UART_Disable(obj->base, NULL);
     serial_init_peripheral(obj);
+    /* SCB is enabled at the and of serial_init_peripheral() call */
 }
 
+
 void serial_putc(serial_t *obj_in, int c)
 {
     serial_obj_t *obj = OBJ_P(obj_in);
-    while (!serial_writable(obj_in)) {
-        // empty
+
+    while (0 == serial_writable(obj_in)) {
+        /* There is an entry to be written */
     }
-    Cy_SCB_UART_Put(obj->base, c);
+
+    Cy_SCB_WriteTxFifo(obj->base, (uint32_t) c);
 }
 
 int serial_getc(serial_t *obj_in)
 {
     serial_obj_t *obj = OBJ_P(obj_in);
-    while (!serial_readable(obj_in)) {
-        // empty
+
+    while (0 == serial_readable(obj_in)) {
+        /* There is an item to be read */
     }
+
     return Cy_SCB_UART_Get(obj->base);
 }
 
+
 int serial_readable(serial_t *obj_in)
 {
     serial_obj_t *obj = OBJ_P(obj_in);
-    return Cy_SCB_GetNumInRxFifo(obj->base) != 0;
+    return Cy_SCB_GetNumInRxFifo(obj->base);
 }
 
+
 int serial_writable(serial_t *obj_in)
 {
     serial_obj_t *obj = OBJ_P(obj_in);
-    return Cy_SCB_GetNumInTxFifo(obj->base) != Cy_SCB_GetFifoSize(obj->base);
+    return (Cy_SCB_GetFifoSize(obj->base) != Cy_SCB_GetNumInTxFifo(obj->base));
 }
 
+
 void serial_clear(serial_t *obj_in)
 {
     serial_obj_t *obj = OBJ_P(obj_in);
 
+    /* The hardware FIFOs and statuses are cleared when SCB is disabled */
     Cy_SCB_UART_Disable(obj->base, NULL);
-    Cy_SCB_ClearTxFifo(obj->base);
-    Cy_SCB_ClearRxFifo(obj->base);
     serial_init_peripheral(obj);
+    /* SCB is enabled at the and of serial_init_peripheral() call */
 }
 
+
 void serial_break_set(serial_t *obj_in)
 {
     serial_obj_t *obj = OBJ_P(obj_in);
@@ -550,6 +644,7 @@
     Cy_GPIO_Write(port_tx, CY_PIN(obj->pin_tx), 0);
 }
 
+
 void serial_break_clear(serial_t *obj_in)
 {
     serial_obj_t *obj = OBJ_P(obj_in);
@@ -560,10 +655,21 @@
     Cy_GPIO_Pin_FastInit(port_tx, CY_PIN(obj->pin_tx), CY_GPIO_DM_STRONG_IN_OFF, 0, CY_PIN_HSIOM(tx_function));
 }
 
+
+void serial_pinout_tx(PinName tx)
+{
+    error("This function is not supported.");
+}
+
+
 void serial_set_flow_control(serial_t *obj_in, FlowControl type, PinName rxflow, PinName txflow)
 {
     serial_obj_t *obj = OBJ_P(obj_in);
 
+    /* Do not perform pins reservation second time for the same pins */ 
+    if ((obj->pin_rts == rxflow) && (obj->pin_cts == txflow))
+        return;
+
     Cy_SCB_UART_Disable(obj->base, NULL);
 
     switch (type) {
@@ -585,10 +691,11 @@
             break;
     }
 
+    serial_init_flow_pins(obj);
     serial_init_peripheral(obj);
-    serial_init_flow_pins(obj);
 }
 
+
 #if DEVICE_SERIAL_ASYNCH
 
 void serial_irq_handler(serial_t *obj_in, uart_irq_handler handler, uint32_t id)
@@ -597,121 +704,145 @@
     irq_info_t *info = &irq_info[obj->serial_id];
 
     if (info->irqn != unconnected_IRQn) {
+        /* Seccessful serial_irq_setup_channel enables interrupt in NVIC */
         NVIC_DisableIRQ(info->irqn);
     }
+
     info->handler = handler;
     info->id_arg = id;
-    serial_irq_setup_channel(obj);
+
+    if (0 != serial_irq_setup_channel(obj)) {
+        error("Interrupt setup failed.");
+    }
 }
 
+
 void serial_irq_set(serial_t *obj_in, SerialIrq irq, uint32_t enable)
 {
     serial_obj_t *obj = OBJ_P(obj_in);
 
     switch (irq) {
-        case RxIrq:
-            if (enable) {
-                Cy_SCB_SetRxInterruptMask(obj->base,  CY_SCB_RX_INTR_NOT_EMPTY);
-            } else {
-                Cy_SCB_SetRxInterruptMask(obj->base, 0);
-            }
+        case RxIrq: /* RxIrq for receive (buffer is not empty) */
+            Cy_SCB_SetRxInterruptMask(obj->base, (0 != enable) ? CY_SCB_RX_INTR_NOT_EMPTY : 0);
             break;
-        case TxIrq:
-            if (enable) {
-                Cy_SCB_SetTxInterruptMask(obj->base, CY_SCB_TX_INTR_LEVEL | CY_SCB_UART_TX_DONE);
-            } else {
-                Cy_SCB_SetTxInterruptMask(obj->base, 0);
-            }
+
+        case TxIrq: /* TxIrq for transmit (buffer is empty) */
+            Cy_SCB_SetTxInterruptMask(obj->base, (0 != enable) ? CY_SCB_UART_TX_EMPTY : 0);
             break;
     }
 }
 
+
+int serial_tx_asynch(serial_t *obj_in, const void *tx, size_t tx_length, uint8_t tx_width, uint32_t handler, uint32_t event, DMAUsage hint)
+{
+    (void) tx_width; /* Deprecated argument */
+    (void) hint;     /* At the moment we do not support DMA transfers, so this parameter gets ignored. */
+
+    serial_obj_t *obj = OBJ_P(obj_in);
+    const uint8_t *p_buf = tx;
+
+    if (obj->tx_pending || (tx_length == 0)) {
+        return 0;
+    }
+
+    /* Configure interrupt handler */
+    obj->async_handler = (cy_israddress)handler;
+    if (serial_irq_setup_channel(obj) < 0) {
+        return 0;
+    }
+
+    /* Clear TX_DONE interrupt it might remain set from previous call */
+    Cy_SCB_ClearTxInterrupt(obj->base, CY_SCB_UART_TX_DONE | CY_SCB_TX_INTR_LEVEL);
+
+    /* Write as much as possible into the FIFO first */
+    while ((tx_length > 0) && (0 != Cy_SCB_UART_Put(obj->base, *p_buf))) {
+        ++p_buf;
+        --tx_length;
+    }
+
+    if (tx_length > 0) {
+        obj->tx_pending = true;
+        obj->tx_events  = event;
+        obj_in->tx_buff.pos    = 0;
+        obj_in->tx_buff.buffer = (void *)p_buf;
+        obj_in->tx_buff.length = tx_length;
+
+        /* Enable LEVEL interrupt to complete transmission */
+        Cy_SCB_SetTxInterruptMask(obj->base, CY_SCB_TX_INTR_LEVEL);
+    } else {
+        /* Enable DONE interrupt to signal completing of the transmission */
+        Cy_SCB_SetTxInterruptMask(obj->base, CY_SCB_UART_TX_DONE);
+    }
+
+    return tx_length;
+}
+
+
+void serial_rx_asynch(serial_t *obj_in, void *rx, size_t rx_length, uint8_t rx_width, uint32_t handler, uint32_t event, uint8_t char_match, DMAUsage hint)
+{
+    (void) rx_width; /* Deprecated argument */
+    (void) hint;     /* At the moment we do not support DMA transfers, so this parameter gets ignored. */
+
+    serial_obj_t *obj = OBJ_P(obj_in);
+
+    if (obj->rx_pending || (rx_length == 0)) {
+        return;
+    }
+
+    /* Configure interrupt handler */
+    obj->async_handler = (cy_israddress)handler;
+    if (serial_irq_setup_channel(obj) < 0) {
+        return;
+    }
+
+    obj->rx_pending = true;
+    obj->rx_events  = event;
+    obj_in->char_match = char_match;
+    obj_in->char_found = false;
+    obj_in->rx_buff.pos    = 0;
+    obj_in->rx_buff.buffer = rx;
+    obj_in->rx_buff.length = rx_length;
+
+    /* Enable interrupts to start receiving */
+    Cy_SCB_SetRxInterruptMask(obj->base, UART_RX_INTR_MASK);
+}
+
+
+uint8_t serial_tx_active(serial_t *obj)
+{
+    return obj->serial.tx_pending;
+}
+
+
+uint8_t serial_rx_active(serial_t *obj)
+{
+    return obj->serial.rx_pending;
+}
+
+
+/** Finishes TX asynchronous transfer: disable TX interrupts and clear
+ * pending state.
+ *
+ * @param obj The serial object
+ */
 static void serial_finish_tx_asynch(serial_obj_t *obj)
 {
     Cy_SCB_SetTxInterruptMask(obj->base, 0);
     obj->tx_pending = false;
 }
 
+
+/** Finishes TX asynchronous transfer: disable TX interrupts and clear
+ * pending state.
+ *
+ * @param obj The serial object
+ */
 static void serial_finish_rx_asynch(serial_obj_t *obj)
 {
     Cy_SCB_SetRxInterruptMask(obj->base, 0);
     obj->rx_pending = false;
 }
 
-int serial_tx_asynch(serial_t *obj_in, const void *tx, size_t tx_length, uint8_t tx_width, uint32_t handler, uint32_t event, DMAUsage hint)
-{
-    serial_obj_t *obj = OBJ_P(obj_in);
-    const uint8_t *p_buf = tx;
-
-    (void)tx_width; // Obsolete argument
-    (void)hint; // At the moment we do not support DAM transfers, so this parameter gets ignored.
-
-    if (obj->tx_pending) {
-        return 0;
-    }
-
-    obj->async_handler = (cy_israddress)handler;
-    if (serial_irq_setup_channel(obj) < 0) {
-        return 0;
-    }
-
-    // Write as much as possible into the FIFO first.
-    while ((tx_length > 0) && Cy_SCB_UART_Put(obj->base, *p_buf)) {
-        ++p_buf;
-        --tx_length;
-    }
-
-    if (tx_length > 0) {
-        obj->tx_events = event;
-        obj_in->tx_buff.buffer = (void *)p_buf;
-        obj_in->tx_buff.length = tx_length;
-        obj_in->tx_buff.pos = 0;
-        obj->tx_pending = true;
-        // Enable interrupts to complete transmission.
-        Cy_SCB_SetRxInterruptMask(obj->base, CY_SCB_TX_INTR_LEVEL | CY_SCB_UART_TX_DONE);
-
-    } else {
-        // Enable interrupt to signal completing of the transmission.
-        Cy_SCB_SetRxInterruptMask(obj->base, CY_SCB_UART_TX_DONE);
-    }
-    return tx_length;
-}
-
-void serial_rx_asynch(serial_t *obj_in, void *rx, size_t rx_length, uint8_t rx_width, uint32_t handler, uint32_t event, uint8_t char_match, DMAUsage hint)
-{
-    serial_obj_t *obj = OBJ_P(obj_in);
-
-    (void)rx_width; // Obsolete argument
-    (void)hint; // At the moment we do not support DAM transfers, so this parameter gets ignored.
-
-    if (obj->rx_pending || (rx_length == 0)) {
-        return;
-    }
-
-    obj_in->char_match = char_match;
-    obj_in->char_found = false;
-    obj->rx_events = event;
-    obj_in->rx_buff.buffer = rx;
-    obj_in->rx_buff.length = rx_length;
-    obj_in->rx_buff.pos = 0;
-    obj->async_handler = (cy_israddress)handler;
-    if (serial_irq_setup_channel(obj) < 0) {
-        return;
-    }
-    obj->rx_pending = true;
-    // Enable interrupts to start receiving.
-    Cy_SCB_SetRxInterruptMask(obj->base, CY_SCB_UART_RX_INTR_MASK & ~CY_SCB_RX_INTR_UART_BREAK_DETECT);
-}
-
-uint8_t serial_tx_active(serial_t *obj)
-{
-    return obj->serial.tx_pending;
-}
-
-uint8_t serial_rx_active(serial_t *obj)
-{
-    return obj->serial.rx_pending;
-}
 
 int serial_irq_handler_asynch(serial_t *obj_in)
 {
@@ -721,83 +852,104 @@
 
     serial_obj_t *obj = OBJ_P(obj_in);
 
-    rx_status = Cy_SCB_GetRxInterruptStatusMasked(obj->base);
+    /* Interrupt cause is TX */
+    if (0 != (CY_SCB_TX_INTR & Cy_SCB_GetInterruptCause(obj->base))) {
 
-    tx_status = Cy_SCB_GetTxInterruptStatusMasked(obj->base);
+        /* Get interrupt sources and clear them */
+        tx_status = Cy_SCB_GetTxInterruptStatusMasked(obj->base);
+        Cy_SCB_ClearTxInterrupt(obj->base, tx_status);
 
+        if (0 != (tx_status & CY_SCB_TX_INTR_LEVEL)) {
+
+            /* Get current buffer position */
+            uint8_t *ptr = obj_in->tx_buff.buffer;
+            ptr += obj_in->tx_buff.pos;
 
-    if (tx_status & CY_SCB_TX_INTR_LEVEL) {
-        // FIFO has space available for more TX
-        uint8_t *ptr = obj_in->tx_buff.buffer;
-        ptr += obj_in->tx_buff.pos;
-        while ((obj_in->tx_buff.pos < obj_in->tx_buff.length) &&
-                Cy_SCB_UART_Put(obj->base, *ptr)) {
-            ++ptr;
-            ++(obj_in->tx_buff.pos);
+            /* FIFO has space available for more TX */
+            while ((obj_in->tx_buff.pos < obj_in->tx_buff.length) &&
+                    (0 != Cy_SCB_UART_Put(obj->base, *ptr))) {
+                ++ptr;
+                ++(obj_in->tx_buff.pos);
+            }
+
+            if (obj_in->tx_buff.pos == obj_in->tx_buff.length) {
+                /* No more bytes to follow; check to see if we need to signal completion */
+                if (0 != (obj->tx_events & SERIAL_EVENT_TX_COMPLETE)) {
+                    /* Disable TX_LEVEL and enable TX_DONE to get completion event */
+                    Cy_SCB_SetTxInterruptMask(obj->base, CY_SCB_UART_TX_DONE);
+                } else {
+                    /* Nothing more to do, mark end of transmission */
+                    serial_finish_tx_asynch(obj);
+                }
+            }
         }
-        if (obj_in->tx_buff.pos == obj_in->tx_buff.length) {
-            // No more bytes to follow; check to see if we need to signal completion.
-            if (obj->tx_events & SERIAL_EVENT_TX_COMPLETE) {
-                // Disable FIFO interrupt as there are no more bytes to follow.
-                Cy_SCB_SetRxInterruptMask(obj->base, CY_SCB_UART_TX_DONE);
-            } else {
-                // Nothing more to do, mark end of transmission.
-                serial_finish_tx_asynch(obj);
-            }
+
+        if (0 != (tx_status & CY_SCB_TX_INTR_UART_DONE)) {
+            /* Mark end of the transmission */
+            serial_finish_tx_asynch(obj);
+            cur_events |= SERIAL_EVENT_TX_COMPLETE;
         }
     }
 
-    if (tx_status & CY_SCB_TX_INTR_UART_DONE) {
-        // Mark end of the transmission.
-        serial_finish_tx_asynch(obj);
-        cur_events |= SERIAL_EVENT_TX_COMPLETE & obj->tx_events;
-    }
+    /* Interrupt cause is RX */
+    if (0 != (CY_SCB_RX_INTR & Cy_SCB_GetInterruptCause(obj->base))) {
 
-    Cy_SCB_ClearTxInterrupt(obj->base, tx_status);
+        /* Get interrupt sources and clear them */
+        rx_status = Cy_SCB_GetRxInterruptStatusMasked(obj->base);
+        Cy_SCB_ClearRxInterrupt(obj->base, rx_status);
 
-    if (rx_status & CY_SCB_RX_INTR_OVERFLOW) {
-        cur_events |= SERIAL_EVENT_RX_OVERRUN_ERROR & obj->rx_events;
-    }
+        if (0 != (rx_status & CY_SCB_RX_INTR_OVERFLOW)) {
+            cur_events |= SERIAL_EVENT_RX_OVERRUN_ERROR;
+        }
 
-    if (rx_status & CY_SCB_RX_INTR_UART_FRAME_ERROR) {
-        cur_events |= SERIAL_EVENT_RX_FRAMING_ERROR & obj->rx_events;
-    }
+        if (0 != (rx_status & CY_SCB_RX_INTR_UART_FRAME_ERROR)) {
+            cur_events |= SERIAL_EVENT_RX_FRAMING_ERROR;
+        }
+
+        if (0 != (rx_status & CY_SCB_RX_INTR_UART_PARITY_ERROR)) {
+            cur_events |= SERIAL_EVENT_RX_PARITY_ERROR;
+        }
+
+        if (0 != (rx_status & CY_SCB_RX_INTR_LEVEL)) {
 
-    if (rx_status & CY_SCB_RX_INTR_UART_PARITY_ERROR) {
-        cur_events |= SERIAL_EVENT_RX_PARITY_ERROR & obj->rx_events;
-    }
+            /* Get current buffer position */
+            uint8_t *ptr = obj_in->rx_buff.buffer;
+            ptr += obj_in->rx_buff.pos;
+
+            /* Get data from the RX FIFO */
+            while (obj_in->rx_buff.pos < obj_in->rx_buff.length) {
+                uint32_t c = Cy_SCB_UART_Get(obj->base);
+
+                if (c == CY_SCB_UART_RX_NO_DATA) {
+                    break;
+                }
 
-    if (rx_status & CY_SCB_RX_INTR_LEVEL) {
-        uint8_t *ptr = obj_in->rx_buff.buffer;
-        ptr += obj_in->rx_buff.pos;
-        while (obj_in->rx_buff.pos < obj_in->rx_buff.length) {
-            uint32_t c = Cy_SCB_UART_Get(obj->base);
-            if (c == CY_SCB_UART_RX_NO_DATA) {
-                break;
-            }
-            *ptr++ = (uint8_t)c;
-            ++(obj_in->rx_buff.pos);
-            // Check for character match condition.
-            if (obj_in->char_match != SERIAL_RESERVED_CHAR_MATCH) {
-                if (c == obj_in->char_match) {
-                    obj_in->char_found = true;
-                    cur_events |= SERIAL_EVENT_RX_CHARACTER_MATCH & obj->rx_events;
-                    // Clamp RX.
-                    obj_in->rx_buff.length = obj_in->rx_buff.pos;
-                    break;
+                *ptr++ = (uint8_t) c;
+                ++(obj_in->rx_buff.pos);
+
+                /* Check for character match condition */
+                if (obj_in->char_match != SERIAL_RESERVED_CHAR_MATCH) {
+                    if (c == obj_in->char_match)  {
+                        obj_in->char_found = true;
+                        cur_events |= SERIAL_EVENT_RX_CHARACTER_MATCH;
+
+                        /* Clamp RX buffer */
+                        obj_in->rx_buff.length = obj_in->rx_buff.pos;
+                        break;
+                    }
                 }
             }
         }
+
+        if (obj_in->rx_buff.pos == obj_in->rx_buff.length) {
+            serial_finish_rx_asynch(obj);
+            cur_events |= SERIAL_EVENT_RX_COMPLETE;
+        }
     }
 
-    if (obj_in->rx_buff.pos == obj_in->rx_buff.length) {
-        serial_finish_rx_asynch(obj);
-    }
+    return (cur_events & (obj->tx_events | obj->rx_events));
+}
 
-    Cy_SCB_ClearRxInterrupt(obj->base, rx_status);
-
-    return cur_events;
-}
 
 void serial_tx_abort_asynch(serial_t *obj_in)
 {
@@ -813,8 +965,9 @@
 
     serial_finish_rx_asynch(obj);
     Cy_SCB_UART_ClearRxFifo(obj->base);
+    Cy_SCB_ClearRxInterrupt(obj->base, CY_SCB_UART_RX_INTR_MASK);
 }
 
-#endif // DEVICE_SERIAL_ASYNCH
+#endif /* DEVICE_SERIAL_ASYNCH */
 
-#endif // DEVICE_SERIAL
+#endif /* DEVICE_SERIAL */