aboutsummaryrefslogtreecommitdiffstats
path: root/os
diff options
context:
space:
mode:
authorgdisirio <gdisirio@35acf78f-673a-0410-8e92-d51de3d6d3f4>2010-01-01 13:41:31 +0000
committergdisirio <gdisirio@35acf78f-673a-0410-8e92-d51de3d6d3f4>2010-01-01 13:41:31 +0000
commitf8c40043e469d81f2a9f380d6723b92c79bd30bc (patch)
tree3611911703c617241bb91c00c48163f147e3b123 /os
parent320a3f140e693a0d8647fd05ec6d2d4cb10c523a (diff)
downloadChibiOS-f8c40043e469d81f2a9f380d6723b92c79bd30bc.tar.gz
ChibiOS-f8c40043e469d81f2a9f380d6723b92c79bd30bc.tar.bz2
ChibiOS-f8c40043e469d81f2a9f380d6723b92c79bd30bc.zip
Serial driver enhancements for STM32 and AT91SAM7.
git-svn-id: svn://svn.code.sf.net/p/chibios/svn/trunk@1485 35acf78f-673a-0410-8e92-d51de3d6d3f4
Diffstat (limited to 'os')
-rw-r--r--os/hal/include/serial.h61
-rw-r--r--os/hal/platforms/AT91SAM7/serial_lld.c122
-rw-r--r--os/hal/platforms/AT91SAM7/serial_lld.h81
-rw-r--r--os/hal/platforms/STM32/serial_lld.c157
-rw-r--r--os/hal/platforms/STM32/serial_lld.h100
-rw-r--r--os/hal/src/serial.c99
-rw-r--r--os/kernel/include/channels.h32
7 files changed, 375 insertions, 277 deletions
diff --git a/os/hal/include/serial.h b/os/hal/include/serial.h
index 6f80985ab..9a2c8ec78 100644
--- a/os/hal/include/serial.h
+++ b/os/hal/include/serial.h
@@ -33,25 +33,37 @@
/* Driver constants. */
/*===========================================================================*/
-/** No pending conditions.*/
+/** @brief No pending conditions.*/
#define SD_NO_ERROR 0
-/** Connection happened.*/
+/** @brief Connection happened.*/
#define SD_CONNECTED 1
-/** Disconnection happened.*/
+/** @brief Disconnection happened.*/
#define SD_DISCONNECTED 2
-/** Parity error happened.*/
+/** @brief Parity error happened.*/
#define SD_PARITY_ERROR 4
-/** Framing error happened.*/
+/** @brief Framing error happened.*/
#define SD_FRAMING_ERROR 8
-/** Overflow happened.*/
+/** @brief Overflow happened.*/
#define SD_OVERRUN_ERROR 16
-/** Break detected.*/
-#define SD_BREAK_DETECTED 32
+/** @brief Noise on the line.*/
+#define SD_NOISE_ERROR 32
+/** @brief Break detected.*/
+#define SD_BREAK_DETECTED 64
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
+/**
+ * @brief Serial buffers size.
+ * @details Configuration parameter, you can change the depth of the queue
+ * buffers depending on the requirements of your application.
+ * @note The default is 64 bytes for both the transmission and receive buffers.
+ */
+#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
+#define SERIAL_BUFFERS_SIZE 128
+#endif
+
/*===========================================================================*/
/* Derived constants and error checks. */
/*===========================================================================*/
@@ -61,6 +73,15 @@
/*===========================================================================*/
/**
+ * @brief Driver state machine possible states.
+ */
+typedef enum {
+ SD_UNINIT = 0, /**< @brief Not initialized. */
+ SD_STOP = 1, /**< @brief Stopped. */
+ SD_READY = 2 /**< @brief Ready. */
+} sdstate_t;
+
+/**
* @brief Structure representing a serial driver.
*/
typedef struct _SerialDriver SerialDriver;
@@ -106,15 +127,15 @@ struct _SerialDriver {
/**
* @p BaseChannel class inherited data.
*/
- struct _base_channel_data d0;
+ struct _base_channel_data bc;
/**
* @p BaseAsynchronousChannel class inherited data.
*/
- struct _base_asynchronous_channel_data d1;
+ struct _base_asynchronous_channel_data bac;
/**
* @p SerialDriver specific data.
*/
- struct _serial_driver_data d2;
+ struct _serial_driver_data sd;
};
/*===========================================================================*/
@@ -128,7 +149,7 @@ struct _SerialDriver {
* be used to check different channels implementations.
* @see chIOPutWouldBlock()
*/
-#define sdPutWouldBlock(sdp) chOQIsFull(&(sdp)->d2.oqueue)
+#define sdPutWouldBlock(sdp) chOQIsFull(&(sdp)->sd.oqueue)
/**
* @brief Direct input check on a @p SerialDriver.
@@ -137,7 +158,7 @@ struct _SerialDriver {
* be used to check different channels implementations.
* @see chIOGetWouldBlock()
*/
-#define sdGetWouldBlock(sdp) chIQIsEmpty(&(sdp)->d2.iqueue)
+#define sdGetWouldBlock(sdp) chIQIsEmpty(&(sdp)->sd.iqueue)
/**
* @brief Direct blocking write to a @p SerialDriver.
@@ -146,7 +167,7 @@ struct _SerialDriver {
* be used to write to different channels implementations.
* @see chIOPut()
*/
-#define sdPut(sdp, b) chOQPut(&(sdp)->d2.oqueue, b)
+#define sdPut(sdp, b) chOQPut(&(sdp)->sd.oqueue, b)
/**
* @brief Direct blocking write on a @p SerialDriver with timeout
@@ -156,7 +177,7 @@ struct _SerialDriver {
* be used to write to different channels implementations.
* @see chIOPutTimeout()
*/
-#define sdPutTimeout(sdp, b, t) chOQPutTimeout(&(sdp)->d2.iqueue, b, t)
+#define sdPutTimeout(sdp, b, t) chOQPutTimeout(&(sdp)->sd.iqueue, b, t)
/**
* @brief Direct blocking read from a @p SerialDriver.
@@ -165,7 +186,7 @@ struct _SerialDriver {
* be used to read from different channels implementations.
* @see chIOGet()
*/
-#define sdGet(sdp) chIQGet(&(sdp)->d2.iqueue)
+#define sdGet(sdp) chIQGet(&(sdp)->sd.iqueue)
/**
* @brief Direct blocking read from a @p SerialDriver with timeout
@@ -175,7 +196,7 @@ struct _SerialDriver {
* be used to read from different channels implementations.
* @see chIOGetTimeout()
*/
-#define sdGetTimeout(sdp, t) chIQGetTimeout(&(sdp)->d2.iqueue, t)
+#define sdGetTimeout(sdp, t) chIQGetTimeout(&(sdp)->sd.iqueue, t)
/**
* @brief Direct non-blocking write to a @p SerialDriver.
@@ -184,7 +205,7 @@ struct _SerialDriver {
* be used to write from different channels implementations.
* @see chIOWrite()
*/
-#define sdWrite(sdp, b, n) chOQWrite(&(sdp)->d2.oqueue, b, n)
+#define sdWrite(sdp, b, n) chOQWrite(&(sdp)->sd.oqueue, b, n)
/**
* @brief Direct non-blocking read on a @p SerialDriver.
@@ -193,7 +214,7 @@ struct _SerialDriver {
* be used to read from different channels implementations.
* @see chIORead()
*/
-#define sdRead(sdp, b, n) chIQRead(&(sdp)->d2.iqueue, b, n)
+#define sdRead(sdp, b, n) chIQRead(&(sdp)->sd.iqueue, b, n)
/*===========================================================================*/
/* External declarations. */
@@ -204,7 +225,7 @@ extern "C" {
#endif
void sdInit(void);
void sdObjectInit(SerialDriver *sdp, qnotify_t inotify, qnotify_t onotify);
- void sdStart(SerialDriver *sdp, const SerialDriverConfig *config);
+ void sdStart(SerialDriver *sdp, const SerialConfig *config);
void sdStop(SerialDriver *sdp);
void sdIncomingDataI(SerialDriver *sdp, uint8_t b);
msg_t sdRequestDataI(SerialDriver *sdp);
diff --git a/os/hal/platforms/AT91SAM7/serial_lld.c b/os/hal/platforms/AT91SAM7/serial_lld.c
index be28045fc..8fac96e33 100644
--- a/os/hal/platforms/AT91SAM7/serial_lld.c
+++ b/os/hal/platforms/AT91SAM7/serial_lld.c
@@ -66,7 +66,7 @@ SerialDriver SD2;
/*===========================================================================*/
/** @brief Driver default configuration.*/
-static const SerialDriverConfig default_config = {
+static const SerialConfig default_config = {
38400,
AT91C_US_USMODE_NORMAL | AT91C_US_CLKS_CLOCK |
AT91C_US_CHRL_8_BITS | AT91C_US_PAR_NONE | AT91C_US_NBSTOP_1_BIT
@@ -78,21 +78,22 @@ static const SerialDriverConfig default_config = {
/**
* @brief USART initialization.
- * @param[in] u pointer to an USART I/O block
- * @param[in] config the architecture-dependent serial driver configuration
+ *
+ * @param[in] sdp communication channel associated to the USART
*/
-static void usart_init(AT91PS_USART u, const SerialDriverConfig *config) {
+static void usart_init(SerialDriver *sdp) {
+ AT91PS_USART u = sdp->sd.usart;
/* Disables IRQ sources and stop operations.*/
u->US_IDR = 0xFFFFFFFF;
u->US_CR = AT91C_US_RSTRX | AT91C_US_RSTTX | AT91C_US_RSTSTA;
/* New parameters setup.*/
- if (config->mr & AT91C_US_OVER)
- u->US_BRGR = MCK / (config->speed * 8);
+ if (sdp->sd.config->sc_mr & AT91C_US_OVER)
+ u->US_BRGR = MCK / (sdp->sd.config->sc_speed * 8);
else
- u->US_BRGR = MCK / (config->speed * 16);
- u->US_MR = config->mr;
+ u->US_BRGR = MCK / (sdp->sd.config->sc_speed * 16);
+ u->US_MR = sdp->sd.config->sc_mr;
u->US_RTOR = 0;
u->US_TTGR = 0;
@@ -121,7 +122,7 @@ static void usart_deinit(AT91PS_USART u) {
* @param[in] err USART CSR register value
* @param[in] sdp communication channel associated to the USART
*/
-static void set_error(AT91_REG csr, SerialDriver *sdp) {
+static void set_error(SerialDriver *sdp, AT91_REG csr) {
sdflags_t sts = 0;
if (csr & AT91C_US_OVRE)
@@ -142,27 +143,35 @@ __attribute__((noinline))
#endif
/**
* @brief Common IRQ handler.
- * @param[in] u pointer to an USART I/O block
- * @param[in] com communication channel associated to the USART
+ *
+ * @param[in] sdp communication channel associated to the USART
*/
-static void serve_interrupt(AT91PS_USART u, SerialDriver *sdp) {
+static void serve_interrupt(SerialDriver *sdp) {
+ uint32_t csr;
+ AT91PS_USART u = sdp->sd.usart;
- if (u->US_CSR & AT91C_US_RXRDY) {
+ csr = u->US_CSR;
+ if (csr & AT91C_US_RXRDY) {
chSysLockFromIsr();
sdIncomingDataI(sdp, u->US_RHR);
chSysUnlockFromIsr();
}
- if (u->US_CSR & AT91C_US_TXRDY) {
+ if ((u->US_IMR & AT91C_US_TXRDY) && (csr & AT91C_US_TXRDY)) {
+ msg_t b;
+
chSysLockFromIsr();
- msg_t b = sdRequestDataI(sdp);
- chSysUnlockFromIsr();
- if (b < Q_OK)
+ b = chOQGetI(&sdp->sd.oqueue);
+ if (b < Q_OK) {
+ chEvtBroadcastI(&sdp->bac.oevent);
u->US_IDR = AT91C_US_TXRDY;
+ }
else
u->US_THR = b;
+ chSysUnlockFromIsr();
}
- if (u->US_CSR & (AT91C_US_OVRE | AT91C_US_FRAME | AT91C_US_PARE | AT91C_US_RXBRK)) {
- set_error(u->US_CSR, sdp);
+ csr &= (AT91C_US_OVRE | AT91C_US_FRAME | AT91C_US_PARE | AT91C_US_RXBRK);
+ if (csr != 0) {
+ set_error(sdp, csr);
u->US_CR = AT91C_US_RSTSTA;
}
AT91C_BASE_AIC->AIC_EOICR = 0;
@@ -191,7 +200,7 @@ CH_IRQ_HANDLER(USART0IrqHandler) {
CH_IRQ_PROLOGUE();
- serve_interrupt(AT91C_BASE_US0, &SD1);
+ serve_interrupt(&SD1);
CH_IRQ_EPILOGUE();
}
@@ -202,7 +211,7 @@ CH_IRQ_HANDLER(USART1IrqHandler) {
CH_IRQ_PROLOGUE();
- serve_interrupt(AT91C_BASE_US1, &SD2);
+ serve_interrupt(&SD2);
CH_IRQ_EPILOGUE();
}
@@ -219,6 +228,7 @@ void sd_lld_init(void) {
#if USE_SAM7_USART0
sdObjectInit(&SD1, NULL, notify1);
+ SD1.sd.usart = AT91C_BASE_US0;
AT91C_BASE_PIOA->PIO_PDR = SAM7_USART0_RX | SAM7_USART0_TX;
AT91C_BASE_PIOA->PIO_ASR = SAM7_USART0_RX | SAM7_USART0_TX;
AT91C_BASE_PIOA->PIO_PPUDR = SAM7_USART0_RX | SAM7_USART0_TX;
@@ -229,6 +239,7 @@ void sd_lld_init(void) {
#if USE_SAM7_USART1
sdObjectInit(&SD2, NULL, notify2);
+ SD2.sd.usart = AT91C_BASE_US1;
AT91C_BASE_PIOA->PIO_PDR = SAM7_USART1_RX | SAM7_USART1_TX;
AT91C_BASE_PIOA->PIO_ASR = SAM7_USART1_RX | SAM7_USART1_TX;
AT91C_BASE_PIOA->PIO_PPUDR = SAM7_USART1_RX | SAM7_USART1_TX;
@@ -242,37 +253,33 @@ void sd_lld_init(void) {
* @brief Low level serial driver configuration and (re)start.
*
* @param[in] sdp pointer to a @p SerialDriver object
- * @param[in] config the architecture-dependent serial driver configuration.
- * If this parameter is set to @p NULL then a default
- * configuration is used.
*/
-void sd_lld_start(SerialDriver *sdp, const SerialDriverConfig *config) {
+void sd_lld_start(SerialDriver *sdp) {
- if (config == NULL)
- config = &default_config;
+ if (sdp->sd.config == NULL)
+ sdp->sd.config = &default_config;
+ if (sdp->sd.state == SD_STOP) {
#if USE_SAM7_USART0
- if (&SD1 == sdp) {
- /* Starts the clock and clears possible sources of immediate interrupts.*/
- AT91C_BASE_PMC->PMC_PCER = (1 << AT91C_ID_US0);
- /* USART initialization.*/
- usart_init(AT91C_BASE_US0, config);
- /* Enables associated interrupt vector.*/
- AIC_EnableIT(AT91C_ID_US0);
- return;
- }
+ if (&SD1 == sdp) {
+ /* Starts the clock and clears possible sources of immediate interrupts.*/
+ AT91C_BASE_PMC->PMC_PCER = (1 << AT91C_ID_US0);
+ /* Enables associated interrupt vector.*/
+ AIC_EnableIT(AT91C_ID_US0);
+ return;
+ }
#endif
#if USE_SAM7_USART1
- if (&SD2 == sdp) {
- /* Starts the clock and clears possible sources of immediate interrupts.*/
- AT91C_BASE_PMC->PMC_PCER = (1 << AT91C_ID_US1);
- /* USART initialization.*/
- usart_init(AT91C_BASE_US1, config);
- /* Enables associated interrupt vector.*/
- AIC_EnableIT(AT91C_ID_US1);
- return;
- }
+ if (&SD2 == sdp) {
+ /* Starts the clock and clears possible sources of immediate interrupts.*/
+ AT91C_BASE_PMC->PMC_PCER = (1 << AT91C_ID_US1);
+ /* Enables associated interrupt vector.*/
+ AIC_EnableIT(AT91C_ID_US1);
+ return;
+ }
#endif
+ }
+ usart_init(sdp);
}
/**
@@ -284,22 +291,23 @@ void sd_lld_start(SerialDriver *sdp, const SerialDriverConfig *config) {
*/
void sd_lld_stop(SerialDriver *sdp) {
+ if (sdp->sd.state == SD_READY) {
+ usart_deinit(sdp->sd.usart);
#if USE_SAM7_USART0
- if (&SD1 == sdp) {
- usart_deinit(AT91C_BASE_US0);
- AT91C_BASE_PMC->PMC_PCDR = (1 << AT91C_ID_US0);
- AIC_DisableIT(AT91C_ID_US0);
- return;
- }
+ if (&SD1 == sdp) {
+ AT91C_BASE_PMC->PMC_PCDR = (1 << AT91C_ID_US0);
+ AIC_DisableIT(AT91C_ID_US0);
+ return;
+ }
#endif
#if USE_SAM7_USART1
- if (&SD2 == sdp) {
- usart_deinit(AT91C_BASE_US1);
- AT91C_BASE_PMC->PMC_PCDR = (1 << AT91C_ID_US1);
- AIC_DisableIT(AT91C_ID_US1);
- return;
- }
+ if (&SD2 == sdp) {
+ AT91C_BASE_PMC->PMC_PCDR = (1 << AT91C_ID_US1);
+ AIC_DisableIT(AT91C_ID_US1);
+ return;
+ }
#endif
+ }
}
#endif /* CH_HAL_USE_SERIAL */
diff --git a/os/hal/platforms/AT91SAM7/serial_lld.h b/os/hal/platforms/AT91SAM7/serial_lld.h
index b5394aeed..7b7deba95 100644
--- a/os/hal/platforms/AT91SAM7/serial_lld.h
+++ b/os/hal/platforms/AT91SAM7/serial_lld.h
@@ -38,16 +38,6 @@
/*===========================================================================*/
/**
- * @brief Serial buffers size.
- * @details Configuration parameter, you can change the depth of the queue
- * buffers depending on the requirements of your application.
- * @note The default is 128 bytes for both the transmission and receive buffers.
- */
-#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
-#define SERIAL_BUFFERS_SIZE 128
-#endif
-
-/**
* @brief UART0 driver enable switch.
* @details If set to @p TRUE the support for USART1 is included.
* @note The default is @p TRUE.
@@ -93,48 +83,67 @@
typedef uint32_t sdflags_t;
/**
+ * @brief AT91SAM7 Serial Driver configuration structure.
+ * @details An instance of this structure must be passed to @p sdStart()
+ * in order to configure and start a serial driver operations.
+ */
+typedef struct {
+ /**
+ * @brief Bit rate.
+ */
+ uint32_t sc_speed;
+ /**
+ * @brief Initialization value for the MR register.
+ */
+ uint32_t sc_mr;
+} SerialConfig;
+
+/**
* @brief @p SerialDriver specific data.
*/
struct _serial_driver_data {
/**
- * Input queue, incoming data can be read from this input queue by
- * using the queues APIs.
+ * @brief Driver state.
+ */
+ sdstate_t state;
+ /**
+ * @brief Current configuration data.
+ */
+ const SerialConfig *config;
+ /**
+ * @brief Input queue, incoming data can be read from this input queue by
+ * using the queues APIs.
+ */
+ InputQueue iqueue;
+ /**
+ * @brief Output queue, outgoing data can be written to this output queue by
+ * using the queues APIs.
*/
- InputQueue iqueue;
+ OutputQueue oqueue;
/**
- * Output queue, outgoing data can be written to this output queue by
- * using the queues APIs.
+ * @brief Status Change @p EventSource. This event is generated when one or
+ * more condition flags change.
*/
- OutputQueue oqueue;
+ EventSource sevent;
/**
- * Status Change @p EventSource. This event is generated when one or more
- * condition flags change.
+ * @brief I/O driver status flags.
*/
- EventSource sevent;
+ sdflags_t flags;
/**
- * I/O driver status flags.
+ * @brief Input circular buffer.
*/
- sdflags_t flags;
+ uint8_t ib[SERIAL_BUFFERS_SIZE];
/**
- * Input circular buffer.
+ * @brief Output circular buffer.
*/
- uint8_t ib[SERIAL_BUFFERS_SIZE];
+ uint8_t ob[SERIAL_BUFFERS_SIZE];
+ /* End of the mandatory fields.*/
/**
- * Output circular buffer.
+ * @brief Pointer to the USART registers block.
*/
- uint8_t ob[SERIAL_BUFFERS_SIZE];
+ AT91PS_USART usart;
};
-/**
- * @brief AT91SAM7 Serial Driver configuration structure.
- * @details An instance of this structure must be passed to @p sdStart()
- * in order to configure and start a serial driver operations.
- */
-typedef struct {
- uint32_t speed;
- uint32_t mr;
-} SerialDriverConfig;
-
/*===========================================================================*/
/* Driver macros. */
/*===========================================================================*/
@@ -155,7 +164,7 @@ extern SerialDriver SD2;
extern "C" {
#endif
void sd_lld_init(void);
- void sd_lld_start(SerialDriver *sdp, const SerialDriverConfig *config);
+ void sd_lld_start(SerialDriver *sdp);
void sd_lld_stop(SerialDriver *sdp);
#ifdef __cplusplus
}
diff --git a/os/hal/platforms/STM32/serial_lld.c b/os/hal/platforms/STM32/serial_lld.c
index afa0bffc6..6d28fe71f 100644
--- a/os/hal/platforms/STM32/serial_lld.c
+++ b/os/hal/platforms/STM32/serial_lld.c
@@ -53,7 +53,7 @@ SerialDriver SD3;
/*===========================================================================*/
/** @brief Driver default configuration.*/
-static const SerialDriverConfig default_config =
+static const SerialConfig default_config =
{
38400,
0,
@@ -69,26 +69,29 @@ static const SerialDriverConfig default_config =
* @brief USART initialization.
* @details This function must be invoked with interrupts disabled.
*
- * @param[in] u pointer to an USART I/O block
- * @param[in] config the architecture-dependent serial driver configuration
+ * @param[in] sdp pointer to a @p SerialDriver object
*/
-static void usart_init(USART_TypeDef *u, const SerialDriverConfig *config) {
+static void usart_init(SerialDriver *sdp) {
+ USART_TypeDef *u = sdp->sd.usart;
/*
* Baud rate setting.
*/
- if (u == USART1)
- u->BRR = APB2CLK / config->speed;
+ if (sdp->sd.usart == USART1)
+ u->BRR = APB2CLK / sdp->sd.config->sc_speed;
else
- u->BRR = APB1CLK / config->speed;
+ u->BRR = APB1CLK / sdp->sd.config->sc_speed;
/*
* Note that some bits are enforced.
*/
- u->CR1 = config->cr1 | USART_CR1_UE | USART_CR1_PEIE | USART_CR1_RXNEIE |
- USART_CR1_TE | USART_CR1_RE;
- u->CR2 = config->cr2;
- u->CR3 = config->cr3 | USART_CR3_EIE;
+ u->CR1 = sdp->sd.config->sc_cr1 | USART_CR1_UE | USART_CR1_PEIE |
+ USART_CR1_RXNEIE | USART_CR1_TE |
+ USART_CR1_RE;
+ u->CR2 = sdp->sd.config->sc_cr2 | USART_CR2_LBDIE;
+ u->CR3 = sdp->sd.config->sc_cr3 | USART_CR3_EIE;
+ (void)u->SR; /* SR reset step 1.*/
+ (void)u->DR; /* SR reset step 2.*/
}
/**
@@ -106,10 +109,11 @@ static void usart_deinit(USART_TypeDef *u) {
/**
* @brief Error handling routine.
+ *
+ * @param[in] sdp pointer to a @p SerialDriver object
* @param[in] sr USART SR register value
- * @param[in] com communication channel associated to the USART
*/
-static void set_error(uint16_t sr, SerialDriver *sdp) {
+static void set_error(SerialDriver *sdp, uint16_t sr) {
sdflags_t sts = 0;
if (sr & USART_SR_ORE)
@@ -118,6 +122,8 @@ static void set_error(uint16_t sr, SerialDriver *sdp) {
sts |= SD_PARITY_ERROR;
if (sr & USART_SR_FE)
sts |= SD_FRAMING_ERROR;
+ if (sr & USART_SR_NE)
+ sts |= SD_NOISE_ERROR;
if (sr & USART_SR_LBD)
sts |= SD_BREAK_DETECTED;
chSysLockFromIsr();
@@ -127,27 +133,36 @@ static void set_error(uint16_t sr, SerialDriver *sdp) {
/**
* @brief Common IRQ handler.
- * @param[in] u pointer to an USART I/O block
- * @param[in] com communication channel associated to the USART
+ *
+ * @param[in] sdp communication channel associated to the USART
*/
-static void serve_interrupt(USART_TypeDef *u, SerialDriver *sdp) {
- uint16_t sr = u->SR;
-
- if (sr & (USART_SR_ORE | USART_SR_FE | USART_SR_PE | USART_SR_LBD))
- set_error(sr, sdp);
+static void serve_interrupt(SerialDriver *sdp) {
+ USART_TypeDef *u = sdp->sd.usart;
+ uint16_t cr1 = u->CR1;
+ uint16_t sr = u->SR; /* SR reset step 1.*/
+ uint16_t dr = u->DR; /* SR reset step 2.*/
+
+ if (sr & (USART_SR_LBD | USART_SR_ORE | USART_SR_NE |
+ USART_SR_FE | USART_SR_PE)) {
+ set_error(sdp, sr);
+ u->SR = 0; /* Clears the LBD bit in the SR.*/
+ }
if (sr & USART_SR_RXNE) {
chSysLockFromIsr();
- sdIncomingDataI(sdp, u->DR);
+ sdIncomingDataI(sdp, (uint8_t)dr);
chSysUnlockFromIsr();
}
- if (sr & USART_SR_TXE) {
+ if ((cr1 & USART_CR1_TXEIE) && (sr & USART_SR_TXE)) {
+ msg_t b;
chSysLockFromIsr();
- msg_t b = sdRequestDataI(sdp);
- chSysUnlockFromIsr();
- if (b < Q_OK)
- u->CR1 &= ~USART_CR1_TXEIE;
+ b = chOQGetI(&sdp->sd.oqueue);
+ if (b < Q_OK) {
+ chEvtBroadcastI(&sdp->bac.oevent);
+ u->CR1 = cr1 & ~USART_CR1_TXEIE;
+ }
else
u->DR = b;
+ chSysUnlockFromIsr();
}
}
@@ -181,7 +196,7 @@ CH_IRQ_HANDLER(VectorD4) {
CH_IRQ_PROLOGUE();
- serve_interrupt(USART1, &SD1);
+ serve_interrupt(&SD1);
CH_IRQ_EPILOGUE();
}
@@ -192,7 +207,7 @@ CH_IRQ_HANDLER(VectorD8) {
CH_IRQ_PROLOGUE();
- serve_interrupt(USART2, &SD2);
+ serve_interrupt(&SD2);
CH_IRQ_EPILOGUE();
}
@@ -203,7 +218,7 @@ CH_IRQ_HANDLER(VectorDC) {
CH_IRQ_PROLOGUE();
- serve_interrupt(USART3, &SD3);
+ serve_interrupt(&SD3);
CH_IRQ_EPILOGUE();
}
@@ -220,14 +235,17 @@ void sd_lld_init(void) {
#if USE_STM32_USART1
sdObjectInit(&SD1, NULL, notify1);
+ SD1.sd.usart = USART1;
#endif
#if USE_STM32_USART2
sdObjectInit(&SD2, NULL, notify2);
+ SD2.sd.usart = USART2;
#endif
#if USE_STM32_USART3
sdObjectInit(&SD3, NULL, notify3);
+ SD3.sd.usart = USART3;
#endif
}
@@ -235,39 +253,36 @@ void sd_lld_init(void) {
* @brief Low level serial driver configuration and (re)start.
*
* @param[in] sdp pointer to a @p SerialDriver object
- * @param[in] config the architecture-dependent serial driver configuration.
- * If this parameter is set to @p NULL then a default
- * configuration is used.
*/
-void sd_lld_start(SerialDriver *sdp, const SerialDriverConfig *config) {
+void sd_lld_start(SerialDriver *sdp) {
- if (config == NULL)
- config = &default_config;
+ if (sdp->sd.config == NULL)
+ sdp->sd.config = &default_config;
+ if (sdp->sd.state == SD_STOP) {
#if USE_STM32_USART1
- if (&SD1 == sdp) {
- RCC->APB2ENR |= RCC_APB2ENR_USART1EN;
- usart_init(USART1, config);
- NVICEnableVector(USART1_IRQn, STM32_USART1_PRIORITY);
- return;
- }
+ if (&SD1 == sdp) {
+ RCC->APB2ENR |= RCC_APB2ENR_USART1EN;
+ NVICEnableVector(USART1_IRQn, STM32_USART1_PRIORITY);
+ return;
+ }
#endif
#if USE_STM32_USART2
- if (&SD2 == sdp) {
- RCC->APB1ENR |= RCC_APB1ENR_USART2EN;
- usart_init(USART2, config);
- NVICEnableVector(USART2_IRQn, STM32_USART2_PRIORITY);
- return;
- }
+ if (&SD2 == sdp) {
+ RCC->APB1ENR |= RCC_APB1ENR_USART2EN;
+ NVICEnableVector(USART2_IRQn, STM32_USART2_PRIORITY);
+ return;
+ }
#endif
#if USE_STM32_USART3
- if (&SD3 == sdp) {
- RCC->APB1ENR |= RCC_APB1ENR_USART3EN;
- usart_init(USART3, config);
- NVICEnableVector(USART3_IRQn, STM32_USART3_PRIORITY);
- return;
- }
+ if (&SD3 == sdp) {
+ RCC->APB1ENR |= RCC_APB1ENR_USART3EN;
+ NVICEnableVector(USART3_IRQn, STM32_USART3_PRIORITY);
+ return;
+ }
#endif
+ }
+ usart_init(sdp);
}
/**
@@ -279,30 +294,30 @@ void sd_lld_start(SerialDriver *sdp, const SerialDriverConfig *config) {
*/
void sd_lld_stop(SerialDriver *sdp) {
+ if (sdp->sd.state == SD_READY) {
+ usart_deinit(sdp->sd.usart);
#if USE_STM32_USART1
- if (&SD1 == sdp) {
- usart_deinit(USART1);
- RCC->APB2ENR &= ~RCC_APB2ENR_USART1EN;
- NVICDisableVector(USART1_IRQn);
- return;
- }
+ if (&SD1 == sdp) {
+ RCC->APB2ENR &= ~RCC_APB2ENR_USART1EN;
+ NVICDisableVector(USART1_IRQn);
+ return;
+ }
#endif
#if USE_STM32_USART2
- if (&SD2 == sdp) {
- usart_deinit(USART2);
- RCC->APB1ENR &= ~RCC_APB1ENR_USART2EN;
- NVICDisableVector(USART2_IRQn);
- return;
- }
+ if (&SD2 == sdp) {
+ RCC->APB1ENR &= ~RCC_APB1ENR_USART2EN;
+ NVICDisableVector(USART2_IRQn);
+ return;
+ }
#endif
#if USE_STM32_USART3
- if (&SD3 == sdp) {
- usart_deinit(USART3);
- RCC->APB1ENR &= ~RCC_APB1ENR_USART3EN;
- NVICDisableVector(USART3_IRQn);
- return;
- }
+ if (&SD3 == sdp) {
+ RCC->APB1ENR &= ~RCC_APB1ENR_USART3EN;
+ NVICDisableVector(USART3_IRQn);
+ return;
+ }
#endif
+ }
}
#endif /* CH_HAL_USE_SERIAL */
diff --git a/os/hal/platforms/STM32/serial_lld.h b/os/hal/platforms/STM32/serial_lld.h
index 073f8be1f..64c74f5f9 100644
--- a/os/hal/platforms/STM32/serial_lld.h
+++ b/os/hal/platforms/STM32/serial_lld.h
@@ -38,16 +38,6 @@
/*===========================================================================*/
/**
- * @brief Serial buffers size setting.
- * @details Configuration parameter, you can change the depth of the queue
- * buffers depending on the requirements of your application.
- * @note The default is 128 bytes for both the transmission and receive buffers.
- */
-#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
-#define SERIAL_BUFFERS_SIZE 128
-#endif
-
-/**
* @brief USART1 driver enable switch.
* @details If set to @p TRUE the support for USART1 is included.
* @note The default is @p FALSE.
@@ -112,55 +102,79 @@
typedef uint32_t sdflags_t;
/**
+ * @brief STM32 Serial Driver configuration structure.
+ * @details An instance of this structure must be passed to @p sdStart()
+ * in order to configure and start a serial driver operations.
+ *
+ * @note This structure content is architecture dependent, each driver
+ * implementation defines its own version and the custom static
+ * initializers.
+ */
+typedef struct {
+ /**
+ * @brief Bit rate.
+ */
+ uint32_t sc_speed;
+ /**
+ * @brief Initialization value for the CR1 register.
+ */
+ uint16_t sc_cr1;
+ /**
+ * @brief Initialization value for the CR2 register.
+ */
+ uint16_t sc_cr2;
+ /**
+ * @brief Initialization value for the CR3 register.
+ */
+ uint16_t sc_cr3;
+} SerialConfig;
+
+/**
* @brief @p SerialDriver specific data.
*/
struct _serial_driver_data {
/**
- * Input queue, incoming data can be read from this input queue by
- * using the queues APIs.
+ * @brief Driver state.
+ */
+ sdstate_t state;
+ /**
+ * @brief Current configuration data.
+ */
+ const SerialConfig *config;
+ /**
+ * @brief Input queue, incoming data can be read from this input queue by
+ * using the queues APIs.
+ */
+ InputQueue iqueue;
+ /**
+ * @brief Output queue, outgoing data can be written to this output queue by
+ * using the queues APIs.
*/
- InputQueue iqueue;
+ OutputQueue oqueue;
/**
- * Output queue, outgoing data can be written to this output queue by
- * using the queues APIs.
+ * @brief Status Change @p EventSource. This event is generated when one or
+ * more condition flags change.
*/
- OutputQueue oqueue;
+ EventSource sevent;
/**
- * Status Change @p EventSource. This event is generated when one or more
- * condition flags change.
+ * @brief I/O driver status flags.
*/
- EventSource sevent;
+ sdflags_t flags;
/**
- * I/O driver status flags.
+ * @brief Input circular buffer.
*/
- sdflags_t flags;
+ uint8_t ib[SERIAL_BUFFERS_SIZE];
/**
- * Input circular buffer.
+ * @brief Output circular buffer.
*/
- uint8_t ib[SERIAL_BUFFERS_SIZE];
+ uint8_t ob[SERIAL_BUFFERS_SIZE];
+ /* End of the mandatory fields.*/
/**
- * Output circular buffer.
+ * @brief Pointer to the USART registers block.
*/
- uint8_t ob[SERIAL_BUFFERS_SIZE];
+ USART_TypeDef *usart;
};
-/**
- * @brief STM32 Serial Driver configuration structure.
- * @details An instance of this structure must be passed to @p sdStart()
- * in order to configure and start a serial driver operations.
- *
- * @note This structure content is architecture dependent, each driver
- * implementation defines its own version and the custom static
- * initializers.
- */
-typedef struct {
-
- uint32_t speed;
- uint16_t cr1;
- uint16_t cr2;
- uint16_t cr3;
-} SerialDriverConfig;
-
/*===========================================================================*/
/* Driver macros. */
/*===========================================================================*/
@@ -192,7 +206,7 @@ extern SerialDriver SD3;
extern "C" {
#endif
void sd_lld_init(void);
- void sd_lld_start(SerialDriver *sdp, const SerialDriverConfig *config);
+ void sd_lld_start(SerialDriver *sdp);
void sd_lld_stop(SerialDriver *sdp);
#ifdef __cplusplus
}
diff --git a/os/hal/src/serial.c b/os/hal/src/serial.c
index 5df69d1a0..4c2cb71c9 100644
--- a/os/hal/src/serial.c
+++ b/os/hal/src/serial.c
@@ -47,32 +47,32 @@
*/
static bool_t putwouldblock(void *ip) {
- return chOQIsFull(&((SerialDriver *)ip)->d2.oqueue);
+ return chOQIsFull(&((SerialDriver *)ip)->sd.oqueue);
}
static bool_t getwouldblock(void *ip) {
- return chIQIsEmpty(&((SerialDriver *)ip)->d2.iqueue);
+ return chIQIsEmpty(&((SerialDriver *)ip)->sd.iqueue);
}
static msg_t put(void *ip, uint8_t b, systime_t timeout) {
- return chOQPutTimeout(&((SerialDriver *)ip)->d2.oqueue, b, timeout);
+ return chOQPutTimeout(&((SerialDriver *)ip)->sd.oqueue, b, timeout);
}
static msg_t get(void *ip, systime_t timeout) {
- return chIQGetTimeout(&((SerialDriver *)ip)->d2.iqueue, timeout);
+ return chIQGetTimeout(&((SerialDriver *)ip)->sd.iqueue, timeout);
}
static size_t write(void *ip, uint8_t *buffer, size_t n) {
- return chOQWrite(&((SerialDriver *)ip)->d2.oqueue, buffer, n);
+ return chOQWrite(&((SerialDriver *)ip)->sd.oqueue, buffer, n);
}
static size_t read(void *ip, uint8_t *buffer, size_t n) {
- return chIQRead(&((SerialDriver *)ip)->d2.iqueue, buffer, n);
+ return chIQRead(&((SerialDriver *)ip)->sd.iqueue, buffer, n);
}
static const struct SerialDriverVMT vmt = {
@@ -109,12 +109,13 @@ void sdInit(void) {
void sdObjectInit(SerialDriver *sdp, qnotify_t inotify, qnotify_t onotify) {
sdp->vmt = &vmt;
- chEvtInit(&sdp->d1.ievent);
- chEvtInit(&sdp->d1.oevent);
- chEvtInit(&sdp->d2.sevent);
- sdp->d2.flags = SD_NO_ERROR;
- chIQInit(&sdp->d2.iqueue, sdp->d2.ib, SERIAL_BUFFERS_SIZE, inotify);
- chOQInit(&sdp->d2.oqueue, sdp->d2.ob, SERIAL_BUFFERS_SIZE, onotify);
+ chEvtInit(&sdp->bac.ievent);
+ chEvtInit(&sdp->bac.oevent);
+ chEvtInit(&sdp->sd.sevent);
+ sdp->sd.flags = SD_NO_ERROR;
+ chIQInit(&sdp->sd.iqueue, sdp->sd.ib, SERIAL_BUFFERS_SIZE, inotify);
+ chOQInit(&sdp->sd.oqueue, sdp->sd.ob, SERIAL_BUFFERS_SIZE, onotify);
+ sdp->sd.state = SD_STOP;
}
/**
@@ -125,10 +126,17 @@ void sdObjectInit(SerialDriver *sdp, qnotify_t inotify, qnotify_t onotify) {
* If this parameter is set to @p NULL then a default
* configuration is used.
*/
-void sdStart(SerialDriver *sdp, const SerialDriverConfig *config) {
+void sdStart(SerialDriver *sdp, const SerialConfig *config) {
+
+ chDbgCheck((sdp != NULL) && (config != NULL), "sdStart");
chSysLock();
- sd_lld_start(sdp, config);
+ chDbgAssert((sdp->sd.state == SD_STOP) || (sdp->sd.state == SD_READY),
+ "sdStart(), #1",
+ "invalid state");
+ sdp->sd.config = config;
+ sd_lld_start(sdp);
+ sdp->sd.state = SD_READY;
chSysUnlock();
}
@@ -141,10 +149,16 @@ void sdStart(SerialDriver *sdp, const SerialDriverConfig *config) {
*/
void sdStop(SerialDriver *sdp) {
+ chDbgCheck(sdp != NULL, "sdStop");
+
chSysLock();
+ chDbgAssert((sdp->sd.state == SD_STOP) || (sdp->sd.state == SD_READY),
+ "sdStop(), #1",
+ "invalid state");
sd_lld_stop(sdp);
- chOQResetI(&sdp->d2.oqueue);
- chIQResetI(&sdp->d2.iqueue);
+ sdp->sd.state = SD_STOP;
+ chOQResetI(&sdp->sd.oqueue);
+ chIQResetI(&sdp->sd.iqueue);
chSchRescheduleS();
chSysUnlock();
}
@@ -154,32 +168,45 @@ void sdStop(SerialDriver *sdp) {
* @details This function must be called from the input interrupt service
* routine in order to enqueue incoming data and generate the
* related events.
- * @param[in] sd pointer to a @p SerialDriver structure
+ * @note The incoming data event is only generated when the input queue
+ * becomes non-empty.
+ * @note In order to gain some performance it is suggested to not use
+ * this function directly but copy this code directly into the
+ * interrupt service routine.
+ *
+ * @param[in] sdp pointer to a @p SerialDriver structure
* @param[in] b the byte to be written in the driver's Input Queue
*/
-void sdIncomingDataI(SerialDriver *sd, uint8_t b) {
+void sdIncomingDataI(SerialDriver *sdp, uint8_t b) {
+
+ chDbgCheck(sdp != NULL, "sdIncomingDataI");
- if (chIQPutI(&sd->d2.iqueue, b) < Q_OK)
- sdAddFlagsI(sd, SD_OVERRUN_ERROR);
- else
- chEvtBroadcastI(&sd->d1.ievent);
+ if (chIQIsEmpty(&sdp->sd.iqueue))
+ chEvtBroadcastI(&sdp->bac.ievent);
+ if (chIQPutI(&sdp->sd.iqueue, b) < Q_OK)
+ sdAddFlagsI(sdp, SD_OVERRUN_ERROR);
}
/**
* @brief Handles outgoing data.
* @details Must be called from the output interrupt service routine in order
* to get the next byte to be transmitted.
+ * @note In order to gain some performance it is suggested to not use
+ * this function directly but copy this code directly into the
+ * interrupt service routine.
*
- * @param[in] sd pointer to a @p SerialDriver structure
+ * @param[in] sdp pointer to a @p SerialDriver structure
* @return The byte value read from the driver's output queue.
* @retval Q_EMPTY if the queue is empty (the lower driver usually disables
* the interrupt source when this happens).
*/
-msg_t sdRequestDataI(SerialDriver *sd) {
+msg_t sdRequestDataI(SerialDriver *sdp) {
- msg_t b = chOQGetI(&sd->d2.oqueue);
+ chDbgCheck(sdp != NULL, "sdRequestDataI");
+
+ msg_t b = chOQGetI(&sdp->sd.oqueue);
if (b < Q_OK)
- chEvtBroadcastI(&sd->d1.oevent);
+ chEvtBroadcastI(&sdp->bac.oevent);
return b;
}
@@ -188,27 +215,31 @@ msg_t sdRequestDataI(SerialDriver *sd) {
* @details Must be called from the I/O interrupt service routine in order to
* notify I/O conditions as errors, signals change etc.
*
- * @param[in] sd pointer to a @p SerialDriver structure
+ * @param[in] sdp pointer to a @p SerialDriver structure
* @param[in] mask condition flags to be added to the mask
*/
-void sdAddFlagsI(SerialDriver *sd, sdflags_t mask) {
+void sdAddFlagsI(SerialDriver *sdp, sdflags_t mask) {
+
+ chDbgCheck(sdp != NULL, "sdAddFlagsI");
- sd->d2.flags |= mask;
- chEvtBroadcastI(&sd->d2.sevent);
+ sdp->sd.flags |= mask;
+ chEvtBroadcastI(&sdp->sd.sevent);
}
/**
* @brief Returns and clears the errors mask associated to the driver.
*
- * @param[in] sd pointer to a @p SerialDriver structure
+ * @param[in] sdp pointer to a @p SerialDriver structure
* @return The condition flags modified since last time this function was
* invoked.
*/
-sdflags_t sdGetAndClearFlags(SerialDriver *sd) {
+sdflags_t sdGetAndClearFlags(SerialDriver *sdp) {
sdflags_t mask;
- mask = sd->d2.flags;
- sd->d2.flags = SD_NO_ERROR;
+ chDbgCheck(sdp != NULL, "sdGetAndClearFlags");
+
+ mask = sdp->sd.flags;
+ sdp->sd.flags = SD_NO_ERROR;
return mask;
}
diff --git a/os/kernel/include/channels.h b/os/kernel/include/channels.h
index 83abcdb1a..e9cc956a6 100644
--- a/os/kernel/include/channels.h
+++ b/os/kernel/include/channels.h
@@ -68,7 +68,7 @@ struct BaseChannelVMT {
/**
* @p BaseChannel class specific methods.
*/
- struct _base_channel_methods m0;
+ struct _base_channel_methods bc;
};
/**
@@ -83,7 +83,7 @@ typedef struct {
/**
* @p BaseChannel class specific data.
*/
- struct _base_channel_data d0;
+ struct _base_channel_data bc;
} BaseChannel;
/**
@@ -96,7 +96,7 @@ typedef struct {
* operation.
* @retval TRUE if the output queue is full and would block a write operation.
*/
-#define chIOPutWouldBlock(ip) ((ip)->vmt->m0.putwouldblock(ip))
+#define chIOPutWouldBlock(ip) ((ip)->vmt->bc.putwouldblock(ip))
/**
* @brief Channel input check.
@@ -108,7 +108,7 @@ typedef struct {
* operation.
* @retval TRUE if the input queue is empty and would block a read operation.
*/
-#define chIOGetWouldBlock(ip) ((ip)->vmt->m0.getwouldblock(ip))
+#define chIOGetWouldBlock(ip) ((ip)->vmt->bc.getwouldblock(ip))
/**
* @brief Channel blocking byte write.
@@ -121,7 +121,7 @@ typedef struct {
* @retval Q_OK if the operation succeeded.
* @retval Q_RESET if the channel associated queue (if any) was reset.
*/
-#define chIOPut(ip, b) ((ip)->vmt->m0.put(ip, b, TIME_INFINITE))
+#define chIOPut(ip, b) ((ip)->vmt->bc.put(ip, b, TIME_INFINITE))
/**
* @brief Channel blocking byte write with timeout.
@@ -140,7 +140,7 @@ typedef struct {
* @retval Q_TIMEOUT if the specified time expired.
* @retval Q_RESET if the channel associated queue (if any) was reset.
*/
-#define chIOPutTimeout(ip, b, timeout) ((ip)->vmt->m0.put(ip, b, timeout))
+#define chIOPutTimeout(ip, b, timeout) ((ip)->vmt->bc.put(ip, b, timeout))
/**
* @brief Channel blocking byte read.
@@ -151,7 +151,7 @@ typedef struct {
* @return A byte value from the queue or:
* @retval Q_RESET if the channel associated queue (if any) was reset.
*/
-#define chIOGet(ip) ((ip)->vmt->m0.get(ip, TIME_INFINITE))
+#define chIOGet(ip) ((ip)->vmt->bc.get(ip, TIME_INFINITE))
/**
* @brief Channel blocking byte read with timeout.
@@ -168,7 +168,7 @@ typedef struct {
* @retval Q_TIMEOUT if the specified time expired.
* @retval Q_RESET if the channel associated queue (if any) was reset.
*/
-#define chIOGetTimeout(ip, timeout) ((ip)->vmt->m0.get(ip, timeout))
+#define chIOGetTimeout(ip, timeout) ((ip)->vmt->bc.get(ip, timeout))
#if CH_USE_EVENTS
/**
@@ -210,11 +210,11 @@ struct BaseAsynchronousChannelVMT {
/**
* @p BaseChannel class inherited methods.
*/
- struct _base_channel_methods m0;
+ struct _base_channel_methods bc;
/**
* @p BaseAsynchronousChannel class specific methods.
*/
- struct _base_asynchronous_channel_methods m1;
+ struct _base_asynchronous_channel_methods bac;
};
/**
@@ -232,11 +232,11 @@ typedef struct {
/**
* @p BaseChannel class inherited data.
*/
- struct _base_channel_data d0;
+ struct _base_channel_data bc;
/**
* @p BaseAsynchronousChannel class specific data.
*/
- struct _base_asynchronous_channel_data d1;
+ struct _base_asynchronous_channel_data bac;
} BaseAsynchronousChannel;
/**
@@ -250,7 +250,7 @@ typedef struct {
* @param[in] n the maximum amount of data to be transferred
* @return The number of bytes transferred.
*/
-#define chIOWrite(ip, bp, n) ((ip)->vmt->m1.write(ip, bp, n))
+#define chIOWrite(ip, bp, n) ((ip)->vmt->bac.write(ip, bp, n))
/**
* @brief Channel non-blocking read.
@@ -263,7 +263,7 @@ typedef struct {
* @param[in] n the maximum amount of data to be transferred
* @return The number of bytes transferred.
*/
-#define chIORead(ip, bp, n) ((ip)->vmt->m1.read(ip, bp, n))
+#define chIORead(ip, bp, n) ((ip)->vmt->bac.read(ip, bp, n))
/**
* @brief Returns the write event source.
@@ -273,7 +273,7 @@ typedef struct {
* @param[in] ip pointer to a @p BaseAsynchronousChannel or derived class
* @return A pointer to an @p EventSource object.
*/
-#define chIOGetWriteEventSource(ip) (&((ip)->vmt->d1.oevent))
+#define chIOGetWriteEventSource(ip) (&((ip)->vmt->bac.oevent))
/**
* @brief Returns the read event source.
@@ -283,7 +283,7 @@ typedef struct {
* @param[in] ip pointer to a @p BaseAsynchronousChannel or derived class
* @return A pointer to an @p EventSource object.
*/
-#define chIOGetReadEventSource(ip) (&((ip)->vmt->d1.ievent))
+#define chIOGetReadEventSource(ip) (&((ip)->vmt->bac.ievent))
#endif /* CH_USE_EVENTS */