1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-08-17 20:01:42 +02:00

Merge remote-tracking branch 'upstream/devt' into devt

This commit is contained in:
me
2021-04-20 14:39:15 -07:00
47 changed files with 1254 additions and 444 deletions

View File

@@ -59,6 +59,19 @@ void machine_init() {
#endif
}
// Converts Cartesian to motors with no motion control
static void cartesian_to_motors(float* position) {
float motors[MAX_N_AXIS];
motors[X_AXIS] = geometry_factor * position[X_AXIS] + position[Y_AXIS];
motors[Y_AXIS] = geometry_factor * position[X_AXIS] - position[Y_AXIS];
position[X_AXIS] = motors[X_AXIS];
position[Y_AXIS] = motors[Y_AXIS];
// Z and higher just pass through unchanged
}
// Cycle mask is 0 unless the user sends a single axis command like $HZ
// This will always return true to prevent the normal Grbl homing cycle
bool user_defined_homing(uint8_t cycle_mask) {
@@ -135,7 +148,7 @@ bool user_defined_homing(uint8_t cycle_mask) {
}
// convert back to motor steps
inverse_kinematics(target);
cartesian_to_motors(target);
pl_data->feed_rate = homing_rate; // feed or seek rates
plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
@@ -226,7 +239,7 @@ bool user_defined_homing(uint8_t cycle_mask) {
}
// convert to motors
inverse_kinematics(target);
cartesian_to_motors(target);
// convert to steps
for (axis = X_AXIS; axis <= Y_AXIS; axis++) {
sys_position[axis] = target[axis] * axis_settings[axis]->steps_per_mm->get();
@@ -242,24 +255,10 @@ bool user_defined_homing(uint8_t cycle_mask) {
return true;
}
// This function is used by Grbl convert Cartesian to motors
// this does not do any motion control
void inverse_kinematics(float* position) {
float motors[MAX_N_AXIS];
motors[X_AXIS] = geometry_factor * position[X_AXIS] + position[Y_AXIS];
motors[Y_AXIS] = geometry_factor * position[X_AXIS] - position[Y_AXIS];
position[X_AXIS] = motors[X_AXIS];
position[Y_AXIS] = motors[Y_AXIS];
// Z and higher just pass through unchanged
}
// Inverse Kinematics calculates motor positions from real world cartesian positions
// position is the current position
// Breaking into segments is not needed with CoreXY, because it is a linear system.
void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) //The target and position are provided in MPos
bool inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) //The target and position are provided in MPos
{
float dx, dy, dz; // distances in each cartesian axis
float motors[MAX_N_AXIS];
@@ -288,7 +287,7 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
memcpy(last_motors, motors, sizeof(motors));
mc_line(motors, pl_data);
return mc_line(motors, pl_data);
}
// motors -> cartesian
@@ -314,7 +313,7 @@ void forward_kinematics(float* position) {
// apply the forward kinemetics to the machine coordinates
// https://corexy.com/theory.html
//calc_fwd[X_AXIS] = 0.5 / geometry_factor * (position[X_AXIS] + position[Y_AXIS]);
calc_fwd[X_AXIS] = ((0.5 * (print_position[X_AXIS] + print_position[Y_AXIS]) * geometry_factor) - wco[X_AXIS]);
calc_fwd[X_AXIS] = ((0.5 * (print_position[X_AXIS] + print_position[Y_AXIS]) / geometry_factor) - wco[X_AXIS]);
calc_fwd[Y_AXIS] = ((0.5 * (print_position[X_AXIS] - print_position[Y_AXIS])) - wco[Y_AXIS]);
for (int axis = 0; axis < n_axis; axis++) {
@@ -336,9 +335,9 @@ void kinematics_post_homing() {
}
}
// this is used used by Grbl soft limits to see if the range of the machine is exceeded.
uint8_t kinematic_limits_check(float* target) {
return true;
// this is used used by Limits.cpp to see if the range of the machine is exceeded.
bool limitsCheckTravel(float* target) {
return false;
}
void user_m30() {}

View File

@@ -54,7 +54,6 @@ special things your machine needs at startup.
void machine_init() {}
#endif
#ifdef USE_CUSTOM_HOMING
/*
user_defined_homing(uint8_t cycle_mask) is called at the begining of the normal Grbl_ESP32 homing
sequence. If user_defined_homing(uint8_t cycle_mask) returns false, the rest of normal Grbl_ESP32
@@ -66,9 +65,7 @@ bool user_defined_homing(uint8_t cycle_mask) {
// True = done with homing, false = continue with normal Grbl_ESP32 homing
return true;
}
#endif
#ifdef USE_KINEMATICS
/*
Inverse Kinematics converts X,Y,Z cartesian coordinate to the steps
on your "joint" motors. It requires the following three functions:
@@ -86,9 +83,9 @@ bool user_defined_homing(uint8_t cycle_mask) {
pl_data = planner data (see the definition of this type to see what it is)
position = an N_AXIS array of where the machine is starting from for this move
*/
void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) {
bool inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) {
// this simply moves to the target. Replace with your kinematics.
mc_line(target, pl_data);
return mc_line(target, pl_data);
}
/*
@@ -97,8 +94,7 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
cycle_mask is a bit mask of the axes being homed this time.
*/
bool kinematics_pre_homing(uint8_t cycle_mask))
{
bool kinematics_pre_homing(uint8_t cycle_mask) {
return false; // finish normal homing cycle
}
@@ -106,9 +102,15 @@ bool kinematics_pre_homing(uint8_t cycle_mask))
kinematics_post_homing() is called at the end of normal homing
*/
void kinematics_post_homing() {}
#endif
#ifdef USE_FWD_KINEMATICS
/*
limitsCheckTravel() is called to check soft limits
It returns true if the motion is outside the limit values
*/
bool limitsCheckTravel() {
return false;
}
/*
The status command uses forward_kinematics() to convert
your motor positions to cartesian X,Y,Z... coordinates.
@@ -119,7 +121,6 @@ void forward_kinematics(float* position) {
// position[X_AXIS] =
// position[Y_AXIS] =
}
#endif
#ifdef USE_TOOL_CHANGE
/*

View File

@@ -0,0 +1,280 @@
/*
oled_basic.cpp
Part of Grbl_ESP32
copyright (c) 2018 - Bart Dring This file was modified for use on the ESP32
CPU. Do not use this with Grbl for atMega328P
Grbl 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.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
--------------------------------------------------------------
This is a minimal implentation of a display as a test project.
It is designed to be used with a machine that has no easily accessible serial connection
It shows basic status and connection information.
When in alarm mode it will show the current Wifi/BT paramaters and status
Most machines will start in alarm mode (needs homing)
If the machine is running a job from SD it will show the progress
In other modes it will show state and 3 axis DROs
Thats All!
Library Infor:
https://github.com/ThingPulse/esp8266-oled-ssd1306
Install to PlatformIO with this typed at the terminal
platformio lib install 562
Add this to your machine definition file
#define DISPLAY_CODE_FILENAME "Custom/oled_basic.cpp"
*/
// Include the correct display library
#include "SSD1306Wire.h"
#include "../src/WebUI/WebSettings.h"
#ifndef OLED_ADDRESS
# define OLED_ADDRESS 0x3c
#endif
#ifndef OLED_SDA
# define OLED_SDA GPIO_NUM_14
#endif
#ifndef OLED_SCL
# define OLED_SCL GPIO_NUM_13
#endif
#ifndef OLED_GEOMETRY
# define OLED_GEOMETRY GEOMETRY_128_64
#endif
SSD1306Wire display(OLED_ADDRESS, OLED_SDA, OLED_SCL, OLED_GEOMETRY);
static TaskHandle_t displayUpdateTaskHandle = 0;
// This displays the status of the ESP32 Radios...BT, WiFi, etc
void displayRadioInfo() {
String radio_addr = "";
String radio_name = "";
String radio_status = "";
#ifdef ENABLE_BLUETOOTH
if (WebUI::wifi_radio_mode->get() == ESP_BT) {
radio_name = String("BT: ") + WebUI::bt_name->get();
}
#endif
#ifdef ENABLE_WIFI
if ((WiFi.getMode() == WIFI_MODE_STA) || (WiFi.getMode() == WIFI_MODE_APSTA)) {
radio_name = "STA: " + WiFi.SSID();
radio_addr = WiFi.localIP().toString();
} else if ((WiFi.getMode() == WIFI_MODE_AP) || (WiFi.getMode() == WIFI_MODE_APSTA)) {
radio_name = String("AP:") + WebUI::wifi_ap_ssid->get();
radio_addr = WiFi.softAPIP().toString();
}
#endif
#ifdef WIFI_OR_BLUETOOTH
if (WebUI::wifi_radio_mode->get() == ESP_RADIO_OFF) {
radio_name = "Radio Mode: None";
}
#else
radio_name = "Radio Mode:Disabled";
#endif
display.setTextAlignment(TEXT_ALIGN_LEFT);
display.setFont(ArialMT_Plain_10);
if (sys.state == State::Alarm) { // print below Alarm:
display.drawString(0, 18, radio_name);
display.drawString(0, 30, radio_addr);
} else { // print next to status
if (WebUI::wifi_radio_mode->get() == ESP_BT) {
display.drawString(55, 2, radio_name);
} else {
display.drawString(55, 2, radio_addr);
}
}
}
// Here changes begin Here changes begin Here changes begin Here changes begin Here changes begin
void draw_checkbox(int16_t x, int16_t y, int16_t width, int16_t height, bool checked) {
if (checked)
display.fillRect(x, y, width, height); // If log.0
else
display.drawRect(x, y, width, height); // If log.1
}
void displayDRO() {
uint8_t oled_y_pos;
float print_position[MAX_N_AXIS];
//float wco[MAX_N_AXIS];
display.setTextAlignment(TEXT_ALIGN_LEFT);
display.setFont(ArialMT_Plain_10);
char axisVal[20];
display.drawString(80, 14, "L"); // Limit switch
auto n_axis = number_axis->get();
AxisMask lim_pin_state = limits_get_state();
ControlPins ctrl_pin_state = system_control_get_state();
bool prb_pin_state = probe_get_state();
if (bit_istrue(status_mask->get(), RtStatus::Position)) {
calc_mpos(print_position);
} else {
calc_wpos(print_position);
}
for (uint8_t axis = X_AXIS; axis < n_axis; axis++) {
oled_y_pos = 24 + (axis * 10);
String axis_letter = String(report_get_axis_letter(axis));
axis_letter += ":";
display.setTextAlignment(TEXT_ALIGN_LEFT);
display.drawString(0, oled_y_pos, axis_letter); // String('X') + ":");
display.setTextAlignment(TEXT_ALIGN_RIGHT);
snprintf(axisVal, 20 - 1, "%.3f", print_position[axis]);
display.drawString(60, oled_y_pos, axisVal);
if (limitsSwitchDefined(axis, 0)) { // olny draw the box if a switch has been defined
draw_checkbox(80, 27 + (axis * 10), 7, 7, bit_istrue(lim_pin_state, bit(axis)));
}
}
oled_y_pos = 14;
if (PROBE_PIN != UNDEFINED_PIN) {
display.drawString(110, oled_y_pos, "P");
draw_checkbox(120, oled_y_pos + 3, 7, 7, prb_pin_state);
oled_y_pos += 10;
}
#ifdef CONTROL_FEED_HOLD_PIN
display.drawString(110, oled_y_pos, "H");
draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pin_state.bit.feedHold);
oled_y_pos += 10;
#endif
#ifdef CONTROL_CYCLE_START_PIN
display.drawString(110, oled_y_pos, "S");
draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pin_state.bit.cycleStart);
oled_y_pos += 10;
#endif
#ifdef CONTROL_RESET_PIN
display.drawString(110, oled_y_pos, "R");
draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pin_state.bit.reset);
oled_y_pos += 10;
#endif
#ifdef CONTROL_SAFETY_DOOR_PIN
display.drawString(110, oled_y_pos, "D");
draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pin_state.bit.safetyDoor);
#endif
}
void displayUpdate(void* pvParameters) {
TickType_t xLastWakeTime;
const TickType_t xDisplayFrequency = 100; // in ticks (typically ms)
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
vTaskDelay(2500);
uint16_t sd_file_ticker = 0;
display.init();
display.flipScreenVertically();
while (true) {
display.clear();
String state_string = "";
display.setTextAlignment(TEXT_ALIGN_LEFT);
display.setFont(ArialMT_Plain_16);
display.drawString(0, 0, report_state_text());
if (get_sd_state(false) == SDState::BusyPrinting) {
display.clear();
display.setTextAlignment(TEXT_ALIGN_CENTER);
display.setFont(ArialMT_Plain_10);
state_string = "SD File";
for (int i = 0; i < sd_file_ticker % 10; i++) {
state_string += ".";
}
sd_file_ticker++;
display.drawString(63, 0, state_string);
char path[50];
sd_get_current_filename(path);
display.drawString(63, 12, path);
int progress = sd_report_perc_complete();
// draw the progress bar
display.drawProgressBar(0, 45, 120, 10, progress);
// draw the percentage as String
display.setFont(ArialMT_Plain_10);
display.setTextAlignment(TEXT_ALIGN_CENTER);
display.drawString(64, 25, String(progress) + "%");
} else if (sys.state == State::Alarm) {
displayRadioInfo();
} else {
displayDRO();
displayRadioInfo();
}
display.display();
vTaskDelayUntil(&xLastWakeTime, xDisplayFrequency);
}
}
void display_init() {
// Initialising the UI will init the display too.
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Init Basic OLED SDA:%s SCL:%s", pinName(OLED_SDA), pinName(OLED_SCL));
display.init();
display.flipScreenVertically();
display.clear();
display.setTextAlignment(TEXT_ALIGN_CENTER);
display.setFont(ArialMT_Plain_10);
String mach_name = MACHINE_NAME;
// remove characters from the end until the string fits
while (display.getStringWidth(mach_name) > 128) {
mach_name = mach_name.substring(0, mach_name.length() - 1);
}
display.drawString(63, 0, mach_name);
display.display();
xTaskCreatePinnedToCore(displayUpdate, // task
"displayUpdateTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
&displayUpdateTaskHandle,
CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core
// core
);
}

