initial commit

This commit is contained in:
proddy
2020-07-05 18:29:08 +02:00
parent 26b201ea2f
commit c5933e8c14
739 changed files with 86566 additions and 20952 deletions

270
src/uart/emsuart_esp32.cpp Normal file
View File

@@ -0,0 +1,270 @@
/*
* EMS-ESP - https://github.com/proddy/EMS-ESP
* Copyright 2019 Paul Derbyshire
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* ESP32 UART port by @ArwedL and improved by @MichaelDvP. See https://github.com/proddy/EMS-ESP/issues/380
*/
#if defined(ESP32)
#include "uart/emsuart_esp32.h"
#include "emsesp.h"
namespace emsesp {
static intr_handle_t uart_handle;
static RingbufHandle_t buf_handle = NULL;
static hw_timer_t * timer = NULL;
bool drop_next_rx = true;
uint8_t tx_mode_ = 0xFF;
uint8_t emsTxBuf[EMS_MAXBUFFERSIZE];
uint8_t emsTxBufIdx;
uint8_t emsTxBufLen;
uint32_t emsTxWait;
/*
* Task to handle the incoming data
*/
void EMSuart::emsuart_recvTask(void * para) {
while (1) {
size_t item_size;
uint8_t * telegram = (uint8_t *)xRingbufferReceive(buf_handle, &item_size, portMAX_DELAY);
uint8_t telegramSize = item_size;
if (telegram) {
EMSESP::incoming_telegram(telegram, telegramSize);
vRingbufferReturnItem(buf_handle, (void *)telegram);
}
}
}
/*
* UART interrupt, on break read the fifo and put the whole telegram to ringbuffer
*/
void IRAM_ATTR EMSuart::emsuart_rx_intr_handler(void * para) {
static uint8_t rxbuf[EMS_MAXBUFFERSIZE];
static uint8_t length;
if (EMS_UART.int_st.brk_det) {
EMS_UART.int_clr.brk_det = 1; // clear flag
EMS_UART.conf0.txd_brk = 0; // disable <brk>
if (emsTxBufIdx < emsTxBufLen) { // timer tx_mode is interrupted by <brk>
emsTxBufIdx = emsTxBufLen; // stop timer mode
drop_next_rx = true; // we have trash in buffer
}
length = 0;
while (EMS_UART.status.rxfifo_cnt) {
uint8_t rx = EMS_UART.fifo.rw_byte; // read all bytes from fifo
if (length < EMS_MAXBUFFERSIZE) {
rxbuf[length++] = rx;
} else {
drop_next_rx = true; // we have a overflow
}
}
if ((!drop_next_rx) && ((length == 2) || (length > 4))) {
int baseType = 0;
xRingbufferSendFromISR(buf_handle, rxbuf, length - 1, &baseType);
}
drop_next_rx = false;
}
}
void IRAM_ATTR EMSuart::emsuart_tx_timer_intr_handler() {
if (emsTxBufLen == 0) {
return;
}
if (tx_mode_ > 50) {
for (uint8_t i = 0; i < emsTxBufLen; i++) {
EMS_UART.fifo.rw_byte = emsTxBuf[i];
}
EMS_UART.conf0.txd_brk = 1; // <brk> after send
} else {
if (emsTxBufIdx + 1 < emsTxBufLen) {
EMS_UART.fifo.rw_byte = emsTxBuf[emsTxBufIdx];
timerAlarmWrite(timer, emsTxWait, false);
timerAlarmEnable(timer);
} else if (emsTxBufIdx + 1 == emsTxBufLen) {
EMS_UART.fifo.rw_byte = emsTxBuf[emsTxBufIdx];
EMS_UART.conf0.txd_brk = 1; // <brk> after send
}
emsTxBufIdx++;
}
}
/*
* init UART driver
*/
void EMSuart::start(const uint8_t tx_mode) {
if (tx_mode_ != 0xFF) { // uart already initialized
tx_mode_ = tx_mode;
restart();
return;
}
tx_mode_ = tx_mode;
uart_config_t uart_config = {
.baud_rate = EMSUART_BAUD,
.data_bits = UART_DATA_8_BITS,
.parity = UART_PARITY_DISABLE,
.stop_bits = UART_STOP_BITS_1,
.flow_ctrl = UART_HW_FLOWCTRL_DISABLE,
};
uart_param_config(EMSUART_UART, &uart_config);
uart_set_pin(EMSUART_UART, EMSUART_TXPIN, EMSUART_RXPIN, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
EMS_UART.int_ena.val = 0; // disable all intr.
EMS_UART.int_clr.val = 0xFFFFFFFF; // clear all intr. flags
EMS_UART.idle_conf.tx_brk_num = 11; // breaklength 11 bit
EMS_UART.idle_conf.rx_idle_thrhd = 256;
drop_next_rx = true;
buf_handle = xRingbufferCreate(128, RINGBUF_TYPE_NOSPLIT);
uart_isr_register(EMSUART_UART, emsuart_rx_intr_handler, NULL, ESP_INTR_FLAG_IRAM, &uart_handle);
xTaskCreate(emsuart_recvTask, "emsuart_recvTask", 2048, NULL, configMAX_PRIORITIES - 1, NULL);
timer = timerBegin(1, 80, true); // timer prescale to 1 µs, countup
timerAttachInterrupt(timer, &emsuart_tx_timer_intr_handler, true); // Timer with edge interrupt
restart();
}
/*
* Stop, disables interrupt
*/
void EMSuart::stop() {
EMS_UART.int_ena.val = 0; // disable all intr.
// timerAlarmDisable(timer);
};
/*
* Restart Interrupt
*/
void EMSuart::restart() {
if (EMS_UART.int_raw.brk_det) {
EMS_UART.int_clr.brk_det = 1; // clear flag
drop_next_rx = true; // and drop first frame
}
EMS_UART.int_ena.brk_det = 1; // activate only break
emsTxBufIdx = 0;
emsTxBufLen = 0;
if (tx_mode_ == 1) {
EMS_UART.idle_conf.tx_idle_num = 5;
} else if (tx_mode_ == 2) {
EMS_UART.idle_conf.tx_idle_num = 10;
} else if (tx_mode_ == 3) {
EMS_UART.idle_conf.tx_idle_num = 7;
} else if (tx_mode_ == 4) {
EMS_UART.idle_conf.tx_idle_num = 2;
} else if (tx_mode_ == 5) {
EMS_UART.idle_conf.tx_idle_num = 2;
} else if (tx_mode_ <= 50) {
EMS_UART.idle_conf.tx_idle_num = tx_mode_;
emsTxWait = EMSUART_TX_BIT_TIME * (tx_mode_ + 10);
} else {
EMS_UART.idle_conf.tx_idle_num = 2;
emsTxWait = EMSUART_TX_BIT_TIME * (tx_mode_ - 50);
}
}
/*
* Sends a 1-byte poll, ending with a <BRK>
*/
void EMSuart::send_poll(const uint8_t data) {
EMS_UART.fifo.rw_byte = data;
EMS_UART.conf0.txd_brk = 1; // <brk> after send
return;
}
/*
* Send data to Tx line, ending with a <BRK>
* buf contains the CRC and len is #bytes including the CRC
* returns code, 1=success
*/
uint16_t EMSuart::transmit(const uint8_t * buf, const uint8_t len) {
if (len == 0 || len >= EMS_MAXBUFFERSIZE) {
return EMS_TX_STATUS_ERR;
}
// needs to be disabled for the delayed modes otherwise the uart makes a <brk> after every byte
EMS_UART.conf0.txd_brk = 0;
if (tx_mode_ > 5) { // timer controlled modes
for (uint8_t i = 0; i < len; i++) {
emsTxBuf[i] = buf[i];
}
emsTxBufIdx = 0;
emsTxBufLen = len;
timerAlarmWrite(timer, emsTxWait, false);
timerAlarmEnable(timer);
return EMS_TX_STATUS_OK;
}
if (tx_mode_ == 5) { // wait before sending
vTaskDelay(4 / portTICK_PERIOD_MS);
for (uint8_t i = 0; i < len; i++) {
EMS_UART.fifo.rw_byte = buf[i];
}
EMS_UART.conf0.txd_brk = 1; // <brk> after send
return EMS_TX_STATUS_OK;
}
if (tx_mode_ == EMS_TXMODE_NEW) { // hardware controlled modes
for (uint8_t i = 0; i < len; i++) {
EMS_UART.fifo.rw_byte = buf[i];
}
EMS_UART.conf0.txd_brk = 1; // <brk> after send
return EMS_TX_STATUS_OK;
}
if (tx_mode_ == EMS_TXMODE_EMSPLUS) { // EMS+ with long delay
for (uint8_t i = 0; i < len - 1; i++) {
EMS_UART.fifo.rw_byte = buf[i];
delayMicroseconds(EMSUART_TX_WAIT_PLUS);
}
EMS_UART.fifo.rw_byte = buf[len - 1];
EMS_UART.conf0.txd_brk = 1; // <brk> after send, cleard by hardware after send
return EMS_TX_STATUS_OK;
}
if (tx_mode_ == EMS_TXMODE_HT3) { // HT3 with 7 bittimes delay
for (uint8_t i = 0; i < len - 1; i++) {
EMS_UART.fifo.rw_byte = buf[i];
delayMicroseconds(EMSUART_TX_WAIT_HT3);
}
EMS_UART.fifo.rw_byte = buf[len - 1];
EMS_UART.conf0.txd_brk = 1; // <brk> after send, cleard by hardware after send
return EMS_TX_STATUS_OK;
}
// mode 1
// flush fifos -- not supported in ESP32 uart #2!
// EMS_UART.conf0.rxfifo_rst = 1;
// EMS_UART.conf0.txfifo_rst = 1;
for (uint8_t i = 0; i < len - 1; i++) {
volatile uint8_t _usrxc = EMS_UART.status.rxfifo_cnt;
EMS_UART.fifo.rw_byte = buf[i]; // send each Tx byte
uint16_t timeoutcnt = EMSUART_TX_TIMEOUT;
while ((EMS_UART.status.rxfifo_cnt == _usrxc) && (--timeoutcnt > 0)) {
delayMicroseconds(EMSUART_TX_BUSY_WAIT); // burn CPU cycles...
}
}
EMS_UART.fifo.rw_byte = buf[len - 1]; // send each Tx byte
EMS_UART.conf0.txd_brk = 1; // <brk> after send, cleard by hardware after send
return EMS_TX_STATUS_OK;
}
} // namespace emsesp
#endif

98
src/uart/emsuart_esp32.h Normal file
View File

@@ -0,0 +1,98 @@
/*
* EMS-ESP - https://github.com/proddy/EMS-ESP
* Copyright 2019 Paul Derbyshire
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* ESP32 UART port by @ArwedL and improved by @MichaelDvP. See https://github.com/proddy/EMS-ESP/issues/380
*/
#if defined(ESP32)
#ifndef EMSESP_EMSUART_H
#define EMSESP_EMSUART_H
#include <Arduino.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/ringbuf.h"
#include "freertos/queue.h"
#include <driver/uart.h>
#include <driver/timer.h>
#define EMS_MAXBUFFERSIZE 33 // max size of the buffer. EMS packets are max 32 bytes, plus extra for BRK
#define EMSUART_UART UART_NUM_2 // on the ESP32 we're using UART2
#define EMS_UART UART2 // for intr setting
#define EMSUART_BAUD 9600 // uart baud rate for the EMS circuit
#define EMS_TXMODE_DEFAULT 1
#define EMS_TXMODE_EMSPLUS 2
#define EMS_TXMODE_HT3 3
#define EMS_TXMODE_NEW 4 // for michael's testing
// LEGACY
#define EMSUART_TX_BIT_TIME 104 // bit time @9600 baud
#define EMSUART_TX_WAIT_BRK (EMSUART_TX_BIT_TIME * 11) // 1144
// EMS 1.0
#define EMSUART_TX_BUSY_WAIT (EMSUART_TX_BIT_TIME / 8) // 13
#define EMSUART_TX_TIMEOUT (32 * EMSUART_TX_BIT_TIME / EMSUART_TX_BUSY_WAIT) // 256
// HT3/Junkers - Time to send one Byte (8 Bits, 1 Start Bit, 1 Stop Bit) plus 7 bit delay. The -8 is for lag compensation.
// since we use a faster processor the lag is negligible
#define EMSUART_TX_WAIT_HT3 (EMSUART_TX_BIT_TIME * 17) // 1768
// EMS+ - Time to send one Byte (8 Bits, 1 Start Bit, 1 Stop Bit) and delay of another Bytetime.
#define EMSUART_TX_WAIT_PLUS (EMSUART_TX_BIT_TIME * 20) // 2080
// customize the GPIO pins for RX and TX here
#ifdef WEMOS_D1_32
#define EMSUART_RXPIN 23 // 17 is UART2 RX. Use 23 for D7 on a Wemos D1-32 mini for backwards compatabilty
#define EMSUART_TXPIN 5 // 16 is UART2 TX. Use 5 for D8 on a Wemos D1-32 mini for backwards compatabilty
#else
#define EMSUART_RXPIN 17 // 17 is UART2 RX. Use 23 for D7 on a Wemos D1-32 mini for backwards compatabilty
#define EMSUART_TXPIN 16 // 16 is UART2 TX. Use 5 for D8 on a Wemos D1-32 mini for backwards compatabilty
#endif
namespace emsesp {
#define EMS_TX_STATUS_OK 1
#define EMS_TX_STATUS_ERR 0
class EMSuart {
public:
EMSuart() = default;
~EMSuart() = default;
static void start(const uint8_t tx_mode);
static void send_poll(const uint8_t data);
static void stop();
static void restart();
static uint16_t transmit(const uint8_t * buf, const uint8_t len);
private:
static void emsuart_recvTask(void * para);
static void IRAM_ATTR emsuart_rx_intr_handler(void * para);
static void IRAM_ATTR emsuart_tx_timer_intr_handler();
};
} // namespace emsesp
#endif
#endif

View File

@@ -0,0 +1,437 @@
/*
* EMS-ESP - https://github.com/proddy/EMS-ESP
* Copyright 2019 Paul Derbyshire
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#if defined(ESP8266)
#include "uart/emsuart_esp8266.h"
#include "emsesp.h"
namespace emsesp {
os_event_t recvTaskQueue[EMSUART_recvTaskQueueLen]; // our Rx queue
EMSuart::EMSRxBuf_t * pEMSRxBuf;
EMSuart::EMSRxBuf_t * paEMSRxBuf[EMS_MAXBUFFERS];
uint8_t emsRxBufIdx = 0;
uint8_t tx_mode_ = 0xFF;
bool drop_next_rx = true;
uint8_t emsTxBuf[EMS_MAXBUFFERSIZE];
uint8_t emsTxBufIdx;
uint8_t emsTxBufLen;
uint32_t emsTxWait;
bool EMSuart::sending_ = false;
//
// Main interrupt handler
// Important: must not use ICACHE_FLASH_ATTR
//
void ICACHE_RAM_ATTR EMSuart::emsuart_rx_intr_handler(void * para) {
static uint8_t length = 0;
static uint8_t uart_buffer[EMS_MAXBUFFERSIZE + 2];
if (USIS(EMSUART_UART) & ((1 << UIBD))) { // BREAK detection = End of EMS data block
USC0(EMSUART_UART) &= ~(1 << UCBRK); // reset tx-brk
if (emsTxBufIdx < emsTxBufLen) { // irq tx_mode is interrupted by <brk>
emsTxBufIdx = emsTxBufLen; // stop tx
drop_next_rx = true; // we have trash in buffer
}
USIC(EMSUART_UART) = (1 << UIBD); // INT clear the BREAK detect interrupt
USIE(EMSUART_UART) &= ~(1 << UIFF); // disable fifo-full irq
length = 0;
while ((USS(EMSUART_UART) >> USRXC) & 0x0FF) { // read fifo into buffer
uint8_t rx = USF(EMSUART_UART);
if (length < EMS_MAXBUFFERSIZE) {
uart_buffer[length++] = rx;
} else {
drop_next_rx = true;
}
}
if (!drop_next_rx) {
pEMSRxBuf->length = length;
os_memcpy((void *)pEMSRxBuf->buffer, (void *)&uart_buffer, pEMSRxBuf->length); // copy data into transfer buffer, including the BRK 0x00 at the end
system_os_post(EMSUART_recvTaskPrio, 0, 0); // call emsuart_recvTask() at next opportunity
}
drop_next_rx = false;
sending_ = false;
}
}
/*
* system task triggered on BRK interrupt
* incoming received messages are always asynchronous
* The full buffer is sent to EMSESP::incoming_telegram()
*/
void ICACHE_FLASH_ATTR EMSuart::emsuart_recvTask(os_event_t * events) {
EMSRxBuf_t * pCurrent = pEMSRxBuf;
pEMSRxBuf = paEMSRxBuf[++emsRxBufIdx % EMS_MAXBUFFERS]; // next free EMS Receive buffer
uint8_t length = pCurrent->length; // number of bytes including the BRK at the end
pCurrent->length = 0;
// Ignore telegrams with no data value, then transmit EMS buffer, excluding the BRK
if (length > 4 || length == 2) {
EMSESP::incoming_telegram((uint8_t *)pCurrent->buffer, length - 1);
}
}
/*
* flush everything left over in buffer, this clears both rx and tx FIFOs
*/
void ICACHE_FLASH_ATTR EMSuart::emsuart_flush_fifos() {
USC0(EMSUART_UART) |= ((1 << UCRXRST) | (1 << UCTXRST)); // set bits
USC0(EMSUART_UART) &= ~((1 << UCRXRST) | (1 << UCTXRST)); // clear bits
}
// ISR to Fire when Timer is triggered
void ICACHE_RAM_ATTR EMSuart::emsuart_tx_timer_intr_handler() {
if (tx_mode_ > 50) {
for (uint8_t i = 0; i < emsTxBufLen; i++) {
USF(EMSUART_UART) = emsTxBuf[i];
}
USC0(EMSUART_UART) |= (1 << UCBRK); // set <BRK>
} else {
if (emsTxBufIdx > emsTxBufLen) {
return;
}
if (emsTxBufIdx < emsTxBufLen) {
USF(EMSUART_UART) = emsTxBuf[emsTxBufIdx];
timer1_write(emsTxWait);
} else if (emsTxBufIdx == emsTxBufLen) {
USC0(EMSUART_UART) |= (1 << UCBRK); // set <BRK>
}
emsTxBufIdx++;
}
}
/*
* init UART0 driver
*/
void ICACHE_FLASH_ATTR EMSuart::start(uint8_t tx_mode) {
if (tx_mode > 50) {
emsTxWait = 5 * EMSUART_TX_BIT_TIME * (tx_mode - 50); // bittimes wait before sending
} else if (tx_mode > 5) {
emsTxWait = 5 * EMSUART_TX_BIT_TIME * (tx_mode + 10); // bittimes wait between bytes
}
if (tx_mode_ != 0xFF) { // it's a restart no need to configure uart
tx_mode_ = tx_mode;
restart();
return;
}
tx_mode_ = tx_mode;
// allocate and preset EMS Receive buffers
for (int i = 0; i < EMS_MAXBUFFERS; i++) {
EMSRxBuf_t * p = (EMSRxBuf_t *)malloc(sizeof(EMSRxBuf_t));
p->length = 0;
paEMSRxBuf[i] = p;
}
pEMSRxBuf = paEMSRxBuf[0]; // reset EMS Rx Buffer
ETS_UART_INTR_DISABLE();
ETS_UART_INTR_ATTACH(nullptr, nullptr);
// pin settings
PIN_PULLUP_DIS(PERIPHS_IO_MUX_U0TXD_U);
PIN_FUNC_SELECT(PERIPHS_IO_MUX_U0TXD_U, FUNC_U0TXD);
PIN_PULLUP_DIS(PERIPHS_IO_MUX_U0RXD_U);
PIN_FUNC_SELECT(PERIPHS_IO_MUX_U0RXD_U, FUNC_U0RXD);
// set 9600, 8 bits, no parity check, 1 stop bit
USD(EMSUART_UART) = (UART_CLK_FREQ / EMSUART_BAUD);
if (tx_mode_ == 5) {
USC0(EMSUART_UART) = 0x2C; // 8N1.5
} else {
USC0(EMSUART_UART) = EMSUART_CONFIG; // 8N1
}
emsuart_flush_fifos();
// conf1 params
// UCTOE = RX TimeOut enable (default is 1)
// UCTOT = RX TimeOut Threshold (7 bit) = want this when no more data after 1 characters (default is 2)
// UCFFT = RX FIFO Full Threshold (7 bit) = want this to be 31 for 32 bytes of buffer (default was 127)
// see https://www.espressif.com/sites/default/files/documentation/esp8266-technical_reference_en.pdf
//
// change: we set UCFFT to 1 to get an immediate indicator about incoming traffic.
// Otherwise, we're only noticed by UCTOT or RxBRK!
// change: don't care, we do not use these interrupts
USC1(EMSUART_UART) = 0; // reset config first
// USC1(EMSUART_UART) = (0x7F << UCFFT) | (0x01 << UCTOT) | (1 << UCTOE); // enable interupts
// set interrupts for triggers
USIC(EMSUART_UART) = 0xFFFF; // clear all interupts
USIE(EMSUART_UART) = 0; // disable all interrupts
// enable rx break, fifo full and timeout.
// but not frame error UIFR (because they are too frequent) or overflow UIOF because our buffer is only max 32 bytes
// change: we don't care about Rx Timeout - it may lead to wrong readouts
// change:we don't care about Fifo full and read only on break-detect
USIE(EMSUART_UART) = (1 << UIBD) | (0 << UIFF) | (0 << UITO);
// set up interrupt callbacks for Rx
system_os_task(emsuart_recvTask, EMSUART_recvTaskPrio, recvTaskQueue, EMSUART_recvTaskQueueLen);
// disable esp debug which will go to Tx and mess up the line - see https://github.com/espruino/Espruino/issues/655
system_set_os_print(0);
// swap Rx and Tx pins to use GPIO13 (D7) and GPIO15 (D8) respectively
system_uart_swap();
ETS_UART_INTR_ATTACH(emsuart_rx_intr_handler, nullptr);
ETS_UART_INTR_ENABLE();
drop_next_rx = true;
// for sending with large delay in EMS+ mode we use a timer interrupt
timer1_attachInterrupt(emsuart_tx_timer_intr_handler); // Add ISR Function
timer1_enable(TIM_DIV16, TIM_EDGE, TIM_SINGLE); // 5 MHz timer
}
/*
* stop UART0 driver
* This is called prior to an OTA upload and also before a save to the filesystem to prevent conflicts
*/
void ICACHE_FLASH_ATTR EMSuart::stop() {
ETS_UART_INTR_DISABLE();
timer1_disable();
}
/*
* re-start UART0 driver
*/
void ICACHE_FLASH_ATTR EMSuart::restart() {
if (USIR(EMSUART_UART) & ((1 << UIBD))) {
USIC(EMSUART_UART) = (1 << UIBD); // INT clear the BREAK detect interrupt
drop_next_rx = true;
}
ETS_UART_INTR_ENABLE();
emsTxBufIdx = 0;
emsTxBufLen = 0;
timer1_enable(TIM_DIV16, TIM_EDGE, TIM_SINGLE);
}
/*
* Send a BRK signal
* Which is a 11-bit set of zero's (11 cycles)
*/
void ICACHE_FLASH_ATTR EMSuart::tx_brk() {
// make sure Tx FIFO is empty
while (((USS(EMSUART_UART) >> USTXC) & 0xFF)) {
}
// To create a 11-bit <BRK> we set TXD_BRK bit so the break signal will
// automatically be sent when the tx fifo is empty
ETS_UART_INTR_DISABLE();
USC0(EMSUART_UART) |= (1 << UCBRK); // set bit
// also for EMS+ there is no need to wait longer, we are finished and can free the bus.
delayMicroseconds(EMSUART_TX_WAIT_BRK); // 1144
USC0(EMSUART_UART) &= ~(1 << UCBRK); // clear BRK bit
ETS_UART_INTR_ENABLE();
}
/*
* Sends a 1-byte poll, ending with a <BRK>
* It's a bit dirty. there is no special wait logic per tx_mode type, fifo flushes or error checking
*/
void EMSuart::send_poll(uint8_t data) {
// reset tx-brk, just in case it is accidentally set
USC0(EMSUART_UART) &= ~(1 << UCBRK);
sending_ = true;
if (tx_mode_ > 50) { // timer controlled modes
emsTxBuf[0] = data;
emsTxBufLen = 1;
timer1_write(emsTxWait);
} else if (tx_mode_ > 5) { // timer controlled modes
emsTxBuf[0] = data;
emsTxBufIdx = 0;
emsTxBufLen = 1;
timer1_write(emsTxWait);
} else if (tx_mode_ == 5) {
delayMicroseconds(3000);
USF(EMSUART_UART) = data;
USC0(EMSUART_UART) |= (1 << UCBRK);
} else if (tx_mode_ == EMS_TXMODE_NEW) { // hardware controlled modes
USF(EMSUART_UART) = data;
USC0(EMSUART_UART) |= (1 << UCBRK);
} else if (tx_mode_ == EMS_TXMODE_HT3) {
USF(EMSUART_UART) = data;
delayMicroseconds(EMSUART_TX_WAIT_HT3);
tx_brk(); // send <BRK>
} else if (tx_mode_ == EMS_TXMODE_EMSPLUS) {
USF(EMSUART_UART) = data;
delayMicroseconds(EMSUART_TX_WAIT_PLUS);
tx_brk(); // send <BRK>
} else {
// tx_mode 1
// EMS1.0, same logic as in transmit
ETS_UART_INTR_DISABLE();
volatile uint8_t _usrxc = (USS(EMSUART_UART) >> USRXC) & 0xFF;
USF(EMSUART_UART) = data;
uint16_t timeoutcnt = EMSUART_TX_TIMEOUT;
while ((((USS(EMSUART_UART) >> USRXC) & 0xFF) == _usrxc) && (--timeoutcnt > 0)) {
delayMicroseconds(EMSUART_TX_BUSY_WAIT); // burn CPU cycles...
}
USC0(EMSUART_UART) |= (1 << UCBRK); // set <BRK>
timeoutcnt = EMSUART_TX_TIMEOUT;
while (!(USIR(EMSUART_UART) & (1 << UIBD)) && (--timeoutcnt > 0)) {
delayMicroseconds(EMSUART_TX_BUSY_WAIT);
}
USC0(EMSUART_UART) &= ~(1 << UCBRK); // clear <BRK>
ETS_UART_INTR_ENABLE();
}
}
/*
* Send data to Tx line, ending with a <BRK>
* buf contains the CRC and len is #bytes including the CRC
* returns code, 0=success, 1=brk error, 2=watchdog timeout
*/
uint16_t ICACHE_FLASH_ATTR EMSuart::transmit(uint8_t * buf, uint8_t len) {
if (len == 0 || len >= EMS_MAXBUFFERSIZE) {
return EMS_TX_STATUS_ERR; // nothing or to much to send
}
// reset tx-brk, just in case it is accidentally set
USC0(EMSUART_UART) &= ~(1 << UCBRK);
sending_ = true;
// all at once after a inititial timer delay
if (tx_mode_ > 50) {
for (uint8_t i = 0; i < len; i++) {
emsTxBuf[i] = buf[i];
}
emsTxBufLen = len;
timer1_write(emsTxWait);
return EMS_TX_STATUS_OK;
}
// timer controlled modes with extra delay
if (tx_mode_ > 5) {
for (uint8_t i = 0; i < len; i++) {
emsTxBuf[i] = buf[i];
}
emsTxBufIdx = 0;
emsTxBufLen = len;
timer1_write(emsTxWait);
return EMS_TX_STATUS_OK;
}
// fixed dealy before sending
if (tx_mode_ == 5) {
delayMicroseconds(3000);
for (uint8_t i = 0; i < len; i++) {
USF(EMSUART_UART) = buf[i];
}
USC0(EMSUART_UART) |= (1 << UCBRK); // send <BRK> at the end
return EMS_TX_STATUS_OK;
}
// new code from Michael. See https://github.com/proddy/EMS-ESP/issues/380
if (tx_mode_ == EMS_TXMODE_NEW) { // tx_mode 4
for (uint8_t i = 0; i < len; i++) {
USF(EMSUART_UART) = buf[i];
}
USC0(EMSUART_UART) |= (1 << UCBRK); // send <BRK> at the end
return EMS_TX_STATUS_OK;
}
// EMS+ https://github.com/proddy/EMS-ESP/issues/23#
if (tx_mode_ == EMS_TXMODE_EMSPLUS) { // tx_mode 2, With extra tx delay for EMS+
for (uint8_t i = 0; i < len; i++) {
USF(EMSUART_UART) = buf[i];
delayMicroseconds(EMSUART_TX_WAIT_PLUS); // 2070
}
tx_brk(); // send <BRK>
return EMS_TX_STATUS_OK;
}
// Junkers logic by @philrich, tx_mode 3
if (tx_mode_ == EMS_TXMODE_HT3) {
for (uint8_t i = 0; i < len; i++) {
USF(EMSUART_UART) = buf[i];
// just to be safe wait for tx fifo empty (still needed?)
while (((USS(EMSUART_UART) >> USTXC) & 0xff)) {
}
// wait until bits are sent on wire
delayMicroseconds(EMSUART_TX_WAIT_HT3);
}
tx_brk(); // send <BRK>
return EMS_TX_STATUS_OK;
}
/*
* Logic for tx_mode of 1
* based on code from https://github.com/proddy/EMS-ESP/issues/103 by @susisstrolch
*
* Logic:
* we emit the whole telegram, with Rx interrupt disabled, collecting busmaster response in FIFO.
* after sending the last char we poll the Rx status until either
* - size(Rx FIFO) == size(Tx-Telegram)
* - <BRK> is detected
* At end of receive we re-enable Rx-INT and send a Tx-BRK in loopback mode.
*
* EMS-Bus error handling
* 1. Busmaster stops echoing on Tx w/o permission
* 2. Busmaster cancel telegram by sending a BRK
*
* Case 1. is handled by a watchdog counter which is reset on each
* Tx attempt. The timeout should be 20x EMSUART_TX_BIT_TIME plus
* some smart guess for processing time on targeted EMS device.
* We set Status to EMS_TX_WTD_TIMEOUT and return
*
* Case 2. is handled via a BRK chk during transmission.
* We set Status to EMS_TX_BRK_DETECT and return
*
*/
// disable rx interrupt
// clear Rx status register, resetting the Rx FIFO and flush it
ETS_UART_INTR_DISABLE();
emsuart_flush_fifos();
// send the bytes along the serial line
for (uint8_t i = 0; i < len; i++) {
volatile uint8_t _usrxc = (USS(EMSUART_UART) >> USRXC) & 0xFF;
uint16_t timeoutcnt = EMSUART_TX_TIMEOUT;
USF(EMSUART_UART) = buf[i]; // send each Tx byte
// wait for echo
while ((((USS(EMSUART_UART) >> USRXC) & 0xFF) == _usrxc) && (--timeoutcnt > 0)) {
delayMicroseconds(EMSUART_TX_BUSY_WAIT); // burn CPU cycles...
}
}
// we got the whole telegram in the Rx buffer
// on Rx-BRK (bus collision), we simply enable Rx and leave it
// otherwise we send the final Tx-BRK in the loopback and re=enable Rx-INT.
// worst case, we'll see an additional Rx-BRK...
// neither bus collision nor timeout - send terminating BRK signal
if (!(USIS(EMSUART_UART) & (1 << UIBD))) {
// no bus collision - send terminating BRK signal
USC0(EMSUART_UART) |= (1 << UCBRK); // set <BRK>
uint16_t timeoutcnt = EMSUART_TX_TIMEOUT;
// wait until BRK detected...
while (!(USIR(EMSUART_UART) & (1 << UIBD)) && (--timeoutcnt > 0)) {
delayMicroseconds(EMSUART_TX_BUSY_WAIT);
}
USC0(EMSUART_UART) &= ~(1 << UCBRK); // clear <BRK>
}
ETS_UART_INTR_ENABLE(); // open up the FIFO again to start receiving
return EMS_TX_STATUS_OK; // send the Tx ok status back
}
} // namespace emsesp
#endif

