aboutsummaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
authorgdisirio <gdisirio@35acf78f-673a-0410-8e92-d51de3d6d3f4>2009-02-06 17:40:24 +0000
committergdisirio <gdisirio@35acf78f-673a-0410-8e92-d51de3d6d3f4>2009-02-06 17:40:24 +0000
commit1ddd49eec7be60413d5054937ee1a1c001842769 (patch)
tree4826e224810d14ba396582952cd614bb9f2da925
parent87805ba16625d490475be626372a87d7c53e700c (diff)
downloadChibiOS-1ddd49eec7be60413d5054937ee1a1c001842769.tar.gz
ChibiOS-1ddd49eec7be60413d5054937ee1a1c001842769.tar.bz2
ChibiOS-1ddd49eec7be60413d5054937ee1a1c001842769.zip
git-svn-id: svn://svn.code.sf.net/p/chibios/svn/trunk@725 35acf78f-673a-0410-8e92-d51de3d6d3f4
-rw-r--r--demos/ARM7-LPC214x-G++/board.c6
-rw-r--r--demos/ARM7-LPC214x-GCC-minimal/board.c6
-rw-r--r--demos/ARM7-LPC214x-GCC/board.c6
-rw-r--r--demos/ARM7-LPC214x-GCC/mmcsd.c4
-rw-r--r--demos/ARMCM3-STM32F103-GCC/board.c2
-rw-r--r--docs/Doxyfile4
-rw-r--r--ports/ARM7-LPC214x/lpc214x_serial.c150
-rw-r--r--ports/ARM7-LPC214x/lpc214x_serial.h77
-rw-r--r--ports/ARM7-LPC214x/lpc214x_ssp.c58
-rw-r--r--ports/ARM7-LPC214x/lpc214x_ssp.h27
-rw-r--r--ports/ARM7-LPC214x/port.dox29
-rw-r--r--ports/ARM7-LPC214x/vic.c25
-rw-r--r--ports/ARM7-LPC214x/vic.h11
-rw-r--r--ports/ARMCM3-STM32F103/port.dox11
-rw-r--r--ports/ARMCM3-STM32F103/stm32_serial.c104
-rw-r--r--ports/ARMCM3-STM32F103/stm32_serial.h177
-rw-r--r--ports/MSP430/msp430_serial.c6
-rw-r--r--src/chheap.c2
18 files changed, 492 insertions, 213 deletions
diff --git a/demos/ARM7-LPC214x-G++/board.c b/demos/ARM7-LPC214x-G++/board.c
index 2bced8d70..93227e0ed 100644
--- a/demos/ARM7-LPC214x-G++/board.c
+++ b/demos/ARM7-LPC214x-G++/board.c
@@ -119,7 +119,7 @@ void hwinit1(void) {
/*
* Interrupt vectors assignment.
*/
- InitVIC();
+ lpc214x_vic_init();
VICDefVectAddr = (IOREG32)IrqHandler;
/*
@@ -137,8 +137,8 @@ void hwinit1(void) {
/*
* Other subsystems.
*/
- InitSerial(1, 2);
-// InitSSP();
+ lpc2148x_serial_init(1, 2);
+// lpc214x_ssp_init();
// InitMMC();
// InitBuzzer();
diff --git a/demos/ARM7-LPC214x-GCC-minimal/board.c b/demos/ARM7-LPC214x-GCC-minimal/board.c
index b234cb7a1..76e4c7eb8 100644
--- a/demos/ARM7-LPC214x-GCC-minimal/board.c
+++ b/demos/ARM7-LPC214x-GCC-minimal/board.c
@@ -119,7 +119,7 @@ void hwinit1(void) {
/*
* Interrupt vectors assignment.
*/
- InitVIC();
+ lpc214x_vic_init();
VICDefVectAddr = (IOREG32)IrqHandler;
/*
@@ -137,8 +137,8 @@ void hwinit1(void) {
/*
* Other subsystems.
*/
-// InitSerial(1, 2);
-// InitSSP();
+// lpc2148x_serial_init(1, 2);
+// lpc214x_ssp_init();
// InitMMC();
// InitBuzzer();
diff --git a/demos/ARM7-LPC214x-GCC/board.c b/demos/ARM7-LPC214x-GCC/board.c
index 8e0bcfb34..9d6d77fc7 100644
--- a/demos/ARM7-LPC214x-GCC/board.c
+++ b/demos/ARM7-LPC214x-GCC/board.c
@@ -119,7 +119,7 @@ void hwinit1(void) {
/*
* Interrupt vectors assignment.
*/
- InitVIC();
+ lpc214x_vic_init();
VICDefVectAddr = (IOREG32)IrqHandler;
/*
@@ -137,8 +137,8 @@ void hwinit1(void) {
/*
* Other subsystems.
*/
- InitSerial(1, 2);
- InitSSP();
+ lpc2148x_serial_init(1, 2);
+ lpc214x_ssp_init();
InitMMC();
InitBuzzer();
diff --git a/demos/ARM7-LPC214x-GCC/mmcsd.c b/demos/ARM7-LPC214x-GCC/mmcsd.c
index bd1997fce..10e6c6c5b 100644
--- a/demos/ARM7-LPC214x-GCC/mmcsd.c
+++ b/demos/ARM7-LPC214x-GCC/mmcsd.c
@@ -167,7 +167,7 @@ bool_t mmcInit(void) {
/*
* Starting initialization with slow clock mode.
*/
- SetSSP(254, CR0_DSS8BIT | CR0_FRFSPI | CR0_CLOCKRATE(0), 0);
+ lpc214x_ssp_setup(254, CR0_DSS8BIT | CR0_FRFSPI | CR0_CLOCKRATE(0), 0);
/*
* SPI mode selection.
@@ -200,7 +200,7 @@ bool_t mmcInit(void) {
/*
* Full speed.
*/
- SetSSP(2, CR0_DSS8BIT | CR0_FRFSPI | CR0_CLOCKRATE(0), 0);
+ lpc214x_ssp_setup(2, CR0_DSS8BIT | CR0_FRFSPI | CR0_CLOCKRATE(0), 0);
return FALSE;
}
diff --git a/demos/ARMCM3-STM32F103-GCC/board.c b/demos/ARMCM3-STM32F103-GCC/board.c
index 6a13c126b..c545728ec 100644
--- a/demos/ARMCM3-STM32F103-GCC/board.c
+++ b/demos/ARMCM3-STM32F103-GCC/board.c
@@ -104,7 +104,7 @@ void hwinit1(void) {
/*
* Other subsystems initialization.
*/
- InitSerial(0xC0, 0xC0, 0xC0);
+ stm32_serial_init(0xC0, 0xC0, 0xC0);
/*
* ChibiOS/RT initialization.
diff --git a/docs/Doxyfile b/docs/Doxyfile
index 7b5b62bac..1b11e4d16 100644
--- a/docs/Doxyfile
+++ b/docs/Doxyfile
@@ -583,10 +583,10 @@ INPUT = ../src/include \
../ports/ARM7/crt0.s \
../ports/ARM7/chcoreasm.s \
../ports/ARM7-AT91SAM7X/port.dox \
- ../ports/ARM7-LPC214x/port.dox \
+ ../ports/ARM7-LPC214x \
../ports/ARMCM3 \
../ports/ARMCM3/crt0.s \
- ../ports/ARMCM3-STM32F103/port.dox \
+ ../ports/ARMCM3-STM32F103 \
../ports/MSP430 \
../ports/AVR
diff --git a/ports/ARM7-LPC214x/lpc214x_serial.c b/ports/ARM7-LPC214x/lpc214x_serial.c
index 62c602dfd..e36512049 100644
--- a/ports/ARM7-LPC214x/lpc214x_serial.c
+++ b/ports/ARM7-LPC214x/lpc214x_serial.c
@@ -17,6 +17,13 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
+/**
+ * @file ports/ARM7-LPC214x/lpc214x_serial.c
+ * @brief LPC214x Serial driver code.
+ * @addtogroup LPC214x_SERIAL
+ * @{
+ */
+
#include <ch.h>
#include "lpc214x.h"
@@ -24,14 +31,27 @@
#include "lpc214x_serial.h"
#include "board.h"
+#if USE_LPC214x_UART0 || defined(__DOXYGEN__)
+/** @brief UART0 serial driver identifier.*/
FullDuplexDriver COM1;
+
static uint8_t ib1[SERIAL_BUFFERS_SIZE];
static uint8_t ob1[SERIAL_BUFFERS_SIZE];
+#endif
+#if USE_LPC214x_UART1 || defined(__DOXYGEN__)
+/** @brief UART1 serial driver identifier.*/
FullDuplexDriver COM2;
+
static uint8_t ib2[SERIAL_BUFFERS_SIZE];
static uint8_t ob2[SERIAL_BUFFERS_SIZE];
+#endif
+/**
+ * @brief Error handling routine.
+ * @param[in] err UART LSR register value
+ * @param[in] com communication channel associated to the USART
+ */
static void SetError(IOREG32 err, FullDuplexDriver *com) {
dflags_t sts = 0;
@@ -48,11 +68,16 @@ static void SetError(IOREG32 err, FullDuplexDriver *com) {
chSysUnlockFromIsr();
}
-/*
- * Tries hard to clear all the pending interrupt sources, we dont want to
- * go through the whole ISR and have another interrupt soon after.
- */
+/** @cond never*/
__attribute__((noinline))
+/** @endcond*/
+/**
+ * @brief Common IRQ handler.
+ * @param[in] u pointer to an UART I/O block
+ * @param[in] com communication channel associated to the UART
+ * @note Tries hard to clear all the pending interrupt sources, we dont want to
+ * go through the whole ISR and have another interrupt soon after.
+ */
static void ServeInterrupt(UART *u, FullDuplexDriver *com) {
while (TRUE) {
@@ -77,8 +102,8 @@ static void ServeInterrupt(UART *u, FullDuplexDriver *com) {
break;
case IIR_SRC_TX:
{
-#ifdef FIFO_PRELOAD
- int i = FIFO_PRELOAD;
+#if LPC214x_UART_FIFO_PRELOAD > 0
+ int i = LPC214x_UART_FIFO_PRELOAD;
do {
chSysLockFromIsr();
msg_t b = chOQGetI(&com->sd_oqueue);
@@ -109,31 +134,11 @@ static void ServeInterrupt(UART *u, FullDuplexDriver *com) {
}
}
-CH_IRQ_HANDLER(UART0IrqHandler) {
-
- CH_IRQ_PROLOGUE();
-
- ServeInterrupt(U0Base, &COM1);
- VICVectAddr = 0;
-
- CH_IRQ_EPILOGUE();
-}
-
-CH_IRQ_HANDLER(UART1IrqHandler) {
-
- CH_IRQ_PROLOGUE();
-
- ServeInterrupt(U1Base, &COM2);
- VICVectAddr = 0;
-
- CH_IRQ_EPILOGUE();
-}
-
-#ifdef FIFO_PRELOAD
+#if LPC214x_UART_FIFO_PRELOAD > 0
static void preload(UART *u, FullDuplexDriver *com) {
if (u->UART_LSR & LSR_THRE) {
- int i = FIFO_PRELOAD;
+ int i = LPC214x_UART_FIFO_PRELOAD;
do {
chSysLockFromIsr();
msg_t b = chOQGetI(&com->sd_oqueue);
@@ -151,12 +156,25 @@ static void preload(UART *u, FullDuplexDriver *com) {
}
#endif
-/*
- * Invoked by the high driver when one or more bytes are inserted in the
- * output queue.
+#if USE_LPC214x_UART0 || defined(__DOXYGEN__)
+/**
+ * @brief UART0 IRQ service routine.
+ */
+CH_IRQ_HANDLER(UART0IrqHandler) {
+
+ CH_IRQ_PROLOGUE();
+
+ ServeInterrupt(U0Base, &COM1);
+ VICVectAddr = 0;
+
+ CH_IRQ_EPILOGUE();
+}
+
+/**
+ * @brief Output queue insertion notification from the high driver.
*/
static void OutNotify1(void) {
-#ifdef FIFO_PRELOAD
+#if LPC214x_UART_FIFO_PRELOAD > 0
preload(U0Base, &COM1);
#else
@@ -170,13 +188,27 @@ static void OutNotify1(void) {
u->UART_IER |= IER_THRE;
#endif
}
+#endif
-/*
- * Invoked by the high driver when one or more bytes are inserted in the
- * output queue.
+#if USE_LPC214x_UART1 || defined(__DOXYGEN__)
+/**
+ * @brief UART1 IRQ service routine.
+ */
+CH_IRQ_HANDLER(UART1IrqHandler) {
+
+ CH_IRQ_PROLOGUE();
+
+ ServeInterrupt(U1Base, &COM2);
+ VICVectAddr = 0;
+
+ CH_IRQ_EPILOGUE();
+}
+
+/**
+ * @brief Output queue insertion notification from the high driver.
*/
static void OutNotify2(void) {
-#ifdef FIFO_PRELOAD
+#if LPC214x_UART_FIFO_PRELOAD > 0
preload(U1Base, &COM2);
#else
@@ -187,9 +219,15 @@ static void OutNotify2(void) {
u->UART_IER |= IER_THRE;
#endif
}
+#endif
-/*
- * UART setup, must be invoked with interrupts disabled.
+/**
+ * @brief UART setup.
+ * @param[in] u pointer to an UART I/O block
+ * @param[in] speed serial port speed in bits per second
+ * @param[in] lcr the value for the @p LCR register
+ * @param[in] fcr the value for the @p FCR register
+ * @note Must be invoked with interrupts disabled.
*/
void SetUART(UART *u, int speed, int lcr, int fcr) {
@@ -205,21 +243,37 @@ void SetUART(UART *u, int speed, int lcr, int fcr) {
u->UART_IER = IER_RBR | IER_STATUS;
}
-/*
- * Serial subsystem initialization.
+/**
+ * @brief Serial driver initialization.
+ * @param[in] vector1 IRC vector to be used for UART0
+ * @param[in] vector2 IRC vector to be used for UART1
+ * @note Handshake pads are not enabled inside this function because they
+ * may have another use, enable them externally if needed.
+ * RX and TX pads are handled inside.
*/
-void InitSerial(int vector1, int vector2) {
+void lpc2148x_serial_init(int vector1, int vector2) {
+#if USE_LPC214x_UART0
SetVICVector(UART0IrqHandler, vector1, SOURCE_UART0);
- SetVICVector(UART1IrqHandler, vector2, SOURCE_UART1);
-
- PCONP = (PCONP & PCALL) | PCUART0 | PCUART1;
-
+ PCONP = (PCONP & PCALL) | PCUART0;
chFDDInit(&COM1, ib1, sizeof ib1, NULL, ob1, sizeof ob1, OutNotify1);
- SetUART(U0Base, 38400, LCR_WL8 | LCR_STOP1 | LCR_NOPARITY, FCR_TRIGGER0);
+ SetUART(U0Base,
+ LPC214x_UART_BITRATE,
+ LCR_WL8 | LCR_STOP1 | LCR_NOPARITY,
+ FCR_TRIGGER0);
+ VICIntEnable = INTMASK(SOURCE_UART0);
+#endif
+#if USE_LPC214x_UART1
+ SetVICVector(UART1IrqHandler, vector2, SOURCE_UART1);
+ PCONP = (PCONP & PCALL) | PCUART1;
chFDDInit(&COM2, ib2, sizeof ib2, NULL, ob2, sizeof ob2, OutNotify2);
- SetUART(U1Base, 38400, LCR_WL8 | LCR_STOP1 | LCR_NOPARITY, FCR_TRIGGER0);
-
+ SetUART(U1Base,
+ LPC214x_UART_BITRATE,
+ LCR_WL8 | LCR_STOP1 | LCR_NOPARITY,
+ FCR_TRIGGER0);
VICIntEnable = INTMASK(SOURCE_UART0) | INTMASK(SOURCE_UART1);
+#endif
}
+
+/** @} */
diff --git a/ports/ARM7-LPC214x/lpc214x_serial.h b/ports/ARM7-LPC214x/lpc214x_serial.h
index ce457dadf..ee60a48f4 100644
--- a/ports/ARM7-LPC214x/lpc214x_serial.h
+++ b/ports/ARM7-LPC214x/lpc214x_serial.h
@@ -17,30 +17,75 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
+/**
+ * @file ports/ARM7-LPC214x/lpc214x_serial.h
+ * @brief LPC214x Serial driver macros and structures.
+ * @addtogroup LPC214x_SERIAL
+ * @{
+ */
+
#ifndef _LPC214x_SERIAL_H_
#define _LPC214x_SERIAL_H_
-/*
- * Configuration parameter, this values defines how many bytes are preloaded
- * in the HW transmit FIFO for each interrupt, the maximum value is 16 the
- * minimum is 2.
- * NOTE: A greater value reduces the number of interrupts generated but can
- * also increase the worst case interrupt response time.
- * NOTE: You can undefine the following macro and revert to a simpler code
- * that will generate an interrupt for each output byte,
+/**
+ * @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.
*/
-#define FIFO_PRELOAD 16
+#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
+#define SERIAL_BUFFERS_SIZE 128
+#endif
-/*
- * Configuration parameter, you can change the depth of the queue buffers
- * depending on the requirements of your application.
+/**
+ * @brief Default bit rate.
+ * @details Configuration parameter, at startup the UARTs are configured at
+ * this speed.
+ * @note It is possible to use @p SetUART() in order to change the working
+ * parameters at runtime.
*/
-#define SERIAL_BUFFERS_SIZE 128
+#if !defined(LPC214x_UART_BITRATE) || defined(__DOXYGEN__)
+#define LPC214x_UART_BITRATE 38400
+#endif
+
+/**
+ * @brief FIFO preload parameter.
+ * @details Configuration parameter, this values defines how many bytes are
+ * preloaded in the HW transmit FIFO for each interrupt, the maximum value is
+ * 16 the minimum is 2, the value 0 disables the feature.
+ * @note An high value reduces the number of interrupts generated but can
+ * also increase the worst case interrupt response time because the
+ * preload loops.
+ * @note The value zero disables the feature and reverts to a simpler code
+ * that will generate an interrupt for each output byte but is much
+ * smaller and simpler.
+ */
+#if !defined(LPC214x_UART_FIFO_PRELOAD) || defined(__DOXYGEN__)
+#define LPC214x_UART_FIFO_PRELOAD 16
+#endif
+
+/**
+ * @brief UART0 driver enable switch.
+ * @details If set to @p TRUE the support for USART1 is included.
+ * @note The default is @p TRUE .
+ */
+#if !defined(USE_LPC214x_UART0) || defined(__DOXYGEN__)
+#define USE_LPC214x_UART0 TRUE
+#endif
+
+/**
+ * @brief UART1 driver enable switch.
+ * @details If set to @p TRUE the support for USART2 is included.
+ * @note The default is @p TRUE.
+ */
+#if !defined(USE_LPC214x_UART1) || defined(__DOXYGEN__)
+#define USE_LPC214x_UART1 TRUE
+#endif
#ifdef __cplusplus
extern "C" {
#endif
- void InitSerial(int vector1, int vector2);
+ void lpc2148x_serial_init(int vector1, int vector2);
void SetUART(UART *u, int speed, int lcr, int fcr);
CH_IRQ_HANDLER(UART0IrqHandler);
CH_IRQ_HANDLER(UART1IrqHandler);
@@ -48,6 +93,10 @@ extern "C" {
}
#endif
+/** @cond never*/
extern FullDuplexDriver COM1, COM2;
+/** @endcond*/
#endif /* _LPC214x_SERIAL_H_*/
+
+/** @} */
diff --git a/ports/ARM7-LPC214x/lpc214x_ssp.c b/ports/ARM7-LPC214x/lpc214x_ssp.c
index 145badcf5..ebe29b6e7 100644
--- a/ports/ARM7-LPC214x/lpc214x_ssp.c
+++ b/ports/ARM7-LPC214x/lpc214x_ssp.c
@@ -17,38 +17,55 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
+/**
+ * @file ports/ARM7-LPC214x/lpc214x_ssp.c
+ * @brief LPC214x SSP driver code.
+ * @addtogroup LPC214x_SSP
+ * @{
+ */
+
#include <ch.h>
#include "lpc214x.h"
#include "lpc214x_ssp.h"
-#ifdef SSP_USE_MUTEX
+#if LPC214x_SSP_USE_MUTEX
static Semaphore me;
#endif
+/**
+ * @brief Aquires access to the SSP bus.
+ * @note This function also handles the mutual exclusion on the SSP bus if
+ * the @p LPC214x_SSP_USE_MUTEX option is enabled.
+ */
void sspAcquireBus(void) {
-#ifdef SSP_USE_MUTEX
+#if LPC214x_SSP_USE_MUTEX
chSemWait(&me);
#endif
IO0CLR = 1 << 20;
}
+/**
+ * @brief Releases the SSP bus.
+ * @note This function also handles the mutual exclusion on the SSP bus if
+ * the @p LPC214x_SSP_USE_MUTEX option is enabled.
+ */
void sspReleaseBus(void) {
IO0SET = 1 << 20;
-#ifdef SSP_USE_MUTEX
+#if LPC214x_SSP_USE_MUTEX
chSemSignal(&me);
#endif
}
-/*
- * Synchronous SSP transfer.
- * @param in pointer to the incoming data buffer, if this parameter is set to
- * \p NULL then the incoming data is discarded.
- * @param out pointer to the outgoing data buffer, if this parameter is set to
- * \p NULL then 0xFF bytes will be output.
- * @param n the number of bytes to be transferred
+/**
+ * @brief Synchronous SSP transfer.
+ * @param[in] in pointer to the incoming data buffer, if this parameter is set
+ * to @p NULL then the incoming data is discarded
+ * @param[out] out pointer to the outgoing data buffer, if this parameter is
+ * set to @p NULL then 0xFF bytes will be output
+ * @param[in] n the number of bytes to be transferred
* @note The transfer is performed in a software loop and is not interrupt
* driven for performance reasons, this function should be invoked
* by a low priority thread in order to "play nice" with the
@@ -81,10 +98,13 @@ void sspRW(uint8_t *in, uint8_t *out, size_t n) {
}
}
-/*
- * SSP setup.
+/**
+ * @brief SSP setup.
+ * @param[in] cpsr the value for the @p CPSR register
+ * @param[in] cr0 the value for the @p CR0 register
+ * @param[in] cr1 the value for the @p CR1 register
*/
-void SetSSP(int cpsr, int cr0, int cr1) {
+void lpc214x_ssp_setup(int cpsr, int cr0, int cr1) {
SSP *ssp = SSPBase;
ssp->SSP_CR1 = 0;
@@ -93,18 +113,20 @@ void SetSSP(int cpsr, int cr0, int cr1) {
ssp->SSP_CR1 = cr1 | CR1_SSE;
}
-/*
- * SSP subsystem initialization.
+/**
+ * @brief SSP subsystem initialization.
*/
-void InitSSP(void) {
+void lpc214x_ssp_init(void) {
/* Enables the SPI1 clock */
PCONP = (PCONP & PCALL) | PCSPI1;
/* Clock = PCLK / 2 (fastest). */
- SetSSP(2, CR0_DSS8BIT | CR0_FRFSPI | CR0_CLOCKRATE(0), 0);
+ lpc214x_ssp_setup(2, CR0_DSS8BIT | CR0_FRFSPI | CR0_CLOCKRATE(0), 0);
-#ifdef SSP_USE_MUTEX
+#if LPC214x_SSP_USE_MUTEX
chSemInit(&me, 1);
#endif
}
+
+/** @} */
diff --git a/ports/ARM7-LPC214x/lpc214x_ssp.h b/ports/ARM7-LPC214x/lpc214x_ssp.h
index 55929c2d8..411ef5016 100644
--- a/ports/ARM7-LPC214x/lpc214x_ssp.h
+++ b/ports/ARM7-LPC214x/lpc214x_ssp.h
@@ -17,21 +17,32 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
+/**
+ * @file ports/ARM7-LPC214x/lpc214x_ssp.h
+ * @brief LPC214x SSP driver macros and structures.
+ * @addtogroup LPC214x_SSP
+ * @{
+ */
+
#ifndef _LPC214x_SSP_H_
#define _LPC214x_SSP_H_
-/*
- * Configuration parameter, if defined this macro enforces mutual exclusion
- * when invoking \p sspAcquireBus() and \p sspReleaseBus().
+/**
+ * @brief SSP bus mutual exclusion control.
+ * @details Configuration parameter, if defined this macro enforces mutual
+ * exclusion when invoking @p sspAcquireBus() and @p sspReleaseBus().
+ * @note The internally used synchronization mechanism is a @p Semaphore.
+ * @todo Make it use Mutexes or Semaphores like the Heap subsystem.
*/
-#define SSP_USE_MUTEX
+#if !defined(LPC214x_SSP_USE_MUTEX) || defined(__DOXYGEN__)
+#define LPC214x_SSP_USE_MUTEX TRUE
+#endif
#ifdef __cplusplus
}
#endif
- void InitSSP(void);
- void SetSSP(int cpsr, int cr0, int cr1);
-
+ void lpc214x_ssp_init(void);
+ void lpc214x_ssp_setup(int cpsr, int cr0, int cr1);
void sspAcquireBus(void);
void sspReleaseBus(void);
void sspRW(uint8_t *in, uint8_t *out, size_t n);
@@ -40,3 +51,5 @@
#endif
#endif /* _LPC214x_SSP_H_*/
+
+/** @} */
diff --git a/ports/ARM7-LPC214x/port.dox b/ports/ARM7-LPC214x/port.dox
index 5d7a4a591..efffe45c0 100644
--- a/ports/ARM7-LPC214x/port.dox
+++ b/ports/ARM7-LPC214x/port.dox
@@ -15,3 +15,32 @@
* @ingroup ARM7
*/
/** @} */
+
+/**
+ * @defgroup LPC214x_VIC VIC Support
+ * @{
+ * @brief VIC peripheral support.
+ *
+ * @ingroup LPC214x
+ */
+/** @} */
+
+/**
+ * @defgroup LPC214x_SERIAL UART Support
+ * @{
+ * @brief UART peripherals support.
+ * @details The serial driver supports the LPC214x UART peripherals.
+ *
+ * @ingroup LPC214x
+ */
+/** @} */
+
+/**
+ * @defgroup LPC214x_SSP SSP Support
+ * @{
+ * @brief SSP peripheral support.
+ * @details This SPI driver supports the LPC214x SSP peripheral.
+ *
+ * @ingroup LPC214x
+ */
+/** @} */
diff --git a/ports/ARM7-LPC214x/vic.c b/ports/ARM7-LPC214x/vic.c
index 969c4aa3b..739a259c1 100644
--- a/ports/ARM7-LPC214x/vic.c
+++ b/ports/ARM7-LPC214x/vic.c
@@ -17,15 +17,22 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
+/**
+ * @file ports/ARM7-LPC214x/vic.c
+ * @brief LPC214x VIC peripheral support code.
+ * @addtogroup LPC214x_VIC
+ * @{
+ */
+
#include <ch.h>
#include "lpc214x.h"
-/*
- * VIC Initialization.
- * NOTE: Better reset everything in the VIC, it is a HUGE source of trouble.
+/**
+ * @brief VIC Initialization.
+ * @note Better reset everything in the VIC, it is a HUGE source of trouble.
*/
-void InitVIC(void) {
+void lpc214x_vic_init(void) {
int i;
VIC *vic = VICBase;
@@ -39,8 +46,12 @@ void InitVIC(void) {
}
}
-/*
- * Set a vector for an interrupt source, the vector is enabled too.
+/**
+ * @brief Initializes a VIC vector.
+ * @details Set a vector for an interrupt source and enables it.
+ * @param[in] handler the pointer to the IRQ service routine
+ * @param[in] vector the vector number
+ * @param[in] source the IRQ source to be associated to the vector
*/
void SetVICVector(void *handler, int vector, int source) {
@@ -48,3 +59,5 @@ void SetVICVector(void *handler, int vector, int source) {
vicp->VIC_VectAddrs[vector] = (IOREG32)handler;
vicp->VIC_VectCntls[vector] = (IOREG32)(source | 0x20);
}
+
+/** @} */
diff --git a/ports/ARM7-LPC214x/vic.h b/ports/ARM7-LPC214x/vic.h
index 2c3fdd32d..a219f4a32 100644
--- a/ports/ARM7-LPC214x/vic.h
+++ b/ports/ARM7-LPC214x/vic.h
@@ -17,16 +17,25 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
+/**
+ * @file ports/ARM7-LPC214x/vic.h
+ * @brief LPC214x VIC peripheral support code.
+ * @addtogroup LPC214x_VIC
+ * @{
+ */
+
#ifndef _VIC_H_
#define _VIC_H_
#ifdef __cplusplus
extern "C" {
#endif
- void InitVIC(void);
+ void lpc214x_vic_init(void);
void SetVICVector(void *handler, int vector, int source);
#ifdef __cplusplus
}
#endif
#endif /* _VIC_H_ */
+
+/** @} */
diff --git a/ports/ARMCM3-STM32F103/port.dox b/ports/ARMCM3-STM32F103/port.dox
index 08fd2d519..991a7c7cb 100644
--- a/ports/ARMCM3-STM32F103/port.dox
+++ b/ports/ARMCM3-STM32F103/port.dox
@@ -9,3 +9,14 @@
* @ingroup ARMCM3
*/
/** @} */
+
+/**
+ * @defgroup STM32F103_SERIAL USART Support
+ * @{
+ * @brief USART peripherals support.
+ * @details The serial driver supports the STM32F103 USARTs in asynchronous
+ * mode.
+ *
+ * @ingroup STM32F103
+ */
+/** @} */
diff --git a/ports/ARMCM3-STM32F103/stm32_serial.c b/ports/ARMCM3-STM32F103/stm32_serial.c
index 725fe3480..9d0534b04 100644
--- a/ports/ARMCM3-STM32F103/stm32_serial.c
+++ b/ports/ARMCM3-STM32F103/stm32_serial.c
@@ -17,6 +17,13 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
+/**
+ * @file ports/ARMCM3-STM32F103/stm32_serial.c
+ * @brief STM32F103 Serial driver code.
+ * @addtogroup STM32F103_SERIAL
+ * @{
+ */
+
#include <ch.h>
#include "board.h"
@@ -24,26 +31,35 @@
#include "stm32_serial.h"
#include "stm32lib/stm32f10x_nvic.h"
-#define USART_BITRATE (38400)
-
-#ifdef USE_USART1
+#if USE_STM32_USART1 || defined(__DOXYGEN__)
+/** @brief USART1 serial driver identifier.*/
FullDuplexDriver COM1;
+
static uint8_t ib1[SERIAL_BUFFERS_SIZE];
static uint8_t ob1[SERIAL_BUFFERS_SIZE];
#endif
-#ifdef USE_USART2
+#if USE_STM32_USART2 || defined(__DOXYGEN__)
+/** @brief USART2 serial driver identifier.*/
FullDuplexDriver COM2;
+
static uint8_t ib2[SERIAL_BUFFERS_SIZE];
static uint8_t ob2[SERIAL_BUFFERS_SIZE];
#endif
-#ifdef USE_USART3
+#if USE_STM32_USART3 || defined(__DOXYGEN__)
+/** @brief USART3 serial driver identifier.*/
FullDuplexDriver COM3;
+
static uint8_t ib3[SERIAL_BUFFERS_SIZE];
static uint8_t ob3[SERIAL_BUFFERS_SIZE];
#endif
+/**
+ * @brief Error handling routine.
+ * @param[in] sr USART SR register value
+ * @param[in] com communication channel associated to the USART
+ */
static void SetError(uint16_t sr, FullDuplexDriver *com) {
dflags_t sts = 0;
@@ -60,6 +76,11 @@ static void SetError(uint16_t sr, FullDuplexDriver *com) {
chSysUnlockFromIsr();
}
+/**
+ * @brief Common IRQ handler.
+ * @param[in] u pointer to an USART I/O block
+ * @param[in] com communication channel associated to the USART
+ */
static void ServeInterrupt(USART_TypeDef *u, FullDuplexDriver *com) {
uint16_t sr = u->SR;
@@ -81,9 +102,9 @@ static void ServeInterrupt(USART_TypeDef *u, FullDuplexDriver *com) {
}
}
-#ifdef USE_USART1
-/*
- * USART1 IRQ service routine.
+#if USE_STM32_USART1 || defined(__DOXYGEN__)
+/**
+ * @brief USART1 IRQ service routine.
*/
CH_IRQ_HANDLER(VectorD4) {
@@ -94,9 +115,8 @@ CH_IRQ_HANDLER(VectorD4) {
CH_IRQ_EPILOGUE();
}
-/*
- * Invoked by the high driver when one or more bytes are inserted in the
- * output queue.
+/**
+ * @brief Output queue insertion notification from the high driver.
*/
static void OutNotify1(void) {
@@ -104,9 +124,9 @@ static void OutNotify1(void) {
}
#endif
-#ifdef USE_USART2
-/*
- * USART2 IRQ service routine.
+#if USE_STM32_USART2 || defined(__DOXYGEN__)
+/**
+ * @brief USART2 IRQ service routine.
*/
CH_IRQ_HANDLER(VectorD8) {
@@ -117,9 +137,8 @@ CH_IRQ_HANDLER(VectorD8) {
CH_IRQ_EPILOGUE();
}
-/*
- * Invoked by the high driver when one or more bytes are inserted in the
- * output queue.
+/**
+ * @brief Output queue insertion notification from the high driver.
*/
static void OutNotify2(void) {
@@ -127,9 +146,9 @@ static void OutNotify2(void) {
}
#endif
-#ifdef USE_USART3
-/*
- * USART3 IRQ service routine.
+#if USE_STM32_USART3 || defined(__DOXYGEN__)
+/**
+ * @brief USART3 IRQ service routine.
*/
CH_IRQ_HANDLER(VectorDC) {
@@ -140,9 +159,8 @@ CH_IRQ_HANDLER(VectorDC) {
CH_IRQ_EPILOGUE();
}
-/*
- * Invoked by the high driver when one or more bytes are inserted in the
- * output queue.
+/**
+ * @brief Output queue insertion notification from the high driver.
*/
static void OutNotify3(void) {
@@ -150,9 +168,15 @@ static void OutNotify3(void) {
}
#endif
-/*
- * USART setup, must be invoked with interrupts disabled.
- * NOTE: Does not reset I/O queues.
+/**
+ * @brief USART1 setup.
+ * @details This function must be invoked with interrupts disabled.
+ * @param[in] u pointer to an USART I/O block
+ * @param[in] speed serial port speed in bits per second
+ * @param[in] cr1 the value for the @p CR1 register
+ * @param[in] cr2 the value for the @p CR2 register
+ * @param[in] cr3 the value for the @p CR3 register
+ * @note Does not reset the I/O queues.
*/
void SetUSART(USART_TypeDef *u, uint32_t speed, uint16_t cr1,
uint16_t cr2, uint16_t cr3) {
@@ -173,34 +197,40 @@ void SetUSART(USART_TypeDef *u, uint32_t speed, uint16_t cr1,
u->CR3 = cr3 | CR3_EIE;
}
-/*
- * Serial subsystem initialization.
- * NOTE: Handshake pins are not switched to their function because they may have
- * another use. Enable them externally if needed.
+/**
+ * @brief Serial driver initialization.
+ * @param[in] prio1 priority to be assigned to the USART1 IRQ
+ * @param[in] prio2 priority to be assigned to the USART2 IRQ
+ * @param[in] prio3 priority to be assigned to the USART3 IRQ
+ * @note Handshake pads are not enabled inside this function because they
+ * may have another use, enable them externally if needed.
+ * RX and TX pads are handled inside.
*/
-void InitSerial(uint32_t prio1, uint32_t prio2, uint32_t prio3) {
+void stm32_serial_init(uint32_t prio1, uint32_t prio2, uint32_t prio3) {
-#ifdef USE_USART1
+#if USE_STM32_USART1
chFDDInit(&COM1, ib1, sizeof ib1, NULL, ob1, sizeof ob1, OutNotify1);
RCC->APB2ENR |= 0x00004000;
- SetUSART(USART1, USART_BITRATE, 0, CR2_STOP1_BITS | CR2_LINEN, 0);
+ SetUSART(USART1, STM32_USART_BITRATE, 0, CR2_STOP1_BITS | CR2_LINEN, 0);
GPIOA->CRH = (GPIOA->CRH & 0xFFFFF00F) | 0x000004B0;
NVICEnableVector(USART1_IRQChannel, prio1);
#endif
-#ifdef USE_USART2
+#if USE_STM32_USART2
chFDDInit(&COM2, ib2, sizeof ib2, NULL, ob2, sizeof ob2, OutNotify2);
RCC->APB1ENR |= 0x00020000;
- SetUSART(USART2, USART_BITRATE, 0, CR2_STOP1_BITS | CR2_LINEN, 0);
+ SetUSART(USART2, STM32_USART_BITRATE, 0, CR2_STOP1_BITS | CR2_LINEN, 0);
GPIOA->CRL = (GPIOA->CRL & 0xFFFF00FF) | 0x00004B00;
NVICEnableVector(USART2_IRQChannel, prio2);
#endif
-#ifdef USE_USART3
+#if USE_STM32_USART3
chFDDInit(&COM3, ib3, sizeof ib3, NULL, ob3, sizeof ob3, OutNotify3);
RCC->APB1ENR |= 0x00040000;
- SetUSART(USART3, USART_BITRATE, 0, CR2_STOP1_BITS | CR2_LINEN, 0);
+ SetUSART(USART3, STM32_USART_BITRATE, 0, CR2_STOP1_BITS | CR2_LINEN, 0);
GPIOB->CRH = (GPIOB->CRH & 0xFFFF00FF) | 0x00004B00;
NVICEnableVector(USART3_IRQChannel, prio3);
#endif
}
+
+/** @} */
diff --git a/ports/ARMCM3-STM32F103/stm32_serial.h b/ports/ARMCM3-STM32F103/stm32_serial.h
index 93163dc50..4f0c622b2 100644
--- a/ports/ARMCM3-STM32F103/stm32_serial.h
+++ b/ports/ARMCM3-STM32F103/stm32_serial.h
@@ -17,88 +17,135 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
+/**
+ * @file ports/ARMCM3-STM32F103/stm32_serial.h
+ * @brief STM32F103 Serial driver macros and structures.
+ * @addtogroup STM32F103_SERIAL
+ * @{
+ */
+
#ifndef _STM32_SERIAL_H_
#define _STM32_SERIAL_H_
-//#define USE_USART1
-#define USE_USART2
-//#define USE_USART3
-
-/*
- * Configuration parameter, you can change the depth of the queue buffers
- * depending on the requirements of your application.
+/**
+ * @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 Default bit rate.
+ * @details Configuration parameter, at startup the USARTs are configured at
+ * this speed.
+ * @note It is possible to use @p SetUSART() in order to change the working
+ * parameters at runtime.
+ */
+#if !defined(STM32_USART_BITRATE) || defined(__DOXYGEN__)
+#define STM32_USART_BITRATE 38400
+#endif
+
+/**
+ * @brief USART1 driver enable switch.
+ * @details If set to @p TRUE the support for USART1 is included.
+ * @note The default is @p FALSE.
+ */
+#if !defined(USE_STM32_USART1) || defined(__DOXYGEN__)
+#define USE_STM32_USART1 FALSE
+#endif
+
+/**
+ * @brief USART2 driver enable switch.
+ * @details If set to @p TRUE the support for USART2 is included.
+ * @note The default is @p TRUE.
+ */
+#if !defined(USE_STM32_USART2) || defined(__DOXYGEN__)
+#define USE_STM32_USART2 1
+#endif
+
+/**
+ * @brief USART3 driver enable switch.
+ * @details If set to @p TRUE the support for USART3 is included.
+ * @note The default is @p FALSE.
+ */
+#if !defined(USE_STM32_USART3) || defined(__DOXYGEN__)
+#define USE_STM32_USART3 FALSE
+#endif
/*
- * USARTs definitions here, ST headers are not good enough IMHO.
+ * USARTs definitions here.
*/
-#define SR_PE (1 << 0)
-#define SR_FE (1 << 1)
-#define SR_NE (1 << 2)
-#define SR_ORE (1 << 3)
-#define SR_IDLE (1 << 4)
-#define SR_RXNE (1 << 5)
-#define SR_TC (1 << 6)
-#define SR_TXE (1 << 7)
-#define SR_LBD (1 << 8)
-#define SR_CTS (1 << 9)
-
-#define CR1_SBK (1 << 0)
-#define CR1_RWU (1 << 1)
-#define CR1_RE (1 << 2)
-#define CR1_TE (1 << 3)
-#define CR1_IDLEIE (1 << 4)
-#define CR1_RXNEIE (1 << 5)
-#define CR1_TCIE (1 << 6)
-#define CR1_TXEIE (1 << 7)
-#define CR1_PEIE (1 << 8)
-#define CR1_PS (1 << 9)
-#define CR1_PCE (1 << 10)
-#define CR1_WAKE (1 << 11)
-#define CR1_M (1 << 12)
-#define CR1_UE (1 << 13)
-
-#define CR2_ADD_MASK (15 << 0)
-#define CR2_LBDL (1 << 5)
-#define CR2_LBDIE (1 << 6)
-#define CR2_CBCL (1 << 8)
-#define CR2_CPHA (1 << 9)
-#define CR2_CPOL (1 << 10)
-#define CR2_CLKEN (1 << 11)
-#define CR2_STOP_MASK (3 << 12)
-#define CR2_STOP1_BITS (0 << 12)
-#define CR2_STOP0P5_BITS (1 << 12)
-#define CR2_STOP2_BITS (2 << 12)
-#define CR2_STOP1P5_BITS (3 << 12)
-#define CR2_LINEN (1 << 14)
-
-#define CR3_EIE (1 << 0)
-#define CR3_IREN (1 << 1)
-#define CR3_IRLP (1 << 2)
-#define CR3_HDSEL (1 << 3)
-#define CR3_NACK (1 << 4)
-#define CR3_SCEN (1 << 5)
-#define CR3_DMAR (1 << 6)
-#define CR3_DMAT (1 << 7)
-#define CR3_RTSE (1 << 8)
-#define CR3_CTSE (1 << 9)
-#define CR3_CTSIE (1 << 10)
-
-#ifdef USE_USART1
+#define SR_PE (1 << 0) /**< @brief SR PE bit.*/
+#define SR_FE (1 << 1) /**< @brief SR FE bit.*/
+#define SR_NE (1 << 2) /**< @brief SR NE bit.*/
+#define SR_ORE (1 << 3) /**< @brief SR ORE bit.*/
+#define SR_IDLE (1 << 4) /**< @brief SR IDLE bit.*/
+#define SR_RXNE (1 << 5) /**< @brief SR RXNE bit.*/
+#define SR_TC (1 << 6) /**< @brief SR TC bit.*/
+#define SR_TXE (1 << 7) /**< @brief SR TXE bit.*/
+#define SR_LBD (1 << 8) /**< @brief SR LBD bit.*/
+#define SR_CTS (1 << 9) /**< @brief SR CTS bit.*/
+
+#define CR1_SBK (1 << 0) /**< @brief CR1 SBK bit.*/
+#define CR1_RWU (1 << 1) /**< @brief CR1 RWU bit.*/
+#define CR1_RE (1 << 2) /**< @brief CR1 RE bit.*/
+#define CR1_TE (1 << 3) /**< @brief CR1 TE bit.*/
+#define CR1_IDLEIE (1 << 4) /**< @brief CR1 IDLEIE bit.*/
+#define CR1_RXNEIE (1 << 5) /**< @brief CR1 RXNEIE bit.*/
+#define CR1_TCIE (1 << 6) /**< @brief CR1 TCTE bit.*/
+#define CR1_TXEIE (1 << 7) /**< @brief CR1 TXEIE bit.*/
+#define CR1_PEIE (1 << 8) /**< @brief CR1 PEIE bit.*/
+#define CR1_PS (1 << 9) /**< @brief CR1 PS bit.*/
+#define CR1_PCE (1 << 10) /**< @brief CR1 PCE bit.*/
+#define CR1_WAKE (1 << 11) /**< @brief CR1 WAKE bit.*/
+#define CR1_M (1 << 12) /**< @brief CR1 M bit.*/
+#define CR1_UE (1 << 13) /**< @brief CR1 UE bit.*/
+
+#define CR2_ADD_MASK (15 << 0) /**< @brief CR2 ADD field mask.*/
+#define CR2_LBDL (1 << 5) /**< @brief CR2 LBDL bit.*/
+#define CR2_LBDIE (1 << 6) /**< @brief CR2 LBDIE bit.*/
+#define CR2_CBCL (1 << 8) /**< @brief CR2 CBCL bit.*/
+#define CR2_CPHA (1 << 9) /**< @brief CR2 CPHA bit.*/
+#define CR2_CPOL (1 << 10) /**< @brief CR2 CPOL bit.*/
+#define CR2_CLKEN (1 << 11) /**< @brief CR2 CLKEN bit.*/
+#define CR2_STOP_MASK (3 << 12) /**< @brief CR2 STOP field mask.*/
+#define CR2_STOP1_BITS (0 << 12) /**< @brief CR2 1 stop bit value.*/
+#define CR2_STOP0P5_BITS (1 << 12) /**< @brief CR2 0.5 stop bit value.*/
+#define CR2_STOP2_BITS (2 << 12) /**< @brief CR2 2 stop bit value.*/
+#define CR2_STOP1P5_BITS (3 << 12) /**< @brief CR2 1.5 stop bit value.*/
+#define CR2_LINEN (1 << 14) /**< @brief CR2 LINEN bit.*/
+
+#define CR3_EIE (1 << 0) /**< @brief CR3 EIE bit.*/
+#define CR3_IREN (1 << 1) /**< @brief CR3 IREN bit.*/
+#define CR3_IRLP (1 << 2) /**< @brief CR3 IRLP bit.*/
+#define CR3_HDSEL (1 << 3) /**< @brief CR3 HDSEL bit.*/
+#define CR3_NACK (1 << 4) /**< @brief CR3 NACK bit.*/
+#define CR3_SCEN (1 << 5) /**< @brief CR3 SCEN bit.*/
+#define CR3_DMAR (1 << 6) /**< @brief CR3 DMAR bit.*/
+#define CR3_DMAT (1 << 7) /**< @brief CR3 DMAT bit.*/
+#define CR3_RTSE (1 << 8) /**< @brief CR3 RTSE bit.*/
+#define CR3_CTSE (1 << 9) /**< @brief CR3 CTSE bit.*/
+#define CR3_CTSIE (1 << 10) /**< @brief CR3 CTSIE bit.*/
+
+/** @cond never*/
+#if USE_STM32_USART1
extern FullDuplexDriver COM1;
#endif
-#ifdef USE_USART2
+#if USE_STM32_USART2
extern FullDuplexDriver COM2;
#endif
-#ifdef USE_USART3
+#if USE_STM32_USART3
extern FullDuplexDriver COM3;
#endif
+/** @endcond*/
#ifdef __cplusplus
extern "C" {
#endif
- void InitSerial(uint32_t prio1, uint32_t prio2, uint32_t prio3);
+ void stm32_serial_init(uint32_t prio1, uint32_t prio2, uint32_t prio3);
void SetUSART(USART_TypeDef *u, uint32_t speed, uint16_t cr1,
uint16_t cr2, uint16_t cr3);
#ifdef __cplusplus
@@ -106,3 +153,5 @@ extern "C" {
#endif
#endif /* _STM32_SERIAL_H_ */
+
+/** @} */
diff --git a/ports/MSP430/msp430_serial.c b/ports/MSP430/msp430_serial.c
index 6bac2bab9..81e09a195 100644
--- a/ports/MSP430/msp430_serial.c
+++ b/ports/MSP430/msp430_serial.c
@@ -178,9 +178,9 @@ static void OutNotify2(void) {
/**
* @brief USART1 setup.
* @details This function must be invoked with interrupts disabled.
- * @param div The divider value as calculated by the @p UBR() macro.
- * @param mod The value for the @p U1MCTL register.
- * @param ctl The value for the @p U1CTL register.
+ * @param[in] div the divider value as calculated by the @p UBR() macro
+ * @param[in] mod the value for the @p U1MCTL register
+ * @param[in] ctl the value for the @p U1CTL register.
* @note Does not reset the I/O queues.
*/
void SetUSART1(uint16_t div, uint8_t mod, uint8_t ctl) {
diff --git a/src/chheap.c b/src/chheap.c
index 72be4a57f..46b26f7d8 100644
--- a/src/chheap.c
+++ b/src/chheap.c
@@ -231,7 +231,7 @@ static Semaphore hsem;
#error "The heap allocator requires mutexes or semaphores to be enabled"
#endif
-void chHeapInit(void) {
+void heap_init(void) {
#if defined(CH_USE_MUTEXES)
chMtxInit(&hmtx);