View File

@@ -135,23 +135,12 @@ bool user_defined_homing(uint8_t cycle_mask) { // true = do not continue with n
}
// This function is used by Grbl
void inverse_kinematics(float* position) {
float motor_angles[3];
read_settings();
delta_calcInverse(position, motor_angles);
position[0] = motor_angles[0];
position[1] = motor_angles[1];
position[2] = motor_angles[2];
}
// This function is used by Grbl
void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) //The target and position are provided in MPos
bool inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) //The target and position are provided in MPos
{
float dx, dy, dz; // distances in each cartesian axis
float motor_angles[3];
float seg_target[3]; // The target of the current segment
float seg_target[3]; // The target of the current segment
float feed_rate = pl_data->feed_rate; // save original feed rate
bool show_error = true; // shows error once
@@ -210,7 +199,7 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
pl_data->feed_rate = (feed_rate * delta_distance / segment_dist);
}
mc_line(motor_angles, pl_data);
return mc_line(motor_angles, pl_data);
} else {
if (show_error) {
@@ -222,36 +211,35 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
// motor_angles[1],
// motor_angles[2]);
show_error = false;
return false;
}
}
}
}
// this is used used by Grbl soft limits to see if the range of the machine is exceeded.
uint8_t kinematic_limits_check(float* target) {
bool limitsCheckTravel(float* target) {
float motor_angles[3];
read_settings();
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin Soft Check %3.3f, %3.3f, %3.3f", target[0], target[1], target[2]);
KinematicError status = delta_calcInverse(target, motor_angles);
switch (status) {
switch (delta_calcInverse(target, motor_angles)) {
case KinematicError::OUT_OF_RANGE:
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin target out of range");
break;
return true;
case KinematicError::ANGLE_TOO_NEGATIVE:
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin target max negative");
break;
return true;
case KinematicError::ANGLE_TOO_POSITIVE:
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin target max positive");
break;
return true;
case KinematicError::NONE:
break;
return false;
}
return (status == KinematicError::NONE);
return false;
}
// inverse kinematics: cartesian -> angles

View File

@@ -85,7 +85,7 @@ void kinematics_post_homing() {
*/
void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) {
bool inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) {
//static float last_angle = 0;
//static float last_radius = 0;
float dx, dy, dz; // distances in each cartesian axis
@@ -111,6 +111,7 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
segment_count = ceil(dist / SEGMENT_LENGTH); // determine the number of segments we need ... round up so there is at least 1
}
dist /= segment_count; // segment distance
bool added = false;
for (uint32_t segment = 1; segment <= segment_count; segment++) {
// determine this segment's target
seg_target[X_AXIS] = position[X_AXIS] + (dx / float(segment_count) * segment) - x_offset;
@@ -141,9 +142,10 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
polar[Z_AXIS] += z_offset;
last_radius = polar[RADIUS_AXIS];
last_angle = polar[POLAR_AXIS];
mc_line(polar, pl_data);
added = mc_line(polar, pl_data);
}
// TO DO don't need a feedrate for rapids
return added;
}
/*

View File

Before

Width:  |  Height:  |  Size: 1.1 KiB

After

Width:  |  Height:  |  Size: 1.1 KiB

View File

@@ -6,3 +6,7 @@
#ifdef CUSTOM_CODE_FILENAME
# include CUSTOM_CODE_FILENAME
#endif
#ifdef DISPLAY_CODE_FILENAME
# include DISPLAY_CODE_FILENAME
#endif

View File

@@ -1287,11 +1287,12 @@ Error gc_execute_line(char* line, uint8_t client) {
FAIL(Error::InvalidJogCommand);
}
// Initialize planner data to current spindle and coolant modal state.
pl_data->spindle_speed = gc_state.spindle_speed;
pl_data->spindle = gc_state.modal.spindle;
pl_data->coolant = gc_state.modal.coolant;
Error status = jog_execute(pl_data, &gc_block);
if (status == Error::Ok) {
pl_data->spindle_speed = gc_state.spindle_speed;
pl_data->spindle = gc_state.modal.spindle;
pl_data->coolant = gc_state.modal.coolant;
bool cancelledInflight = false;
Error status = jog_execute(pl_data, &gc_block, &cancelledInflight);
if (status == Error::Ok && !cancelledInflight) {
memcpy(gc_state.position, gc_block.values.xyz, sizeof(gc_block.values.xyz));
}
return status;
@@ -1485,9 +1486,9 @@ Error gc_execute_line(char* line, uint8_t client) {
// and absolute and incremental modes.
pl_data->motion.rapidMotion = 1; // Set rapid motion flag.
if (axis_command != AxisCommand::None) {
mc_line_kins(gc_block.values.xyz, pl_data, gc_state.position);
inverse_kinematics(gc_block.values.xyz, pl_data, gc_state.position);
}
mc_line_kins(coord_data, pl_data, gc_state.position);
inverse_kinematics(coord_data, pl_data, gc_state.position);
memcpy(gc_state.position, coord_data, sizeof(gc_state.position));
break;
case NonModal::SetHome0:
@@ -1515,12 +1516,10 @@ Error gc_execute_line(char* line, uint8_t client) {
if (axis_command == AxisCommand::MotionMode) {
GCUpdatePos gc_update_pos = GCUpdatePos::Target;
if (gc_state.modal.motion == Motion::Linear) {
//mc_line(gc_block.values.xyz, pl_data);
mc_line_kins(gc_block.values.xyz, pl_data, gc_state.position);
inverse_kinematics(gc_block.values.xyz, pl_data, gc_state.position);
} else if (gc_state.modal.motion == Motion::Seek) {
pl_data->motion.rapidMotion = 1; // Set rapid motion flag.
//mc_line(gc_block.values.xyz, pl_data);
mc_line_kins(gc_block.values.xyz, pl_data, gc_state.position);
inverse_kinematics(gc_block.values.xyz, pl_data, gc_state.position);
} else if ((gc_state.modal.motion == Motion::CwArc) || (gc_state.modal.motion == Motion::CcwArc)) {
mc_arc(gc_block.values.xyz,
pl_data,

View File

@@ -30,7 +30,8 @@ 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
// show the map name at startup
@@ -39,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
@@ -92,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();
@@ -104,6 +105,10 @@ static void reset_variables() {
plan_sync_position();
gc_sync_position();
report_init_message(CLIENT_ALL);
// used to keep track of a jog command sent to mc_line() so we can cancel it.
// this is needed if a jogCancel comes along after we have already parsed a jog and it is in-flight.
sys_pl_data_inflight = NULL;
}
void run_once() {
@@ -116,6 +121,7 @@ void run_once() {
void __attribute__((weak)) machine_init() {}
void __attribute__((weak)) display_init() {}
/*
setup() and loop() in the Arduino .ino implements this control flow:

View File

@@ -22,7 +22,7 @@
// Grbl versioning system
const char* const GRBL_VERSION = "1.3a";
const char* const GRBL_VERSION_BUILD = "20210311";
const char* const GRBL_VERSION_BUILD = "20210420";
//#include <sdkconfig.h>
#include <Arduino.h>
@@ -51,8 +51,9 @@ const char* const GRBL_VERSION_BUILD = "20210311";
#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"
@@ -65,6 +66,8 @@ const char* const GRBL_VERSION_BUILD = "20210311";
#include "UserOutput.h"
#include <Wire.h>
// Do not guard this because it is needed for local files too
#include "SDCard.h"
@@ -90,20 +93,18 @@ const char* const GRBL_VERSION_BUILD = "20210311";
void grbl_init();
void run_once();
// Called if USE_MACHINE_INIT is defined
void machine_init();
void machine_init(); // weak definition in Grbl.cpp
void display_init(); // weak definition in Grbl.cpp
bool user_defined_homing(uint8_t cycle_mask); // weak definition in Limits.cpp
// Called if USE_KINEMATICS is defined
// weak definitions in MotionControl.cpp
bool inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position);
bool kinematics_pre_homing(uint8_t cycle_mask);
void kinematics_post_homing();
void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position);
bool kinematics_pre_homing(uint8_t cycle_mask);
void kinematics_post_homing();
uint8_t kinematic_limits_check(float* target);
bool limitsCheckTravel(float* target); // weak in Limits.cpp; true if out of range
// Called if USE_FWD_KINEMATICS is defined
void inverse_kinematics(float* position); // used to return a converted value
void forward_kinematics(float* position); // weak definition in Report.cpp
// Called if MACRO_BUTTON_0_PIN or MACRO_BUTTON_1_PIN or MACRO_BUTTON_2_PIN is defined

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

@@ -24,11 +24,13 @@
#include "Grbl.h"
// Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog.
Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block) {
// cancelledInflight will be set to true if was not added to parser due to a cancelJog.
Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block, bool* cancelledInflight) {
// Initialize planner data struct for jogging motions.
// NOTE: Spindle and coolant are allowed to fully function with overrides during a jog.
pl_data->feed_rate = gc_block->values.f;
pl_data->motion.noFeedOverride = 1;
pl_data->is_jog = true;
#ifdef USE_LINE_NUMBERS
pl_data->line_number = gc_block->values.n;
#endif
@@ -37,12 +39,12 @@ Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block) {
return Error::TravelExceeded;
}
}
// Valid jog command. Plan, set state, and execute.
#ifndef USE_KINEMATICS
mc_line(gc_block->values.xyz, pl_data);
#else // else use kinematics
inverse_kinematics(gc_block->values.xyz, pl_data, gc_state.position);
#endif
// Valid jog command. Plan, set state, and execute.
if (!inverse_kinematics(gc_block->values.xyz, pl_data, gc_state.position)) {
if (cancelledInflight)
*cancelledInflight = true;
return Error::Ok;
}
if (sys.state == State::Idle) {
if (plan_get_current_block() != NULL) { // Check if there is a block to execute.

View File

@@ -28,4 +28,5 @@
const int JOG_LINE_NUMBER = 0;
// Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog.
Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block);
// cancelledInflight will be set to true if was not added to parser due to a cancelJog.
Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block, bool* cancelledInflight);

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
}
@@ -392,19 +396,24 @@ float limitsMinPosition(uint8_t axis) {
// Checks and reports if target array exceeds machine travel limits.
// Return true if exceeding limits
bool limitsCheckTravel(float* target) {
// Set $<axis>/MaxTravel=0 to selectively remove an axis from soft limit checks
bool __attribute__((weak)) limitsCheckTravel(float* target) {
uint8_t idx;
auto n_axis = number_axis->get();
for (idx = 0; idx < n_axis; idx++) {
float max_mpos, min_mpos;
if (target[idx] < limitsMinPosition(idx) || target[idx] > limitsMaxPosition(idx)) {
if ((target[idx] < limitsMinPosition(idx) || target[idx] > limitsMaxPosition(idx)) && axis_settings[idx]->max_travel->get() > 0) {
return true;
}
}
return false;
}
bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index) {
return (limit_pins[axis][gang_index] != UNDEFINED_PIN);
}
bool __attribute__((weak)) user_defined_homing(uint8_t cycle_mask) {
return false;
}

View File

@@ -54,3 +54,6 @@ float limitsMinPosition(uint8_t axis);
// Internal factor used by limits_soft_check
bool limitsCheckTravel(float* target);
// check if a switch has been defined
bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index);

View File

@@ -30,8 +30,6 @@
#define CUSTOM_CODE_FILENAME "../Custom/CoreXY.cpp"
#define MIDTBOT // applies the geometry correction to the kinematics
#define USE_KINEMATICS // there are kinematic equations for this machine
#define USE_FWD_KINEMATICS // report in cartesian
#define USE_MACHINE_INIT // There is some custom initialization for this machine
#define USE_CUSTOM_HOMING

View File

@@ -37,8 +37,6 @@
#define POLAR_AXIS 1
#define SEGMENT_LENGTH 0.5 // segment length in mm
#define USE_KINEMATICS
#define USE_FWD_KINEMATICS // report in cartesian
#define USE_M30
#define X_STEP_PIN GPIO_NUM_15

View File

@@ -25,8 +25,6 @@
// ================= Firmware Customization ===================
#define USE_KINEMATICS // there are kinematic equations for this machine
#define USE_FWD_KINEMATICS // report in cartesian
#define USE_MACHINE_INIT // There is some custom initialization for this machine
// ================== Delta Geometry ===========================

View File

@@ -41,8 +41,6 @@
#define N_AXIS 3
#define USE_KINEMATICS // there are kinematic equations for this machine
#define USE_FWD_KINEMATICS // report in cartesian
#define USE_MACHINE_INIT // There is some custom initialization for this machine
// ================== Delta Geometry ===========================

View File

@@ -33,15 +33,6 @@
SquaringMode ganged_mode = SquaringMode::Dual;
// this allows kinematics to be used.
void mc_line_kins(float* target, plan_line_data_t* pl_data, float* position) {
#ifndef USE_KINEMATICS
mc_line(target, pl_data);
#else // else use kinematics
inverse_kinematics(target, pl_data, position);
#endif
}
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
// (1 minute)/feed_rate time.
@@ -49,7 +40,11 @@ void mc_line_kins(float* target, plan_line_data_t* pl_data, float* position) {
// segments, must pass through this routine before being passed to the planner. The seperation of
// mc_line and plan_buffer_line is done primarily to place non-planner-type functions from being
// in the planner and to let backlash compensation or canned cycle integration simple and direct.
void mc_line(float* target, plan_line_data_t* pl_data) {
// returns true if line was submitted to planner, or false if intentionally dropped.
bool mc_line(float* target, plan_line_data_t* pl_data) {
bool submitted_result = false;
// store the plan data so it can be cancelled by the protocol system if needed
sys_pl_data_inflight = pl_data;
// If enabled, check for soft limit violations. Placed here all line motions are picked up
// from everywhere in Grbl.
if (soft_limits->get()) {
@@ -60,7 +55,8 @@ void mc_line(float* target, plan_line_data_t* pl_data) {
}
// If in check gcode mode, prevent motion by blocking planner. Soft limits still work.
if (sys.state == State::CheckMode) {
return;
sys_pl_data_inflight = NULL;
return submitted_result;
}
// NOTE: Backlash compensation may be installed here. It will need direction info to track when
// to insert a backlash line motion(s) before the intended line motion and will require its own
@@ -80,7 +76,8 @@ void mc_line(float* target, plan_line_data_t* pl_data) {
do {
protocol_execute_realtime(); // Check for any run-time commands
if (sys.abort) {
return; // Bail, if system abort.
sys_pl_data_inflight = NULL;
return submitted_result; // Bail, if system abort.
}
if (plan_check_full_buffer()) {
protocol_auto_cycle_start(); // Auto-cycle start when buffer is full.
@@ -90,9 +87,25 @@ void mc_line(float* target, plan_line_data_t* pl_data) {
} while (1);
// Plan and queue motion into planner buffer
// uint8_t plan_status; // Not used in normal operation.
plan_buffer_line(target, pl_data);
if (sys_pl_data_inflight == pl_data) {
plan_buffer_line(target, pl_data);
submitted_result = true;
}
sys_pl_data_inflight = NULL;
return submitted_result;
}
bool __attribute__((weak)) inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) {
return mc_line(target, pl_data);
}
bool __attribute__((weak)) kinematics_pre_homing(uint8_t cycle_mask) {
return false; // finish normal homing cycle
}
void __attribute__((weak)) kinematics_post_homing() {}
void __attribute__((weak)) forward_kinematics(float* position) {}
// Execute an arc in offset mode format. position == current xyz, target == target xyz,
// offset == offset from current xyz, axis_X defines circle plane in tool space, axis_linear is
// the direction of helical travel, radius == circle radius, isclockwise boolean. Used
@@ -117,14 +130,12 @@ void mc_arc(float* target,
float rt_axis1 = target[axis_1] - center_axis1;
float previous_position[MAX_N_AXIS] = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
#ifdef USE_KINEMATICS
uint16_t n;
auto n_axis = number_axis->get();
for (n = 0; n < n_axis; n++) {
previous_position[n] = position[n];
}
#endif
// CCW angle between position and target from circle center. Only one atan2() trig computation required.
float angular_travel = atan2(r_axis0 * rt_axis1 - r_axis1 * rt_axis0, r_axis0 * rt_axis0 + r_axis1 * rt_axis1);
if (is_clockwise_arc) { // Correct atan2 output per direction
@@ -206,15 +217,11 @@ void mc_arc(float* target,
position[axis_0] = center_axis0 + r_axis0;
position[axis_1] = center_axis1 + r_axis1;
position[axis_linear] += linear_per_segment;
#ifdef USE_KINEMATICS
pl_data->feed_rate = original_feedrate; // This restores the feedrate kinematics may have altered
mc_line_kins(position, pl_data, previous_position);
inverse_kinematics(position, pl_data, previous_position);
previous_position[axis_0] = position[axis_0];
previous_position[axis_1] = position[axis_1];
previous_position[axis_linear] = position[axis_linear];
#else
mc_line(position, pl_data);
#endif
// Bail mid-circle on system abort. Runtime command check already performed by mc_line.
if (sys.abort) {
return;
@@ -222,7 +229,7 @@ void mc_arc(float* target,
}
}
// Ensure last segment arrives at target location.
mc_line_kins(target, pl_data, previous_position);
inverse_kinematics(target, pl_data, previous_position);
}
// Execute dwell in seconds.
@@ -292,11 +299,9 @@ void mc_homing_cycle(uint8_t cycle_mask) {
// This give kinematics a chance to do something before normal homing
// if it returns true, the homing is canceled.
#ifdef USE_KINEMATICS
if (kinematics_pre_homing(cycle_mask)) {
return;
}
#endif
// Check and abort homing cycle, if hard limits are already enabled. Helps prevent problems
// with machines with limits wired on both ends of travel to one limit pin.
// TODO: Move the pin-specific LIMIT_PIN call to Limits.cpp as a function.
@@ -366,10 +371,8 @@ void mc_homing_cycle(uint8_t cycle_mask) {
// Sync gcode parser and planner positions to homed position.
gc_sync_position();
plan_sync_position();
#ifdef USE_KINEMATICS
// This give kinematics a chance to do something after normal homing
kinematics_post_homing();
#endif
// If hard limits feature enabled, re-enable hard limits pin change register after homing cycle.
limits_init();
}
@@ -412,7 +415,7 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
}
// Setup and queue probing motion. Auto cycle-start should not start the cycle.
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Found");
mc_line_kins(target, pl_data, gc_state.position);
inverse_kinematics(target, pl_data, gc_state.position);
// Activate the probing state monitor in the stepper module.
sys_probe_state = Probe::Active;
// Perform probing cycle. Wait here until probe is triggered or motion completes.
@@ -499,6 +502,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

@@ -35,8 +35,8 @@ const int PARKING_MOTION_LINE_NUMBER = 0;
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
// (1 minute)/feed_rate time.
void mc_line_kins(float* target, plan_line_data_t* pl_data, float* position);
void mc_line(float* target, plan_line_data_t* pl_data);
bool inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position);
bool mc_line(float* target, plan_line_data_t* pl_data); // returns true if line was submitted to planner
// Execute an arc in offset mode format. position == current xyz, target == target xyz,
// offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is

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

@@ -91,6 +91,7 @@ typedef struct {
#ifdef USE_LINE_NUMBERS
int32_t line_number; // Desired line number to report when executing.
#endif
bool is_jog; // true if this was generated due to a jog command
} plan_line_data_t;
// Initialize and reset the motion plan subsystem

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:
@@ -567,6 +567,12 @@ static void protocol_exec_rt_suspend() {
if (sys.abort) {
return;
}
// if a jogCancel comes in and we have a jog "in-flight" (parsed and handed over to mc_line()),
// then we need to cancel it before it reaches the planner. otherwise we may try to move way out of
// normal bounds, especially with senders that issue a series of jog commands before sending a cancel.
if (sys.suspend.bit.jogCancel && sys_pl_data_inflight != NULL && ((plan_line_data_t*)sys_pl_data_inflight)->is_jog) {
sys_pl_data_inflight = NULL;
}
// Block until initial hold is complete and the machine has stopped motion.
if (sys.suspend.bit.holdComplete) {
// Parking manager. Handles de/re-energizing, switch state checks, and parking motions for

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
@@ -291,13 +269,13 @@ std::map<Message, const char*> MessageText = {
// NOTE: For interfaces, messages are always placed within brackets. And if silent mode
// is installed, the message number codes are less than zero.
void report_feedback_message(Message message) { // ok to send to all clients
#if defined (ENABLE_SD_CARD)
#if defined(ENABLE_SD_CARD)
if (message == Message::SdFileQuit) {
grbl_notifyf("SD print canceled", "Reset during SD file at line: %d", sd_get_current_line_number());
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Reset during SD file at line: %d", sd_get_current_line_number());
} else
#endif //ENABLE_SD_CARD
} else
#endif //ENABLE_SD_CARD
{
auto it = MessageText.find(message);
if (it != MessageText.end()) {
@@ -592,82 +570,52 @@ void report_echo_line_received(char* line, uint8_t client) {
grbl_sendf(client, "[echo: %s]\r\n", line);
}
// Calculate the position for status reports.
// float print_position = returned position
// float wco = returns the work coordinate offset
// bool wpos = true for work position compensation
void report_calc_status_position(float* print_position, float* wco, bool wpos) {
int32_t current_position[MAX_N_AXIS]; // Copy current state of the system position variable
memcpy(current_position, sys_position, sizeof(sys_position));
system_convert_array_steps_to_mpos(print_position, current_position);
//float wco[MAX_N_AXIS];
if (wpos || (sys.report_wco_counter == 0)) {
auto n_axis = number_axis->get();
for (uint8_t idx = 0; idx < n_axis; idx++) {
// Apply work coordinate offsets and tool length offset to current position.
wco[idx] = gc_state.coord_system[idx] + gc_state.coord_offset[idx];
if (idx == TOOL_LENGTH_OFFSET_AXIS) {
wco[idx] += gc_state.tool_length_offset;
}
if (wpos) {
print_position[idx] -= wco[idx];
}
}
}
forward_kinematics(print_position); // a weak definition does nothing. Users can provide strong version
}
// Prints real-time data. This function grabs a real-time snapshot of the stepper subprogram
// and the actual location of the CNC machine. Users may change the following function to their
// specific needs, but the desired real-time data report must be as short as possible. This is
// requires as it minimizes the computational overhead and allows grbl to keep running smoothly,
// especially during g-code programs with fast, short line segments and high frequency reports (5-20Hz).
void report_realtime_status(uint8_t client) {
uint8_t idx;
int32_t current_position[MAX_N_AXIS]; // Copy current state of the system position variable
memcpy(current_position, sys_position, sizeof(sys_position));
float print_position[MAX_N_AXIS];
char status[200];
char temp[MAX_N_AXIS * 20];
system_convert_array_steps_to_mpos(print_position, current_position);
// Report current machine state and sub-states
strcpy(status, "<");
switch (sys.state) {
case State::Idle:
strcat(status, "Idle");
break;
case State::Cycle:
strcat(status, "Run");
break;
case State::Hold:
if (!(sys.suspend.bit.jogCancel)) {
strcat(status, "Hold:");
strcat(status, sys.suspend.bit.holdComplete ? "0" : "1"); // Ready to resume
break;
} // Continues to print jog state during jog cancel.
case State::Jog:
strcat(status, "Jog");
break;
case State::Homing:
strcat(status, "Home");
break;
case State::Alarm:
strcat(status, "Alarm");
break;
case State::CheckMode:
strcat(status, "Check");
break;
case State::SafetyDoor:
strcat(status, "Door:");
if (sys.suspend.bit.initiateRestore) {
strcat(status, "3"); // Restoring
} else {
if (sys.suspend.bit.retractComplete) {
strcat(status, sys.suspend.bit.safetyDoorAjar ? "1" : "0"); // Door ajar
// Door closed and ready to resume
} else {
strcat(status, "2"); // Retracting
}
}
break;
case State::Sleep:
strcat(status, "Sleep");
break;
}
float wco[MAX_N_AXIS];
if (bit_isfalse(status_mask->get(), RtStatus::Position) || (sys.report_wco_counter == 0)) {
auto n_axis = number_axis->get();
for (idx = 0; idx < n_axis; idx++) {
// Apply work coordinate offsets and tool length offset to current position.
wco[idx] = gc_state.coord_system[idx] + gc_state.coord_offset[idx];
if (idx == TOOL_LENGTH_OFFSET_AXIS) {
wco[idx] += gc_state.tool_length_offset;
}
if (bit_isfalse(status_mask->get(), RtStatus::Position)) {
print_position[idx] -= wco[idx];
}
}
}
forward_kinematics(print_position); // a weak definition does nothing. Users can provide strong version
// Report machine position
strcat(status, report_state_text());
// Report position
if (bit_istrue(status_mask->get(), RtStatus::Position)) {
calc_mpos(print_position);
strcat(status, "|MPos:");
} else {
calc_wpos(print_position);
strcat(status, "|WPos:");
}
report_util_axis_values(print_position, temp);
@@ -688,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);
@@ -793,7 +741,7 @@ void report_realtime_status(uint8_t client) {
sys.report_ovr_counter = 1; // Set override on next report.
}
strcat(status, "|WCO:");
report_util_axis_values(wco, temp);
report_util_axis_values(get_wco(), temp);
strcat(status, temp);
}
#endif
@@ -913,6 +861,54 @@ void report_hex_msg(uint8_t* buf, const char* prefix, int len) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "%s", report);
}
char* report_state_text() {
static char state[10];
switch (sys.state) {
case State::Idle:
strcpy(state, "Idle");
break;
case State::Cycle:
strcpy(state, "Run");
break;
case State::Hold:
if (!(sys.suspend.bit.jogCancel)) {
sys.suspend.bit.holdComplete ? strcpy(state, "Hold:0") : strcpy(state, "Hold:1");
break;
} // Continues to print jog state during jog cancel.
case State::Jog:
strcpy(state, "Jog");
break;
case State::Homing:
strcpy(state, "Home");
break;
case State::Alarm:
strcpy(state, "Alarm");
break;
case State::CheckMode:
strcpy(state, "Check");
break;
case State::SafetyDoor:
strcpy(state, "Door:");
if (sys.suspend.bit.initiateRestore) {
strcat(state, "3"); // Restoring
} else {
if (sys.suspend.bit.retractComplete) {
sys.suspend.bit.safetyDoorAjar ? strcat(state, "1") : strcat(state, "0");
; // Door ajar
// Door closed and ready to resume
} else {
strcat(state, "2"); // Retracting
}
}
break;
case State::Sleep:
strcpy(state, "Sleep");
break;
}
return state;
}
char report_get_axis_letter(uint8_t axis) {
switch (axis) {
case X_AXIS:
@@ -960,4 +956,37 @@ void reportTaskStackSize(UBaseType_t& saved) {
#endif
}
void calc_mpos(float* print_position) {
int32_t current_position[MAX_N_AXIS]; // Copy current state of the system position variable
memcpy(current_position, sys_position, sizeof(sys_position));
system_convert_array_steps_to_mpos(print_position, current_position);
forward_kinematics(print_position); // a weak definition does nothing. Users can provide strong version
}
void calc_wpos(float* print_position) {
int32_t current_position[MAX_N_AXIS]; // Copy current state of the system position variable
memcpy(current_position, sys_position, sizeof(sys_position));
system_convert_array_steps_to_mpos(print_position, current_position);
float* wco = get_wco();
auto n_axis = number_axis->get();
for (int idx = 0; idx < n_axis; idx++) {
print_position[idx] -= wco[idx];
}
forward_kinematics(print_position); // a weak definition does nothing. Users can provide strong version
}
float* get_wco() {
static float wco[MAX_N_AXIS];
auto n_axis = number_axis->get();
for (int idx = 0; idx < n_axis; idx++) {
// Apply work coordinate offsets and tool length offset to current position.
wco[idx] = gc_state.coord_system[idx] + gc_state.coord_offset[idx];
if (idx == TOOL_LENGTH_OFFSET_AXIS) {
wco[idx] += gc_state.tool_length_offset;
}
}
return wco;
}
void __attribute__((weak)) forward_kinematics(float* position) {} // This version does nothing. Make your own to do something with it

View File

@@ -92,6 +92,9 @@ void report_grbl_settings(uint8_t client, uint8_t show_extended);
// Prints an echo of the pre-parsed line received right before execution.
void report_echo_line_received(char* line, uint8_t client);
// calculate the postion for status reports
void report_calc_status_position(float* print_position, float* wco, bool wpos);
// Prints realtime status report
void report_realtime_status(uint8_t client);
@@ -122,10 +125,14 @@ void report_machine_type(uint8_t client);
void report_hex_msg(char* buf, const char* prefix, int len);
void report_hex_msg(uint8_t* buf, const char* prefix, int len);
char report_get_axis_letter(uint8_t axis);
char report_get_axis_letter(uint8_t axis);
char* reportAxisLimitsMsg(uint8_t axis);
char* reportAxisNameMsg(uint8_t axis);
char* reportAxisNameMsg(uint8_t axis, uint8_t dual_axis);
void reportTaskStackSize(UBaseType_t& saved);
char* report_state_text();
float* get_wco();
void calc_mpos(float* print_position);
void calc_wpos(float* print_position);

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

@@ -301,7 +301,7 @@ void make_settings() {
}
for (axis = MAX_N_AXIS - 1; axis >= 0; axis--) {
def = &axis_defaults[axis];
auto setting = new FloatSetting(GRBL, WG, makeGrblName(axis, 130), makename(def->name, "MaxTravel"), def->max_travel, 1.0, 100000.0);
auto setting = new FloatSetting(GRBL, WG, makeGrblName(axis, 130), makename(def->name, "MaxTravel"), def->max_travel, 0, 100000.0);
setting->setAxis(axis);
axis_settings[axis]->max_travel = setting;
}

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

@@ -38,6 +38,7 @@
#include "H2ASpindle.h"
#include "BESCSpindle.h"
#include "10vSpindle.h"
#include "YL620Spindle.h"
namespace Spindles {
// An instance of each type of spindle is created here.
@@ -51,6 +52,7 @@ namespace Spindles {
H2A h2a;
BESC besc;
_10v _10v;
YL620 yl620;
void Spindle::select() {
switch (static_cast<SpindleType>(spindle_type->get())) {
@@ -78,6 +80,9 @@ namespace Spindles {
case SpindleType::H2A:
spindle = &h2a;
break;
case SpindleType::YL620:
spindle = &yl620;
break;
case SpindleType::NONE:
default:
spindle = &null;

View File

@@ -38,6 +38,7 @@ enum class SpindleType : int8_t {
BESC,
_10V,
H2A,
YL620,
};
#include "../Grbl.h"

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

@@ -0,0 +1,232 @@
#include "YL620Spindle.h"
/*
YL620Spindle.cpp
This is for a Yalang YL620/YL620-A VFD based spindle to be controlled via RS485 Modbus RTU.
Part of Grbl_ESP32
2021 - Marco Wagner
Grbl 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.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
WARNING!!!!
VFDs are very dangerous. They have high voltages and are very powerful
Remove power before changing bits.
=============================================================================================================
Configuration required for the YL620
Parameter number Description Value
-------------------------------------------------------------------------------
P00.00 Main frequency 400.00Hz (match to your spindle)
P00.01 Command source 3
P03.00 RS485 Baud rate 3 (9600)
P03.01 RS485 address 1
P03.02 RS485 protocol 2
P03.08 Frequency given lower limit 100.0Hz (match to your spindle cooling-type)
===============================================================================================================
RS485 communication is standard Modbus RTU
Therefore, the following operation codes are relevant:
0x03: read single holding register
0x06: write single holding register
Holding register address Description
---------------------------------------------------------------------------
0x0000 main frequency
0x0308 frequency given lower limit
0x2000 command register (further information below)
0x2001 Modbus485 frequency command (x0.1Hz => 2500 = 250.0Hz)
0x200A Target frequency
0x200B Output frequency
0x200C Output current
Command register at holding address 0x2000
--------------------------------------------------------------------------
bit 1:0 b00: No function
b01: shutdown command
b10: start command
b11: Jog command
bit 3:2 reserved
bit 5:4 b00: No function
b01: Forward command
b10: Reverse command
b11: change direction
bit 7:6 b00: No function
b01: reset an error flag
b10: reset all error flags
b11: reserved
*/
namespace Spindles {
YL620::YL620() : VFD() {}
void YL620::direction_command(SpindleState mode, ModbusCommand& data) {
// NOTE: data length is excluding the CRC16 checksum.
data.tx_length = 6;
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[3] = 0x00;
data.msg[4] = 0x00; // High-Byte of command always 0x00
switch (mode) {
case SpindleState::Cw:
data.msg[5] = 0x12; // Start in forward direction
break;
case SpindleState::Ccw:
data.msg[5] = 0x22; // Start in reverse direction
break;
default: // SpindleState::Disable
data.msg[5] = 0x01; // Disable spindle
break;
}
}
void YL620::set_speed_command(uint32_t rpm, ModbusCommand& data) {
// NOTE: data length is excluding the CRC16 checksum.
data.tx_length = 6;
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_frequency = this->_maxFrequency;
uint16_t freqFromRPM = (uint16_t(rpm) * uint16_t(max_frequency)) / uint16_t(max_rpm);
#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
data.msg[1] = 0x06;
data.msg[2] = 0x20;
data.msg[3] = 0x01;
data.msg[4] = uint8_t(freqFromRPM >> 8);
data.msg[5] = uint8_t(freqFromRPM & 0xFF);
}
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;
data.msg[1] = 0x03;
data.msg[2] = 0x03;
data.msg[3] = 0x08;
data.msg[4] = 0x00;
data.msg[5] = 0x01;
// Recv: 01 03 02 03 E8 xx xx
// -- -- = 1000
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
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "YL620 allows minimum frequency of %d Hz", int(yl620->_minFrequency));
#endif
return true;
};
} else if (index == -2) {
// NOTE: data length is excluding the CRC16 checksum.
data.tx_length = 6;
data.rx_length = 5;
data.msg[1] = 0x03;
data.msg[2] = 0x00;
data.msg[3] = 0x00;
data.msg[4] = 0x00;
data.msg[5] = 0x01;
// Recv: 01 03 02 0F A0 xx xx
// -- -- = 4000
return [](const uint8_t* response, Spindles::VFD* vfd) -> bool {
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.
#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
return true;
};
} else {
return nullptr;
}
}
VFD::response_parser YL620::get_current_rpm(ModbusCommand& data) {
// NOTE: data length is excluding the CRC16 checksum.
data.tx_length = 6;
data.rx_length = 5;
// Send: 01 03 200B 0001
data.msg[1] = 0x03;
data.msg[2] = 0x20;
data.msg[3] = 0x0B;
data.msg[4] = 0x00;
data.msg[5] = 0x01;
// Recv: 01 03 02 05 DC xx xx
// ---- = 1500
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);
uint16_t rpm = freq * uint16_t(vfd->_max_rpm) / uint16_t(yl620->_maxFrequency);
// Set current RPM value? Somewhere?
vfd->_sync_rpm = rpm;
return true;
};
}
VFD::response_parser YL620::get_current_direction(ModbusCommand& data) {
// NOTE: data length is excluding the CRC16 checksum.
data.tx_length = 6;
data.rx_length = 5;
// Send: 01 03 20 00 00 01
data.msg[1] = 0x03;
data.msg[2] = 0x20;
data.msg[3] = 0x00;
data.msg[4] = 0x00;
data.msg[5] = 0x01;
// Receive: 01 03 02 00 0A xx xx
// ----- status is in 00 0A bit 5:4
// TODO: What are we going to do with this? Update sys.spindle_speed? Update vfd state?
return [](const uint8_t* response, Spindles::VFD* vfd) -> bool { return true; };
}
}

