first commit
This commit is contained in:
154
MGOSCompat/HardwareSPI.cpp
Normal file
154
MGOSCompat/HardwareSPI.cpp
Normal file
@@ -0,0 +1,154 @@
|
||||
// ArduinoCompat/HardwareSPI.cpp
|
||||
//
|
||||
// Interface between Arduino-like SPI interface and STM32F4 Discovery and similar
|
||||
// using STM32F4xx_DSP_StdPeriph_Lib_V1.3.0
|
||||
|
||||
#include <RadioHead.h>
|
||||
#if (RH_PLATFORM == RH_PLATFORM_MONGOOSE_OS)
|
||||
|
||||
#include <mgos.h>
|
||||
#include <mgos_spi.h>
|
||||
#include <HardwareSPI.h>
|
||||
|
||||
HardwareSPI::HardwareSPI(uint32_t spiPortNumber) : spiPortNumber(spiPortNumber)
|
||||
{
|
||||
}
|
||||
|
||||
void HardwareSPI::begin(int frequency, uint32_t bitOrder, uint32_t mode)
|
||||
{
|
||||
//Set the SPI tx/rx buffer pointers.
|
||||
txn.fd.tx_data = spiTXBuf;
|
||||
txn.fd.rx_data = spiRXBuf;
|
||||
|
||||
txn.freq = frequency;
|
||||
this->bitOrder = bitOrder;
|
||||
txn.mode = mode;
|
||||
#ifdef RH_USE_SPI
|
||||
txn.cs = mgos_sys_config_get_rh_spi_cs();
|
||||
#else
|
||||
txn.cs = -1;
|
||||
#endif
|
||||
}
|
||||
|
||||
void HardwareSPI::end(void)
|
||||
{
|
||||
struct mgos_spi *spi = mgos_spi_get_global();
|
||||
mgos_spi_close(spi);
|
||||
}
|
||||
|
||||
uint8_t HardwareSPI::reverseBits(uint8_t value)
|
||||
{
|
||||
value = (value & 0xF0) >> 4 | (value & 0x0F) << 4;
|
||||
value = (value & 0xCC) >> 2 | (value & 0x33) << 2;
|
||||
value = (value & 0xAA) >> 1 | (value & 0x55) << 1;
|
||||
return value;
|
||||
}
|
||||
|
||||
uint8_t HardwareSPI::transfer(uint8_t data)
|
||||
{
|
||||
uint8_t status=0;
|
||||
txn.fd.len=1;
|
||||
spiTXBuf[0]=data;
|
||||
if( bitOrder != MSBFIRST ) {
|
||||
spiTXBuf[0]=reverseBits(spiTXBuf[0]);
|
||||
}
|
||||
bool success = mgos_spi_run_txn( mgos_spi_get_global(), true, &txn);
|
||||
if( !success ) {
|
||||
LOG(LL_INFO, ("%s: Failed SPI transfer()", __FUNCTION__) );
|
||||
}
|
||||
status = spiRXBuf[0];
|
||||
if( bitOrder != MSBFIRST ) {
|
||||
status = reverseBits(status);
|
||||
}
|
||||
return status;
|
||||
}
|
||||
|
||||
uint8_t HardwareSPI::transfer2B(uint8_t byte0, uint8_t byte1)
|
||||
{
|
||||
uint8_t status=0;
|
||||
txn.fd.len=2;
|
||||
spiTXBuf[0]=byte0;
|
||||
spiTXBuf[1]=byte1;
|
||||
if( bitOrder != MSBFIRST ) {
|
||||
spiTXBuf[0]=reverseBits(spiTXBuf[0]);
|
||||
spiTXBuf[1]=reverseBits(spiTXBuf[1]);
|
||||
}
|
||||
bool success = mgos_spi_run_txn( mgos_spi_get_global(), true, &txn);
|
||||
if( !success ) {
|
||||
LOG(LL_INFO, ("%s: Failed SPI transfer()", __FUNCTION__) );
|
||||
}
|
||||
|
||||
status = spiRXBuf[0];
|
||||
if( bitOrder != MSBFIRST ) {
|
||||
status = reverseBits(status);
|
||||
}
|
||||
return status;
|
||||
}
|
||||
|
||||
uint8_t HardwareSPI::spiBurstRead(uint8_t reg, uint8_t* dest, uint8_t len) {
|
||||
uint8_t status=0;
|
||||
if( len+1 <= SPI_RX_BUFFER_SIZE ) {
|
||||
txn.fd.len=len+1;
|
||||
memset(spiTXBuf, 0, SPI_RX_BUFFER_SIZE);
|
||||
spiTXBuf[0]=reg;
|
||||
if( bitOrder != MSBFIRST ) {
|
||||
spiTXBuf[0]=reverseBits(spiTXBuf[0]);
|
||||
}
|
||||
bool success = mgos_spi_run_txn( mgos_spi_get_global(), true, &txn);
|
||||
if( !success ) {
|
||||
LOG(LL_INFO, ("%s: Failed SPI transfer()", __FUNCTION__) );
|
||||
}
|
||||
if( bitOrder != MSBFIRST ) {
|
||||
uint8_t index=0;
|
||||
for( index=0 ; index<len+1 ; index++) {
|
||||
spiRXBuf[0]=reverseBits(spiRXBuf[0]);
|
||||
}
|
||||
}
|
||||
memcpy(dest, spiRXBuf+1, len); //copy all but the status byte to the data read buffer
|
||||
status = spiRXBuf[0]; //return the status byte
|
||||
}
|
||||
else {
|
||||
LOG(LL_INFO, ("%s: RX buffer not large enough (rx buf length = %d bytes message length = %d bytes).", __FUNCTION__, SPI_RX_BUFFER_SIZE, len) );
|
||||
}
|
||||
return status;
|
||||
}
|
||||
|
||||
uint8_t HardwareSPI::spiBurstWrite(uint8_t reg, const uint8_t* src, uint8_t len) {
|
||||
uint8_t status=0;
|
||||
txn.fd.len=len+1;
|
||||
memcpy(spiTXBuf+1, src, len);
|
||||
spiTXBuf[0]=reg;
|
||||
if( bitOrder != MSBFIRST ) {
|
||||
uint8_t index=0;
|
||||
for( index=0 ; index<len+1 ; index++) {
|
||||
spiTXBuf[index]=reverseBits(spiTXBuf[index]);
|
||||
}
|
||||
}
|
||||
memset(spiRXBuf, 0, SPI_RX_BUFFER_SIZE);
|
||||
bool success = mgos_spi_run_txn( mgos_spi_get_global(), true, &txn);
|
||||
if( !success ) {
|
||||
LOG(LL_INFO, ("%s: Failed SPI transfer()", __FUNCTION__) );
|
||||
}
|
||||
status = spiRXBuf[0];
|
||||
if( bitOrder != MSBFIRST ) {
|
||||
status = reverseBits(status);
|
||||
}
|
||||
return status;
|
||||
}
|
||||
|
||||
int8_t HardwareSPI::getCSGpio() {
|
||||
uint8_t rhSPICSPin=-1;
|
||||
|
||||
if( txn.cs == 0 ) {
|
||||
rhSPICSPin = mgos_sys_config_get_spi_cs0_gpio();
|
||||
}
|
||||
else if ( txn.cs == 1 ) {
|
||||
rhSPICSPin = mgos_sys_config_get_spi_cs1_gpio();
|
||||
}
|
||||
else if ( txn.cs == 2 ) {
|
||||
rhSPICSPin = mgos_sys_config_get_spi_cs2_gpio();
|
||||
}
|
||||
return rhSPICSPin;
|
||||
}
|
||||
|
||||
#endif
|
49
MGOSCompat/HardwareSPI.h
Normal file
49
MGOSCompat/HardwareSPI.h
Normal file
@@ -0,0 +1,49 @@
|
||||
// ArduinoCompat/HardwareSPI.h
|
||||
// STM32 implementattion of Arduino compatible SPI class
|
||||
|
||||
#ifndef _HardwareSPI_h
|
||||
#define _HardwareSPI_h
|
||||
#include <mgos.h>
|
||||
#include <mgos_spi.h>
|
||||
#include <stdint.h>
|
||||
|
||||
extern "C"
|
||||
{
|
||||
struct mgos_spi *mgos_spi_get_global(void);
|
||||
bool mgos_spi_run_txn(struct mgos_spi *spi, bool full_duplex, const struct mgos_spi_txn *txn);
|
||||
}
|
||||
|
||||
//Not used on MGOS as SPI config is set in mos.yml
|
||||
#define SPI_MODE0 0x00
|
||||
#define SPI_MODE1 0x01
|
||||
#define SPI_MODE2 0x03
|
||||
#define SPI_MODE3 0x02
|
||||
|
||||
#define SPI_TX_BUFFER_SIZE 64
|
||||
#define SPI_RX_BUFFER_SIZE 64
|
||||
|
||||
class HardwareSPI
|
||||
{
|
||||
public:
|
||||
HardwareSPI(uint32_t spiPortNumber); // Only port SPI1 is currently supported
|
||||
void begin(int frequency, uint32_t bitOrder, uint32_t mode);
|
||||
void end(void);
|
||||
uint8_t reverseBits(uint8_t value);
|
||||
int8_t getCSGpio();
|
||||
uint8_t transfer(uint8_t data);
|
||||
uint8_t transfer2B(uint8_t byte0, uint8_t byte1);
|
||||
uint8_t spiBurstRead(uint8_t reg, uint8_t* dest, uint8_t len);
|
||||
uint8_t spiBurstWrite(uint8_t reg, const uint8_t* src, uint8_t len);
|
||||
private:
|
||||
uint32_t spiPortNumber; // Not used
|
||||
struct mgos_spi_txn txn;
|
||||
uint32_t bitOrder;
|
||||
//Define spi TX and RX buffers.This is a little wasteful of memory
|
||||
//but no dynamic memory allocation fits with the RadioHead library.
|
||||
uint8_t spiTXBuf[SPI_TX_BUFFER_SIZE];
|
||||
uint8_t spiRXBuf[SPI_RX_BUFFER_SIZE];
|
||||
};
|
||||
extern HardwareSPI SPI;
|
||||
|
||||
|
||||
#endif
|
189
MGOSCompat/HardwareSerial.cpp
Normal file
189
MGOSCompat/HardwareSerial.cpp
Normal file
@@ -0,0 +1,189 @@
|
||||
// ArduinoCompat/HardwareSerial.cpp
|
||||
//
|
||||
// Author: mikem@airspayce.com
|
||||
|
||||
#include <RadioHead.h>
|
||||
#if (RH_PLATFORM == RH_PLATFORM_MONGOOSE_OS)
|
||||
#include <mgos.h>
|
||||
#include <HardwareSerial.h>
|
||||
|
||||
extern "C" {
|
||||
static inline void mgos_sys_config_set_rh_serial_baud(int v);
|
||||
static inline void mgos_sys_config_set_rh_serial_databits(int v);
|
||||
static inline void mgos_sys_config_set_rh_serial_parity(int v);
|
||||
static inline void mgos_sys_config_set_rh_serial_stopbits(int v);
|
||||
|
||||
void mgos_uart_config_set_defaults(int uart_no, struct mgos_uart_config *cfg);
|
||||
bool mgos_uart_configure(int uart_no, const struct mgos_uart_config *cfg);
|
||||
void mgos_uart_set_rx_enabled(int uart_no, bool enabled);
|
||||
size_t mgos_uart_read_avail(int uart_no);
|
||||
size_t mgos_uart_read(int uart_no, void *buf, size_t len);
|
||||
size_t mgos_uart_write(int uart_no, const void *buf, size_t len);
|
||||
};
|
||||
|
||||
|
||||
// instantiate Serial objects
|
||||
HardwareSerial Serial0(0);
|
||||
HardwareSerial Serial1(1);
|
||||
HardwareSerial Serial2(2);
|
||||
|
||||
/*
|
||||
* Serial ports
|
||||
*
|
||||
* ESP8266
|
||||
* The esp8266 device has two uarts (0 and 1), Uart 1 TX is typically used for debugging. No Uart 1 RX is available on the esp8266.
|
||||
*
|
||||
* Uart 0
|
||||
* RX = GPIO3
|
||||
* TX = GPIO1
|
||||
*
|
||||
* Uart 1
|
||||
* TX = GPIO2
|
||||
*
|
||||
* ESP32
|
||||
* The esp32 device has three uarts (0,1 and 2). Uart 0 is typically used for debugging/loading code.
|
||||
*
|
||||
* Uart 0
|
||||
* RX = GPIO3
|
||||
* TX = GPIO1
|
||||
* CTS = GPIO19
|
||||
* RTS = GPIO22
|
||||
*
|
||||
* Uart 1
|
||||
* RX = GPIO25
|
||||
* TX = GPIO26
|
||||
* CTS = GPIO27
|
||||
* RTS = GPIO13
|
||||
*
|
||||
* Uart 2
|
||||
* RX = GPIO16
|
||||
* TX = GPIO17
|
||||
* CTS = GPIO14
|
||||
* RTS = GPIO15
|
||||
*/
|
||||
|
||||
///////////////////////////////////////////////////////////////
|
||||
// HardwareSerial
|
||||
///////////////////////////////////////////////////////////////
|
||||
|
||||
HardwareSerial::HardwareSerial(int uartIndex)
|
||||
{
|
||||
this->uartIndex=uartIndex;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Init the serial port.
|
||||
* @param baud If the baud rate is 0 or -ve then the persistent sorage value
|
||||
* is used. Starting at the value in mos.yml.
|
||||
*/
|
||||
void HardwareSerial::begin(int baud)
|
||||
{
|
||||
struct mgos_uart_config ucfg;
|
||||
|
||||
if( mgos_sys_config_get_rh_serial_baud() != baud ) {
|
||||
mgos_sys_config_set_rh_serial_baud(baud);
|
||||
}
|
||||
|
||||
mgos_uart_config_set_defaults(this->uartIndex, &ucfg);
|
||||
ucfg.baud_rate = mgos_sys_config_get_rh_serial_baud();
|
||||
ucfg.num_data_bits = mgos_sys_config_get_rh_serial_databits();
|
||||
ucfg.parity = (mgos_uart_parity)mgos_sys_config_get_rh_serial_parity();
|
||||
ucfg.stop_bits = (mgos_uart_stop_bits)mgos_sys_config_get_rh_serial_stopbits();
|
||||
mgos_uart_configure(this->uartIndex, &ucfg);
|
||||
if( mgos_uart_configure(this->uartIndex, &ucfg) ) {
|
||||
mgos_uart_set_rx_enabled(this->uartIndex, true);
|
||||
mgos_uart_set_dispatcher(this->uartIndex, NULL, NULL);
|
||||
}
|
||||
|
||||
#ifdef NO_ESP32_RXD_PULLUP
|
||||
if( this->uartIndex == 0 ) {
|
||||
mgos_gpio_setup_input(3, MGOS_GPIO_PULL_NONE);
|
||||
}
|
||||
else if( this->uartIndex == 1 ) {
|
||||
mgos_gpio_setup_input(25, MGOS_GPIO_PULL_NONE);
|
||||
}
|
||||
else if( this->uartIndex == 2 ) {
|
||||
mgos_gpio_setup_input(16, MGOS_GPIO_PULL_NONE);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void HardwareSerial::end()
|
||||
{
|
||||
mgos_uart_set_rx_enabled(this->uartIndex, false);
|
||||
}
|
||||
|
||||
int HardwareSerial::available(void)
|
||||
{
|
||||
size_t reqRxByteCount=1;
|
||||
//We have to read the byte because Mongoose OS requires a return
|
||||
//to the RTOS in order to update the value read by mgos_uart_read_avail()
|
||||
rxByteCountAvail = mgos_uart_read(this->uartIndex, &rxByte, reqRxByteCount);
|
||||
return rxByteCountAvail;
|
||||
}
|
||||
|
||||
int HardwareSerial::read(void)
|
||||
{
|
||||
return rxByte;
|
||||
}
|
||||
|
||||
size_t HardwareSerial::write(uint8_t ch)
|
||||
{
|
||||
size_t wr_byte_count = 0;
|
||||
|
||||
wr_byte_count = mgos_uart_write(this->uartIndex, &ch, 1);
|
||||
|
||||
return wr_byte_count;
|
||||
}
|
||||
|
||||
size_t HardwareSerial::print(char ch)
|
||||
{
|
||||
printf("%c", ch);
|
||||
return 0;
|
||||
}
|
||||
|
||||
size_t HardwareSerial::println(char ch)
|
||||
{
|
||||
printf("%c\n", ch);
|
||||
return 0;
|
||||
}
|
||||
|
||||
size_t HardwareSerial::print(unsigned char ch, int base)
|
||||
{
|
||||
if( base == DEC ) {
|
||||
printf("%d", ch);
|
||||
}
|
||||
else if( base == HEX ) {
|
||||
printf("%02x", ch);
|
||||
}
|
||||
else if( base == OCT ) {
|
||||
printf("%o", ch);
|
||||
}
|
||||
//TODO Add binary print
|
||||
return 0;
|
||||
}
|
||||
|
||||
size_t HardwareSerial::println(unsigned char ch, int base)
|
||||
{
|
||||
print((unsigned int)ch, base);
|
||||
printf("\n");
|
||||
return 0;
|
||||
}
|
||||
|
||||
size_t HardwareSerial::println(const char* s)
|
||||
{
|
||||
if( s ) {
|
||||
printf("%s\n",s);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
size_t HardwareSerial::print(const char* s)
|
||||
{
|
||||
if( s) {
|
||||
printf(s);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
#endif
|
49
MGOSCompat/HardwareSerial.h
Normal file
49
MGOSCompat/HardwareSerial.h
Normal file
@@ -0,0 +1,49 @@
|
||||
// ArduinoCompat/HardwareSerial.h
|
||||
// Mongoose OS implementation of Arduino compatible serial class
|
||||
|
||||
#include <RadioHead.h>
|
||||
#if (RH_PLATFORM == RH_PLATFORM_MONGOOSE_OS)
|
||||
#ifndef _HardwareSerial_h
|
||||
#define _HardwareSerial_h
|
||||
|
||||
#include <mgos.h>
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
|
||||
// Mostly compatible wuith Arduino HardwareSerial
|
||||
// There is just enough here to support RadioHead RH_Serial
|
||||
class HardwareSerial
|
||||
{
|
||||
public:
|
||||
HardwareSerial(int uart_index);
|
||||
void begin(int baud);
|
||||
void end();
|
||||
virtual int available(void);
|
||||
virtual int read(void);
|
||||
virtual size_t write(uint8_t);
|
||||
inline size_t write(unsigned long n) { return write((uint8_t)n); }
|
||||
inline size_t write(long n) { return write((uint8_t)n); }
|
||||
inline size_t write(unsigned int n) { return write((uint8_t)n); }
|
||||
inline size_t write(int n) { return write((uint8_t)n); }
|
||||
|
||||
//These methods will send debug info on the debug serial port (if enabled)
|
||||
size_t println(unsigned char ch, int base);
|
||||
size_t print(unsigned char ch, int base);
|
||||
size_t println(const char ch);
|
||||
size_t print(const char ch);
|
||||
size_t println(const char* s);
|
||||
size_t print(const char* s);
|
||||
|
||||
private:
|
||||
int uartIndex;
|
||||
size_t rxByteCountAvail;
|
||||
uint8_t rxByte;
|
||||
};
|
||||
|
||||
extern HardwareSerial Serial0;
|
||||
extern HardwareSerial Serial1;
|
||||
extern HardwareSerial Serial2;
|
||||
|
||||
#endif
|
||||
|
||||
#endif
|
159
MGOSCompat/MGOS.cpp
Normal file
159
MGOSCompat/MGOS.cpp
Normal file
@@ -0,0 +1,159 @@
|
||||
// RasPi.cpp
|
||||
//
|
||||
// Routines for implementing RadioHead on Raspberry Pi
|
||||
// using BCM2835 library for GPIO
|
||||
//
|
||||
// Contributed by Mike Poublon and used with permission
|
||||
|
||||
|
||||
#include <RadioHead.h>
|
||||
|
||||
#if (RH_PLATFORM == RH_PLATFORM_MONGOOSE_OS)
|
||||
|
||||
#include "mgos.h"
|
||||
|
||||
int pwmFreq = 1000;
|
||||
float pwmDutyCycle = 0.5;
|
||||
|
||||
/**
|
||||
* @brief Set the direction of a GPIO pin.
|
||||
* @param pin the Pin whose direction is to be set.
|
||||
* @param mode The direction of the pin (OUTPUT or INPUT)
|
||||
**/
|
||||
void pinMode(uint8_t pin, WiringPinMode mode)
|
||||
{
|
||||
|
||||
//SPI CS GPIO controlled by MGOS lib call so don't allow it to be set here
|
||||
if( SPI.getCSGpio() != pin ) {
|
||||
if (mode == OUTPUT)
|
||||
{
|
||||
mgos_gpio_set_mode(pin, MGOS_GPIO_MODE_OUTPUT);
|
||||
}
|
||||
else if (mode == OUTPUT_OPEN_DRAIN)
|
||||
{
|
||||
mgos_gpio_set_pull(pin, MGOS_GPIO_PULL_UP);
|
||||
mgos_gpio_set_mode(pin, MGOS_GPIO_MODE_OUTPUT);
|
||||
}
|
||||
else if (mode == INPUT || mode == INPUT_FLOATING )
|
||||
{
|
||||
mgos_gpio_set_mode(pin, MGOS_GPIO_MODE_INPUT);
|
||||
}
|
||||
else if (mode == INPUT_ANALOG)
|
||||
{
|
||||
mgos_adc_enable(pin);
|
||||
}
|
||||
else if (mode == INPUT_PULLUP)
|
||||
{
|
||||
mgos_gpio_set_pull(pin, MGOS_GPIO_PULL_UP);
|
||||
mgos_gpio_set_mode(pin, MGOS_GPIO_MODE_INPUT);
|
||||
}
|
||||
else if (mode == INPUT_PULLDOWN)
|
||||
{
|
||||
mgos_gpio_set_pull(pin, MGOS_GPIO_PULL_DOWN);
|
||||
mgos_gpio_set_mode(pin, MGOS_GPIO_MODE_INPUT);
|
||||
}
|
||||
else if (mode == PWM)
|
||||
{
|
||||
mgos_pwm_set(pin, pwmFreq, pwmDutyCycle);
|
||||
}
|
||||
else if (mode == PWM_OPEN_DRAIN) {
|
||||
mgos_pwm_set(pin, pwmFreq, pwmDutyCycle);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Set the state of a GPIO pin.
|
||||
* @param pin the Pin whose state is to be set.
|
||||
* @param value The state of the pin.
|
||||
*/
|
||||
void digitalWrite(unsigned char pin, unsigned char value)
|
||||
{
|
||||
|
||||
//SPI CS GPIO controlled by MGOS lib call so don't allow it to be set here
|
||||
if( SPI.getCSGpio() != pin ) {
|
||||
mgos_gpio_write(pin,value);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Read the state of a GPIO pin.
|
||||
* @param pin the Pin whose state is to be set.
|
||||
* @return 1 If high, 0 if low.
|
||||
*/
|
||||
uint8_t digitalRead(uint8_t pin)
|
||||
{
|
||||
uint8_t pinState=0;
|
||||
//SPI CS GPIO controlled by MGOS lib call so don't allow it to be set here
|
||||
if( SPI.getCSGpio() != pin ) {
|
||||
pinState = (uint8_t)mgos_gpio_read(pin);
|
||||
}
|
||||
return pinState;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get the number of elapsed milliseconds since the last boot.
|
||||
*/
|
||||
uint32_t millis(void)
|
||||
{
|
||||
return (uint32_t)mgos_uptime_micros()/1000;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Provide a delay in milliseconds.
|
||||
* @param ms The number of Milli Seconds to delay.
|
||||
*/
|
||||
void delay (unsigned long ms)
|
||||
{
|
||||
mgos_msleep(ms);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Generate a random number between limits.
|
||||
* @param min The minimum random value to be generated.
|
||||
* @param max The maximum random value to be generated.
|
||||
*/
|
||||
long random(long min, long max)
|
||||
{
|
||||
return mgos_rand_range( (float)min, (float)max);
|
||||
}
|
||||
|
||||
static void mgos_gpio_int_handler(int pin, void *arg) {
|
||||
void (*handler)(void) = (void (*)())arg;
|
||||
//Note that this handler is executed in interrupt context (ISR)
|
||||
//therefore ensure that actions performed here are acceptable for the
|
||||
//platform on which the code will execute.
|
||||
//E.G
|
||||
//Use of the LOG macro to send debug data on the serial port crashes
|
||||
//esp8266 and esp32 code.
|
||||
handler();
|
||||
(void) pin;
|
||||
(void) arg;
|
||||
}
|
||||
|
||||
void attachInterrupt(uint8_t pin, void (*handler)(void), int rh_mode)
|
||||
{
|
||||
mgos_gpio_int_mode mgos_mode = MGOS_GPIO_INT_NONE;
|
||||
if( rh_mode == CHANGE ) {
|
||||
mgos_mode = MGOS_GPIO_INT_EDGE_ANY;
|
||||
} else if( rh_mode == FALLING ) {
|
||||
mgos_mode = MGOS_GPIO_INT_EDGE_NEG;
|
||||
} else if( rh_mode == RISING ) {
|
||||
mgos_mode = MGOS_GPIO_INT_EDGE_POS;
|
||||
}
|
||||
mgos_gpio_set_int_handler_isr((int)pin, mgos_mode, mgos_gpio_int_handler, (void*)handler);
|
||||
}
|
||||
|
||||
void enableInterupt(uint8_t pin) {
|
||||
mgos_gpio_enable_int(pin);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Perform functions that under Mongoose OS we would normally return
|
||||
* to the RTOS. E,G flush the TX UART buffer.
|
||||
*/
|
||||
void mgosYield(void) {
|
||||
mgos_uart_flush(RH_SERIAL_PORT);
|
||||
}
|
||||
|
||||
#endif
|
101
MGOSCompat/MGOS.h
Normal file
101
MGOSCompat/MGOS.h
Normal file
@@ -0,0 +1,101 @@
|
||||
// MGOS.h
|
||||
//
|
||||
// Routines for implementing RadioHead when using Mongoose OS
|
||||
// see https://mongoose-os.com/mos.html for H/W support when using Mongoose OS
|
||||
// Contributed by Paul Austen
|
||||
|
||||
#ifndef MGOS_h
|
||||
#define MGOS_h
|
||||
|
||||
#define PROGMEM
|
||||
#define memcpy_P memcpy
|
||||
|
||||
#define DEC 10
|
||||
#define HEX 16
|
||||
#define OCT 8
|
||||
#define BIN 2
|
||||
|
||||
#define HIGH 0x1
|
||||
#define LOW 0x0
|
||||
|
||||
#define LSBFIRST 0
|
||||
#define MSBFIRST 1
|
||||
|
||||
#define CHANGE 1
|
||||
#define FALLING 2
|
||||
#define RISING 3
|
||||
|
||||
typedef enum WiringPinMode {
|
||||
OUTPUT, /**< Basic digital output: when the pin is HIGH, the
|
||||
voltage is held at +3.3v (Vcc) and when it is LOW, it
|
||||
is pulled down to ground. */
|
||||
|
||||
OUTPUT_OPEN_DRAIN, /**< In open drain mode, the pin indicates
|
||||
"low" by accepting current flow to ground
|
||||
and "high" by providing increased
|
||||
impedance. An example use would be to
|
||||
connect a pin to a bus line (which is pulled
|
||||
up to a positive voltage by a separate
|
||||
supply through a large resistor). When the
|
||||
pin is high, not much current flows through
|
||||
to ground and the line stays at positive
|
||||
voltage; when the pin is low, the bus
|
||||
"drains" to ground with a small amount of
|
||||
current constantly flowing through the large
|
||||
resistor from the external supply. In this
|
||||
mode, no current is ever actually sourced
|
||||
from the pin. */
|
||||
|
||||
INPUT, /**< Basic digital input. The pin voltage is sampled; when
|
||||
it is closer to 3.3v (Vcc) the pin status is high, and
|
||||
when it is closer to 0v (ground) it is low. If no
|
||||
external circuit is pulling the pin voltage to high or
|
||||
low, it will tend to randomly oscillate and be very
|
||||
sensitive to noise (e.g., a breath of air across the pin
|
||||
might cause the state to flip). */
|
||||
|
||||
INPUT_ANALOG, /**< This is a special mode for when the pin will be
|
||||
used for analog (not digital) reads. Enables ADC
|
||||
conversion to be performed on the voltage at the
|
||||
pin. */
|
||||
|
||||
INPUT_PULLUP, /**< The state of the pin in this mode is reported
|
||||
the same way as with INPUT, but the pin voltage
|
||||
is gently "pulled up" towards +3.3v. This means
|
||||
the state will be high unless an external device
|
||||
is specifically pulling the pin down to ground,
|
||||
in which case the "gentle" pull up will not
|
||||
affect the state of the input. */
|
||||
|
||||
INPUT_PULLDOWN, /**< The state of the pin in this mode is reported
|
||||
the same way as with INPUT, but the pin voltage
|
||||
is gently "pulled down" towards 0v. This means
|
||||
the state will be low unless an external device
|
||||
is specifically pulling the pin up to 3.3v, in
|
||||
which case the "gentle" pull down will not
|
||||
affect the state of the input. */
|
||||
|
||||
INPUT_FLOATING, /**< Synonym for INPUT. */
|
||||
|
||||
PWM, /**< This is a special mode for when the pin will be used for
|
||||
PWM output (a special case of digital output). */
|
||||
|
||||
PWM_OPEN_DRAIN, /**< Like PWM, except that instead of alternating
|
||||
cycles of LOW and HIGH, the voltage on the pin
|
||||
consists of alternating cycles of LOW and
|
||||
floating (disconnected). */
|
||||
} WiringPinMode;
|
||||
|
||||
extern "C" {
|
||||
void pinMode(uint8_t pin, WiringPinMode mode);
|
||||
void digitalWrite(unsigned char pin, unsigned char value);
|
||||
uint8_t digitalRead(uint8_t pin);
|
||||
uint32_t millis(void);
|
||||
void delay (unsigned long ms);
|
||||
long random(long min, long max);
|
||||
void attachInterrupt(uint8_t pin, void (*handler)(void), int rh_mode);
|
||||
void mgosYield(void);
|
||||
void enableInterupt(uint8_t pin);
|
||||
}
|
||||
|
||||
#endif
|
1
MGOSCompat/README
Normal file
1
MGOSCompat/README
Normal file
@@ -0,0 +1 @@
|
||||
This directory contains some files to allow RadioHead to be built on Mongoose OS.
|
Reference in New Issue
Block a user