Skip to content

Commit

Permalink
[nRF52] Arduinize some APIs and implement missing methods
Browse files Browse the repository at this point in the history
  • Loading branch information
facchinm committed Jun 21, 2019
1 parent 506a945 commit bb77ad5
Show file tree
Hide file tree
Showing 15 changed files with 300 additions and 47 deletions.
17 changes: 15 additions & 2 deletions cores/arduino/Arduino.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ using namespace arduino;
extern "C"{
#endif

// avr-libc defines _NOP() since 1.6.2
#ifndef _NOP
#define _NOP() do { __asm__ volatile ("nop"); } while (0)
#endif
Expand All @@ -65,12 +64,25 @@ extern "C"{
#endif // abs
#define abs(x) ((x)>0?(x):-(x))

#define interrupts() __enable_irq()
#define noInterrupts() __disable_irq()

#ifdef __cplusplus
} // extern "C"
#endif

#include "pins_arduino.h"

/* Types used for the table below */
typedef struct _PinDescription
{
PinName name;
mbed::InterruptIn* irq;
} PinDescription ;

/* Pins table to be instantiated into variant.cpp */
extern PinDescription g_APinDescription[];

#include "Serial.h"
#if defined(SERIAL_CDC)
#define Serial SerialUSB
Expand All @@ -83,6 +95,7 @@ extern "C"{
#define Serial2 UART3
#endif

#include "RPC.h"
#include "RPC_internal.h"
#include "overloads.h"

#endif
13 changes: 13 additions & 0 deletions cores/arduino/Interrupts.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,19 @@

#include "Arduino.h"

void attachInterruptParam(PinName interruptNum, voidFuncPtrParam func, PinStatus mode, void* param) {
mbed::InterruptIn* irq = new mbed::InterruptIn(interruptNum);
if (mode == FALLING) {
irq->fall(mbed::callback(func, param));
} else {
irq->rise(mbed::callback(func, param));
}
}

void attachInterrupt(PinName interruptNum, voidFuncPtr func, PinStatus mode) {
attachInterruptParam(interruptNum, (voidFuncPtrParam)func, mode, NULL);
}

void attachInterruptParam(pin_size_t interruptNum, voidFuncPtrParam func, PinStatus mode, void* param) {
mbed::InterruptIn* irq = new mbed::InterruptIn((PinName)interruptNum);
if (mode == FALLING) {
Expand Down
15 changes: 6 additions & 9 deletions cores/arduino/Serial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,18 +13,15 @@ void UART::begin(unsigned long baudrate, uint16_t config) {

void UART::begin(unsigned long baudrate) {
if (_serial == NULL) {
_serial = new mbed::Serial(tx, rx, baudrate);
_serial = new mbed::RawSerial(tx, rx, baudrate);
}
#ifdef DEVICE_SERIAL_ASYNCH
_serial->read(intermediate_buf, 1, mbed::callback(this, &UART::on_rx));
#endif
_serial->attach(mbed::callback(this, &UART::on_rx), mbed::SerialBase::RxIrq);
}

void UART::on_rx(int howmany) {
rx_buffer.store_char(intermediate_buf[0]);
#ifdef DEVICE_SERIAL_ASYNCH
_serial->read(intermediate_buf, 1, mbed::callback(this, &UART::on_rx));
#endif
void UART::on_rx() {
while(_serial->readable()) {
rx_buffer.store_char(_serial->getc());
}
}

void UART::end() {
Expand Down
4 changes: 2 additions & 2 deletions cores/arduino/Serial.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ class UART : public HardwareSerial {
operator bool();

private:
void on_rx(int howmany);
mbed::Serial* _serial = NULL;
void on_rx();
mbed::RawSerial* _serial = NULL;
PinName tx, rx;
RingBufferN<256> rx_buffer;
uint8_t intermediate_buf[4];
Expand Down
3 changes: 3 additions & 0 deletions cores/arduino/macros.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
#define analogPinToPinName(P) (P < A0 ? g_APinDescription[P+A0].name : g_APinDescription[P].name)
#define digitalPinToPinName(P) (g_APinDescription[P].name)
#define digitalPinToInterrupt(P) (P)
Original file line number Diff line number Diff line change
Expand Up @@ -218,13 +218,6 @@ typedef enum {
D14 = p26,
D15 = p27,

A0 = p3,
A1 = p4,
A2 = p28,
A3 = p29,
A4 = p30,
A5 = p31,

/**** QSPI pins ****/
QSPI1_IO0 = P0_20,
QSPI1_IO1 = P0_21,
Expand Down
15 changes: 15 additions & 0 deletions cores/arduino/overloads.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
void pinMode(PinName pinNumber, PinMode pinMode);
void digitalWrite(PinName pinNumber, PinStatus status);
PinStatus digitalRead(PinName pinNumber);
int analogRead(PinName pinNumber);
void analogWrite(PinName pinNumber, int value);

unsigned long pulseIn(PinName pin, uint8_t state, unsigned long timeout);
unsigned long pulseInLong(PinName pin, uint8_t state, unsigned long timeout);

void shiftOut(PinName dataPin, PinName clockPin, BitOrder bitOrder, uint8_t val);
uint8_t shiftIn(PinName dataPin, PinName clockPin, BitOrder bitOrder);

void attachInterrupt(PinName interruptNumber, voidFuncPtr callback, PinStatus mode);
void attachInterruptParam(PinName interruptNumber, voidFuncPtrParam callback, PinStatus mode, void* param);
void detachInterrupt(PinName interruptNumber);
4 changes: 2 additions & 2 deletions cores/arduino/wiring.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,12 @@ unsigned long micros() {

void delay(unsigned long ms)
{
wait((float)ms / 1000.0f);
wait_ms(ms);
}

/* Delay for the given number of microseconds. Assumes a 1, 8, 12, 16, 20 or 24 MHz clock. */
void delayMicroseconds(unsigned int us)
{
wait_us(us);
}

void init()
Expand Down
30 changes: 26 additions & 4 deletions cores/arduino/wiring_analog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,15 +23,37 @@
#include "Arduino.h"
#include "pins_arduino.h"

static int resolution = 10;
static int write_resolution = 10;
static int read_resolution = 10;

void analogWrite(PinName pin, int val)
{
float percent = (float)val/(float)(1 << write_resolution);
mbed::PwmOut(pin).write(percent);
}

void analogWrite(pin_size_t pin, int val)
{
float percent = (float)val/(float)(1 << resolution);
mbed::PwmOut((PinName)pin).write(percent);
float percent = (float)val/(float)(1 << write_resolution);
mbed::PwmOut(digitalPinToPinName(pin)).write(percent);
}

void analogWriteResolution(int bits)
{
write_resolution = bits;
}

int analogRead(PinName pin)
{
return mbed::AnalogIn(pin).read_u16() >> (16 - read_resolution);
}

int analogRead(pin_size_t pin)
{
return mbed::AnalogIn((PinName)pin).read_u16();
return mbed::AnalogIn(analogPinToPinName(pin)).read_u16() >> (16 - read_resolution);
}

void analogReadResolution(int bits)
{
read_resolution = bits;
}
39 changes: 33 additions & 6 deletions cores/arduino/wiring_digital.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,31 +23,58 @@
#include "Arduino.h"
#include "pins_arduino.h"

void pinMode(PinName pin, PinMode mode)
{
switch (mode) {
case INPUT:
mbed::DigitalIn(pin).mode(PullNone);
break;
case OUTPUT:
mbed::DigitalOut(pin, 0);
break;
case INPUT_PULLUP:
mbed::DigitalIn(pin).mode(PullUp);
break;
case INPUT_PULLDOWN:
mbed::DigitalIn(pin).mode(PullDown);
break;
}
}

void pinMode(pin_size_t pin, PinMode mode)
{
switch (mode) {
case INPUT:
mbed::DigitalIn((PinName)pin).mode(PullNone);
mbed::DigitalIn(digitalPinToPinName(pin)).mode(PullNone);
break;
case OUTPUT:
mbed::DigitalOut((PinName)pin);
mbed::DigitalOut(digitalPinToPinName(pin));
break;
case INPUT_PULLUP:
mbed::DigitalIn((PinName)pin).mode(PullUp);
mbed::DigitalIn(digitalPinToPinName(pin)).mode(PullUp);
break;
case INPUT_PULLDOWN:
mbed::DigitalIn((PinName)pin).mode(PullDown);
mbed::DigitalIn(digitalPinToPinName(pin)).mode(PullDown);
break;
}
}

void digitalWrite(PinName pin, PinStatus val)
{
mbed::DigitalOut(pin).write((int)val);
}

void digitalWrite(pin_size_t pin, PinStatus val)
{
mbed::DigitalOut((PinName)pin).write((int)val);
mbed::DigitalOut(digitalPinToPinName(pin)).write((int)val);
}

PinStatus digitalRead(PinName pin)
{
return (PinStatus)mbed::DigitalIn(pin).read();
}

PinStatus digitalRead(pin_size_t pin)
{
return (PinStatus)mbed::DigitalIn((PinName)pin).read();
return (PinStatus)mbed::DigitalIn(digitalPinToPinName(pin)).read();
}
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,27 @@

#include "arduino_openamp.h"
#include "RPC.h"
#include <iostream>
#include "rpc/server.h"

void setup() {
RPC1.begin();
Serial.begin(115200);

rpc::server srv(8080);

// Binding the name "foo" to free function foo.
// note: the signature is automatically captured
srv.bind("foo", &foo);

// Binding a lambda function to the name "add".
srv.bind("add", [](int a, int b) {
return a + b;
});

// Run the server loop.
srv.run();

}

void loop() {
Expand Down
2 changes: 1 addition & 1 deletion libraries/rpclib/src/rpc/client.h
Original file line number Diff line number Diff line change
Expand Up @@ -144,4 +144,4 @@ class client {
};
}

#include "rpc/client.inl"
//#include "rpc/client.inl"
2 changes: 1 addition & 1 deletion platform.txt
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ build.zip.pattern={recipe.size.pattern}
recipe.c.o.pattern="{compiler.path}{compiler.c.cmd}" {compiler.c.flags} -DARDUINO={runtime.ide.version} -DARDUINO_{build.board} -DARDUINO_ARCH_{build.arch} {build.extra_flags} {compiler.c.extra_flags} "-I{build.core.path}/api/deprecated" {includes} "-iprefix{build.core.path}" "@{compiler.mbed.includes}" -o "{object_file}" "{source_file}"

## Compile c++ files
recipe.cpp.o.pattern="{compiler.path}{compiler.cpp.cmd}" {compiler.cpp.flags} -DARDUINO={runtime.ide.version} -DARDUINO_{build.board} -DARDUINO_ARCH_{build.arch} {build.extra_flags} {compiler.cpp.extra_flags} "-I{build.core.path}/api/deprecated" {includes} "-iprefix{build.core.path}" "@{compiler.mbed.includes}" "{source_file}" -o "{object_file}"
recipe.cpp.o.pattern="{compiler.path}{compiler.cpp.cmd}" {compiler.cpp.flags} -DARDUINO={runtime.ide.version} -DARDUINO_{build.board} -DARDUINO_ARCH_{build.arch} {includes} {build.extra_flags} {compiler.cpp.extra_flags} "-I{build.core.path}/api/deprecated" "-iprefix{build.core.path}" "@{compiler.mbed.includes}" "{source_file}" -o "{object_file}"

## Create archives
recipe.ar.pattern="{compiler.path}{compiler.ar.cmd}" {compiler.ar.flags} {compiler.ar.extra_flags} "{archive_file_path}" "{object_file}"
Expand Down
Loading

0 comments on commit bb77ad5

Please sign in to comment.