View File

@@ -0,0 +1,94 @@
/*
* EMS-ESP - https://github.com/proddy/EMS-ESP
* Copyright 2019 Paul Derbyshire
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#if defined(ESP8266)
#ifndef EMSESP_EMSUART_H
#define EMSESP_EMSUART_H
#include <Arduino.h>
#include <user_interface.h>
#define EMSUART_UART 0 // UART 0
#define EMSUART_CONFIG 0x1C // 8N1 (8 bits, no parity, 1 stop bit)
#define EMSUART_BAUD 9600 // uart baud rate for the EMS circuit
#define EMS_MAXBUFFERS 3 // buffers for circular filling to avoid collisions
#define EMS_MAXBUFFERSIZE 33 // max size of the buffer. EMS packets are max 32 bytes, plus extra 2 for BRKs
#define EMSUART_recvTaskPrio 2 // 0, 1 or 2. 0 being the lowest
#define EMSUART_recvTaskQueueLen 10 // number of queued Rx triggers
#define EMS_TXMODE_DEFAULT 1
#define EMS_TXMODE_EMSPLUS 2
#define EMS_TXMODE_HT3 3
#define EMS_TXMODE_NEW 4 // for michael's testing
// LEGACY
#define EMSUART_TX_BIT_TIME 104 // bit time @9600 baud
#define EMSUART_TX_WAIT_BRK (EMSUART_TX_BIT_TIME * 11) // 1144
// EMS 1.0
#define EMSUART_TX_BUSY_WAIT (EMSUART_TX_BIT_TIME / 8) // 13
// #define EMSUART_TX_TIMEOUT (22 * EMSUART_TX_BIT_TIME / EMSUART_TX_BUSY_WAIT) // 176
#define EMSUART_TX_TIMEOUT (32 * 8) // 256 for tx_mode 1 - see https://github.com/proddy/EMS-ESP/issues/398#issuecomment-645886277
// HT3/Junkers - Time to send one Byte (8 Bits, 1 Start Bit, 1 Stop Bit) plus 7 bit delay. The -8 is for lag compensation.
// since we use a faster processor the lag is negligible
#define EMSUART_TX_WAIT_HT3 (EMSUART_TX_BIT_TIME * 17) // 1768
// EMS+ - Time to send one Byte (8 Bits, 1 Start Bit, 1 Stop Bit) and delay of another Bytetime.
#define EMSUART_TX_WAIT_PLUS (EMSUART_TX_BIT_TIME * 20) // 2080
namespace emsesp {
#define EMS_TX_STATUS_ERR 0
#define EMS_TX_STATUS_OK 1
class EMSuart {
public:
EMSuart() = default;
~EMSuart() = default;
static void ICACHE_FLASH_ATTR start(uint8_t tx_mode);
static void ICACHE_FLASH_ATTR stop();
static void ICACHE_FLASH_ATTR restart();
static void ICACHE_FLASH_ATTR send_poll(uint8_t data);
static uint16_t ICACHE_FLASH_ATTR transmit(uint8_t * buf, uint8_t len);
static bool sending() {
return sending_;
}
typedef struct {
uint8_t length;
uint8_t buffer[EMS_MAXBUFFERSIZE];
} EMSRxBuf_t;
private:
static void ICACHE_RAM_ATTR emsuart_rx_intr_handler(void * para);
static void ICACHE_FLASH_ATTR emsuart_recvTask(os_event_t * events);
static void ICACHE_FLASH_ATTR emsuart_flush_fifos();
static void ICACHE_FLASH_ATTR tx_brk();
static void ICACHE_RAM_ATTR emsuart_tx_timer_intr_handler();
static bool sending_;
};
} // namespace emsesp
#endif
#endif