Hi, I've been using Arduinos for a few years and I've never came across something like this. I'll explain.
I have 2 ESP32's. One ESP32 is connected with a Laser module and the other one with the receiver. Simply I want to transfer data from one ESP32 to the other. I've found some codes and got them together to get it working. Previously tested with 2 UNOs since there are couple of codes I found in the internet. With the UNO's I could not pass the 9600 baud rate, so I thought of moving to ESP32 since more powerful hardware.
For ESP32 things working for 9600 baud rate. But I want to go for higher speeds, at least 19200, 38400 or something because 9600 is slow and it took more than 4mins to send around 140kbytes.
Please can someone let me know how to configure the things here to reach more baud rates?
Transmitter
Manchester.h
#ifndef MANCHESTER_H
#define MANCHESTER_H
#include <Arduino.h>
class Manchester{
public:
Manchester();
void sendByte(uint8_t byte);
void sendArray(uint8_t length, uint8_t *data);
void sendOne(void);
void sendZero(void);
private:
uint8_t counter = 0;
uint8_t delay1 = 92;
uint8_t delay2 = 94;
uint8_t DECOUPLING_MASK = 0b11001010;
};
#endif
Manchester.cpp
#include "Manchester.h"
Manchester::Manchester(){
}
void Manchester::sendByte(uint8_t byte){
for(int8_t i = 0; i < 3; i++){
sendZero();
}
sendOne();
uint16_t mask = 0x80;
uint8_t d = byte ^ DECOUPLING_MASK;
for(uint8_t j = 0; j < 8; j++){
if((d & mask) == 0)
sendZero();
else
sendOne();
mask >>= 1;
}
sendZero();
sendZero();
sendZero();
}
void Manchester::sendArray(uint8_t length, uint8_t *data){
for(int8_t i = 0; i < 3; i++){
sendZero();
}
sendOne();
for(uint8_t i = 0; i < length; i++){
uint16_t mask = 0x80;
uint8_t d = data[i] ^ DECOUPLING_MASK;
for(uint8_t j = 0; j < 8; j++){
if((d & mask) == 0)
sendZero();
else
sendOne();
mask >>= 1;
}
}
sendZero();
sendZero();
sendZero();
}
void Manchester::sendZero(void)
{
REG_SET_BIT(GPIO_OUT_W1TC_REG, BIT21);
delayMicroseconds(delay1);
REG_SET_BIT(GPIO_OUT_W1TS_REG, BIT21);
delayMicroseconds(delay2);
Serial.print("10");
}
void Manchester::sendOne(void)
{
REG_SET_BIT(GPIO_OUT_W1TS_REG, BIT21);
delayMicroseconds(delay1);
REG_SET_BIT(GPIO_OUT_W1TC_REG, BIT21);
delayMicroseconds(delay2);
Serial.print("01");
}
#include "Manchester.h"
Manchester man;
void setup() {
Serial.begin(115200);
REG_SET_BIT(GPIO_ENABLE_REG, BIT21);
REG_WRITE (GPIO_FUNC21_OUT_SEL_CFG_REG, 0x100);
REG_SET_BIT(GPIO_OUT_W1TS_REG, BIT21);
}
uint8_t start[] = {10, 'S', 'T', 'A', 'R', 'T', 'R', 'E', 'C', 'V' };
void loop() {
man.sendArray(10, start);
Serial.println("Sent!");
delay(1000);
}
Receiver
#include "ManchesterRX.h"
#include "BitStream.h"
ManchesterRX man(GPIO_NUM_21, 100);
void setup() {
Serial.begin(115200);
man.startRX();
}
void loop() {
String myString;
BitStream *stream = man.getBuffer();
if(stream != NULL){
memset(ss, 0, 500);
stream->dumpBin(ss, stream->getLength());
String myString;
myString = ss;
delay(10000);
}
delay(5);
}
ManchesterRX.cpp
// Implementation of the Manchester Code receiver
// (c) 2019 miq1_AT_gmx_DOT_de
#include "ManchesterRX.h"
#include "mini-printf.h"
// Constructor. Here the RMT is set up, the data buffers are created and
// initialized.
ManchesterRX::ManchesterRX(gpio_num_t gpio, uint8_t bcnt)
: gpio_pin(gpio), buffer_cnt(bcnt)
{
// Create array of buffers
buffers = new BitStream[buffer_cnt];
// for each buffer, create data packet storage and initialize.
for(uint8_t i=0;i<buffer_cnt;i++)
{
buffers[i].init();
}
active_buffer = 0;
gpio_set_pull_mode(gpio_pin, GPIO_FLOATING); // try....
// Configure RMT
rmt_config_t rmt_rx;
rmt_rx.channel = (rmt_channel_t)0; // RMT channel
rmt_rx.gpio_num = gpio_pin; // GPIO pin
rmt_rx.clk_div = RMT_CLK_DIV; // Clock divider
rmt_rx.mem_block_num = 7; // number of mem blocks used
rmt_rx.rmt_mode = RMT_MODE_RX; // Receive mode
rmt_rx.rx_config.filter_en = true; // Enable filter
rmt_rx.rx_config.filter_ticks_thresh = 350; // Filter all shorter than 100 ticks
rmt_rx.rx_config.idle_threshold = 2000; // Timeout after 2000 ticks
// RMT seems to not initialize on restart sometimes, so shut it down and power it up again
periph_module_disable(PERIPH_RMT_MODULE);
periph_module_enable(PERIPH_RMT_MODULE);
rmt_config(&rmt_rx); // Init channel
rmt_driver_install(rmt_rx.channel, 40000, 0); // Install driver with ring buffer size 4000
rmt_get_ringbuf_handle((rmt_channel_t)0, &rb); //get RMT RX ringbuffer
taskP = NULL; // no task yet
}
// Destructor. Clean up memory and task, if any.
ManchesterRX::~ManchesterRX()
{
// kill task, if active
stopRX();
// clean up memory
delete buffers;
}
// Start receiving Manchester Code.
void ManchesterRX::startRX(void)
{
// Start the RMT
rmt_rx_start((rmt_channel_t)0, 1); // channel 0, clean memory
// If no task is running, create one now
if(taskP==NULL)
{
xTaskCreate(&ManchesterRX::staticReceiveTask, "ManchesterRX", 2048, this, 5, &taskP);
if(taskP)
{
Serial.printf("RX task started: %0X\n", (uint32_t)taskP);
}
}
}
// Stop receiving and kill task, if any.
void ManchesterRX::stopRX(void)
{
// Kill task, if one is active
if(taskP)
{
vTaskDelete(taskP);
Serial.println("RX task stopped");
taskP = NULL;
}
// now stop RMT as well
rmt_rx_stop((rmt_channel_t)0);
}
// Deliver an unprocessed message buffer to the caller, if available
BitStream * ManchesterRX::getBuffer(void)
{
// Scan through all buffers to find one yet unprocessed
for(uint8_t i=0;i<buffer_cnt;i++)
{
if(buffers[i].blocked()) return &buffers[i];
}
// No unprocessed buffer found.
return NULL;
}
// Try switching to another unused buffer
bool ManchesterRX::nextBuffer(void)
{
bool has_buffer = false;
// Scan all buffers
for(uint8_t i=0;i<buffer_cnt;i++)
{
// currently unused?
if(!buffers[i].blocked())
{
// Yes. pick it.
has_buffer = true;
active_buffer = i;
buffers[active_buffer].init();
break;
}
}
return has_buffer;
}
// Static member function to be used as task initiator
void ManchesterRX::staticReceiveTask(void *pvParameter)
{
ManchesterRX* rx = (ManchesterRX*)(pvParameter); //obtain the instance pointer
rx->receive(); //dispatch to the member function, now that we have an instance pointer
}
// The main receiver task.
// will loop forever and check the RMT filled ring buffer for valid messages.
// If one is found, a processing buffer is used and marked and the next ist used.
// if no more buffers are available, the data will remain in the ring buffer -
// hoping there will be a free one again on the next turn.
// Processing thus is doubly asynchronous - RMT to ring buffer and ring buffer to
// processing buffer.
bool ManchesterRX::receive()
{
size_t rx_size = 0; // size of ring buffer block returned
uint32_t cnt = 0; // number of received rmt_item32_t
bool has_buffer = false; // buffer to work on available?
uint16_t bmin, bmax;
const uint8_t statsize = 16;
uint16_t stats[statsize][2];
uint8_t BitCnt[statsize][2];
Serial.print("Receive: Executing on core ");
Serial.println(xPortGetCoreID());
// loop forever...
while(1)
{
// yield a bit to other tasks
//vTaskDelay(25);
// check if buffer is available
has_buffer = nextBuffer();
// Got one?
while(has_buffer)
{
// try to receive data from ringbuffer.
// RMT driver will push all the data it receives to its ringbuffer.
rmt_item32_t* item = (rmt_item32_t*) xRingbufferReceive(rb, &rx_size, RMT_WAIT_CYCLES);
// while we are getting ring buffer blocks, process them
while(item)
{
// Serial.printf("Buffer #%hhu\n", active_buffer);
// Item size ok? All else is no sensor data - fragments, overruns and other devices
if(rx_size>200 && rx_size<400)
{
cnt = 0; // Number of phase changes so far
bmin = 0xffff;
bmax = 0;
Serial.printf("block of %u", rx_size);
// Init decoder
rmt_item32_t *it = item; // local pointer copy for easier handling
// loop for all rmt_item32_t in ringbuffer block - 1st round to find min/max
for(uint32_t i=0;i<rx_size/sizeof(rmt_item32_t);i++)
{
if(it->duration0 && it->duration0<bmin) bmin = it->duration0;
if(it->duration1 && it->duration1<bmin) bmin = it->duration1;
if(it->duration0>bmax) bmax = it->duration0;
if(it->duration1>bmax) bmax = it->duration1;
it++;
}
uint16_t granularity = bmax/(statsize-1);
memset(stats, 0, sizeof(stats));
it = item; // reset pointer to start
// loop for all rmt_item32_t in ringbuffer block - 2nd round to group timings
for(uint32_t i=0;i<rx_size/sizeof(rmt_item32_t);i++)
{
if(it->duration0)
stats[(it->duration0)/granularity][it->level0]++;
else
stats[0][it->level0]++;
if(it->duration1)
stats[(it->duration1)/granularity][it->level1]++;
else
stats[0][it->level1]++;
it++;
}
uint8_t catcnt[2];
bool inCat[2];
memset(catcnt, 0, sizeof(catcnt));
memset(BitCnt, 0, sizeof(BitCnt));
inCat[0] = inCat[1] = false;
for(uint32_t i=0; i<statsize; i++)
{
if(i) // omit zero category
{
for(uint8_t bit=0; bit<2; bit++) // do for both 0 and 1 categories
{
if(inCat[bit]) // are we in a group?
{
// Yes.
if(stats[i][bit]==0) // category group ended
{
inCat[bit] = false;
}
else
{
BitCnt[i][bit] = catcnt[bit];
}
}
else // NO, we are not
{
if(stats[i][bit]>0) // category group starts
{
inCat[bit] = true;
catcnt[bit]++;
BitCnt[i][bit] = catcnt[bit];
}
}
}
}
// Serial.printf("%3d %4d: %4d/%2d %4d/%2d\n", i, i*granularity, stats[i][0], BitCnt[i][0], stats[i][1], BitCnt[i][1]);
}
it = item; // reset pointer to start
if(catcnt[0]<=2 || catcnt[1]<=2) // we can only handle these for now...
{
// loop for all rmt_item32_t in ringbuffer block
for(uint32_t i=0;i<rx_size/sizeof(rmt_item32_t);i++)
{
cnt++;
// now collect bits. As we may have received bit sequences already,
// we need to loop in bitLength steps.
// The Manchester code will in fact have sequences not longer than 2 bits!
// The phase length will be inaccurate in the beginning, but Will
// improve during the initialization sequence.
// With the first data bit it should be exact enough.
Serial.printf("%1d.%3d/%1d.%3d ", it->level0, it->duration0, it->level1, it->duration1);
for(uint32_t j=0; j<BitCnt[it->duration0/granularity][it->level0]; j++)
{
buffers[active_buffer].putBit(it->level0);
}
for(uint32_t j=0; j<BitCnt[it->duration1/granularity][it->level1]; j++)
{
buffers[active_buffer].putBit(it->level1);
}
if(it->duration0==0 || it->duration1==0) break; // Last item
else it++; // next rmt_item32_t!
}
Serial.println("-");
// Packet completely received
// close buffer and start another, if available
buffers[active_buffer].block();
has_buffer = nextBuffer();
}
}
// release ring buffer block
vRingbufferReturnItem(rb, (void*) item);
// if no workable buffer available, bail out
if(!has_buffer) break;
// there may be another item in the meantime
item = (rmt_item32_t*) xRingbufferReceive(rb, &rx_size, RMT_WAIT_CYCLES);
}
}
Serial.println("Out of buffers?");
}
vTaskDelete(NULL);
return false;
}
ManchesterRX.h
// Header for Manchester Code receiver
// Will be run in a separate task!
#ifndef _MANCHESTERRX_H
#define _MANCHESTERRX_H
#include <Arduino.h>
// We will be using the RMT as well as the FreeRTOS task management
extern "C" {
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "freertos/semphr.h"
#include "esp_err.h"
#include "esp_log.h"
#include "driver/rmt.h"
#include "driver/periph_ctrl.h"
#include "soc/rmt_reg.h"
}
#include "BitStream.h"
// Definitions for the RMT setup
#define RMT_CLK_DIV 150 /*!< RMT counter clock divider */
#define RMT_TICK_10_US (80000000/RMT_CLK_DIV/100000) /*!< RMT counter value for 10 us.(Source clock is APB clock) */
#define RMT_WAIT_CYCLES 500
// The receiver class proper
class ManchesterRX
{
protected:
RingbufHandle_t rb; // Ring buffer handle from RMT
gpio_num_t gpio_pin; // GPIO to listen to
BitStream *buffers; // Pointer to packet buffers array
uint8_t buffer_cnt; // number of packet buffers
uint8_t active_buffer; // currently used buffer
TaskHandle_t taskP; // handle for running receive() task
bool nextBuffer(void);
// static receiver task function
static void staticReceiveTask(void *pvParameter);
// the receiver task called by the above
bool receive(void);
public:
// Constructor. Takes the GPIO pin to listen, the number of buffers and
// the size of each buffer as arguments
ManchesterRX(gpio_num_t gpio, uint8_t buffers=2);
// Destructor
~ManchesterRX();
// Start receiving (and task)
void startRX(void);
// Stop receiving (and task)
void stopRX(void);
// Deliver completed, but yet unprocessed buffer to caller
BitStream *getBuffer(void);
};
#endif
[BitStream.cpp|attachment](upload://5ATV8a0yqEfXnNiHsApE7YyVClu.cpp) (2.9 KB)
[BitStream.h|attachment](upload://icucCFCp9k3n99NVDuLUXBIcn48.h) (1.8 KB)
I attached the bitstream