View File

@@ -0,0 +1,44 @@
#pragma once
#include "VFDSpindle.h"
/*
YL620Spindle.h
Part of Grbl_ESP32
2021 - Marco Wagner
Grbl 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.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
namespace Spindles {
class YL620 : public VFD {
protected:
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 direction_command(SpindleState mode, ModbusCommand& data) override;
void set_speed_command(uint32_t rpm, ModbusCommand& data) override;
response_parser initialization_sequence(int index, ModbusCommand& data) override;
response_parser get_current_rpm(ModbusCommand& data) override;
response_parser get_current_direction(ModbusCommand& data) override;
response_parser get_status_ok(ModbusCommand& data) override { return nullptr; }
bool supports_actual_rpm() const override { return true; }
bool safety_polling() const override { return false; }
public:
YL620();
};
}

View File

@@ -30,6 +30,7 @@ volatile ExecState sys_rt_exec_state; // Global realtime executor bitflag v
volatile ExecAlarm sys_rt_exec_alarm; // Global realtime executor bitflag variable for setting various alarms.
volatile ExecAccessory sys_rt_exec_accessory_override; // Global realtime executor bitflag variable for spindle/coolant overrides.
volatile bool cycle_stop; // For state transitions, instead of bitflag
volatile void* sys_pl_data_inflight; // holds a plan_line_data_t while inverse_kinematics has taken ownership of a line motion
#ifdef DEBUG
volatile bool sys_rt_exec_debug;
#endif

View File

@@ -138,6 +138,7 @@ extern volatile Percent sys_rt_f_override; // Feed override
extern volatile Percent sys_rt_r_override; // Rapid feed override value in percent
extern volatile Percent sys_rt_s_override; // Spindle override value in percent
extern volatile bool cycle_stop;
extern volatile void* sys_pl_data_inflight; // holds a plan_line_data_t while inverse_kinematics has taken ownership of a line motion
#ifdef DEBUG
extern volatile bool sys_rt_exec_debug;
#endif

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

@@ -1,12 +1,22 @@
; PlatformIO Project Configuration File
;
; Build options: build flags, source filter
; Upload options: custom upload port, speed and extra flags
; Library options: dependencies, extra library storages
; Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html
[platformio]
src_dir=Grbl_Esp32
lib_dir=libraries
data_dir=Grbl_Esp32/data
default_envs=release
src_dir = Grbl_Esp32
lib_dir = libraries
data_dir = Grbl_Esp32/data
default_envs = release
;extra_configs=debug.ini
[common_env_data]
lib_deps_builtin =
lib_deps_builtin =
ArduinoOTA
BluetoothSerial
DNSServer
@@ -23,37 +33,40 @@ lib_deps_builtin =
WiFiClientSecure
[common]
build_flags =
;-DMACHINE_FILENAME=test_drive.h ;Remove ";" from the beginning of this line and specify the machine file
build_flags =
;-DMACHINE_FILENAME=test_drive.h ;Remove ";" from the beginning of this line and specify the machine file
-DCORE_DEBUG_LEVEL=0
-Wno-unused-variable
-Wno-unused-function
;-DDEBUG_REPORT_HEAP_SIZE
;-DDEBUG_REPORT_STACK_FREE
[env]
lib_deps =
TMCStepper@>=0.7.0,<1.0.0
platform = espressif32
;lib_deps =
; TMCStepper@>=0.7.0,<1.0.0
platform = espressif32@3.0.0 ; temporary fix for lost uart rx characters
board = esp32dev
framework = arduino
upload_speed = 921600
board_build.partitions = min_spiffs.csv
monitor_speed = 115200
monitor_flags =
monitor_flags =
--eol=CRLF
--echo
--filter=esp32_exception_decoder
board_build.f_cpu = 240000000L
; set frequency to 80MHz
board_build.f_flash = 80000000L
board_build.flash_mode = qio
build_flags = ${common.build_flags}
src_filter =
+<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> +<*.ino> +<src/>
-<.git/> -<data/> -<test/> -<tests/>
src_filter =
+<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> +<*.ino> +<src/>
-<.git/> -<data/> -<test/> -<tests/>
[env:release]
lib_deps =
TMCStepper@>=0.7.0,<1.0.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
ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.0