From 7855cb3707a7b6dcbb120da14bc7d92f3bcb7d12 Mon Sep 17 00:00:00 2001
From: Hauke Petersen <hauke.petersen@fu-berlin.de>
Date: Fri, 18 Sep 2015 23:00:31 +0200
Subject: [PATCH] sys: added module for running Arduino code

---
 Makefile.dep                       |   6 +
 sys/Makefile.include               |   4 +
 sys/arduino/Makefile               |   1 +
 sys/arduino/Makefile.include       |   9 +
 sys/arduino/base.cpp               |  61 ++++++
 sys/arduino/doc.txt                | 136 +++++++++++++
 sys/arduino/include/arduino.hpp    |  86 +++++++++
 sys/arduino/include/serialport.hpp | 301 +++++++++++++++++++++++++++++
 sys/arduino/post.snip              |  12 ++
 sys/arduino/pre.snip               |   1 +
 sys/arduino/serialport.cpp         | 181 +++++++++++++++++
 11 files changed, 798 insertions(+)
 create mode 100644 sys/arduino/Makefile
 create mode 100644 sys/arduino/Makefile.include
 create mode 100644 sys/arduino/base.cpp
 create mode 100644 sys/arduino/doc.txt
 create mode 100644 sys/arduino/include/arduino.hpp
 create mode 100644 sys/arduino/include/serialport.hpp
 create mode 100644 sys/arduino/post.snip
 create mode 100644 sys/arduino/pre.snip
 create mode 100644 sys/arduino/serialport.cpp

diff --git a/Makefile.dep b/Makefile.dep
index 8d2327454f..e6c600a0e4 100644
--- a/Makefile.dep
+++ b/Makefile.dep
@@ -381,6 +381,12 @@ ifneq (,$(filter schedstatistics,$(USEMODULE)))
     USEMODULE += xtimer
 endif
 
+ifneq (,$(filter arduino,$(USEMODULE)))
+    FEATURES_REQUIRED += arduino
+    FEATURES_REQUIRED += cpp
+    USEMODULE += xtimer
+endif
+
 ifneq (,$(filter xtimer,$(USEMODULE)))
     FEATURES_REQUIRED += periph_timer
 endif
diff --git a/sys/Makefile.include b/sys/Makefile.include
index eb3523ce0e..38b9fef9c6 100644
--- a/sys/Makefile.include
+++ b/sys/Makefile.include
@@ -65,4 +65,8 @@ ifneq (,$(filter newlib,$(USEMODULE)))
     include $(RIOTBASE)/sys/newlib/Makefile.include
 endif
 
+ifneq (,$(filter arduino,$(USEMODULE)))
+    include $(RIOTBASE)/sys/arduino/Makefile.include
+endif
+
 INCLUDES += -I$(RIOTBASE)/sys/libc/include
