1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-08-16 03:24:15 +02:00
* Oled2 (#834)

* WIP

* WIP

* Update platformio.ini

* WIP

* Cleanup

* Update platformio.ini

* Turn off soft limits with max travel (#836)

https://github.com/bdring/Grbl_Esp32/issues/831

* Yalang YL620 VFD (#838)

* New SpindleType YL620

Files for new SpindleType Yalang 620. So far the contents are a duplicate of H2ASpindle.h and H2ASpindle.cpp

* Added register documentation and implemented read and write data packets

* Some fixes, mostly regarding RX packet length

* OLED and Other Updates (#844)

* publish

* Updates - CoreXY and OLED

- Moved position calculation out of report_realtime_status(...) so other functions can access it.
- Added a function to check if a limit switch is defined
- CoreXY fixed bug in forward kinematics when midtbot is used.
- Modified OLED display.

* Cleanup for PR

* Delete midtbot_x2.h

* Incorporated PR 846

- Some OLED cleanup
- verified correct forward kinematics on MidTbot

* Pio down rev (#850)

* Update platformio.ini

* Update Grbl.h

* Use local UART driver not HardwareSerial (#857)

* Use local UART driver not HardwareSerial

The HardwareSerial driver is broken in Arduino framework versions
1.0.5 and 1.0.6 .  https://github.com/espressif/arduino-esp32/issues/5005
Instead of waiting for a fix, I wrote a very simple UART driver that
does exactly what we need with no unnecessary bells and whistles to
cause problems.

* Added missing files, changed method signatures

The methods implemented by the UART class now
have the same signatures as the HardwareSerial
class, so it will be easy to switch back if we
need to.

* Incorporated suggestions from Stefan

* Fixed TX_IDLE_NUM bug reported by mstrens

* Quick test for Bf: problem

This is not the final solution.

* Fixed stupid typo in last commit

* Another test - check for client_buffer space

* Use the esp-idf uart driver

You can revert to the direct driver for testing by
defining DIRECT_UART

* Uart class now supports VFD and TMC

* data bits, stop bits, parity as enum classes

The constants for data bits, stop bits, and parity
were changed to enum classes so the compiler can
check for argument order mismatches.

* Set half duplex after uart init

* Init TMC UART only once

* rx/tx pin order mixup, missing _uart_started

* Test: use Arduino Serial

This reverts to the Arduino serial driver for
UI communication, leaving the VFS comms on the
Uart class on top of the esp_idf UART driver.

You can switch back and forth with the
   define REVERT_TO_SERIAL
line in Serial.cpp

* REVERT_TO_ARDUINO_SERIAL off by default

* Added debug messages

* Update Grbl.h

* Update platformio.ini

Co-authored-by: bdring <barton.dring@gmail.com>

* Fixed spindle sync for all VFD spindles (#868)

* Implemented H2A spindle sync fix. Untested.

* Changed the spindle sync fix to be in the VFD code.

* Update Grbl.h

Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>
Co-authored-by: bdring <barton.dring@gmail.com>

Co-authored-by: Mitch Bradley <wmb@firmworks.com>
Co-authored-by: marcosprojects <marco1601@web.de>
Co-authored-by: Stefan de Bruijn <atlaste@users.noreply.github.com>
Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>
This commit is contained in:
bdring
2021-04-19 13:46:29 -05:00
committed by GitHub
parent 6c8c613790
commit 48e204e443
23 changed files with 437 additions and 282 deletions

View File

@@ -30,7 +30,7 @@ void grbl_init() {
WiFi.enableSTA(false);
WiFi.enableAP(false);
WiFi.mode(WIFI_OFF);
serial_init(); // Setup serial baud rate and interrupts
client_init(); // Setup serial baud rate and interrupts
display_init();
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Grbl_ESP32 Ver %s Date %s", GRBL_VERSION, GRBL_VERSION_BUILD); // print grbl_esp32 verion info
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Compiled with ESP32 SDK:%s", ESP.getSdkVersion()); // print the SDK version
@@ -40,7 +40,7 @@ void grbl_init() {
#endif
settings_init(); // Load Grbl settings from non-volatile storage
stepper_init(); // Configure stepper pins and interrupt timers
system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files)
system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files)
init_motors();
memset(sys_position, 0, sizeof(sys_position)); // Clear machine position.
machine_init(); // weak definition in Grbl.cpp does nothing
@@ -93,8 +93,8 @@ static void reset_variables() {
sys_rt_s_override = SpindleSpeedOverride::Default;
// Reset Grbl primary systems.
serial_reset_read_buffer(CLIENT_ALL); // Clear serial read buffer
gc_init(); // Set g-code parser to default state
client_reset_read_buffer(CLIENT_ALL);
gc_init(); // Set g-code parser to default state
spindle->stop();
coolant_init();
limits_init();

View File

@@ -22,7 +22,7 @@
// Grbl versioning system
const char* const GRBL_VERSION = "1.3a";
const char* const GRBL_VERSION_BUILD = "20210401";
const char* const GRBL_VERSION_BUILD = "20210419";
//#include <sdkconfig.h>
#include <Arduino.h>
@@ -51,8 +51,9 @@ const char* const GRBL_VERSION_BUILD = "20210401";
#include "Limits.h"
#include "MotionControl.h"
#include "Protocol.h"
#include "Report.h"
#include "Uart.h"
#include "Serial.h"
#include "Report.h"
#include "Pins.h"
#include "Spindles/Spindle.h"
#include "Motors/Motors.h"

View File

@@ -48,6 +48,7 @@
#include "WebUI/ESPResponse.h"
#include "Probe.h"
#include "System.h"
#include "Serial.h"
#include "Report.h"
#include <FreeRTOS.h>

View File

@@ -55,10 +55,12 @@ void IRAM_ATTR isr_limit_switches() {
# ifdef HARD_LIMIT_FORCE_STATE_CHECK
// Check limit pin state.
if (limits_get_state()) {
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Debug, "Hard limits");
mc_reset(); // Initiate system kill.
sys_rt_exec_alarm = ExecAlarm::HardLimit; // Indicate hard limit critical event
}
# else
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Debug, "Hard limits");
mc_reset(); // Initiate system kill.
sys_rt_exec_alarm = ExecAlarm::HardLimit; // Indicate hard limit critical event
# endif
@@ -195,7 +197,8 @@ void limits_go_home(uint8_t cycle_mask) {
if (sys_rt_exec_alarm != ExecAlarm::None) {
motors_set_homing_mode(cycle_mask, false); // tell motors homing is done...failed
mc_reset(); // Stop motors, if they are running.
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Debug, "Homing fail");
mc_reset(); // Stop motors, if they are running.
protocol_execute_realtime();
return;
} else {
@@ -351,6 +354,7 @@ void limits_soft_check(float* target) {
}
} while (sys.state != State::Idle);
}
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Debug, "Soft limits");
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
sys_rt_exec_alarm = ExecAlarm::SoftLimit; // Indicate soft limit critical event
protocol_execute_realtime(); // Execute to enter critical event loop and system abort
@@ -367,7 +371,7 @@ void limitCheckTask(void* pvParameters) {
AxisMask switch_state;
switch_state = limits_get_state();
if (switch_state) {
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Limit Switch State %08d", switch_state);
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Debug, "Limit Switch State %08d", switch_state);
mc_reset(); // Initiate system kill.
sys_rt_exec_alarm = ExecAlarm::HardLimit; // Indicate hard limit critical event
}

View File

@@ -499,6 +499,7 @@ void mc_override_ctrl_update(uint8_t override_state) {
// lost, since there was an abrupt uncontrolled deceleration. Called at an interrupt level by
// realtime abort command and hard limits. So, keep to a minimum.
void mc_reset() {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Debug, "mc_reset()");
// Only this function can set the system reset. Helps prevent multiple kill calls.
if (!sys_rt_exec_state.bit.reset) {
sys_rt_exec_state.bit.reset = true;

View File

@@ -21,6 +21,7 @@
#include "Motor.h"
#include "StandardStepper.h"
#include "../Uart.h"
#include <TMCStepper.h> // https://github.com/teemuatlut/TMCStepper
@@ -63,7 +64,7 @@ const double TRINAMIC_UART_FCLK = 12700000.0; // Internal clock Approx (Hz) use
# define TMC_UART_TX UNDEFINED_PIN
#endif
extern HardwareSerial tmc_serial;
extern Uart tmc_serial;
namespace Motors {
@@ -75,6 +76,9 @@ namespace Motors {
};
class TrinamicUartDriver : public StandardStepper {
private:
static bool _uart_started;
public:
TrinamicUartDriver(uint8_t axis_index,
uint8_t step_pin,
@@ -128,4 +132,4 @@ namespace Motors {
// void config_message() override;
};
}
}

View File

@@ -26,10 +26,12 @@
#include <TMCStepper.h>
HardwareSerial tmc_serial(TMC_UART);
Uart tmc_serial(TMC_UART);
namespace Motors {
bool TrinamicUartDriver::_uart_started = false;
TrinamicUartDriver* TrinamicUartDriver::List = NULL; // a static ist of all drivers for stallguard reporting
/* HW Serial Constructor. */
@@ -41,9 +43,11 @@ namespace Motors {
_r_sense = r_sense;
this->addr = addr;
uart_set_pin(TMC_UART, TMC_UART_TX, TMC_UART_RX, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
tmc_serial.begin(115200, SERIAL_8N1, TMC_UART_RX, TMC_UART_TX);
tmc_serial.setRxBufferSize(128);
if (!_uart_started) {
tmc_serial.setPins(TMC_UART_TX, TMC_UART_RX);
tmc_serial.begin(115200, Uart::Data::Bits8, Uart::Stop::Bits1, Uart::Parity::None);
_uart_started = true;
}
hw_serial_init();
link = List;
@@ -231,7 +235,7 @@ namespace Motors {
tmcstepper->en_spreadCycle(false);
tmcstepper->pwm_autoscale(false);
tmcstepper->TCOOLTHRS(calc_tstep(homing_feed_rate->get(), 150.0));
tmcstepper->SGTHRS(constrain(axis_settings[_axis_index]->stallguard->get(),0,255));
tmcstepper->SGTHRS(constrain(axis_settings[_axis_index]->stallguard->get(), 0, 255));
break;
default:
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Unknown Trinamic mode:d", _mode);
@@ -394,4 +398,4 @@ namespace Motors {
#endif
}
}
}
}

View File

@@ -192,6 +192,7 @@ Error toggle_check_mode(const char* value, WebUI::AuthenticationLevel auth_level
// is idle and ready, regardless of alarm locks. This is mainly to keep things
// simple and consistent.
if (sys.state == State::CheckMode) {
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Debug, "Check mode");
mc_reset();
report_feedback_message(Message::Disabled);
} else {

View File

@@ -103,7 +103,7 @@ bool can_park() {
GRBL PRIMARY LOOP:
*/
void protocol_main_loop() {
serial_reset_read_buffer(CLIENT_ALL);
client_reset_read_buffer(CLIENT_ALL);
empty_lines();
//uint8_t client = CLIENT_SERIAL; // default client
// Perform some machine checks to make sure everything is good to go.
@@ -135,7 +135,7 @@ void protocol_main_loop() {
// Primary loop! Upon a system abort, this exits back to main() to reset the system.
// This is also where Grbl idles while waiting for something to do.
// ---------------------------------------------------------------------------------
uint8_t c;
int c;
for (;;) {
#ifdef ENABLE_SD_CARD
if (SD_ready_next) {
@@ -157,7 +157,7 @@ void protocol_main_loop() {
uint8_t client = CLIENT_SERIAL;
char* line;
for (client = 0; client < CLIENT_COUNT; client++) {
while ((c = serial_read(client)) != SERIAL_NO_DATA) {
while ((c = client_read(client)) != -1) {
Error res = add_char_to_line(c, client);
switch (res) {
case Error::Ok:

View File

@@ -54,30 +54,8 @@ EspClass esp;
#endif
const int DEFAULTBUFFERSIZE = 64;
// this is a generic send function that everything should use, so interfaces could be added (Bluetooth, etc)
void grbl_send(uint8_t client, const char* text) {
if (client == CLIENT_INPUT) {
return;
}
#ifdef ENABLE_BLUETOOTH
if (WebUI::SerialBT.hasClient() && (client == CLIENT_BT || client == CLIENT_ALL)) {
WebUI::SerialBT.print(text);
//delay(10); // possible fix for dropped characters
}
#endif
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_OUT)
if (client == CLIENT_WEBUI || client == CLIENT_ALL) {
WebUI::Serial2Socket.write((const uint8_t*)text, strlen(text));
}
#endif
#if defined(ENABLE_WIFI) && defined(ENABLE_TELNET)
if (client == CLIENT_TELNET || client == CLIENT_ALL) {
WebUI::telnet_server.write((const uint8_t*)text, strlen(text));
}
#endif
if (client == CLIENT_SERIAL || client == CLIENT_ALL) {
Serial.print(text);
}
client_write(client, text);
}
// This is a formating version of the grbl_send(CLIENT_ALL,...) function that work like printf
@@ -658,7 +636,7 @@ void report_realtime_status(uint8_t client) {
}
# endif //ENABLE_BLUETOOTH
if (client == CLIENT_SERIAL) {
bufsize = serial_get_rx_buffer_available(CLIENT_SERIAL);
bufsize = client_get_rx_buffer_available(CLIENT_SERIAL);
}
sprintf(temp, "|Bf:%d,%d", plan_get_block_buffer_available(), bufsize);
strcat(status, temp);

View File

@@ -57,15 +57,26 @@
#include "Grbl.h"
// Define this to use the Arduino serial (UART) driver instead
// of the one in Uart.cpp, which uses the ESP-IDF UART driver.
// This is for regression testing, and can be removed after
// testing is complete.
// #define REVERT_TO_ARDUINO_SERIAL
portMUX_TYPE myMutex = portMUX_INITIALIZER_UNLOCKED;
static TaskHandle_t serialCheckTaskHandle = 0;
static TaskHandle_t clientCheckTaskHandle = 0;
WebUI::InputBuffer client_buffer[CLIENT_COUNT]; // create a buffer for each client
// Returns the number of bytes available in a client buffer.
uint8_t serial_get_rx_buffer_available(uint8_t client) {
return client_buffer[client].availableforwrite();
uint8_t client_get_rx_buffer_available(uint8_t client) {
#ifdef REVERT_TO_ARDUINO_SERIAL
return 128 - Serial.available();
#else
return 128 - Uart0.available();
#endif
// return client_buffer[client].availableforwrite();
}
void heapCheckTask(void* pvParameters) {
@@ -85,75 +96,84 @@ void heapCheckTask(void* pvParameters) {
}
}
void serial_init() {
void client_init() {
#ifdef DEBUG_REPORT_HEAP_SIZE
// For a 2000-word stack, uxTaskGetStackHighWaterMark reports 288 words available
xTaskCreatePinnedToCore(heapCheckTask, "heapTask", 2000, NULL, 1, NULL, 1);
#endif
Serial.begin(BAUD_RATE);
Serial.setRxBufferSize(256);
// reset all buffers
serial_reset_read_buffer(CLIENT_ALL);
grbl_send(CLIENT_SERIAL, "\r\n"); // create some white space after ESP32 boot info
serialCheckTaskHandle = 0;
#ifdef REVERT_TO_ARDUINO_SERIAL
Serial.begin(BAUD_RATE, SERIAL_8N1, 3, 1, false);
client_reset_read_buffer(CLIENT_ALL);
Serial.write("\r\n"); // create some white space after ESP32 boot info
#else
Uart0.setPins(1, 3); // Tx 1, Rx 3 - standard hardware pins
Uart0.begin(BAUD_RATE, Uart::Data::Bits8, Uart::Stop::Bits1, Uart::Parity::None);
client_reset_read_buffer(CLIENT_ALL);
Uart0.write("\r\n"); // create some white space after ESP32 boot info
#endif
clientCheckTaskHandle = 0;
// create a task to check for incoming data
// For a 4096-word stack, uxTaskGetStackHighWaterMark reports 244 words available
// after WebUI attaches.
xTaskCreatePinnedToCore(serialCheckTask, // task
"serialCheckTask", // name for task
xTaskCreatePinnedToCore(clientCheckTask, // task
"clientCheckTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
&serialCheckTaskHandle,
&clientCheckTaskHandle,
SUPPORT_TASK_CORE // must run the task on same core
// core
);
}
// this task runs and checks for data on all interfaces
// REaltime stuff is acted upon, then characters are added to the appropriate buffer
void serialCheckTask(void* pvParameters) {
uint8_t data = 0;
uint8_t client = CLIENT_ALL; // who sent the data
static UBaseType_t uxHighWaterMark = 0;
while (true) { // run continuously
while (any_client_has_data()) {
if (Serial.available()) {
client = CLIENT_SERIAL;
data = Serial.read();
} else if (WebUI::inputBuffer.available()) {
client = CLIENT_INPUT;
data = WebUI::inputBuffer.read();
} else {
//currently is wifi or BT but better to prepare both can be live
static uint8_t getClientChar(uint8_t* data) {
int res;
#ifdef REVERT_TO_ARDUINO_SERIAL
if (client_buffer[CLIENT_SERIAL].availableforwrite() && (res = Serial.read()) != -1) {
#else
if (client_buffer[CLIENT_SERIAL].availableforwrite() && (res = Uart0.read()) != -1) {
#endif
*data = res;
return CLIENT_SERIAL;
}
if (WebUI::inputBuffer.available()) {
*data = WebUI::inputBuffer.read();
return CLIENT_INPUT;
}
//currently is wifi or BT but better to prepare both can be live
#ifdef ENABLE_BLUETOOTH
if (WebUI::SerialBT.hasClient() && WebUI::SerialBT.available()) {
client = CLIENT_BT;
data = WebUI::SerialBT.read();
// Serial.write(data); // echo all data to serial.
} else {
if (WebUI::SerialBT.hasClient()) {
if ((res = WebUI::SerialBT.read()) != -1) {
*data = res;
return CLIENT_BT;
}
}
#endif
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
if (WebUI::Serial2Socket.available()) {
client = CLIENT_WEBUI;
data = WebUI::Serial2Socket.read();
} else {
if (WebUI::Serial2Socket.available()) {
*data = WebUI::Serial2Socket.read();
return CLIENT_WEBUI;
}
#endif
#if defined(ENABLE_WIFI) && defined(ENABLE_TELNET)
if (WebUI::telnet_server.available()) {
client = CLIENT_TELNET;
data = WebUI::telnet_server.read();
}
if (WebUI::telnet_server.available()) {
*data = WebUI::telnet_server.read();
return CLIENT_TELNET;
}
#endif
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
}
#endif
#ifdef ENABLE_BLUETOOTH
}
#endif
}
return CLIENT_ALL;
}
// this task runs and checks for data on all interfaces
// REaltime stuff is acted upon, then characters are added to the appropriate buffer
void clientCheckTask(void* pvParameters) {
uint8_t data = 0;
uint8_t client; // who sent the data
static UBaseType_t uxHighWaterMark = 0;
while (true) { // run continuously
while ((client = getClientChar(&data)) != CLIENT_ALL) {
// Pick off realtime command characters directly from the serial stream. These characters are
// not passed into the main buffer, but these set system state flag bits for realtime execution.
if (is_realtime_command(data)) {
@@ -161,7 +181,7 @@ void serialCheckTask(void* pvParameters) {
} else {
#if defined(ENABLE_SD_CARD)
if (get_sd_state(false) < SDState::Busy) {
#endif //ENABLE_SD_CARD
#endif //ENABLE_SD_CARD
vTaskEnterCritical(&myMutex);
client_buffer[client].write(data);
vTaskExitCritical(&myMutex);
@@ -172,7 +192,7 @@ void serialCheckTask(void* pvParameters) {
grbl_msg_sendf(client, MsgLevel::Info, "SD card job running");
}
}
#endif //ENABLE_SD_CARD
#endif //ENABLE_SD_CARD
}
} // if something available
WebUI::COMMANDS::handle();
@@ -194,7 +214,7 @@ void serialCheckTask(void* pvParameters) {
}
}
void serial_reset_read_buffer(uint8_t client) {
void client_reset_read_buffer(uint8_t client) {
for (uint8_t client_num = 0; client_num < CLIENT_COUNT; client_num++) {
if (client == client_num || client == CLIENT_ALL) {
client_buffer[client_num].begin();
@@ -202,38 +222,12 @@ void serial_reset_read_buffer(uint8_t client) {
}
}
// Writes one byte to the TX serial buffer. Called by main program.
void serial_write(uint8_t data) {
Serial.write((char)data);
}
// Fetches the first byte in the serial read buffer. Called by protocol loop.
uint8_t serial_read(uint8_t client) {
uint8_t data;
// Fetches the first byte in the client read buffer. Called by protocol loop.
int client_read(uint8_t client) {
vTaskEnterCritical(&myMutex);
if (client_buffer[client].available()) {
data = client_buffer[client].read();
vTaskExitCritical(&myMutex);
//Serial.write((char)data);
return data;
} else {
vTaskExitCritical(&myMutex);
return SERIAL_NO_DATA;
}
}
bool any_client_has_data() {
return (Serial.available() || WebUI::inputBuffer.available()
#ifdef ENABLE_BLUETOOTH
|| (WebUI::SerialBT.hasClient() && WebUI::SerialBT.available())
#endif
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|| WebUI::Serial2Socket.available()
#endif
#if defined(ENABLE_WIFI) && defined(ENABLE_TELNET)
|| WebUI::telnet_server.available()
#endif
);
int data = client_buffer[client].read();
vTaskExitCritical(&myMutex);
return data;
}
// checks to see if a character is a realtime character
@@ -249,6 +243,7 @@ bool is_realtime_command(uint8_t data) {
void execute_realtime_command(Cmd command, uint8_t client) {
switch (command) {
case Cmd::Reset:
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Debug, "Cmd::Reset");
mc_reset(); // Call motion control reset routine.
break;
case Cmd::StatusReport:
@@ -350,3 +345,32 @@ void execute_realtime_command(Cmd command, uint8_t client) {
break;
}
}
void client_write(uint8_t client, const char* text) {
if (client == CLIENT_INPUT) {
return;
}
#ifdef ENABLE_BLUETOOTH
if (WebUI::SerialBT.hasClient() && (client == CLIENT_BT || client == CLIENT_ALL)) {
WebUI::SerialBT.print(text);
//delay(10); // possible fix for dropped characters
}
#endif
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_OUT)
if (client == CLIENT_WEBUI || client == CLIENT_ALL) {
WebUI::Serial2Socket.write((const uint8_t*)text, strlen(text));
}
#endif
#if defined(ENABLE_WIFI) && defined(ENABLE_TELNET)
if (client == CLIENT_TELNET || client == CLIENT_ALL) {
WebUI::telnet_server.write((const uint8_t*)text, strlen(text));
}
#endif
if (client == CLIENT_SERIAL || client == CLIENT_ALL) {
#ifdef REVERT_TO_ARDUINO_SERIAL
Serial.write(text);
#else
Uart0.write(text);
#endif
}
}

View File

@@ -20,7 +20,7 @@
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#include "Grbl.h"
#include "stdint.h"
#ifndef RX_BUFFER_SIZE
# define RX_BUFFER_SIZE 256
@@ -33,24 +33,22 @@
# endif
#endif
const float SERIAL_NO_DATA = 0xff;
// a task to read for incoming data from serial port
void serialCheckTask(void* pvParameters);
void clientCheckTask(void* pvParameters);
void client_write(uint8_t client, const char* text);
void serial_write(uint8_t data);
// Fetches the first byte in the serial read buffer. Called by main program.
uint8_t serial_read(uint8_t client);
int client_read(uint8_t client);
// See if the character is an action command like feedhold or jogging. If so, do the action and return true
uint8_t check_action_command(uint8_t data);
void serial_init();
void serial_reset_read_buffer(uint8_t client);
void client_init();
void client_reset_read_buffer(uint8_t client);
// Returns the number of bytes available in the RX serial buffer.
uint8_t serial_get_rx_buffer_available(uint8_t client);
uint8_t client_get_rx_buffer_available(uint8_t client);
void execute_realtime_command(Cmd command, uint8_t client);
bool any_client_has_data();
bool is_realtime_command(uint8_t data);

View File

@@ -28,17 +28,10 @@
managed to piece together.
*/
#include <driver/uart.h>
namespace Spindles {
void H2A::default_modbus_settings(uart_config_t& uart) {
// sets the uart to 19200 8E1
VFD::default_modbus_settings(uart);
uart.baud_rate = 19200;
uart.data_bits = UART_DATA_8_BITS;
uart.parity = UART_PARITY_EVEN;
uart.stop_bits = UART_STOP_BITS_1;
H2A::H2A() : VFD() {
_baudrate = 19200;
_parity = Uart::Parity::Even;
}
void H2A::direction_command(SpindleState mode, ModbusCommand& data) {

View File

@@ -24,8 +24,6 @@
namespace Spindles {
class H2A : public VFD {
protected:
void default_modbus_settings(uart_config_t& uart) override;
void direction_command(SpindleState mode, ModbusCommand& data) override;
void set_speed_command(uint32_t rpm, ModbusCommand& data) override;
@@ -36,5 +34,8 @@ namespace Spindles {
bool supports_actual_rpm() const override { return true; }
bool safety_polling() const override { return false; }
public:
H2A();
};
}

View File

@@ -149,15 +149,10 @@
If the frequency is -say- 25 Hz, Huanyang wants us to send 2500 (eg. 25.00 Hz).
*/
#include <driver/uart.h>
namespace Spindles {
void Huanyang::default_modbus_settings(uart_config_t& uart) {
// sets the uart to 9600 8N1
VFD::default_modbus_settings(uart);
// uart.baud_rate = 9600;
// Baud rate is set in the PD164 setting.
Huanyang::Huanyang() : VFD() {
// Baud rate is set in the PD164 setting. If it is not 9600, add, for example,
// _baudrate = 19200;
}
void Huanyang::direction_command(SpindleState mode, ModbusCommand& data) {

View File

@@ -35,8 +35,6 @@ namespace Spindles {
void updateRPM();
void default_modbus_settings(uart_config_t& uart) override;
void direction_command(SpindleState mode, ModbusCommand& data) override;
void set_speed_command(uint32_t rpm, ModbusCommand& data) override;
@@ -45,5 +43,8 @@ namespace Spindles {
response_parser get_current_rpm(ModbusCommand& data) override;
bool supports_actual_rpm() const override { return true; }
public:
Huanyang();
};
}

View File

@@ -42,11 +42,12 @@
// be plenty: assuming 9600 8N1, that's roughly 250 chars. A message of 2x16 chars with 4x4
// chars buffering is just 40 chars.
const uart_port_t VFD_RS485_UART_PORT = UART_NUM_2; // hard coded for this port right now
const int VFD_RS485_BUF_SIZE = 127;
const int VFD_RS485_QUEUE_SIZE = 10; // numv\ber of commands that can be queued up.
const int RESPONSE_WAIT_MILLIS = 1000; // how long to wait for a response in milliseconds
const int VFD_RS485_POLL_RATE = 250; // in milliseconds between commands
const int VFD_RS485_UART_PORT = 2; // hard coded for this port right now
const int VFD_RS485_BUF_SIZE = 127;
const int VFD_RS485_QUEUE_SIZE = 10; // numv\ber of commands that can be queued up.
const int RESPONSE_WAIT_MILLIS = 1000; // how long to wait for a response in milliseconds
const int VFD_RS485_POLL_RATE = 250; // in milliseconds between commands
const TickType_t response_ticks = RESPONSE_WAIT_MILLIS / portTICK_PERIOD_MS; // in milliseconds between commands
// OK to change these
// #define them in your machine definition file if you want different values
@@ -55,9 +56,48 @@ const int VFD_RS485_POLL_RATE = 250; // in milliseconds between comma
#endif
namespace Spindles {
Uart _uart(VFD_RS485_UART_PORT);
QueueHandle_t VFD::vfd_cmd_queue = nullptr;
TaskHandle_t VFD::vfd_cmdTaskHandle = nullptr;
VFD::VFD() :
_txd_pin(
#ifdef VFD_RS485_TXD_PIN
VFD_RS485_TXD_PIN
#else
-1
#endif
),
_rxd_pin(
#ifdef VFD_RS485_RXD_PIN
VFD_RS485_RXD_PIN
#else
-1
#endif
),
_rts_pin(
#ifdef VFD_RS485_RTS_PIN
VFD_RS485_RTS_PIN
#else
-1
#endif
),
_baudrate(
#ifdef VFD_RS485_BAUD_RATE
VFD_RS485_BAUD_RATE
#else
9600
#endif
),
_dataBits(Uart::Data::Bits8), _stopBits(Uart::Stop::Bits1), _parity(
#ifdef VFD_RS485_PARITY
VFD_RS485_PARITY
#else
Uart::Parity::None
#endif
) {
}
// The communications task
void VFD::vfd_cmd_task(void* pvParameters) {
static bool unresponsive = false; // to pop off a message once each time it becomes unresponsive
@@ -145,16 +185,15 @@ namespace Spindles {
int retry_count = 0;
for (; retry_count < MAX_RETRIES; ++retry_count) {
// Flush the UART:
uart_flush(VFD_RS485_UART_PORT);
_uart.flush();
// Write the data:
uart_write_bytes(VFD_RS485_UART_PORT, reinterpret_cast<const char*>(next_cmd.msg), next_cmd.tx_length);
uart_wait_tx_done(VFD_RS485_UART_PORT, RESPONSE_WAIT_MILLIS / portTICK_PERIOD_MS);
_uart.write(reinterpret_cast<const char*>(next_cmd.msg), next_cmd.tx_length);
_uart.flushTxTimed(response_ticks);
// Read the response
uint16_t read_length = 0;
uint16_t current_read =
uart_read_bytes(VFD_RS485_UART_PORT, rx_message, next_cmd.rx_length, RESPONSE_WAIT_MILLIS / portTICK_PERIOD_MS);
uint16_t read_length = 0;
uint16_t current_read = _uart.readBytes(rx_message, next_cmd.rx_length, response_ticks);
read_length += current_read;
// Apparently some Huanyang report modbus errors in the correct way, and the rest not. Sigh.
@@ -165,10 +204,7 @@ namespace Spindles {
while (read_length < next_cmd.rx_length && current_read > 0) {
// Try to read more; we're not there yet...
current_read = uart_read_bytes(VFD_RS485_UART_PORT,
rx_message + read_length,
next_cmd.rx_length - read_length,
RESPONSE_WAIT_MILLIS / portTICK_PERIOD_MS);
current_read = _uart.readBytes(rx_message + read_length, next_cmd.rx_length - read_length, response_ticks);
read_length += current_read;
}
if (current_read < 0) {
@@ -257,13 +293,6 @@ namespace Spindles {
}
// ================== Class methods ==================================
void VFD::default_modbus_settings(uart_config_t& uart) {
// Default is 9600 8N1, which is sane for most VFD's:
uart.baud_rate = 9600;
uart.data_bits = UART_DATA_8_BITS;
uart.parity = UART_PARITY_DISABLE;
uart.stop_bits = UART_STOP_BITS_1;
}
void VFD::init() {
vfd_ok = false; // initialize
@@ -281,38 +310,16 @@ namespace Spindles {
// this allows us to init() again later.
// If you change certain settings, init() gets called agian
uart_driver_delete(VFD_RS485_UART_PORT);
// uart_driver_delete(VFD_RS485_UART_PORT);
uart_config_t uart_config;
default_modbus_settings(uart_config);
// Overwrite with user defined defines:
#ifdef VFD_RS485_BAUD_RATE
uart_config.baud_rate = VFD_RS485_BAUD_RATE;
#endif
#ifdef VFD_RS485_PARITY
uart_config.parity = VFD_RS485_PARITY;
#endif
uart_config.flow_ctrl = UART_HW_FLOWCTRL_DISABLE;
uart_config.rx_flow_ctrl_thresh = 122;
if (uart_param_config(VFD_RS485_UART_PORT, &uart_config) != ESP_OK) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "RS485 VFD uart parameters failed");
return;
}
if (uart_set_pin(VFD_RS485_UART_PORT, _txd_pin, _rxd_pin, _rts_pin, UART_PIN_NO_CHANGE) != ESP_OK) {
if (_uart.setPins(_txd_pin, _rxd_pin, _rts_pin)) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "RS485 VFD uart pin config failed");
return;
}
if (uart_driver_install(VFD_RS485_UART_PORT, VFD_RS485_BUF_SIZE * 2, 0, 0, NULL, 0) != ESP_OK) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "RS485 VFD uart driver install failed");
return;
}
_uart.begin(_baudrate, _dataBits, _stopBits, _parity);
if (uart_set_mode(VFD_RS485_UART_PORT, UART_MODE_RS485_HALF_DUPLEX) != ESP_OK) {
if (_uart.setHalfDuplex()) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "RS485 VFD uart set half duplex failed");
return;
}
@@ -349,26 +356,20 @@ namespace Spindles {
bool VFD::get_pins_and_settings() {
bool pins_settings_ok = true;
#ifdef VFD_RS485_TXD_PIN
_txd_pin = VFD_RS485_TXD_PIN;
#else
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_TXD_PIN");
pins_settings_ok = false;
#endif
if (_txd_pin == -1) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_TXD_PIN");
pins_settings_ok = false;
}
#ifdef VFD_RS485_RXD_PIN
_rxd_pin = VFD_RS485_RXD_PIN;
#else
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_RXD_PIN");
pins_settings_ok = false;
#endif
if (_rxd_pin == -1) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_RXD_PIN");
pins_settings_ok = false;
}
#ifdef VFD_RS485_RTS_PIN
_rts_pin = VFD_RS485_RTS_PIN;
#else
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_RTS_PIN");
pins_settings_ok = false;
#endif
if (_rts_pin == -1) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_RTS_PIN");
pins_settings_ok = false;
}
if (laser_mode->get()) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "VFD spindle disabled in laser mode. Set $GCode/LaserMode=Off and restart");
@@ -564,9 +565,12 @@ namespace Spindles {
ModbusCommand rpm_cmd;
rpm_cmd.msg[0] = VFD_RS485_ADDR;
set_speed_command(rpm, rpm_cmd);
// Sometimes sync_rpm is retained between different set_speed_command's. We don't want that - we want
// spindle sync to kick in after we set the speed. This forces that.
_sync_rpm = UINT32_MAX;
rpm_cmd.critical = (rpm == 0);
if (xQueueSend(vfd_cmd_queue, &rpm_cmd, 0) != pdTRUE) {
@@ -576,7 +580,12 @@ namespace Spindles {
return rpm;
}
void VFD::stop() { set_mode(SpindleState::Disable, true); }
void VFD::stop() {
#ifdef VFD_DEBUG_MODE
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Debug, "VFD::stop()");
#endif
set_mode(SpindleState::Disable, true);
}
// state is cached rather than read right now to prevent delays
SpindleState VFD::get_state() { return _current_state; }

View File

@@ -20,11 +20,12 @@
*/
#include "Spindle.h"
#include <driver/uart.h>
#include "../Uart.h"
// #define VFD_DEBUG_MODE
namespace Spindles {
extern Uart _uart;
class VFD : public Spindle {
private:
@@ -34,9 +35,9 @@ namespace Spindles {
bool set_mode(SpindleState mode, bool critical);
bool get_pins_and_settings();
uint8_t _txd_pin;
uint8_t _rxd_pin;
uint8_t _rts_pin;
int _txd_pin;
int _rxd_pin;
int _rts_pin;
uint32_t _current_rpm = 0;
bool _task_running = false;
@@ -57,8 +58,6 @@ namespace Spindles {
uint8_t msg[VFD_RS485_MAX_MSG_SIZE];
};
virtual void default_modbus_settings(uart_config_t& uart);
// Commands:
virtual void direction_command(SpindleState mode, ModbusCommand& data) = 0;
virtual void set_speed_command(uint32_t rpm, ModbusCommand& data) = 0;
@@ -73,8 +72,14 @@ namespace Spindles {
virtual bool supports_actual_rpm() const { return false; }
virtual bool safety_polling() const { return true; }
// The constructor sets these
int _baudrate;
Uart::Data _dataBits;
Uart::Stop _stopBits;
Uart::Parity _parity;
public:
VFD() = default;
VFD();
VFD(const VFD&) = delete;
VFD(VFD&&) = delete;
VFD& operator=(const VFD&) = delete;

View File

@@ -75,18 +75,8 @@
b11: reserved
*/
#include <driver/uart.h>
namespace Spindles {
void YL620::default_modbus_settings(uart_config_t& uart) {
// sets the uart to 9600 8N1
VFD::default_modbus_settings(uart);
uart.baud_rate = 9600;
uart.data_bits = UART_DATA_8_BITS;
uart.parity = UART_PARITY_DISABLE;
uart.stop_bits = UART_STOP_BITS_1;
}
YL620::YL620() : VFD() {}
void YL620::direction_command(SpindleState mode, ModbusCommand& data) {
// NOTE: data length is excluding the CRC16 checksum.
@@ -94,20 +84,20 @@ namespace Spindles {
data.rx_length = 6;
// data.msg[0] is omitted (modbus address is filled in later)
data.msg[1] = 0x06; // 06: write output register
data.msg[2] = 0x20; // 0x2000: command register address
data.msg[1] = 0x06; // 06: write output register
data.msg[2] = 0x20; // 0x2000: command register address
data.msg[3] = 0x00;
data.msg[4] = 0x00; // High-Byte of command always 0x00
data.msg[4] = 0x00; // High-Byte of command always 0x00
switch (mode) {
case SpindleState::Cw:
data.msg[5] = 0x12; // Start in forward direction
data.msg[5] = 0x12; // Start in forward direction
break;
case SpindleState::Ccw:
data.msg[5] = 0x22; // Start in reverse direction
data.msg[5] = 0x22; // Start in reverse direction
break;
default: // SpindleState::Disable
data.msg[5] = 0x01; // Disable spindle
default: // SpindleState::Disable
data.msg[5] = 0x01; // Disable spindle
break;
}
}
@@ -118,17 +108,17 @@ namespace Spindles {
data.rx_length = 6;
// We have to know the max RPM before we can set the current RPM:
auto max_rpm = this->_max_rpm;
auto max_rpm = this->_max_rpm;
auto max_frequency = this->_maxFrequency;
uint16_t freqFromRPM = (uint16_t(rpm) * uint16_t(max_frequency)) / uint16_t(max_rpm);
#ifdef VFD_DEBUG_MODE
#ifdef VFD_DEBUG_MODE
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "For %d RPM the output frequency is set to %d Hz*10", int(rpm), int(freqFromRPM));
#endif
#endif
data.msg[1] = 0x06;
data.msg[2] = 0x20;
data.msg[2] = 0x20;
data.msg[3] = 0x01;
data.msg[4] = uint8_t(freqFromRPM >> 8);
data.msg[5] = uint8_t(freqFromRPM & 0xFF);
@@ -136,7 +126,6 @@ namespace Spindles {
VFD::response_parser YL620::initialization_sequence(int index, ModbusCommand& data) {
if (index == -1) {
// NOTE: data length is excluding the CRC16 checksum.
data.tx_length = 6;
data.rx_length = 5;
@@ -144,7 +133,7 @@ namespace Spindles {
data.msg[1] = 0x03;
data.msg[2] = 0x03;
data.msg[3] = 0x08;
data.msg[4] = 0x00;
data.msg[4] = 0x00;
data.msg[5] = 0x01;
// Recv: 01 03 02 03 E8 xx xx
@@ -152,15 +141,14 @@ namespace Spindles {
return [](const uint8_t* response, Spindles::VFD* vfd) -> bool {
auto yl620 = static_cast<YL620*>(vfd);
yl620->_minFrequency = (uint16_t(response[3]) << 8) | uint16_t(response[4]);
#ifdef VFD_DEBUG_MODE
#ifdef VFD_DEBUG_MODE
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "YL620 allows minimum frequency of %d Hz", int(yl620->_minFrequency));
#endif
#endif
return true;
};
}
else if (index == -2) {
} else if (index == -2) {
// NOTE: data length is excluding the CRC16 checksum.
data.tx_length = 6;
data.rx_length = 5;
@@ -168,7 +156,7 @@ namespace Spindles {
data.msg[1] = 0x03;
data.msg[2] = 0x00;
data.msg[3] = 0x00;
data.msg[4] = 0x00;
data.msg[4] = 0x00;
data.msg[5] = 0x01;
// Recv: 01 03 02 0F A0 xx xx
@@ -177,18 +165,21 @@ namespace Spindles {
auto yl620 = static_cast<YL620*>(vfd);
yl620->_maxFrequency = (uint16_t(response[3]) << 8) | uint16_t(response[4]);
vfd->_min_rpm = uint32_t(yl620->_minFrequency) * uint32_t(vfd->_max_rpm) / uint32_t(yl620->_maxFrequency); // 1000 * 24000 / 4000 = 6000 RPM.
vfd->_min_rpm = uint32_t(yl620->_minFrequency) * uint32_t(vfd->_max_rpm) /
uint32_t(yl620->_maxFrequency); // 1000 * 24000 / 4000 = 6000 RPM.
#ifdef VFD_DEBUG_MODE
#ifdef VFD_DEBUG_MODE
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "YL620 allows maximum frequency of %d Hz", int(yl620->_maxFrequency));
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Configured maxRPM of %d RPM results in minRPM of %d RPM", int(vfd->_max_rpm), int(vfd->_min_rpm));
#endif
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"Configured maxRPM of %d RPM results in minRPM of %d RPM",
int(vfd->_max_rpm),
int(vfd->_min_rpm));
#endif
return true;
};
}
else {
} else {
return nullptr;
}
}
@@ -200,7 +191,7 @@ namespace Spindles {
// Send: 01 03 200B 0001
data.msg[1] = 0x03;
data.msg[2] = 0x20;
data.msg[2] = 0x20;
data.msg[3] = 0x0B;
data.msg[4] = 0x00;
data.msg[5] = 0x01;
@@ -210,7 +201,7 @@ namespace Spindles {
return [](const uint8_t* response, Spindles::VFD* vfd) -> bool {
uint16_t freq = (uint16_t(response[3]) << 8) | uint16_t(response[4]);
auto yl620 = static_cast<YL620*>(vfd);
auto yl620 = static_cast<YL620*>(vfd);
uint16_t rpm = freq * uint16_t(vfd->_max_rpm) / uint16_t(yl620->_maxFrequency);
@@ -226,10 +217,10 @@ namespace Spindles {
data.rx_length = 5;
// Send: 01 03 20 00 00 01
data.msg[1] = 0x03;
data.msg[2] = 0x20;
data.msg[1] = 0x03;
data.msg[2] = 0x20;
data.msg[3] = 0x00;
data.msg[4] = 0x00;
data.msg[4] = 0x00;
data.msg[5] = 0x01;
// Receive: 01 03 02 00 0A xx xx

View File

@@ -24,10 +24,8 @@
namespace Spindles {
class YL620 : public VFD {
protected:
uint16_t _minFrequency = 0; // frequency lower limit. Factor 10 of actual frequency
uint16_t _minFrequency = 0; // frequency lower limit. Factor 10 of actual frequency
uint16_t _maxFrequency = 4000; // max frequency the VFD will allow. Normally 400.0. Factor 10 of actual frequency
void default_modbus_settings(uart_config_t& uart) override;
void direction_command(SpindleState mode, ModbusCommand& data) override;
void set_speed_command(uint32_t rpm, ModbusCommand& data) override;
@@ -39,5 +37,8 @@ namespace Spindles {
bool supports_actual_rpm() const override { return true; }
bool safety_polling() const override { return false; }
public:
YL620();
};
}

94
Grbl_Esp32/src/Uart.cpp Normal file
View File

@@ -0,0 +1,94 @@
/*
* UART driver that accesses the ESP32 hardware FIFOs directly.
*/
#include "Grbl.h"
#include "esp_system.h"
#include "soc/uart_reg.h"
#include "soc/io_mux_reg.h"
#include "soc/gpio_sig_map.h"
#include "soc/dport_reg.h"
#include "soc/rtc.h"
Uart::Uart(int uart_num) : _uart_num(uart_port_t(uart_num)), _pushback(-1) {}
void Uart::begin(unsigned long baudrate, Data dataBits, Stop stopBits, Parity parity) {
// uart_driver_delete(_uart_num);
uart_config_t conf;
conf.baud_rate = baudrate;
conf.data_bits = uart_word_length_t(dataBits);
conf.parity = uart_parity_t(parity);
conf.stop_bits = uart_stop_bits_t(stopBits);
conf.flow_ctrl = UART_HW_FLOWCTRL_DISABLE;
conf.rx_flow_ctrl_thresh = 0;
conf.use_ref_tick = false;
if (uart_param_config(_uart_num, &conf) != ESP_OK) {
return;
};
uart_driver_install(_uart_num, 256, 0, 0, NULL, 0);
}
int Uart::available() {
size_t size = 0;
uart_get_buffered_data_len(_uart_num, &size);
return size + (_pushback >= 0);
}
int Uart::peek() {
_pushback = read();
return _pushback;
}
int Uart::read(TickType_t timeout) {
if (_pushback >= 0) {
int ret = _pushback;
_pushback = -1;
return ret;
}
uint8_t c;
int res = uart_read_bytes(_uart_num, &c, 1, timeout);
return res != 1 ? -1 : c;
}
int Uart::read() {
return read(0);
}
size_t Uart::readBytes(char* buffer, size_t length, TickType_t timeout) {
bool pushback = _pushback >= 0;
if (pushback && length) {
*buffer++ = _pushback;
_pushback = -1;
--length;
}
int res = uart_read_bytes(_uart_num, (uint8_t*)buffer, length, timeout);
// The Stream class version of readBytes never returns -1,
// so if uart_read_bytes returns -1, we change that to 0
return pushback + (res >= 0 ? res : 0);
}
size_t Uart::readBytes(char* buffer, size_t length) {
return readBytes(buffer, length, (TickType_t)0);
}
size_t Uart::write(uint8_t c) {
return uart_write_bytes(_uart_num, (char*)&c, 1);
}
size_t Uart::write(const uint8_t* buffer, size_t length) {
return uart_write_bytes(_uart_num, (const char*)buffer, length);
}
size_t Uart::write(const char* text) {
return uart_write_bytes(_uart_num, text, strlen(text));
}
bool Uart::setHalfDuplex() {
return uart_set_mode(_uart_num, UART_MODE_RS485_HALF_DUPLEX) != ESP_OK;
}
bool Uart::setPins(int tx_pin, int rx_pin, int rts_pin, int cts_pin) {
return uart_set_pin(_uart_num, tx_pin, rx_pin, rts_pin, cts_pin) != ESP_OK;
}
bool Uart::flushTxTimed(TickType_t ticks) {
return uart_wait_tx_done(_uart_num, ticks) != ESP_OK;
}
Uart Uart0(0);

49
Grbl_Esp32/src/Uart.h Normal file
View File

@@ -0,0 +1,49 @@
#pragma once
#include <driver/uart.h>
class Uart : public Stream {
private:
uart_port_t _uart_num;
int _pushback;
public:
enum class Data : int {
Bits5 = UART_DATA_5_BITS,
Bits6 = UART_DATA_6_BITS,
Bits7 = UART_DATA_7_BITS,
Bits8 = UART_DATA_8_BITS,
};
enum class Stop : int {
Bits1 = UART_STOP_BITS_1,
Bits1_5 = UART_STOP_BITS_1_5,
Bits2 = UART_STOP_BITS_2,
};
enum class Parity : int {
None = UART_PARITY_DISABLE,
Even = UART_PARITY_EVEN,
Odd = UART_PARITY_ODD,
};
Uart(int uart_num);
bool setHalfDuplex();
bool setPins(int tx_pin, int rx_pin, int rts_pin = -1, int cts_pin = -1);
void begin(unsigned long baud, Data dataBits, Stop stopBits, Parity parity);
int available(void) override;
int read(void) override;
int read(TickType_t timeout);
size_t readBytes(char* buffer, size_t length, TickType_t timeout);
size_t readBytes(uint8_t* buffer, size_t length, TickType_t timeout) { return readBytes((char*)buffer, length, timeout); }
size_t readBytes(char* buffer, size_t length) override;
int peek(void) override;
size_t write(uint8_t data);
size_t write(const uint8_t* buffer, size_t length);
inline size_t write(const char* buffer, size_t size) { return write((uint8_t*)buffer, size); }
size_t write(const char* text);
void flush() { uart_flush(_uart_num); }
bool flushTxTimed(TickType_t ticks);
};
extern Uart Uart0;

View File

@@ -63,10 +63,10 @@ src_filter =
[env:release]
lib_deps =
TMCStepper@>=0.7.0,<1.0.0
squix78/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.0
ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.0
[env:debug]
build_type = debug
lib_deps =
TMCStepper@>=0.7.0,<1.0.0
squix78/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.0
ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.0