mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-08-28 16:49:54 +02:00
Changed buffer sizes to 256 throughout various parts of the program. (#626)
This is a patch necessary for F360 personal users, because they decided to add a very lengthy comment... Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>
This commit is contained in:
@@ -31,7 +31,7 @@
|
|||||||
// memory space we can invest into here or we re-write the g-code parser not to have this
|
// memory space we can invest into here or we re-write the g-code parser not to have this
|
||||||
// buffer.
|
// buffer.
|
||||||
#ifndef LINE_BUFFER_SIZE
|
#ifndef LINE_BUFFER_SIZE
|
||||||
# define LINE_BUFFER_SIZE 80
|
# define LINE_BUFFER_SIZE 256
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Starts Grbl main loop. It handles all incoming characters from the serial port and executes
|
// Starts Grbl main loop. It handles all incoming characters from the serial port and executes
|
||||||
|
@@ -70,6 +70,7 @@ uint8_t serial_get_rx_buffer_available(uint8_t client) {
|
|||||||
|
|
||||||
void serial_init() {
|
void serial_init() {
|
||||||
Serial.begin(BAUD_RATE);
|
Serial.begin(BAUD_RATE);
|
||||||
|
Serial.setRxBufferSize(256);
|
||||||
// reset all buffers
|
// reset all buffers
|
||||||
serial_reset_read_buffer(CLIENT_ALL);
|
serial_reset_read_buffer(CLIENT_ALL);
|
||||||
grbl_send(CLIENT_SERIAL, "\r\n"); // create some white space after ESP32 boot info
|
grbl_send(CLIENT_SERIAL, "\r\n"); // create some white space after ESP32 boot info
|
||||||
@@ -104,7 +105,8 @@ void serialCheckTask(void* pvParameters) {
|
|||||||
if (WebUI::SerialBT.hasClient() && WebUI::SerialBT.available()) {
|
if (WebUI::SerialBT.hasClient() && WebUI::SerialBT.available()) {
|
||||||
client = CLIENT_BT;
|
client = CLIENT_BT;
|
||||||
data = WebUI::SerialBT.read();
|
data = WebUI::SerialBT.read();
|
||||||
//Serial.write(data); // echo all data to serial
|
|
||||||
|
// Serial.write(data); // echo all data to serial.
|
||||||
} else {
|
} else {
|
||||||
#endif
|
#endif
|
||||||
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||||
|
@@ -23,7 +23,7 @@
|
|||||||
#include "Grbl.h"
|
#include "Grbl.h"
|
||||||
|
|
||||||
#ifndef RX_BUFFER_SIZE
|
#ifndef RX_BUFFER_SIZE
|
||||||
# define RX_BUFFER_SIZE 128
|
# define RX_BUFFER_SIZE 256
|
||||||
#endif
|
#endif
|
||||||
#ifndef TX_BUFFER_SIZE
|
#ifndef TX_BUFFER_SIZE
|
||||||
# ifdef USE_LINE_NUMBERS
|
# ifdef USE_LINE_NUMBERS
|
||||||
|
@@ -49,7 +49,7 @@ namespace WebUI {
|
|||||||
~InputBuffer();
|
~InputBuffer();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static const int RXBUFFERSIZE = 128;
|
static const int RXBUFFERSIZE = 256;
|
||||||
|
|
||||||
uint8_t _RXbuffer[RXBUFFERSIZE];
|
uint8_t _RXbuffer[RXBUFFERSIZE];
|
||||||
uint16_t _RXbufferSize;
|
uint16_t _RXbufferSize;
|
||||||
|
@@ -28,7 +28,7 @@ class WebSocketsServer;
|
|||||||
namespace WebUI {
|
namespace WebUI {
|
||||||
class Serial_2_Socket : public Print {
|
class Serial_2_Socket : public Print {
|
||||||
static const int TXBUFFERSIZE = 1200;
|
static const int TXBUFFERSIZE = 1200;
|
||||||
static const int RXBUFFERSIZE = 128;
|
static const int RXBUFFERSIZE = 256;
|
||||||
static const int FLUSHTIMEOUT = 500;
|
static const int FLUSHTIMEOUT = 500;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
Reference in New Issue
Block a user