diff --git a/sys/arduino/Makefile b/sys/arduino/Makefile
new file mode 100644
index 0000000000..48422e909a
--- /dev/null
+++ b/sys/arduino/Makefile
@@ -0,0 +1 @@
+include $(RIOTBASE)/Makefile.base
diff --git a/sys/arduino/Makefile.include b/sys/arduino/Makefile.include
new file mode 100644
index 0000000000..02a3cf8614
--- /dev/null
+++ b/sys/arduino/Makefile.include
@@ -0,0 +1,9 @@
+# compile together the Arduino sketches of the application
+SKETCHES = $(wildcard $(APPDIR)*.sketch)
+SRCDIR = $(RIOTBASE)/sys/arduino
+
+# run the Arduino pre-build script
+$(shell $(RIOTBASE)/dist/tools/arduino/pre_build.sh $(SRCDIR) $(APPDIR) $(SKETCHES))
+
+# include the Arduino headers
+export INCLUDES += -I$(RIOTBASE)/sys/arduino/include
diff --git a/sys/arduino/base.cpp b/sys/arduino/base.cpp
new file mode 100644
index 0000000000..d3c06be1ab
--- /dev/null
+++ b/sys/arduino/base.cpp
@@ -0,0 +1,61 @@
+/*
+ * Copyright (C) 2015 Freie Universität Berlin
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser General
+ * Public License v2.1. See the file LICENSE in the top level directory for more
+ * details.
+ */
+
+/**
+ * @ingroup     sys_arduino
+ * @{
+ *
+ * @file
+ * @brief       Implementation of Arduino core functionality
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ *
+ * @}
+ */
+
+extern "C" {
+#include "xtimer.h"
+#include "periph/gpio.h"
+}
+
+#include "arduino.hpp"
+
+static inline gpio_dir_t _dir(int mode)
+{
+    return (mode == OUTPUT) ? GPIO_DIR_OUT : GPIO_DIR_IN;
+}
+
+static inline gpio_pp_t _pr(int mode)
+{
+    return (mode == INPUT_PULLUP) ? GPIO_PULLUP : GPIO_NOPULL;
+}
+
+void pinMode(int pin, int mode)
+{
+    gpio_init(arduino_pinmap[pin], _dir(mode), _pr(mode));
+}
+
+void digitalWrite(int pin, int state)
+{
+    gpio_write(arduino_pinmap[pin], state);
+}
+
+int digitalRead(int pin)
+{
+    if (gpio_read(arduino_pinmap[pin])) {
+        return HIGH;
+    }
+    else {
+        return LOW;
+    }
+}
+
+void delay(int msec)
+{
+    xtimer_usleep(1000 * msec);
+}
diff --git a/sys/arduino/doc.txt b/sys/arduino/doc.txt
new file mode 100644
index 0000000000..9f2cb75c43
--- /dev/null
+++ b/sys/arduino/doc.txt
@@ -0,0 +1,136 @@
+/**
+ * @defgroup    sys_arduino Arduino
+ * @ingroup     sys
+ * @brief       Arduino in RIOT
+ *
+ * @section sec_about About
+ *
+ * This module enables users to run unmodified Arduino sketches in RIOT. For
+ * this we aim at supporting the full Arduino API.
+ *
+ * The support of the Arduino API in RIOT is useful for multiple reasons:
+ * - starting point for beginners
+ * - run your existing sketches on any non-Arduino hardware supported by RIOT
+ * - makes it easy to move from Arduino to RIOT
+ * - use Ardunio device drivers in RIOT
+ * - is fun to implement :-)
+ *
+ * Refer to @ref sys_arduino_api for the actual API documentation
+ *
+ *
+ * @section sec_usage General usage
+ *
+ * To run you Arduino sketch in RIOT, just follow these steps:
+ *
+ * -# create an empty application
+ * -# add the `arduino` module to your application, your `Makefile` should now
+ *    look something like this:
+ * @code
+ * APPLICATION = YOUR_APP_NAME
+ * BOARD ?= YOUR_TARGET_PLATFORM
+ * RIOTBASE ?= PATH_TO_RIOT_ROOT
+ *
+ * USEMODULE += arduino
+ *
+ * include $(RIOTBASE)/Makefile.include
+ * @endcode
+ *
+ * -# copy you Arduino sktech(es) into your application folder. Currently they
+ *    must have the file ending `*.sketch` to be processed.
+ * -# build, flash, and run your application the usual RIOT-way: simply call
+ *    `make all`, `make flash`, `make term`, etc.
+ *
+ * Thats all. As bonus you can of course use any existing RIOT code inside your
+ * Arduino sketches - you simply have to add the includes to your sketch and
+ * the corresponding modules to your `Makefile`.
+ *
+ * @note  So far, all Arduino sketches MUST have the file ending `*.sketch` to
+ *        be recognized by RIOT's build system
+ *
+ *
+ * @section sec_concept Concept
+ *
+ * For enabling RIOT to run Arduino sketches, we extended the build system to
+ * handle `*.sketch` files and we implemented the Arduino API using RIOT's
+ * native functions.
+ *
+ * @subsection sec_concept_build Extension of the build system
+ *
+ * Building Arduino sketches in RIOT is done in a two step process.
+ *
+ * First, the make system calls a dedicated
+ * [Arduino build script](https://github.com/RIOT-OS/RIOT/tree/master/dist/tools/arduino/pre_build.sh),
+ * which is called from the
+ * [Makefile.include](https://github.com/RIOT-OS/RIOT/tree/master/sys/arduino/Makefile.include)
+ * of the RIOT Arduino module.
+ *
+ * This script creates a temporary file called '_sketches.cpp' inside the
+ * application folder. Into this file, the script copies some Arduino glue code (
+ * [pre.snip](https://github.com/RIOT-OS/RIOT/blob/master/sys/arduino/pre.snip)
+ *  and
+ * [post.snip](https://github.com/RIOT-OS/RIOT/blob/master/sys/arduino/post.snip))
+ * together with the contents of all `*.sketch` files contained in the
+ * application folder.
+ *
+ * Second, the RIOT make system is called as usual, processing the temporary
+ * file containing all the Arduino code. Simple :-)
+ *
+ * @subsection sec_conecpt_api Implementation of the Arduino API
+ *
+ * For supporting the Arduino API, we have created our own function and class
+ * definitions, using the exact same signatures as in the original Arduino
+ * header files. These headers are then implemented using standard RIOT APIs,
+ * e.g. the peripheral drivers, `xtimer`, etc.
+ *
+ *
+ * @section sec_boardsupport Add Arduino support to a board
+ *
+ * @note As prerequisite, the board must have support for C++.
+ *
+ * To add Arduino support to a board, it has to provice the following:
+ *
+ * In `RIOT/board/BOARD/include/arduino_board.h`:
+ * - a mapping of GPIO pins to Arduino pin numbers named `arduino_pinmap`, e.g.
+ * @code{c}
+ *  static const gpio_t arduino_pinmap[] = {
+ *      GPIO_PIN(PORT_D, 12),
+ *      GPIO_PIN(PORT_D, 13),
+ *      GPIO_PIN(PORT_D, 14),
+ *      GPIO_PIN(PORT_D, 15),
+ *      GPIO_PIN(PORT_A, 12),
+ *      GPIO_PIN(PORT_A, 15),
+ *      GPIO_PIN(PORT_B, 1),
+ *      GPIO_PIN(PORT_B, 2),
+ *      ...
+ *  };
+ * @endcode
+ *
+ * - a define `ARDUINO_LED` that is mapped to an Arduino pin number connected to
+ *   any on-board LED, or to pin 0 in case no LED is defined:
+ * @code{c}
+ *  #define ARDUINO_LED         (2)
+ * @endcode
+ *   This links to the third entry in the `arduino_pinmap` array.
+ *
+ * In addition, you have to add the 'arduino' feature to the board. for this,
+ * just add `FEATURES_PROVIDED += arduino` to the 'other features' section in
+ * your boards `Makefile.features'.
+ *
+ * That's it, your board can now run Ardunio sketches.
+ *
+ *
+ * @section sec_todo Open issues
+ *
+ * @todo Make it possible to bootstrap Arduino code manually from any RIOT
+ *       application. Include a pseudomule as e.g. arduino_base, which does not
+ *       implement a main function calling `setup()` and `loop()`, so these
+ *       functions have to be called manually from a RIOT application.
+ * @todo Implement analog outputs (PWM mapping)
+ * @todo Implement analog inputs (ADC mapping)
+ * @todo Implement SPI interface class
+ * @todo Add support for the 'Wrie Library' (I2C)
+ * @todo Add means to include various Arduino Libraries (maybe as pkg?)
+ * @todo Implement anything else that is missing...
+ * @todo Adapt Arduino build script, so sketches do not have to have the file
+ *       ending `*.sketch` anymore
+ */
diff --git a/sys/arduino/include/arduino.hpp b/sys/arduino/include/arduino.hpp
new file mode 100644
index 0000000000..585a8ef004
--- /dev/null
+++ b/sys/arduino/include/arduino.hpp
@@ -0,0 +1,86 @@
+/*
+ * Copyright (C) 2015 Freie Universität Berlin
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser
+ * General Public License v2.1. See the file LICENSE in the top level
+ * directory for more details.
+ */
+
+/**
+ * @defgroup    sys_arduino_api Arduino API
+ * @ingroup     sys_arduino
+ * @brief       Implementation of the Arduino API in RIOT
+ * @{
+ *
+ * @file
+ * @brief       Main interface definition of the Arduino API
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ */
+
+#ifndef ARDUINO_H
+#define ARDUINO_H
+
+extern "C" {
+#include "periph/gpio.h"
+#include "arduino_board.h"
+}
+
+#include "serialport.hpp"
+
+/**
+ * @brief   Possible pin configurations
+ */
+enum {
+    INPUT,              /**< configure pin as input */
+    OUTPUT,             /**< configure pin as output */
+    INPUT_PULLUP,       /**< configure pin as input with pull-up resistor */
+};
+
+/**
+ * @brief   Possible pin states
+ */
+enum {
+    LOW = 0,            /**< pin is cleared */
+    HIGH = 1,           /**< pin is set */
+};
+
+/**
+ * @brief   Primary serial port (mapped to UART_DEV(0))
+ */
+static SerialPort Serial(UART_DEV(0));
+
+/**
+ * @brief   Configure a pin as either input or output
+ *
+ * @param[in] pin       pin to configure
+ * @param[in] mode      mode to set the pin to
+ */
+void pinMode(int pin, int mode);
+
+/**
+ * @brief   Set the value for the given pin
+ *
+ * @param[in] pin       pin to set
+ * @param[in] state     HIGH or LOW
+ */
+void digitalWrite(int pin, int state);
+
+/**
+ * @brief   Read the current state of the given pin
+ *
+ * @param[in] pin       pin to read
+ *
+ * @return  state of the given pin, HIGH or LOW
+ */
+int digitalRead(int pin);
+
+/**
+ * @brief   Sleep for a given amount of time [milliseconds]
+ *
+ * @param[in] msec      number of milliseconds to sleep
+ */
+void delay(int msec);
+
+#endif /* ARDUINO_H */
+/** @} */
diff --git a/sys/arduino/include/serialport.hpp b/sys/arduino/include/serialport.hpp
new file mode 100644
index 0000000000..6acbb49456
--- /dev/null
+++ b/sys/arduino/include/serialport.hpp
@@ -0,0 +1,301 @@
+/*
+ * Copyright (C) 2015 Freie Universität Berlin
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser
+ * General Public License v2.1. See the file LICENSE in the top level
+ * directory for more details.
+ */
+
+/**
+ * @ingroup     sys_arduino_api
+ * @{
+ *
+ * @file
+ * @brief       Definition of the Arduino 'Serial' interface
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ */
+
+#ifndef ARDUINO_SERIAL_H
+#define ARDUINO_SERIAL_H
+
+extern "C" {
+#include "ringbuffer.h"
+#include "periph/uart.h"
+}
+
+/**
+ * @brief   Default RX buffer size - same as the original Arduino...
+ */
+#define SERIAL_RX_BUFSIZE       (64)
+
+/**
+ * @brief   Formatting options for Serial.print(int, format)
+ */
+enum SerialFormat {
+    BIN,            /**< format to binary representation */
+    OCT,            /**< format to octal representation */
+    DEC,            /**< format to decimal representation */
+    HEX,            /**< format to hex representation */
+};
+
+/**
+ * @brief   Arduino Serial Interface
+ */
+class SerialPort {
+
+private:
+    uart_t dev;
+    char rx_mem[SERIAL_RX_BUFSIZE];
+    ringbuffer_t rx_buf;
+
+public:
+    /**
+     * @brief   Constructor maps the serial port to a RIOT UART device
+     *
+     * @param[in] dev       RIOT UART device
+     */
+    SerialPort(uart_t dev);
+
+    /**
+     * @brief   Get the number of bytes (characters) available for reading from
+     *          the serial port
+     *
+     * This is data that's already arrived and stored in the serial receive
+     * buffer (which holds 64 bytes). available() inherits from the Stream
+     * utility class.
+     *
+     * Copied from https://www.arduino.cc/en/Serial/Available
+     *
+     * @return  The number of bytes available to read
+     */
+    int available(void);
+
+    /**
+     * @brief   Sets the data rate in bits per second (baud) for serial data
+     *          transmission
+     *
+     * For communicating with the computer, use one of these rates: 300, 600,
+     * 1200, 2400, 4800, 9600, 14400, 19200, 28800, 38400, 57600, or 115200. You
+     * can, however, specify other rates - for example, to communicate over
+     * pins 0 and 1 with a component that requires a particular baud rate.
+     *
+     * Copied from https://www.arduino.cc/en/Serial/Begin
+     *
+     * @param[in] speed     speed in bits per second (baud)
+     */
+    void begin(int speed);
+
+    /**
+     * @brief   Disables serial communication, allowing the RX and TX pins to be
+     *          used for general input and output
+     *
+     * To re-enable serial communication, call @ref begin()
+     *
+     * Copied from https://www.arduino.cc/en/Serial/End
+     */
+    void end(void);
+
+    /**
+     * @brief   Prints data to the serial port as human-readable ASCII text
+     *
+     * Prints data to the serial port as human-readable ASCII text. This command
+     * can take many forms. Numbers are printed using an ASCII character for
+     * each digit. Floats are similarly printed as ASCII digits, defaulting to
+     * two decimal places. Bytes are sent as a single character. Characters and
+     * strings are sent as is.
+     *
+     * Copied from https://www.arduino.cc/en/Serial/Print
+     *
+     * @param[in] val       the value to print
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    size_t print(int val);
+
+    /**
+     * @brief   Prints data to the serial port as human-readable ASCII text
+     *
+     * @see print()
+     *
+     * @param[in] val       the value to print
+     * @param[in] format    specifies the number base
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    size_t print(int val, SerialFormat format);
+
+    /**
+     * @brief   Prints data to the serial port as human-readable ASCII text
+     *
+     * @param[in] val       the value to print
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    size_t print(float val);
+
+    /**
+     * @brief   Prints data to the serial port as human-readable ASCII text
+     *
+     * @see print()
+     *
+     * @param[in] val       the value to print
+     * @param[in] format    number of decimal places
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    size_t print(float val, int format);
+
+    /**
+     * @brief   Prints data to the serial port as human-readable ASCII text
+     *
+     * @see print()
+     *
+     * @param[in] val       the value to print
+     *
+    * @return  the number of bytes written, reading that number is optional
+     */
+    size_t print(char val);
+
+    /**
+     * @brief   Prints data to the serial port as human-readable ASCII text
+     *
+     * @see print()
+     *
+     * @param[in] val       the value to print
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    size_t print(const char *val);
+
+    /**
+     * @brief   Prints data to the serial port as human-readable ASCII text
+     *          followed by a carriage return character (ASCII 13, or "\r") and
+     *          a newline character (ASCII 10, or "\n")
+     *
+     * This command takes the same forms as @ref print().
+     *
+     * Copied from https://www.arduino.cc/en/Serial/Println
+     *
+     * @param[in] val       the value to print
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    size_t println(int val);
+
+    /**
+     * @brief   Prints data to the serial port as human-readable ASCII text
+     *          followed by a carriage return character (ASCII 13, or "\r") and
+     *          a newline character (ASCII 10, or "\n")
+     *
+     * @see println()
+     *
+     * @param[in] val       the value to print
+     * @param[in] format    specifies the number base
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    size_t println(int val, SerialFormat format);
+
+    /**
+     * @brief   Prints data to the serial port as human-readable ASCII text
+     *          followed by a carriage return character (ASCII 13, or "\r") and
+     *          a newline character (ASCII 10, or "\n")
+     *
+     * @see println()
+     *
+     * @param[in] val       the value to print
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    size_t println(float val);
+
+    /**
+     * @brief   Prints data to the serial port as human-readable ASCII text
+     *          followed by a carriage return character (ASCII 13, or "\r") and
+     *          a newline character (ASCII 10, or "\n")
+     *
+     * @see println()
+     *
+     * @param[in] val       the value to print
+     * @param[in] format    number of decimal places
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    size_t println(float val, int format);
+
+    /**
+     * @brief   Prints data to the serial port as human-readable ASCII text
+     *          followed by a carriage return character (ASCII 13, or "\r") and
+     *          a newline character (ASCII 10, or "\n")
+     *
+     * @see println()
+     *
+     * @param[in] val       the value to print
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    size_t println(char val);
+
+    /**
+     * @brief   Prints data to the serial port as human-readable ASCII text
+     *          followed by a carriage return character (ASCII 13, or "\r") and
+     *          a newline character (ASCII 10, or "\n")
+     *
+     * @see println()
+     *
+     * @param[in] val       the value to print
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    size_t println(const char *val);
+
+    /**
+     * @brief   Reads incoming serial data
+     *
+     * Copied from https://www.arduino.cc/en/Serial/Read
+     *
+     * @return  the first byte of incoming serial data available
+     * @return  -1 if no data is available
+     */
+    int read(void);
+
+    /**
+     * @brief   Writes binary data to the serial port
+     *
+     * This data is sent as a byte or series of bytes; to send the characters
+     * representing the digits of a number use the @ref print() function instead.
+     *
+     * Copied from https://www.arduino.cc/en/Serial/Write
+     *
+     * @param[in] val       a value to send as a single byte
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    int write(int val);
+
+    /**
+     * @brief   Writes binary data to the serial port
+     *
+     * @see write()
+     *
+     * @param[in] str       a string to send as a series of bytes
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    int write(const char *str);
+
+    /**
+     * @brief   Writes binary data to the serial port
+     * @details [long description]
+     *
+     * @param[in] buf       an array to send as a series of bytes
+     * @param[in] len       the length of the buffer
+     *
+     * @return  the number of bytes written, reading that number is optional
+     */
+    int write(char *buf, int len);
+};
+
+#endif /* ARDUINO_SERIAL_H */
+/** @} */
diff --git a/sys/arduino/post.snip b/sys/arduino/post.snip
new file mode 100644
index 0000000000..bfe083e5d7
--- /dev/null
+++ b/sys/arduino/post.snip
@@ -0,0 +1,12 @@
+
+int main(void)
+{
+    /* run the Arduino setup */
+    setup();
+    /* and the event loop */
+    while (1) {
+        loop();
+    }
+    /* never reached */
+    return 0;
+}
diff --git a/sys/arduino/pre.snip b/sys/arduino/pre.snip
new file mode 100644
index 0000000000..48d08c5572
--- /dev/null
+++ b/sys/arduino/pre.snip
@@ -0,0 +1 @@
+#include "arduino.hpp"
diff --git a/sys/arduino/serialport.cpp b/sys/arduino/serialport.cpp
new file mode 100644
index 0000000000..c9512be576
--- /dev/null
+++ b/sys/arduino/serialport.cpp
@@ -0,0 +1,181 @@
+/*
+ * Copyright (C) 2015 Freie Universität Berlin
+ *
+ * This file is subject to the terms and conditions of the GNU Lesser General
+ * Public License v2.1. See the file LICENSE in the top level directory for more
+ * details.
+ */
+
+/**
+ * @ingroup     sys_arduino
+ * @{
+ *
+ * @file
+ * @brief       Implementation of the Arduino 'Serial' interface
+ *
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
+ *
+ * @}
+ */
+extern "C" {
+#include <stdint.h>
+#include <string.h>
+#include <stdio.h>
+
+#include "irq.h"
+}
+
+#include "serialport.hpp"
+
+void rx_cb(void *arg, char c)
+{
+    ringbuffer_t *buf = (ringbuffer_t *)arg;
+    ringbuffer_add_one(buf, c);
+}
+
+SerialPort::SerialPort(uart_t dev)
+{
+    this->dev = dev;
+}
+
+int SerialPort::available(void)
+{
+    return (int)rx_buf.avail;
+}
+
+void SerialPort::begin(int baudrate)
+{
+    /* this clears the contents of the ringbuffer... */
+    ringbuffer_init(&rx_buf, rx_mem, SERIAL_RX_BUFSIZE);
+    uart_init(dev, (uint32_t)baudrate, rx_cb, (void *)&rx_buf);
+}
+
+void SerialPort::end(void)
+{
+    uart_poweroff(dev);
+}
+
+size_t SerialPort::print(int val)
+{
+    return print(val, DEC);
+}
+
+size_t SerialPort::print(int val, SerialFormat format)
+{
+    char buf[64];
+    size_t len;
+    switch (format) {
+        case BIN:
+            /* TODO */
+            return 0;
+        case OCT:
+            len = sprintf(buf, "%o", (unsigned)val);
+            break;
+        case DEC:
+            len = sprintf(buf, "%i", val);
+            break;
+        case HEX:
+            len = sprintf(buf, "%x", (unsigned)val);
+            break;
+        default:
+            return 0;
+    }
+    write(buf, len);
+    return len;
+}
+
+size_t SerialPort::print(float val)
+{
+    return print(val, 2);
+}
+
+size_t SerialPort::print(float val, int format)
+{
+    char buf[64];
+    size_t len = sprintf(buf, "%.*f", format, val);
+    write(buf, len);
+    return len;
+}
+
+size_t SerialPort::print(char val)
+{
+    return (size_t)write((int)val);
+}
+
+size_t SerialPort::print(const char *val)
+{
+    return (size_t)write(val);
+}
+
+size_t SerialPort::println(int val)
+{
+    size_t res = print(val);
+    write("\r\n");
+    return (res + 2);
+}
+
+size_t SerialPort::println(int val, SerialFormat format)
+{
+    size_t res = print(val, format);
+    write("\r\n");
+    return (res + 2);
+}
+
+size_t SerialPort::println(float val)
+{
+    size_t res = print(val);
+    write("\r\n");
+    return (res + 2);
+}
+
+size_t SerialPort::println(float val, int format)
+{
+    size_t res = print(val, format);
+    write("\r\n");
+    return (res + 2);
+}
+
+size_t SerialPort::println(char val)
+{
+    size_t res = print(val);
+    write("\r\n");
+    return (res + 2);
+}
+
+size_t SerialPort::println(const char *val)
+{
+    size_t res = print(val);
+    write("\r\n");
+    return (res + 2);
+}
+
+int SerialPort::read(void)
+{
+    int res = -1;
+
+    disableIRQ();
+    if (rx_buf.avail > 0) {
+        res = ringbuffer_get_one(&rx_buf);
+    }
+    enableIRQ();
+
+    return res;
+}
+
+int SerialPort::write(int val)
+{
+    uart_write(dev, (uint8_t *)&val, 1);
+    return 1;
+}
+
+int SerialPort::write(const char *str)
+{
+    uart_write(dev, (uint8_t *)str, strlen(str));
+    return strlen(str);
+}
+
+int SerialPort::write(char *buf, int len)
+{
+    uart_write(dev, (uint8_t *)buf, len);
+    return len;
+}
-- 
GitLab