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

Clang Format (#514)

* Apply clang-format

* Fixed conflict between "print.h" and <print.h>

print.h and print.cpp are not used.

* machine.h: clang-format off is unnecessary

* ifdef ARDUINO_ARCH_ESP32 is unnecessary

and causes irritiating indentation of other includes

* Revert formatting of nofile.h

But leave pragma changes.

* Fix nofile.h again

* Some files were not formatted ...

and .clang-format needed to be tweaked to
give the same results with clang-format v6 and v10

* clang-format v6 vs v10 compatibility
This commit is contained in:
Mitch Bradley 2020-08-07 10:13:51 -10:00 committed by GitHub
parent b92f75da0a
commit 82b74da72d
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
104 changed files with 7130 additions and 7240 deletions

92
.clang-format Normal file
View File

@ -0,0 +1,92 @@
---
AccessModifierOffset: '-4'
AlignAfterOpenBracket: Align
AlignConsecutiveAssignments: 'true'
AlignConsecutiveDeclarations: 'true'
AlignEscapedNewlines: Right
AlignOperands: 'true'
AlignTrailingComments: 'true'
AllowShortBlocksOnASingleLine: 'true'
AllowShortCaseLabelsOnASingleLine: 'true'
AllowShortFunctionsOnASingleLine: Inline
AllowShortIfStatementsOnASingleLine: 'false'
AllowShortLoopsOnASingleLine: 'false'
AlwaysBreakBeforeMultilineStrings: 'false'
AlwaysBreakTemplateDeclarations: 'true'
BinPackArguments: 'false'
BinPackParameters: 'false'
BreakBeforeBinaryOperators: None
BraceWrapping:
AfterClass: 'true'
AfterControlStatement: 'true'
AfterEnum: 'true'
AfterFunction: 'true'
AfterNamespace: 'true'
AfterObjCDeclaration: 'true'
AfterStruct: 'true'
AfterUnion: 'true'
AfterExternBlock: 'true'
BeforeCatch: 'true'
BeforeElse: 'true'
SplitEmptyFunction: 'false'
SplitEmptyRecord: 'false'
SplitEmptyNamespace: 'false'
BreakBeforeInheritanceComma: 'true'
BreakBeforeTernaryOperators: 'false'
BreakConstructorInitializers: AfterColon
BreakInheritanceList: AfterColon
ColumnLimit: '140'
CommentPragmas: '^ :: '
CompactNamespaces: 'false'
Cpp11BracedListStyle: 'false'
FixNamespaceComments: 'false'
IncludeCategories:
- Regex: '^".*'
Priority: 1
- Regex: '^"(.*)/'
Priority: 2
- Regex: '^<(.*)/'
Priority: 3
- Regex: '.*'
Priority: 4
IncludeBlocks: Regroup
IndentCaseLabels: 'true'
IndentPPDirectives: AfterHash
IndentWidth: '4'
IndentWrappedFunctionNames: 'true'
JavaScriptQuotes: Leave
KeepEmptyLinesAtTheStartOfBlocks: 'false'
Language: Cpp
MaxEmptyLinesToKeep: '1'
NamespaceIndentation: All
PenaltyBreakBeforeFirstCallParameter: 7
PenaltyBreakAssignment: 8
PenaltyBreakComment: 200
PenaltyBreakFirstLessLess: 50
PenaltyBreakString: 100
PenaltyBreakTemplateDeclaration: 10
PenaltyExcessCharacter: 10
PenaltyReturnTypeOnItsOwnLine: 1000000
PointerAlignment: Left
ReflowComments: 'false'
SortIncludes: 'false'
SortUsingDeclarations: 'true'
SpaceAfterTemplateKeyword: 'true'
SpaceBeforeAssignmentOperators: 'true'
SpaceBeforeCpp11BracedList: 'true'
SpaceBeforeCtorInitializerColon: 'true'
SpaceBeforeInheritanceColon: 'true'
SpaceBeforeParens: ControlStatements
SpaceBeforeRangeBasedForLoopColon: 'true'
SpaceInEmptyParentheses: 'false'
SpacesBeforeTrailingComments: '2'
SpacesInAngles: 'false'
SpacesInCStyleCastParentheses: 'false'
SpacesInContainerLiterals: 'false'
SpacesInParentheses: 'false'
SpacesInSquareBrackets: 'false'
Standard: Cpp11
TabWidth: '4'
UseTab: Never
...

80
CodingStyle.md Normal file
View File

@ -0,0 +1,80 @@
# Coding style guidelines
While most software developers have a strong opinion about coding
style and conventions, the general agreement is that having a single
coding style in your project is beneficial for the readability and
maintainability.
Coding style of this project is enforced through `.clang-format`.
Most IDE's nowadays pick up the clang-format file automatically. If
this is not the case, please run it manually before committing code.
Note that different IDE's are compiled against different versions of
clang-format. This clang-format file is created in such a way, that
it should work with most IDE's out-of-the-box, and can apply changes
when the file is saved.
There may be violations of these guidelines in the code, due to
historical reasons or, in rare instances, other considerations.
We intend to fix such violations; patches that correct them
are most welcome - but should be tested carefully across the
supported compilation environments (Arduino and platformio).
## Guidelines
A few guidelines need to be taken into consideration while using
clang-format:
1. Include order and `".."` vs `<...>` matters. Clang-format
automatically re-orders your include files. This configuration
is created in such a way that header file includes always add
the minimum number of implicit dependencies. If this generates
problems, you should be fixing your includes, instead of disabling
clang-format.
2. Preprocessor commands are not formatted nicely in some cases.
This can hurt readibility in rare cases, in which case it's
okay to disable clang-format temporarily with
`// clang-format off` and `// clang-format on`. Most notably,
machine definitions should have clang-format off.
3. Use `#pragma once` in all header files. The reason is that
preprocessor `#ifdef`s are nested automatically, which making
things messy when using the alternative.
## Classes and namespaces
Filenames should correspond with clas names, folder names should
correspond with namespace names. This implies that a file should
have a single class.
## Naming
- Class names and namespace names are named `CamelCase`. Note that
class and namespace names should only start with an `_` if they are
(A) not in the global namespace and (b) should otherwise start with a digit.
For example `_10VSpindle`.
- Class member functions should be `snake_case`
- Class member variables should be `_snake_case` with a leading `_`.
Namespaces should have classes, and classes should have members. Avoid
using functions that have no class attached to them.
## Using namespace
- `using namespace` is not allowed in header files, except when
using it in the body of a function.
- Try to be conservative with `using namespace` in cpp files.
Prefer to use it in a function body whenever possible for clarity
what is used where.
## Including files
- It's a good practice to include just what you need. In general,
try to include as much as possible in the cpp file, and as little
as possible in the header file.
- A CPP file should normally include the corresponding header file
first (e.g. `WebSettings.cpp` should include `WebSettings.h`)
and then everything else.
- When including a system or library file, use `<...>` syntax;
when including a local file, use `"..."` syntax. Some IDE's
actually have trouble compiling if not done correctly.
- Never include a cpp file; always header files!

View File

@ -18,29 +18,26 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifdef ARDUINO_ARCH_ESP32
#include "grbl.h"
#ifdef ENABLE_BLUETOOTH
#include "BluetoothSerial.h"
#include "BTconfig.h"
# include "BluetoothSerial.h"
# include "BTconfig.h"
BTConfig bt_config;
BTConfig bt_config;
BluetoothSerial SerialBT;
#ifdef __cplusplus
# ifdef __cplusplus
extern "C" {
#endif
# endif
const uint8_t* esp_bt_dev_get_address(void);
#ifdef __cplusplus
# ifdef __cplusplus
}
#endif
# endif
String BTConfig::_btname = "";
String BTConfig::_btname = "";
String BTConfig::_btclient = "";
BTConfig::BTConfig() {
}
BTConfig::BTConfig() {}
BTConfig::~BTConfig() {
end();
@ -48,27 +45,25 @@ BTConfig::~BTConfig() {
static void my_spp_cb(esp_spp_cb_event_t event, esp_spp_cb_param_t* param) {
switch (event) {
case ESP_SPP_SRV_OPEN_EVT: { //Server connection open
char str[18];
str[17] = '\0';
uint8_t* addr = param->srv_open.rem_bda;
sprintf(str, "%02X:%02X:%02X:%02X:%02X:%02X", addr[0], addr[1], addr[2], addr[3], addr[4], addr[5]);
BTConfig::_btclient = str;
grbl_sendf(CLIENT_ALL, "[MSG:BT Connected with %s]\r\n", str);
}
break;
case ESP_SPP_CLOSE_EVT://Client connection closed
grbl_send(CLIENT_ALL, "[MSG:BT Disconnected]\r\n");
BTConfig::_btclient = "";
break;
default:
break;
case ESP_SPP_SRV_OPEN_EVT: { //Server connection open
char str[18];
str[17] = '\0';
uint8_t* addr = param->srv_open.rem_bda;
sprintf(str, "%02X:%02X:%02X:%02X:%02X:%02X", addr[0], addr[1], addr[2], addr[3], addr[4], addr[5]);
BTConfig::_btclient = str;
grbl_sendf(CLIENT_ALL, "[MSG:BT Connected with %s]\r\n", str);
} break;
case ESP_SPP_CLOSE_EVT: //Client connection closed
grbl_send(CLIENT_ALL, "[MSG:BT Disconnected]\r\n");
BTConfig::_btclient = "";
break;
default: break;
}
}
const char* BTConfig::info() {
static String result;
String tmp;
String tmp;
result = "[MSG:";
if (Is_BT_on()) {
result += "Mode=BT:Name=";
@ -78,8 +73,10 @@ const char* BTConfig::info() {
result += "):Status=";
if (SerialBT.hasClient())
result += "Connected with " + _btclient;
else result += "Not connected";
} else result += "No BT";
else
result += "Not connected";
} else
result += "No BT";
result += "]\r\n";
return result.c_str();
}
@ -102,7 +99,7 @@ bool BTConfig::isBTnameValid(const char* hostname) {
const char* BTConfig::device_address() {
const uint8_t* point = esp_bt_dev_get_address();
static char str[18];
static char str[18];
str[17] = '\0';
sprintf(str, "%02X:%02X:%02X:%02X:%02X:%02X", (int)point[0], (int)point[1], (int)point[2], (int)point[3], (int)point[4], (int)point[5]);
return str;
@ -122,7 +119,8 @@ void BTConfig::begin() {
SerialBT.register_callback(&my_spp_cb);
grbl_sendf(CLIENT_ALL, "[MSG:BT Started with %s]\r\n", _btname.c_str());
}
} else end();
} else
end();
}
/**
@ -156,7 +154,4 @@ void BTConfig::handle() {
COMMANDS::wait(0);
}
#endif // ENABLE_BLUETOOTH
#endif // ARDUINO_ARCH_ESP32
#endif // ENABLE_BLUETOOTH

View File

@ -20,40 +20,39 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#if !defined(CONFIG_BT_ENABLED) || !defined(CONFIG_BLUEDROID_ENABLED)
#error Bluetooth is not enabled! Please run `make menuconfig` to and enable it
# error Bluetooth is not enabled! Please run `make menuconfig` to and enable it
#endif
//defaults values
#define DEFAULT_BT_NAME "btgrblesp"
//boundaries
#define MAX_BTNAME_LENGTH 32
#define MIN_BTNAME_LENGTH 1
#define MAX_BTNAME_LENGTH 32
#define MIN_BTNAME_LENGTH 1
#define BT_EVENT_DISCONNECTED 0
#define BT_EVENT_CONNECTED 1
#include "BluetoothSerial.h"
extern BluetoothSerial SerialBT;
class BTConfig {
public:
public:
BTConfig();
~BTConfig();
static const char* info();
static void BTEvent(uint8_t event);
static bool isBTnameValid(const char* hostname);
static String BTname() {return _btname;}
static void BTEvent(uint8_t event);
static bool isBTnameValid(const char* hostname);
static String BTname() { return _btname; }
static const char* device_address();
static void begin();
static void end();
static void handle();
static void reset_settings();
static bool Is_BT_on();
static String _btclient;
private :
static void begin();
static void end();
static void handle();
static void reset_settings();
static bool Is_BT_on();
static String _btclient;
private:
static String _btname;
};

View File

@ -28,60 +28,60 @@
// in Machines/atari_1020.h, thus causing this file to be included
// from ../custom_code.cpp
#define HOMING_PHASE_FULL_APPROACH 0 // move to right end
#define HOMING_PHASE_CHECK 1 // check reed switch
#define HOMING_PHASE_RETRACT 2 // retract
#define HOMING_PHASE_SHORT_APPROACH 3 // retract
#define HOMING_PHASE_FULL_APPROACH 0 // move to right end
#define HOMING_PHASE_CHECK 1 // check reed switch
#define HOMING_PHASE_RETRACT 2 // retract
#define HOMING_PHASE_SHORT_APPROACH 3 // retract
static TaskHandle_t solenoidSyncTaskHandle = 0;
static TaskHandle_t atariHomingTaskHandle = 0;
int8_t solenoid_pwm_chan_num;
uint16_t solenoid_pull_count;
bool atari_homing = false;
uint8_t homing_phase = HOMING_PHASE_FULL_APPROACH;
uint8_t current_tool;
static TaskHandle_t atariHomingTaskHandle = 0;
int8_t solenoid_pwm_chan_num;
uint16_t solenoid_pull_count;
bool atari_homing = false;
uint8_t homing_phase = HOMING_PHASE_FULL_APPROACH;
uint8_t current_tool;
void machine_init() {
solenoid_pull_count = 0; // initialize
solenoid_pull_count = 0; // initialize
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Atari 1020 Solenoid");
// setup PWM channel
solenoid_pwm_chan_num = sys_get_next_PWM_chan_num();
ledcSetup(solenoid_pwm_chan_num, SOLENOID_PWM_FREQ, SOLENOID_PWM_RES_BITS);
ledcAttachPin(SOLENOID_PEN_PIN, solenoid_pwm_chan_num);
pinMode(SOLENOID_DIRECTION_PIN, OUTPUT); // this sets the direction of the solenoid current
pinMode(REED_SW_PIN, INPUT_PULLUP); // external pullup required
pinMode(SOLENOID_DIRECTION_PIN, OUTPUT); // this sets the direction of the solenoid current
pinMode(REED_SW_PIN, INPUT_PULLUP); // external pullup required
// setup a task that will calculate solenoid position
xTaskCreatePinnedToCore(solenoidSyncTask, // task
"solenoidSyncTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
xTaskCreatePinnedToCore(solenoidSyncTask, // task
"solenoidSyncTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
&solenoidSyncTaskHandle,
0 // core
);
0 // core
);
// setup a task that will do the custom homing sequence
xTaskCreatePinnedToCore(atari_home_task, // task
"atari_home_task", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
xTaskCreatePinnedToCore(atari_home_task, // task
"atari_home_task", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
&atariHomingTaskHandle,
0 // core
);
0 // core
);
}
// this task tracks the Z position and sets the solenoid
void solenoidSyncTask(void* pvParameters) {
int32_t current_position[N_AXIS]; // copy of current location
float m_pos[N_AXIS]; // machine position in mm
TickType_t xLastWakeTime;
const TickType_t xSolenoidFrequency = SOLENOID_TASK_FREQ; // in ticks (typically ms)
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
int32_t current_position[N_AXIS]; // copy of current location
float m_pos[N_AXIS]; // machine position in mm
TickType_t xLastWakeTime;
const TickType_t xSolenoidFrequency = SOLENOID_TASK_FREQ; // in ticks (typically ms)
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) {
// don't ever return from this or the task dies
memcpy(current_position, sys_position, sizeof(sys_position)); // get current position in step
system_convert_array_steps_to_mpos(m_pos, current_position); // convert to millimeters
calc_solenoid(m_pos[Z_AXIS]); // calculate kinematics and move the servos
memcpy(current_position, sys_position, sizeof(sys_position)); // get current position in step
system_convert_array_steps_to_mpos(m_pos, current_position); // convert to millimeters
calc_solenoid(m_pos[Z_AXIS]); // calculate kinematics and move the servos
vTaskDelayUntil(&xLastWakeTime, xSolenoidFrequency);
}
}
@ -94,7 +94,7 @@ bool user_defined_homing() {
// create and start a task to do the special homing
homing_phase = HOMING_PHASE_FULL_APPROACH;
atari_homing = true;
return true; // this does it...skip the rest of mc_homing_cycle(...)
return true; // this does it...skip the rest of mc_homing_cycle(...)
}
/*
@ -113,54 +113,54 @@ bool user_defined_homing() {
*/
void atari_home_task(void* pvParameters) {
uint8_t homing_attempt = 0; // how many times have we tried to home
TickType_t xLastWakeTime;
const TickType_t xHomingTaskFrequency = 100; // in ticks (typically ms) .... need to make sure there is enough time to get out of idle
char gcode_line[20];
uint8_t homing_attempt = 0; // how many times have we tried to home
TickType_t xLastWakeTime;
const TickType_t xHomingTaskFrequency = 100; // in ticks (typically ms) .... need to make sure there is enough time to get out of idle
char gcode_line[20];
while (true) {
// this task will only last as long as it is homing
if (atari_homing) {
// must be in idle or alarm state
if (sys.state == STATE_IDLE) {
switch (homing_phase) {
case HOMING_PHASE_FULL_APPROACH: // a full width move to insure it hits left end
inputBuffer.push("G90G0Z1\r"); // lift the pen
sprintf(gcode_line, "G91G0X%3.2f\r", -ATARI_PAPER_WIDTH + ATARI_HOME_POS - 3.0); // plus a little extra
inputBuffer.push(gcode_line);
homing_attempt = 1;
homing_phase = HOMING_PHASE_CHECK;
break;
case HOMING_PHASE_CHECK: // check the limits switch
if (digitalRead(REED_SW_PIN) == 0) {
// see if reed switch is grounded
inputBuffer.push("G4P0.1\n"); // dramtic pause
sys_position[X_AXIS] = ATARI_HOME_POS * axis_settings[X_AXIS]->steps_per_mm->get();
sys_position[Y_AXIS] = 0.0;
sys_position[Z_AXIS] = 1.0 * axis_settings[Y_AXIS]->steps_per_mm->get();
gc_sync_position();
plan_sync_position();
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls
case HOMING_PHASE_FULL_APPROACH: // a full width move to insure it hits left end
inputBuffer.push("G90G0Z1\r"); // lift the pen
sprintf(gcode_line, "G91G0X%3.2f\r", -ATARI_PAPER_WIDTH + ATARI_HOME_POS - 3.0); // plus a little extra
inputBuffer.push(gcode_line);
current_tool = 1; // local copy for reference...until actual M6 change
gc_state.tool = current_tool;
atari_homing = false; // done with homing sequence
} else {
homing_phase = HOMING_PHASE_RETRACT;
homing_attempt++;
}
break;
case HOMING_PHASE_RETRACT:
sprintf(gcode_line, "G0X%3.2f\r", -ATARI_HOME_POS);
inputBuffer.push(gcode_line);
sprintf(gcode_line, "G0X%3.2f\r", ATARI_HOME_POS);
inputBuffer.push(gcode_line);
homing_phase = HOMING_PHASE_CHECK;
break;
default:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Homing phase error %d", homing_phase);
atari_homing = false;
; // kills task
break;
homing_attempt = 1;
homing_phase = HOMING_PHASE_CHECK;
break;
case HOMING_PHASE_CHECK: // check the limits switch
if (digitalRead(REED_SW_PIN) == 0) {
// see if reed switch is grounded
inputBuffer.push("G4P0.1\n"); // dramtic pause
sys_position[X_AXIS] = ATARI_HOME_POS * axis_settings[X_AXIS]->steps_per_mm->get();
sys_position[Y_AXIS] = 0.0;
sys_position[Z_AXIS] = 1.0 * axis_settings[Y_AXIS]->steps_per_mm->get();
gc_sync_position();
plan_sync_position();
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls
inputBuffer.push(gcode_line);
current_tool = 1; // local copy for reference...until actual M6 change
gc_state.tool = current_tool;
atari_homing = false; // done with homing sequence
} else {
homing_phase = HOMING_PHASE_RETRACT;
homing_attempt++;
}
break;
case HOMING_PHASE_RETRACT:
sprintf(gcode_line, "G0X%3.2f\r", -ATARI_HOME_POS);
inputBuffer.push(gcode_line);
sprintf(gcode_line, "G0X%3.2f\r", ATARI_HOME_POS);
inputBuffer.push(gcode_line);
homing_phase = HOMING_PHASE_CHECK;
break;
default:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Homing phase error %d", homing_phase);
atari_homing = false;
; // kills task
break;
}
if (homing_attempt > ATARI_HOMING_ATTEMPTS) {
// try all positions plus 1
@ -177,25 +177,25 @@ void atari_home_task(void* pvParameters) {
// calculate and set the PWM value for the servo
void calc_solenoid(float penZ) {
bool isPenUp;
bool isPenUp;
static bool previousPenState = false;
uint32_t solenoid_pen_pulse_len; // duty cycle of solenoid
isPenUp = ((penZ > 0) || (sys.state == STATE_ALARM)); // is pen above Z0 or is there an alarm
uint32_t solenoid_pen_pulse_len; // duty cycle of solenoid
isPenUp = ((penZ > 0) || (sys.state == STATE_ALARM)); // is pen above Z0 or is there an alarm
// if the state has not change, we only count down to the pull time
if (previousPenState == isPenUp) {
// if state is unchanged
if (solenoid_pull_count > 0) {
solenoid_pull_count--;
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_PULL; // stay at full power while counting down
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_PULL; // stay at full power while counting down
} else {
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_HOLD; // pull in delay has expired so lower duty cycle
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_HOLD; // pull in delay has expired so lower duty cycle
}
} else {
// pen direction has changed
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_PULL; // go to full power
solenoid_pull_count = SOLENOID_PULL_DURATION; // set the time to count down
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_PULL; // go to full power
solenoid_pull_count = SOLENOID_PULL_DURATION; // set the time to count down
}
previousPenState = isPenUp; // save the prev state
previousPenState = isPenUp; // save the prev state
digitalWrite(SOLENOID_DIRECTION_PIN, isPenUp);
// skip setting value if it is unchanged
if (ledcRead(solenoid_pwm_chan_num) == solenoid_pen_pulse_len)
@ -214,8 +214,8 @@ void calc_solenoid(float penZ) {
*/
void user_tool_change(uint8_t new_tool) {
uint8_t move_count;
char gcode_line[20];
protocol_buffer_synchronize(); // wait for all previous moves to complete
char gcode_line[20];
protocol_buffer_synchronize(); // wait for all previous moves to complete
if ((new_tool < 1) || (new_tool > MAX_PEN_NUMBER)) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Requested Pen#%d is out of 1-4 range", new_tool);
return;
@ -226,10 +226,10 @@ void user_tool_change(uint8_t new_tool) {
move_count = BUMPS_PER_PEN_CHANGE * (new_tool - current_tool);
else
move_count = BUMPS_PER_PEN_CHANGE * ((MAX_PEN_NUMBER - current_tool) + new_tool);
sprintf(gcode_line, "G0Z%3.2f\r", ATARI_TOOL_CHANGE_Z); // go to tool change height
sprintf(gcode_line, "G0Z%3.2f\r", ATARI_TOOL_CHANGE_Z); // go to tool change height
inputBuffer.push(gcode_line);
for (uint8_t i = 0; i < move_count; i++) {
sprintf(gcode_line, "G0X%3.2f\r", ATARI_HOME_POS); //
sprintf(gcode_line, "G0X%3.2f\r", ATARI_HOME_POS); //
inputBuffer.push(gcode_line);
inputBuffer.push("G0X0\r");
}
@ -251,38 +251,36 @@ void user_defined_macro(uint8_t index) {
char gcode_line[20];
switch (index) {
#ifdef MACRO_BUTTON_0_PIN
case CONTROL_PIN_INDEX_MACRO_0:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Pen switch");
inputBuffer.push("$H\r");
break;
case CONTROL_PIN_INDEX_MACRO_0:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Pen switch");
inputBuffer.push("$H\r");
break;
#endif
#ifdef MACRO_BUTTON_1_PIN
case CONTROL_PIN_INDEX_MACRO_1:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Color switch");
atari_next_pen();
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls
inputBuffer.push(gcode_line);
break;
case CONTROL_PIN_INDEX_MACRO_1:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Color switch");
atari_next_pen();
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls
inputBuffer.push(gcode_line);
break;
#endif
#ifdef MACRO_BUTTON_2_PIN
case CONTROL_PIN_INDEX_MACRO_2:
// feed out some paper and reset the Y 0
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Paper switch");
inputBuffer.push("G0Y-25\r");
inputBuffer.push("G4P0.1\r"); // sync...forces wait for planner to clear
sys_position[Y_AXIS] = 0.0; // reset the Y position
gc_sync_position();
plan_sync_position();
break;
case CONTROL_PIN_INDEX_MACRO_2:
// feed out some paper and reset the Y 0
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Paper switch");
inputBuffer.push("G0Y-25\r");
inputBuffer.push("G4P0.1\r"); // sync...forces wait for planner to clear
sys_position[Y_AXIS] = 0.0; // reset the Y position
gc_sync_position();
plan_sync_position();
break;
#endif
default:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Unknown Switch %d", index);
break;
default: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Unknown Switch %d", index); break;
}
}
void user_m30() {
char gcode_line[20];
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); //
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); //
inputBuffer.push(gcode_line);
}

View File

@ -51,9 +51,7 @@ enabled with USE_ defines in Machines/my_machine.h
machine_init() is called when Grbl_ESP32 first starts. You can use it to do any
special things your machine needs at startup.
*/
void machine_init()
{
}
void machine_init() {}
#endif
#ifdef USE_CUSTOM_HOMING
@ -64,10 +62,9 @@ void machine_init()
example, if you need to manually prep the machine for homing, you could implement
user_defined_homing() to wait for some button to be pressed, then return true.
*/
bool user_defined_homing()
{
// True = done with homing, false = continue with normal Grbl_ESP32 homing
return true;
bool user_defined_homing() {
// True = done with homing, false = continue with normal Grbl_ESP32 homing
return true;
}
#endif
@ -89,10 +86,9 @@ bool user_defined_homing()
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)
{
// this simply moves to the target. Replace with your kinematics.
mc_line(target, pl_data);
void 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);
}
/*
@ -103,15 +99,13 @@ void inverse_kinematics(float *target, plan_line_data_t *pl_data, float *positio
*/
bool kinematics_pre_homing(uint8_t cycle_mask))
{
return false; // finish normal homing cycle
return false; // finish normal homing cycle
}
/*
kinematics_post_homing() is called at the end of normal homing
*/
void kinematics_post_homing()
{
}
void kinematics_post_homing() {}
#endif
#ifdef USE_FWD_KINEMATIC
@ -121,10 +115,9 @@ void kinematics_post_homing()
Convert the N_AXIS array of motor positions to cartesian in your code.
*/
void forward_kinematics(float *position)
{
// position[X_AXIS] =
// position[Y_AXIS] =
void forward_kinematics(float* position) {
// position[X_AXIS] =
// position[Y_AXIS] =
}
#endif
@ -133,9 +126,7 @@ void forward_kinematics(float *position)
user_tool_change() is called when tool change gcode is received,
to perform appropriate actions for your machine.
*/
void user_tool_change(uint8_t new_tool)
{
}
void user_tool_change(uint8_t new_tool) {}
#endif
#if defined(MACRO_BUTTON_0_PIN) || defined(MACRO_BUTTON_1_PIN) || defined(MACRO_BUTTON_2_PIN)
@ -143,18 +134,14 @@ void user_tool_change(uint8_t new_tool)
options. user_defined_macro() is called with the button number to
perform whatever actions you choose.
*/
void user_defined_macro(uint8_t index)
{
}
void user_defined_macro(uint8_t index) {}
#endif
#ifdef USE_M30
/*
user_m30() is called when an M30 gcode signals the end of a gcode file.
*/
void user_m30()
{
}
void user_m30() {}
#endif
#ifdef USE_MACHINE_TRINAMIC_INIT
@ -162,9 +149,7 @@ void user_m30()
machine_triaminic_setup() replaces the normal setup of trinamic
drivers with your own code. For example, you could setup StallGuard
*/
void machine_trinamic_setup()
{
}
void machine_trinamic_setup() {}
#endif
// If you add any additional functions specific to your machine that

View File

@ -51,33 +51,32 @@ enabled with USE_ defines in Machines/my_machine.h
machine_init() is called when Grbl_ESP32 first starts. You can use it to do any
special things your machine needs at startup.
*/
#define STEPPERS_DISABLE_PIN_X 138
#define STEPPERS_DISABLE_PIN_Y 134
#define STEPPERS_DISABLE_PIN_Z 131
#define STEPPERS_DISABLE_PIN_A 139
# define STEPPERS_DISABLE_PIN_X 138
# define STEPPERS_DISABLE_PIN_Y 134
# define STEPPERS_DISABLE_PIN_Z 131
# define STEPPERS_DISABLE_PIN_A 139
#define FAN1_PIN 13
#define FAN2_PIN 142
#define FAN3_PIN 143
# define FAN1_PIN 13
# define FAN2_PIN 142
# define FAN3_PIN 143
#define BED_PIN 4
#define NOZZLE_PIN 2
# define BED_PIN 4
# define NOZZLE_PIN 2
void machine_init()
{
// Enable steppers
digitalWrite(STEPPERS_DISABLE_PIN_X, LOW); // enable
digitalWrite(STEPPERS_DISABLE_PIN_Y, LOW); // enable
digitalWrite(STEPPERS_DISABLE_PIN_Z, LOW); // enable
digitalWrite(STEPPERS_DISABLE_PIN_A, LOW); // enable
void machine_init() {
// Enable steppers
digitalWrite(STEPPERS_DISABLE_PIN_X, LOW); // enable
digitalWrite(STEPPERS_DISABLE_PIN_Y, LOW); // enable
digitalWrite(STEPPERS_DISABLE_PIN_Z, LOW); // enable
digitalWrite(STEPPERS_DISABLE_PIN_A, LOW); // enable
// digitalWrite(FAN1_PIN, LOW); // comment out for JTAG debugging
// digitalWrite(FAN1_PIN, LOW); // comment out for JTAG debugging
digitalWrite(FAN2_PIN, LOW); // disable
digitalWrite(FAN3_PIN, LOW); // disable
digitalWrite(FAN2_PIN, LOW); // disable
digitalWrite(FAN3_PIN, LOW); // disable
digitalWrite(BED_PIN, LOW); // disable
digitalWrite(NOZZLE_PIN, LOW); // disable
digitalWrite(BED_PIN, LOW); // disable
digitalWrite(NOZZLE_PIN, LOW); // disable
}
#endif
@ -89,10 +88,9 @@ void machine_init()
example, if you need to manually prep the machine for homing, you could implement
user_defined_homing() to wait for some button to be pressed, then return true.
*/
bool user_defined_homing()
{
// True = done with homing, false = continue with normal Grbl_ESP32 homing
return true;
bool user_defined_homing() {
// True = done with homing, false = continue with normal Grbl_ESP32 homing
return true;
}
#endif
@ -114,10 +112,9 @@ bool user_defined_homing()
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)
{
// this simply moves to the target. Replace with your kinematics.
mc_line(target, pl_data);
void 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);
}
/*
@ -128,15 +125,13 @@ void inverse_kinematics(float *target, plan_line_data_t *pl_data, float *positio
*/
bool kinematics_pre_homing(uint8_t cycle_mask))
{
return false; // finish normal homing cycle
return false; // finish normal homing cycle
}
/*
kinematics_post_homing() is called at the end of normal homing
*/
void kinematics_post_homing()
{
}
void kinematics_post_homing() {}
#endif
#ifdef USE_FWD_KINEMATIC
@ -146,10 +141,9 @@ void kinematics_post_homing()
Convert the N_AXIS array of motor positions to cartesian in your code.
*/
void forward_kinematics(float *position)
{
// position[X_AXIS] =
// position[Y_AXIS] =
void forward_kinematics(float* position) {
// position[X_AXIS] =
// position[Y_AXIS] =
}
#endif
@ -158,9 +152,7 @@ void forward_kinematics(float *position)
user_tool_change() is called when tool change gcode is received,
to perform appropriate actions for your machine.
*/
void user_tool_change(uint8_t new_tool)
{
}
void user_tool_change(uint8_t new_tool) {}
#endif
#if defined(MACRO_BUTTON_0_PIN) || defined(MACRO_BUTTON_1_PIN) || defined(MACRO_BUTTON_2_PIN)
@ -168,18 +160,14 @@ void user_tool_change(uint8_t new_tool)
options. user_defined_macro() is called with the button number to
perform whatever actions you choose.
*/
void user_defined_macro(uint8_t index)
{
}
void user_defined_macro(uint8_t index) {}
#endif
#ifdef USE_M30
/*
user_m30() is called when an M30 gcode signals the end of a gcode file.
*/
void user_m30()
{
}
void user_m30() {}
#endif
#ifdef USE_MACHINE_TRINAMIC_INIT
@ -187,9 +175,7 @@ void user_m30()
machine_triaminic_setup() replaces the normal setup of trinamic
drivers with your own code. For example, you could setup StallGuard
*/
void machine_trinamic_setup()
{
}
void machine_trinamic_setup() {}
#endif
// If you add any additional functions specific to your machine that

View File

@ -54,18 +54,17 @@
// in Machines/polar_coaster.h, thus causing this file to be included
// from ../custom_code.cpp
void calc_polar(float *target_xyz, float *polar, float last_angle);
void calc_polar(float* target_xyz, float* polar, float last_angle);
float abs_angle(float ang);
static float last_angle = 0;
static float last_angle = 0;
static float last_radius = 0;
// this get called before homing
// return false to complete normal home
// return true to exit normal homing
bool kinematics_pre_homing(uint8_t cycle_mask) {
return false; // finish normal homing cycle
return false; // finish normal homing cycle
}
void kinematics_post_homing() {
@ -86,17 +85,17 @@ void kinematics_post_homing() {
*/
void inverse_kinematics(float *target, plan_line_data_t *pl_data, float *position) {
void 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
float p_dx, p_dy, p_dz; // distances in each polar axis
float dist, polar_dist; // the distances in both systems...used to determine feed rate
uint32_t segment_count; // number of segments the move will be broken in to.
float seg_target[N_AXIS]; // The target of the current segment
float polar[N_AXIS]; // target location in polar coordinates
float x_offset = gc_state.coord_system[X_AXIS] + gc_state.coord_offset[X_AXIS]; // offset from machine coordinate system
float z_offset = gc_state.coord_system[Z_AXIS] + gc_state.coord_offset[Z_AXIS]; // offset from machine coordinate system
float dx, dy, dz; // distances in each cartesian axis
float p_dx, p_dy, p_dz; // distances in each polar axis
float dist, polar_dist; // the distances in both systems...used to determine feed rate
uint32_t segment_count; // number of segments the move will be broken in to.
float seg_target[N_AXIS]; // The target of the current segment
float polar[N_AXIS]; // target location in polar coordinates
float x_offset = gc_state.coord_system[X_AXIS] + gc_state.coord_offset[X_AXIS]; // offset from machine coordinate system
float z_offset = gc_state.coord_system[Z_AXIS] + gc_state.coord_offset[Z_AXIS]; // offset from machine coordinate system
//grbl_sendf(CLIENT_SERIAL, "Position: %4.2f %4.2f %4.2f \r\n", position[X_AXIS] - x_offset, position[Y_AXIS], position[Z_AXIS]);
//grbl_sendf(CLIENT_SERIAL, "Target: %4.2f %4.2f %4.2f \r\n", target[X_AXIS] - x_offset, target[Y_AXIS], target[Z_AXIS]);
// calculate cartesian move distance for each axis
@ -120,11 +119,11 @@ void inverse_kinematics(float *target, plan_line_data_t *pl_data, float *positio
calc_polar(seg_target, polar, last_angle);
// begin determining new feed rate
// calculate move distance for each axis
p_dx = polar[RADIUS_AXIS] - last_radius;
p_dy = polar[POLAR_AXIS] - last_angle;
p_dz = dz;
polar_dist = sqrt((p_dx * p_dx) + (p_dy * p_dy) + (p_dz * p_dz)); // calculate the total move distance
float polar_rate_multiply = 1.0; // fail safe rate
p_dx = polar[RADIUS_AXIS] - last_radius;
p_dy = polar[POLAR_AXIS] - last_angle;
p_dz = dz;
polar_dist = sqrt((p_dx * p_dx) + (p_dy * p_dy) + (p_dz * p_dz)); // calculate the total move distance
float polar_rate_multiply = 1.0; // fail safe rate
if (polar_dist == 0 || dist == 0) {
// prevent 0 feed rate and division by 0
polar_rate_multiply = 1.0; // default to same feed rate
@ -141,7 +140,7 @@ void inverse_kinematics(float *target, plan_line_data_t *pl_data, float *positio
polar[RADIUS_AXIS] += x_offset;
polar[Z_AXIS] += z_offset;
last_radius = polar[RADIUS_AXIS];
last_angle = polar[POLAR_AXIS];
last_angle = polar[POLAR_AXIS];
mc_line(polar, pl_data);
}
// TO DO don't need a feedrate for rapids
@ -160,18 +159,18 @@ position = the current machine position
converted = position with forward kinematics applied.
*/
void forward_kinematics(float *position) {
float original_position[N_AXIS]; // temporary storage of original
float print_position[N_AXIS];
void forward_kinematics(float* position) {
float original_position[N_AXIS]; // temporary storage of original
float print_position[N_AXIS];
int32_t current_position[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);
original_position[X_AXIS] = print_position[X_AXIS] - gc_state.coord_system[X_AXIS] + gc_state.coord_offset[X_AXIS];
original_position[Y_AXIS] = print_position[Y_AXIS] - gc_state.coord_system[Y_AXIS] + gc_state.coord_offset[Y_AXIS];
original_position[Z_AXIS] = print_position[Z_AXIS] - gc_state.coord_system[Z_AXIS] + gc_state.coord_offset[Z_AXIS];
position[X_AXIS] = cos(radians(original_position[Y_AXIS])) * original_position[X_AXIS] * -1;
position[Y_AXIS] = sin(radians(original_position[Y_AXIS])) * original_position[X_AXIS];
position[Z_AXIS] = original_position[Z_AXIS]; // unchanged
position[X_AXIS] = cos(radians(original_position[Y_AXIS])) * original_position[X_AXIS] * -1;
position[Y_AXIS] = sin(radians(original_position[Y_AXIS])) * original_position[X_AXIS];
position[Z_AXIS] = original_position[Z_AXIS]; // unchanged
}
// helper functions
@ -189,7 +188,7 @@ void forward_kinematics(float *position) {
* a long job.
*
*/
void calc_polar(float *target_xyz, float *polar, float last_angle) {
void calc_polar(float* target_xyz, float* polar, float last_angle) {
float delta_ang; // the difference from the last and next angle
polar[RADIUS_AXIS] = hypot_f(target_xyz[X_AXIS], target_xyz[Y_AXIS]);
if (polar[RADIUS_AXIS] == 0) {
@ -200,7 +199,7 @@ void calc_polar(float *target_xyz, float *polar, float last_angle) {
polar[POLAR_AXIS] = abs_angle(polar[POLAR_AXIS]);
}
polar[Z_AXIS] = target_xyz[Z_AXIS]; // Z is unchanged
delta_ang = polar[POLAR_AXIS] - abs_angle(last_angle);
delta_ang = polar[POLAR_AXIS] - abs_angle(last_angle);
// if the delta is above 180 degrees it means we are crossing the 0 degree line
if (fabs(delta_ang) <= 180.0)
polar[POLAR_AXIS] = last_angle + delta_ang;
@ -225,26 +224,24 @@ float abs_angle(float ang) {
void user_defined_macro(uint8_t index) {
switch (index) {
#ifdef MACRO_BUTTON_0_PIN
case CONTROL_PIN_INDEX_MACRO_0:
inputBuffer.push("$H\r"); // home machine
break;
case CONTROL_PIN_INDEX_MACRO_0:
inputBuffer.push("$H\r"); // home machine
break;
#endif
#ifdef MACRO_BUTTON_1_PIN
case CONTROL_PIN_INDEX_MACRO_1:
inputBuffer.push("[ESP220]/1.nc\r"); // run SD card file 1.nc
break;
case CONTROL_PIN_INDEX_MACRO_1:
inputBuffer.push("[ESP220]/1.nc\r"); // run SD card file 1.nc
break;
#endif
#ifdef MACRO_BUTTON_2_PIN
case CONTROL_PIN_INDEX_MACRO_2:
inputBuffer.push("[ESP220]/2.nc\r"); // run SD card file 2.nc
break;
case CONTROL_PIN_INDEX_MACRO_2:
inputBuffer.push("[ESP220]/2.nc\r"); // run SD card file 2.nc
break;
#endif
#ifdef MACRO_BUTTON_3_PIN
case CONTROL_PIN_INDEX_MACRO_3:
break;
case CONTROL_PIN_INDEX_MACRO_3: break;
#endif
default:
break;
default: break;
}
}

View File

@ -25,48 +25,41 @@
#include "Motors/MotorClass.cpp"
// Declare system global variable structure
system_t sys;
int32_t sys_position[N_AXIS]; // Real-time machine (aka home) position vector in steps.
int32_t sys_probe_position[N_AXIS]; // Last probe position in machine coordinates and steps.
volatile uint8_t sys_probe_state; // Probing state value. Used to coordinate the probing cycle with stepper ISR.
volatile uint8_t sys_rt_exec_state; // Global realtime executor bitflag variable for state management. See EXEC bitmasks.
volatile uint8_t sys_rt_exec_alarm; // Global realtime executor bitflag variable for setting various alarms.
volatile uint8_t sys_rt_exec_motion_override; // Global realtime executor bitflag variable for motion-based overrides.
volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bitflag variable for spindle/coolant overrides.
system_t sys;
int32_t sys_position[N_AXIS]; // Real-time machine (aka home) position vector in steps.
int32_t sys_probe_position[N_AXIS]; // Last probe position in machine coordinates and steps.
volatile uint8_t sys_probe_state; // Probing state value. Used to coordinate the probing cycle with stepper ISR.
volatile uint8_t sys_rt_exec_state; // Global realtime executor bitflag variable for state management. See EXEC bitmasks.
volatile uint8_t sys_rt_exec_alarm; // Global realtime executor bitflag variable for setting various alarms.
volatile uint8_t sys_rt_exec_motion_override; // Global realtime executor bitflag variable for motion-based overrides.
volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bitflag variable for spindle/coolant overrides.
#ifdef DEBUG
volatile uint8_t sys_rt_exec_debug;
volatile uint8_t sys_rt_exec_debug;
#endif
Spindle *spindle;
Spindle* spindle;
void setup() {
#ifdef USE_I2S_OUT
i2s_out_init(); // The I2S out must be initialized before it can access the expanded GPIO port
i2s_out_init(); // The I2S out must be initialized before it can access the expanded GPIO port
#endif
WiFi.persistent(false);
WiFi.disconnect(true);
WiFi.enableSTA(false);
WiFi.enableAP(false);
WiFi.mode(WIFI_OFF);
serial_init(); // Setup serial baud rate and interrupts
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Grbl_ESP32 Ver %s Date %s", GRBL_VERSION, GRBL_VERSION_BUILD); // print grbl_esp32 verion info
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Compiled with ESP32 SDK:%s", ESP.getSdkVersion()); // print the SDK version
serial_init(); // Setup serial baud rate and interrupts
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Grbl_ESP32 Ver %s Date %s", GRBL_VERSION, GRBL_VERSION_BUILD); // print grbl_esp32 verion info
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Compiled with ESP32 SDK:%s", ESP.getSdkVersion()); // print the SDK version
// show the map name at startup
#ifdef MACHINE_NAME
#ifdef MACHINE_EXTRA
#define MACHINE_STRING MACHINE_NAME MACHINE_EXTRA
#else
#define MACHINE_STRING MACHINE_NAME
#endif
report_machine_type(CLIENT_SERIAL);
#endif
settings_init(); // Load Grbl settings from EEPROM
stepper_init(); // Configure stepper pins and interrupt timers
settings_init(); // Load Grbl settings from EEPROM
stepper_init(); // Configure stepper pins and interrupt timers
init_motors();
system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files)
memset(sys_position, 0, sizeof(sys_position)); // Clear machine position.
system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files)
memset(sys_position, 0, sizeof(sys_position)); // Clear machine position.
#ifdef USE_PEN_SERVO
servo_init();
#endif
@ -77,7 +70,7 @@ void setup() {
solenoid_init();
#endif
#ifdef USE_MACHINE_INIT
machine_init(); // user supplied function for special initialization
machine_init(); // user supplied function for special initialization
#endif
// Initialize system state.
#ifdef FORCE_INITIALIZATION_ALARM
@ -94,7 +87,8 @@ void setup() {
// not after disabling the alarm locks. Prevents motion startup blocks from crashing into
// things uncontrollably. Very bad.
#ifdef HOMING_INIT_LOCK
if (homing_enable->get()) sys.state = STATE_ALARM;
if (homing_enable->get())
sys.state = STATE_ALARM;
#endif
spindle_select();
#ifdef ENABLE_WIFI
@ -109,26 +103,26 @@ void setup() {
void loop() {
// Reset system variables.
uint8_t prior_state = sys.state;
memset(&sys, 0, sizeof(system_t)); // Clear system struct variable.
sys.state = prior_state;
sys.f_override = DEFAULT_FEED_OVERRIDE; // Set to 100%
sys.r_override = DEFAULT_RAPID_OVERRIDE; // Set to 100%
sys.spindle_speed_ovr = DEFAULT_SPINDLE_SPEED_OVERRIDE; // Set to 100%
memset(sys_probe_position, 0, sizeof(sys_probe_position)); // Clear probe position.
sys_probe_state = 0;
sys_rt_exec_state = 0;
sys_rt_exec_alarm = 0;
sys_rt_exec_motion_override = 0;
memset(&sys, 0, sizeof(system_t)); // Clear system struct variable.
sys.state = prior_state;
sys.f_override = DEFAULT_FEED_OVERRIDE; // Set to 100%
sys.r_override = DEFAULT_RAPID_OVERRIDE; // Set to 100%
sys.spindle_speed_ovr = DEFAULT_SPINDLE_SPEED_OVERRIDE; // Set to 100%
memset(sys_probe_position, 0, sizeof(sys_probe_position)); // Clear probe position.
sys_probe_state = 0;
sys_rt_exec_state = 0;
sys_rt_exec_alarm = 0;
sys_rt_exec_motion_override = 0;
sys_rt_exec_accessory_override = 0;
// Reset Grbl primary systems.
serial_reset_read_buffer(CLIENT_ALL); // Clear serial read buffer
gc_init(); // Set g-code parser to default state
serial_reset_read_buffer(CLIENT_ALL); // Clear serial read buffer
gc_init(); // Set g-code parser to default state
spindle->stop();
coolant_init();
limits_init();
probe_init();
plan_reset(); // Clear block buffer and planner variables
st_reset(); // Clear stepper subsystem variables
plan_reset(); // Clear block buffer and planner variables
st_reset(); // Clear stepper subsystem variables
// Sync cleared gcode and planner positions to current system position.
plan_sync_position();
gc_sync_position();

View File

@ -6,11 +6,7 @@
// Constructor. If _pretty is true, newlines are
// inserted into the JSON string for easy reading.
JSONencoder::JSONencoder(bool pretty) :
pretty(pretty),
level(0),
str("")
{
JSONencoder::JSONencoder(bool pretty) : pretty(pretty), level(0), str("") {
count[level] = 0;
}
@ -38,8 +34,7 @@ void JSONencoder::comma() {
}
// Private function to add a name enclosed with quotes.
void JSONencoder::quoted(const char *s)
{
void JSONencoder::quoted(const char* s) {
add('"');
str.concat(s);
add('"');
@ -65,17 +60,14 @@ void JSONencoder::dec_level() {
void JSONencoder::line() {
if (pretty) {
add('\n');
for (int i=0; i < 2*level; i++) {
for (int i = 0; i < 2 * level; i++) {
add(' ');
}
}
}
// Constructor that supplies a default falue for "pretty"
JSONencoder::JSONencoder() :
JSONencoder(false)
{ }
JSONencoder::JSONencoder() : JSONencoder(false) {}
// Begins the JSON encoding process, creating an unnamed object
void JSONencoder::begin() {
@ -90,14 +82,14 @@ String JSONencoder::end() {
}
// Starts a member element.
void JSONencoder::begin_member(const char *tag) {
void JSONencoder::begin_member(const char* tag) {
comma_line();
quoted(tag);
add(':');
}
// Starts an array with "tag":[
void JSONencoder::begin_array(const char *tag) {
void JSONencoder::begin_array(const char* tag) {
begin_member(tag);
add('[');
inc_level();
@ -122,32 +114,32 @@ void JSONencoder::begin_object() {
// Ends an object with }.
void JSONencoder::end_object() {
dec_level();
if (count[level+1] > 1) {
if (count[level + 1] > 1) {
line();
}
add('}');
}
// Creates a "tag":"value" member from a C-style string
void JSONencoder::member(const char *tag, const char *value) {
void JSONencoder::member(const char* tag, const char* value) {
begin_member(tag);
quoted(value);
}
// Creates a "tag":"value" member from an Arduino string
void JSONencoder::member(const char *tag, String value) {
void JSONencoder::member(const char* tag, String value) {
begin_member(tag);
quoted(value.c_str());
}
// Creates a "tag":"value" member from an integer
void JSONencoder::member(const char *tag, int value) {
void JSONencoder::member(const char* tag, int value) {
member(tag, String(value));
}
// Creates an Esp32_WebUI configuration item specification from
// a value passed in as a C-style string.
void JSONencoder::begin_webui(const char *p, const char *help, const char *type, const char *val) {
void JSONencoder::begin_webui(const char* p, const char* help, const char* type, const char* val) {
begin_object();
member("F", "network");
member("P", p);
@ -158,13 +150,13 @@ void JSONencoder::begin_webui(const char *p, const char *help, const char *type,
// Creates an Esp32_WebUI configuration item specification from
// an integer value.
void JSONencoder::begin_webui(const char *p, const char *help, const char *type, int val) {
void JSONencoder::begin_webui(const char* p, const char* help, const char* type, int val) {
begin_webui(p, help, type, String(val).c_str());
}
// Creates an Esp32_WebUI configuration item specification from
// a C-style string value, with additional min and max arguments.
void JSONencoder::begin_webui(const char *p, const char *help, const char *type, const char *val, int min, int max) {
void JSONencoder::begin_webui(const char* p, const char* help, const char* type, const char* val, int min, int max) {
begin_webui(p, help, type, val);
member("S", max);
member("M", min);

View File

@ -4,19 +4,20 @@
#define MAX_JSON_LEVEL 16
class JSONencoder {
private:
bool pretty;
int level;
private:
bool pretty;
int level;
String str;
int count[MAX_JSON_LEVEL];
void add(char c) { str += c; }
void comma_line();
void comma();
void quoted(const char *s);
void inc_level();
void dec_level();
void line();
public:
int count[MAX_JSON_LEVEL];
void add(char c) { str += c; }
void comma_line();
void comma();
void quoted(const char* s);
void inc_level();
void dec_level();
void line();
public:
// Constructor; set _pretty true for pretty printing
JSONencoder(bool pretty);
// If you don't set _pretty it defaults to false
@ -29,12 +30,12 @@ class JSONencoder {
String end();
// member() creates a "tag":"value" element
void member(const char *tag, const char *value);
void member(const char *tag, String value);
void member(const char *tag, int value);
void member(const char* tag, const char* value);
void member(const char* tag, String value);
void member(const char* tag, int value);
// begin_array() starts a "tag":[ array element
void begin_array(const char *tag);
void begin_array(const char* tag);
// end_array() closes the array with ]
void end_array();
@ -48,7 +49,7 @@ class JSONencoder {
// begin_member() starts the creation of a member.
// The only case where you need to use it directly
// is when you want a member whose value is an object.
void begin_member(const char *tag);
void begin_member(const char* tag);
// The begin_webui() methods are specific to Esp3D_WebUI
// WebUI sends JSON objects to the UI to generate configuration
@ -71,7 +72,7 @@ class JSONencoder {
// S => 0 .. 255
// A => 7 .. 15 (0.0.0.0 .. 255.255.255.255)
// I => 0 .. 2^31-1
void begin_webui(const char *p, const char *help, const char *type, const char *val);
void begin_webui(const char *p, const char *help, const char *type, const int val);
void begin_webui(const char *p, const char *help, const char *type, const char *val, int min, int max);
void begin_webui(const char* p, const char* help, const char* type, const char* val);
void begin_webui(const char* p, const char* help, const char* type, const int val);
void begin_webui(const char* p, const char* help, const char* type, const char* val, int min, int max);
};

View File

@ -38,21 +38,22 @@
#include "RcServoClass.cpp"
//#include "SolenoidClass.cpp"
Motor* myMotor[MAX_AXES][MAX_GANGED]; // number of axes (normal and ganged)
static TaskHandle_t readSgTaskHandle = 0; // for realtime stallguard data diaplay
Motor* myMotor[MAX_AXES][MAX_GANGED]; // number of axes (normal and ganged)
static TaskHandle_t readSgTaskHandle = 0; // for realtime stallguard data diaplay
static TaskHandle_t servoUpdateTaskHandle = 0;
uint8_t rmt_chan_num[MAX_AXES][MAX_GANGED];
uint8_t rmt_chan_num[MAX_AXES][MAX_GANGED];
rmt_item32_t rmtItem[2];
rmt_config_t rmtConfig;
bool motor_class_steps; // true if at least one motor class is handling steps
bool motor_class_steps; // true if at least one motor class is handling steps
void init_motors() {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Init Motors");
#ifdef X_TRINAMIC_DRIVER
myMotor[X_AXIS][0] = new TrinamicDriver(X_AXIS, X_STEP_PIN, X_DIRECTION_PIN, X_DISABLE_PIN, X_CS_PIN, X_TRINAMIC_DRIVER, X_RSENSE, get_next_trinamic_driver_index());
myMotor[X_AXIS][0] = new TrinamicDriver(
X_AXIS, X_STEP_PIN, X_DIRECTION_PIN, X_DISABLE_PIN, X_CS_PIN, X_TRINAMIC_DRIVER, X_RSENSE, get_next_trinamic_driver_index());
#elif defined(X_SERVO_PIN)
myMotor[X_AXIS][0] = new RcServo(X_AXIS, X_SERVO_PIN, X_SERVO_RANGE_MIN, X_SERVO_RANGE_MAX);
#elif defined(X_UNIPOLAR)
@ -64,7 +65,8 @@ void init_motors() {
#endif
#ifdef X2_TRINAMIC_DRIVER
myMotor[X_AXIS][1] = new TrinamicDriver(X2_AXIS, X2_STEP_PIN, X2_DIRECTION_PIN, X2_DISABLE_PIN, X2_CS_PIN, X2_TRINAMIC_DRIVER, X2_RSENSE, get_next_trinamic_driver_index());
myMotor[X_AXIS][1] = new TrinamicDriver(
X2_AXIS, X2_STEP_PIN, X2_DIRECTION_PIN, X2_DISABLE_PIN, X2_CS_PIN, X2_TRINAMIC_DRIVER, X2_RSENSE, get_next_trinamic_driver_index());
#elif defined(X2_SERVO_PIN)
myMotor[X_AXIS][1] = new RcServo(X2_AXIS, X2_SERVO_PIN, X2_SERVO_RANGE_MIN, X2_SERVO_RANGE_MAX);
#elif defined(X2_UNIPOLAR)
@ -75,10 +77,10 @@ void init_motors() {
myMotor[X_AXIS][1] = new Nullmotor();
#endif
// this WILL be done better with settings
#ifdef Y_TRINAMIC_DRIVER
myMotor[Y_AXIS][0] = new TrinamicDriver(Y_AXIS, Y_STEP_PIN, Y_DIRECTION_PIN, Y_DISABLE_PIN, Y_CS_PIN, Y_TRINAMIC_DRIVER, Y_RSENSE, get_next_trinamic_driver_index());
myMotor[Y_AXIS][0] = new TrinamicDriver(
Y_AXIS, Y_STEP_PIN, Y_DIRECTION_PIN, Y_DISABLE_PIN, Y_CS_PIN, Y_TRINAMIC_DRIVER, Y_RSENSE, get_next_trinamic_driver_index());
#elif defined(Y_SERVO_PIN)
myMotor[Y_AXIS][0] = new RcServo(Y_AXIS, Y_SERVO_PIN, Y_SERVO_RANGE_MIN, Y_SERVO_RANGE_MAX);
#elif defined(Y_UNIPOLAR)
@ -90,7 +92,8 @@ void init_motors() {
#endif
#ifdef Y2_TRINAMIC_DRIVER
myMotor[Y_AXIS][1] = new TrinamicDriver(Y2_AXIS, Y2_STEP_PIN, Y2_DIRECTION_PIN, Y2_DISABLE_PIN, Y2_CS_PIN, Y2_TRINAMIC_DRIVER, Y2_RSENSE, get_next_trinamic_driver_index());
myMotor[Y_AXIS][1] = new TrinamicDriver(
Y2_AXIS, Y2_STEP_PIN, Y2_DIRECTION_PIN, Y2_DISABLE_PIN, Y2_CS_PIN, Y2_TRINAMIC_DRIVER, Y2_RSENSE, get_next_trinamic_driver_index());
#elif defined(Y2_SERVO_PIN)
myMotor[Y_AXIS][1] = new RcServo(Y2_AXIS, Y2_SERVO_PIN, Y2_SERVO_RANGE_MIN, Y2_SERVO_RANGE_MAX);
#elif defined(Y2_UNIPOLAR)
@ -101,10 +104,10 @@ void init_motors() {
myMotor[Y_AXIS][1] = new Nullmotor();
#endif
// this WILL be done better with settings
#ifdef Z_TRINAMIC_DRIVER
myMotor[Z_AXIS][0] = new TrinamicDriver(Z_AXIS, Z_STEP_PIN, Z_DIRECTION_PIN, Z_DISABLE_PIN, Z_CS_PIN, Z_TRINAMIC_DRIVER, Z_RSENSE, get_next_trinamic_driver_index());
myMotor[Z_AXIS][0] = new TrinamicDriver(
Z_AXIS, Z_STEP_PIN, Z_DIRECTION_PIN, Z_DISABLE_PIN, Z_CS_PIN, Z_TRINAMIC_DRIVER, Z_RSENSE, get_next_trinamic_driver_index());
#elif defined(Z_SERVO_PIN)
myMotor[Z_AXIS][0] = new RcServo(Z_AXIS, Z_SERVO_PIN, Z_SERVO_RANGE_MIN, Z_SERVO_RANGE_MAX);
#elif defined(Z_UNIPOLAR)
@ -116,7 +119,8 @@ void init_motors() {
#endif
#ifdef Z2_TRINAMIC_DRIVER
myMotor[Z_AXIS][1] = new TrinamicDriver(Z2_AXIS, Z2_STEP_PIN, Z2_DIRECTION_PIN, Z2_DISABLE_PIN, Z2_CS_PIN, Z2_TRINAMIC_DRIVER, Z2_RSENSE, get_next_trinamic_driver_index());
myMotor[Z_AXIS][1] = new TrinamicDriver(
Z2_AXIS, Z2_STEP_PIN, Z2_DIRECTION_PIN, Z2_DISABLE_PIN, Z2_CS_PIN, Z2_TRINAMIC_DRIVER, Z2_RSENSE, get_next_trinamic_driver_index());
#elif defined(Z2_SERVO_PIN)
myMotor[Z_AXIS][1] = new RcServo(Z2_AXIS, Z2_SERVO_PIN, Z2_SERVO_RANGE_MIN, Z2_SERVO_RANGE_MAX);
#elif defined(Z2_UNIPOLAR)
@ -129,7 +133,8 @@ void init_motors() {
// this WILL be done better with settings
#ifdef A_TRINAMIC_DRIVER
myMotor[A_AXIS][0] = new TrinamicDriver(A_AXIS, A_STEP_PIN, A_DIRECTION_PIN, A_DISABLE_PIN, A_CS_PIN, A_TRINAMIC_DRIVER, A_RSENSE, get_next_trinamic_driver_index());
myMotor[A_AXIS][0] = new TrinamicDriver(
A_AXIS, A_STEP_PIN, A_DIRECTION_PIN, A_DISABLE_PIN, A_CS_PIN, A_TRINAMIC_DRIVER, A_RSENSE, get_next_trinamic_driver_index());
#elif defined(A_SERVO_PIN)
myMotor[A_AXIS][0] = new RcServo(A_AXIS, A_SERVO_PIN, A_SERVO_RANGE_MIN, A_SERVO_RANGE_MAX);
#elif defined(A_UNIPOLAR)
@ -141,7 +146,8 @@ void init_motors() {
#endif
#ifdef A2_TRINAMIC_DRIVER
myMotor[A_AXIS][1] = new TrinamicDriver(A2_AXIS, A2_STEP_PIN, A2_DIRECTION_PIN, A2_DISABLE_PIN, A2_CS_PIN, A2_TRINAMIC_DRIVER, A2_RSENSE, get_next_trinamic_driver_index());
myMotor[A_AXIS][1] = new TrinamicDriver(
A2_AXIS, A2_STEP_PIN, A2_DIRECTION_PIN, A2_DISABLE_PIN, A2_CS_PIN, A2_TRINAMIC_DRIVER, A2_RSENSE, get_next_trinamic_driver_index());
#elif defined(A2_SERVO_PIN)
myMotor[A_AXIS][1] = new RcServo(A2_AXIS, A2_SERVO_PIN, A2_SERVO_RANGE_MIN, A2_SERVO_RANGE_MAX);
#elif defined(A2_UNIPOLAR)
@ -154,7 +160,8 @@ void init_motors() {
// this WILL be done better with settings
#ifdef B_TRINAMIC_DRIVER
myMotor[B_AXIS][0] = new TrinamicDriver(B_AXIS, B_STEP_PIN, B_DIRECTION_PIN, B_DISABLE_PIN, B_CS_PIN, B_TRINAMIC_DRIVER, B_RSENSE, get_next_trinamic_driver_index());
myMotor[B_AXIS][0] = new TrinamicDriver(
B_AXIS, B_STEP_PIN, B_DIRECTION_PIN, B_DISABLE_PIN, B_CS_PIN, B_TRINAMIC_DRIVER, B_RSENSE, get_next_trinamic_driver_index());
#elif defined(B_SERVO_PIN)
myMotor[B_AXIS][0] = new RcServo(B_AXIS, B_SERVO_PIN, B_SERVO_RANGE_MIN, B_SERVO_RANGE_MAX);
#elif defined(B_UNIPOLAR)
@ -166,7 +173,8 @@ void init_motors() {
#endif
#ifdef B2_TRINAMIC_DRIVER
myMotor[B_AXIS][1] = new TrinamicDriver(B2_AXIS, B2_STEP_PIN, B2_DIRECTION_PIN, B2_DISABLE_PIN, B2_CS_PIN, B2_TRINAMIC_DRIVER, B2_RSENSE, get_next_trinamic_driver_index());
myMotor[B_AXIS][1] = new TrinamicDriver(
B2_AXIS, B2_STEP_PIN, B2_DIRECTION_PIN, B2_DISABLE_PIN, B2_CS_PIN, B2_TRINAMIC_DRIVER, B2_RSENSE, get_next_trinamic_driver_index());
#elif defined(B2_SERVO_PIN)
myMotor[B_AXIS][1] = new RcServo(B2_AXIS, B2_SERVO_PIN, B2_SERVO_RANGE_MIN, B2_SERVO_RANGE_MAX);
#elif defined(B2_UNIPOLAR)
@ -179,7 +187,8 @@ void init_motors() {
// this WILL be done better with settings
#ifdef C_TRINAMIC_DRIVER
myMotor[C_AXIS][0] = new TrinamicDriver(C_AXIS, C_STEP_PIN, C_DIRECTION_PIN, C_DISABLE_PIN, C_CS_PIN, C_TRINAMIC_DRIVER, C_RSENSE, get_next_trinamic_driver_index());
myMotor[C_AXIS][0] = new TrinamicDriver(
C_AXIS, C_STEP_PIN, C_DIRECTION_PIN, C_DISABLE_PIN, C_CS_PIN, C_TRINAMIC_DRIVER, C_RSENSE, get_next_trinamic_driver_index());
#elif defined(C_SERVO_PIN)
myMotor[C_AXIS][0] = new RcServo(C_AXIS, C_SERVO_PIN, C_SERVO_RANGE_MIN, C_SERVO_RANGE_MAX);
#elif defined(C_UNIPOLAR)
@ -191,7 +200,8 @@ void init_motors() {
#endif
#ifdef C2_TRINAMIC_DRIVER
myMotor[C_AXIS][1] = new TrinamicDriver(C2_AXIS, C2_STEP_PIN, C2_DIRECTION_PIN, C2_DISABLE_PIN, C2_CS_PIN, C2_TRINAMIC_DRIVER, C2_RSENSE, get_next_trinamic_driver_index());
myMotor[C_AXIS][1] = new TrinamicDriver(
C2_AXIS, C2_STEP_PIN, C2_DIRECTION_PIN, C2_DISABLE_PIN, C2_CS_PIN, C2_TRINAMIC_DRIVER, C2_RSENSE, get_next_trinamic_driver_index());
#elif defined(C2_SERVO_PIN)
myMotor[C_AXIS][1] = new RcServo(C2_AXIS, C2_SERVO_PIN, C2_SERVO_RANGE_MIN, C2_SERVO_RANGE_MAX);
#elif defined(C2_UNIPOLAR)
@ -202,61 +212,56 @@ void init_motors() {
myMotor[C_AXIS][1] = new Nullmotor();
#endif
#ifdef USE_STEPSTICK
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Using StepStick Mode");
#ifdef STEPPER_MS1
# ifdef STEPPER_MS1
digitalWrite(STEPPER_MS1, HIGH);
pinMode(STEPPER_MS1, OUTPUT);
#endif
#ifdef STEPPER_MS2
# endif
# ifdef STEPPER_MS2
digitalWrite(STEPPER_MS2, HIGH);
pinMode(STEPPER_MS2, OUTPUT);
#endif
#ifdef STEPPER_X_MS3
# endif
# ifdef STEPPER_X_MS3
digitalWrite(STEPPER_X_MS3, HIGH);
pinMode(STEPPER_X_MS3, OUTPUT);
#endif
#ifdef STEPPER_Y_MS3
# endif
# ifdef STEPPER_Y_MS3
digitalWrite(STEPPER_Y_MS3, HIGH);
pinMode(STEPPER_Y_MS3, OUTPUT);
#endif
#ifdef STEPPER_Z_MS3
# endif
# ifdef STEPPER_Z_MS3
digitalWrite(STEPPER_Z_MS3, HIGH);
pinMode(STEPPER_Z_MS3, OUTPUT);
#endif
#ifdef STEPPER_A_MS3
# endif
# ifdef STEPPER_A_MS3
digitalWrite(STEPPER_A_MS3, HIGH);
pinMode(STEPPER_A_MS3, OUTPUT);
#endif
#ifdef STEPPER_B_MS3
# endif
# ifdef STEPPER_B_MS3
digitalWrite(STEPPER_B_MS3, HIGH);
pinMode(STEPPER_B_MS3, OUTPUT);
#endif
#ifdef STEPPER_C_MS3
# endif
# ifdef STEPPER_C_MS3
digitalWrite(STEPPER_C_MS3, HIGH);
pinMode(STEPPER_C_MS3, OUTPUT);
#endif
#ifdef STEPPER_RESET
# endif
# ifdef STEPPER_RESET
// !RESET pin on steppers (MISO On Schematic)
digitalWrite(STEPPER_RESET, HIGH);
pinMode(STEPPER_RESET, OUTPUT);
#endif
# endif
#endif
if (STEPPERS_DISABLE_PIN != UNDEFINED_PIN) {
pinMode(STEPPERS_DISABLE_PIN, OUTPUT); // global motor enable pin
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"Global stepper disable pin:%s",
pinName(STEPPERS_DISABLE_PIN));
pinMode(STEPPERS_DISABLE_PIN, OUTPUT); // global motor enable pin
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Global stepper disable pin:%s", pinName(STEPPERS_DISABLE_PIN));
}
// certain motors need features to be turned on. Check them here
for (uint8_t axis = X_AXIS; axis < N_AXIS; axis++) {
for (uint8_t gang_index = 0; gang_index < 2; gang_index++) {
if (myMotor[axis][gang_index]->type_id == UNIPOLAR_MOTOR)
motor_class_steps = true;
@ -272,39 +277,36 @@ void init_motors() {
if (motors_have_type_id(TRINAMIC_SPI_MOTOR)) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "TMCStepper Library Ver. 0x%06x", TMCSTEPPER_VERSION);
xTaskCreatePinnedToCore(readSgTask, // task
"readSgTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
xTaskCreatePinnedToCore(readSgTask, // task
"readSgTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
&readSgTaskHandle,
0 // core
);
0 // core
);
if (stallguard_debug_mask->get() != 0)
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Stallguard debug enabled: %d", stallguard_debug_mask->get());
}
if (motors_have_type_id(RC_SERVO_MOTOR)) {
xTaskCreatePinnedToCore(servoUpdateTask, // task
"servoUpdateTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
xTaskCreatePinnedToCore(servoUpdateTask, // task
"servoUpdateTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
&servoUpdateTaskHandle,
0 // core
);
0 // core
);
}
}
void servoUpdateTask(void* pvParameters) {
TickType_t xLastWakeTime;
TickType_t xLastWakeTime;
const TickType_t xUpdate = SERVO_TIMER_INT_FREQ; // in ticks (typically ms)
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) { // don't ever return from this or the task dies
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) { // don't ever return from this or the task dies
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo update");
@ -328,7 +330,6 @@ bool motors_have_type_id(motor_class_id_t id) {
return false;
}
void motors_set_disable(bool disable) {
static bool previous_state = false;
@ -338,7 +339,7 @@ void motors_set_disable(bool disable) {
previous_state = disable;
if (step_enable_invert->get()) {
disable = !disable; // Apply pin invert.
disable = !disable; // Apply pin invert.
}
digitalWrite(STEPPERS_DISABLE_PIN, disable);
@ -369,7 +370,6 @@ void motors_set_homing_mode(uint8_t homing_mask, bool isHoming) {
}
}
void motors_set_direction_pins(uint8_t onMask) {
static uint8_t previous_val = 255; // should never be this value
if (previous_val == onMask)
@ -388,7 +388,7 @@ void motors_set_direction_pins(uint8_t onMask) {
// need to be inserted into the order of axes.
uint8_t get_next_trinamic_driver_index() {
#ifdef TRINAMIC_DAISY_CHAIN
static uint8_t index = 1; // they start at 1
static uint8_t index = 1; // they start at 1
return index++;
#else
return -1;
@ -397,7 +397,7 @@ uint8_t get_next_trinamic_driver_index() {
// some motor objects, like unipolar need step signals
void motors_step(uint8_t step_mask, uint8_t dir_mask) {
if (motor_class_steps) { // determined in init_motors if any motors need to handle steps
if (motor_class_steps) { // determined in init_motors if any motors need to handle steps
for (uint8_t gang_index = 0; gang_index < 2; gang_index++) {
for (uint8_t axis = X_AXIS; axis < N_AXIS; axis++)
myMotor[axis][gang_index]->step(step_mask, dir_mask);
@ -409,11 +409,11 @@ void motors_step(uint8_t step_mask, uint8_t dir_mask) {
This will print StallGuard data that is useful for tuning.
*/
void readSgTask(void* pvParameters) {
TickType_t xLastWakeTime;
TickType_t xLastWakeTime;
const TickType_t xreadSg = 200; // in ticks (typically ms)
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) { // don't ever return from this or the task dies
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) { // don't ever return from this or the task dies
if (motorSettingChanged) {
motors_read_settings();
motorSettingChanged = false;
@ -428,13 +428,12 @@ void readSgTask(void* pvParameters) {
myMotor[axis][gang_index]->debug_message();
}
}
} // sys.state
} // if mask
} // sys.state
} // if mask
vTaskDelayUntil(&xLastWakeTime, xreadSg);
}
}
#ifdef USE_I2S_OUT
//
// Override default function and insert a short delay
@ -445,31 +444,31 @@ void TMC2130Stepper::switchCSpin(bool state) {
}
#endif
// ============================== Class Methods ================================================
Motor :: Motor() {
Motor ::Motor() {
type_id = MOTOR;
}
void Motor :: init() {
void Motor ::init() {
_homing_mask = 0;
}
void Motor :: config_message() {}
void Motor :: debug_message() {}
void Motor :: read_settings() {}
void Motor :: set_disable(bool disable) {}
void Motor :: set_direction_pins(uint8_t onMask) {}
void Motor :: step(uint8_t step_mask, uint8_t dir_mask) {}
bool Motor :: test() {return true;}; // true = OK
void Motor :: update() {}
void Motor ::config_message() {}
void Motor ::debug_message() {}
void Motor ::read_settings() {}
void Motor ::set_disable(bool disable) {}
void Motor ::set_direction_pins(uint8_t onMask) {}
void Motor ::step(uint8_t step_mask, uint8_t dir_mask) {}
bool Motor ::test() {
return true;
}; // true = OK
void Motor ::update() {}
void Motor :: set_axis_name() {
void Motor ::set_axis_name() {
sprintf(_axis_name, "%c%s", report_get_axis_letter(axis_index), dual_axis_index ? "2" : "");
}
void Motor :: set_homing_mode(uint8_t homing_mask, bool isHoming) {
void Motor ::set_homing_mode(uint8_t homing_mask, bool isHoming) {
_homing_mask = homing_mask;
}

View File

@ -30,102 +30,92 @@
*/
#include "../grbl.h"
#include <TMCStepper.h> // https://github.com/teemuatlut/TMCStepper
#include <TMCStepper.h> // https://github.com/teemuatlut/TMCStepper
#include "TrinamicDriverClass.h"
#include "RcServoClass.h"
//#include "SolenoidClass.h"
extern uint8_t rmt_chan_num[MAX_AXES][2];
extern uint8_t rmt_chan_num[MAX_AXES][2];
extern rmt_item32_t rmtItem[2];
extern rmt_config_t rmtConfig;
typedef enum {
MOTOR,
NULL_MOTOR,
STANDARD_MOTOR,
TRINAMIC_SPI_MOTOR,
UNIPOLAR_MOTOR,
RC_SERVO_MOTOR,
SOLENOID
} motor_class_id_t;
typedef enum { MOTOR, NULL_MOTOR, STANDARD_MOTOR, TRINAMIC_SPI_MOTOR, UNIPOLAR_MOTOR, RC_SERVO_MOTOR, SOLENOID } motor_class_id_t;
// These are used for setup and to talk to the motors as a group.
void init_motors();
void init_motors();
uint8_t get_next_trinamic_driver_index();
bool motors_have_type_id(motor_class_id_t id);
void readSgTask(void* pvParameters);
void motors_read_settings();
void motors_set_homing_mode(uint8_t homing_mask, bool isHoming);
void motors_set_disable(bool disable);
void motors_set_direction_pins(uint8_t onMask);
void motors_step(uint8_t step_mask, uint8_t dir_mask);
void servoUpdateTask(void* pvParameters);
bool motors_have_type_id(motor_class_id_t id);
void readSgTask(void* pvParameters);
void motors_read_settings();
void motors_set_homing_mode(uint8_t homing_mask, bool isHoming);
void motors_set_disable(bool disable);
void motors_set_direction_pins(uint8_t onMask);
void motors_step(uint8_t step_mask, uint8_t dir_mask);
void servoUpdateTask(void* pvParameters);
extern bool motor_class_steps; // true if at least one motor class is handling steps
extern bool motor_class_steps; // true if at least one motor class is handling steps
// ==================== Motor Classes ====================
class Motor {
public:
public:
Motor();
virtual void init(); // not in constructor because this also gets called when $$ settings change
virtual void init(); // not in constructor because this also gets called when $$ settings change
virtual void config_message();
virtual void debug_message();
virtual void read_settings();
virtual void set_homing_mode(uint8_t homing_mask, bool isHoming);
virtual void set_disable(bool disable);
virtual void set_direction_pins(uint8_t onMask);
virtual void step(uint8_t step_mask, uint8_t dir_mask); // only used on Unipolar right now
virtual void step(uint8_t step_mask, uint8_t dir_mask); // only used on Unipolar right now
virtual bool test();
virtual void set_axis_name();
virtual void update();
motor_class_id_t type_id;
uint8_t is_active = false;
uint8_t is_active = false;
protected:
uint8_t axis_index; // X_AXIS, etc
uint8_t dual_axis_index; // 0 = primary 1=ganged
protected:
uint8_t axis_index; // X_AXIS, etc
uint8_t dual_axis_index; // 0 = primary 1=ganged
bool _showError;
bool _use_mpos = true;
bool _showError;
bool _use_mpos = true;
uint8_t _homing_mask;
char _axis_name[10];// this the name to use when reporting like "X" or "X2"
char _axis_name[10]; // this the name to use when reporting like "X" or "X2"
};
class Nullmotor : public Motor {
};
class Nullmotor : public Motor {};
class StandardStepper : public Motor {
public:
public:
StandardStepper();
StandardStepper(uint8_t axis_index, uint8_t step_pin, uint8_t dir_pin, uint8_t disable_pin);
virtual void config_message();
virtual void init();
virtual void set_direction_pins(uint8_t onMask);
void init_step_dir_pins();
void init_step_dir_pins();
virtual void set_disable(bool disable);
uint8_t step_pin;
uint8_t step_pin;
protected:
bool _invert_step_pin;
protected:
bool _invert_step_pin;
uint8_t dir_pin;
uint8_t disable_pin;
};
class TrinamicDriver : public StandardStepper {
public:
TrinamicDriver(uint8_t axis_index,
uint8_t step_pin,
uint8_t dir_pin,
uint8_t disable_pin,
uint8_t cs_pin,
uint16_t driver_part_number,
float r_sense,
int8_t spi_index);
public:
TrinamicDriver(uint8_t axis_index,
uint8_t step_pin,
uint8_t dir_pin,
uint8_t disable_pin,
uint8_t cs_pin,
uint16_t driver_part_number,
float r_sense,
int8_t spi_index);
void config_message();
void init();
@ -138,63 +128,63 @@ class TrinamicDriver : public StandardStepper {
void set_disable(bool disable);
bool test();
private:
private:
uint32_t calc_tstep(float speed, float percent);
TMC2130Stepper* tmcstepper; // all other driver types are subclasses of this one
uint8_t _homing_mode;
uint8_t cs_pin = UNDEFINED_PIN; // The chip select pin (can be the same for daisy chain)
uint16_t _driver_part_number; // example: use 2130 for TMC2130
float _r_sense;
int8_t spi_index;
protected:
uint8_t _homing_mode;
uint8_t cs_pin = UNDEFINED_PIN; // The chip select pin (can be the same for daisy chain)
uint16_t _driver_part_number; // example: use 2130 for TMC2130
float _r_sense;
int8_t spi_index;
protected:
uint8_t _mode;
uint8_t _lastMode = 255;
};
class UnipolarMotor : public Motor {
public:
public:
UnipolarMotor();
UnipolarMotor(uint8_t axis_index, uint8_t pin_phase0, uint8_t pin_phase1, uint8_t pin_phase2, uint8_t pin_phase3);
void init();
void config_message();
void set_disable(bool disable);
void step(uint8_t step_mask, uint8_t dir_mask); // only used on Unipolar right now
void step(uint8_t step_mask, uint8_t dir_mask); // only used on Unipolar right now
private:
private:
uint8_t _pin_phase0;
uint8_t _pin_phase1;
uint8_t _pin_phase2;
uint8_t _pin_phase3;
uint8_t _current_phase;
bool _half_step;
bool _enabled;
bool _half_step;
bool _enabled;
};
class RcServo : public Motor {
public:
public:
RcServo();
RcServo(uint8_t axis_index, uint8_t pwm_pin, float min, float max);
virtual void config_message();
virtual void init();
void _write_pwm(uint32_t duty);
void _write_pwm(uint32_t duty);
virtual void set_disable(bool disable);
virtual void update();
void read_settings();
void set_homing_mode(bool is_homing, bool isHoming);
void read_settings();
void set_homing_mode(bool is_homing, bool isHoming);
protected:
protected:
void set_location();
void _get_calibration();
uint8_t _pwm_pin;
uint8_t _channel_num;
uint8_t _pwm_pin;
uint8_t _channel_num;
uint32_t _current_pwm_duty;
bool _disabled;
bool _disabled;
float _position_min;
float _position_max; // position in millimeters
float _position_max; // position in millimeters
float _homing_position;
float _pwm_pulse_min;
@ -202,7 +192,7 @@ class RcServo : public Motor {
};
class Solenoid : public RcServo {
public:
public:
Solenoid();
Solenoid(uint8_t axis_index, gpio_num_t pwm_pin, float transition_poiont);
void config_message();
@ -210,6 +200,6 @@ class Solenoid : public RcServo {
void update();
void init();
void set_disable(bool disable);
float _transition_poiont;
};

View File

@ -45,32 +45,30 @@
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
RcServo :: RcServo() {
RcServo ::RcServo() {}
}
RcServo :: RcServo(uint8_t axis_index, uint8_t pwm_pin, float min, float max) {
type_id = RC_SERVO_MOTOR;
this->axis_index = axis_index % MAX_AXES;
this->dual_axis_index = axis_index < MAX_AXES ? 0 : 1; // 0 = primary 1 = ganged
this->_pwm_pin = pwm_pin;
_position_min = min;
_position_max = max;
RcServo ::RcServo(uint8_t axis_index, uint8_t pwm_pin, float min, float max) {
type_id = RC_SERVO_MOTOR;
this->axis_index = axis_index % MAX_AXES;
this->dual_axis_index = axis_index < MAX_AXES ? 0 : 1; // 0 = primary 1 = ganged
this->_pwm_pin = pwm_pin;
_position_min = min;
_position_max = max;
init();
}
void RcServo :: init() {
void RcServo ::init() {
read_settings();
_channel_num = sys_get_next_PWM_chan_num();
ledcSetup(_channel_num, SERVO_PULSE_FREQ, SERVO_PULSE_RES_BITS);
ledcAttachPin(_pwm_pin, _channel_num);
_current_pwm_duty = 0;
is_active = true; // as opposed to NullMotors, this is a real motor
is_active = true; // as opposed to NullMotors, this is a real motor
set_axis_name();
config_message();
}
void RcServo :: config_message() {
void RcServo ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"%s Axis RC Servo motor Output:%d Min:%5.3fmm Max:%5.3fmm",
@ -106,13 +104,12 @@ void RcServo::set_homing_mode(bool is_homing, bool isHoming) {
return;
if (bit_istrue(homing_dir_mask->get(), bit(axis_index)))
home_pos = _position_min;
home_pos = _position_min;
else
home_pos = _position_max;
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo set home %d %3.2f", is_homing, home_pos);
sys_position[axis_index] = home_pos * axis_settings[axis_index]->steps_per_mm->get(); // convert to steps
sys_position[axis_index] = home_pos * axis_settings[axis_index]->steps_per_mm->get(); // convert to steps
}
void RcServo::update() {
@ -121,7 +118,7 @@ void RcServo::update() {
void RcServo::set_location() {
uint32_t servo_pulse_len;
float servo_pos, mpos, offset;
float servo_pos, mpos, offset;
// skip location if we are in alarm mode
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "locate");
@ -132,15 +129,14 @@ void RcServo::set_location() {
return;
}
mpos = system_convert_axis_steps_to_mpos(sys_position, axis_index); // get the axis machine position in mm
offset = gc_state.coord_system[axis_index] + gc_state.coord_offset[axis_index]; // get the current axis work offset
servo_pos = mpos - offset; // determine the current work position
mpos = system_convert_axis_steps_to_mpos(sys_position, axis_index); // get the axis machine position in mm
offset = gc_state.coord_system[axis_index] + gc_state.coord_offset[axis_index]; // get the current axis work offset
servo_pos = mpos - offset; // determine the current work position
// determine the pulse length
servo_pulse_len = (uint32_t)mapConstrain(servo_pos, _position_min, _position_max, _pwm_pulse_min, _pwm_pulse_max);
_write_pwm(servo_pulse_len);
}
void RcServo::read_settings() {
@ -164,7 +160,11 @@ void RcServo::_get_calibration() {
// make sure the max is in range
// Note: Max travel is set positive via $$, but stored as a negative number
if ((axis_settings[axis_index]->max_travel->get() < SERVO_CAL_MIN) || (axis_settings[axis_index]->max_travel->get() > SERVO_CAL_MAX)) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo calibration ($13%d) value error. %3.2f Reset to 100", axis_index, axis_settings[axis_index]->max_travel->get());
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"Servo calibration ($13%d) value error. %3.2f Reset to 100",
axis_index,
axis_settings[axis_index]->max_travel->get());
char reset_val[] = "100";
axis_settings[axis_index]->max_travel->setStringValue(reset_val);
}
@ -172,12 +172,11 @@ void RcServo::_get_calibration() {
_pwm_pulse_min = SERVO_MIN_PULSE;
_pwm_pulse_max = SERVO_MAX_PULSE;
if (bit_istrue(dir_invert_mask->get(), bit(axis_index))) { // normal direction
if (bit_istrue(dir_invert_mask->get(), bit(axis_index))) { // normal direction
_cal_min = 2.0 - (axis_settings[axis_index]->steps_per_mm->get() / 100.0);
_cal_max = 2.0 - (axis_settings[axis_index]->max_travel->get() / 100.0);
swap(_pwm_pulse_min, _pwm_pulse_max);
} else { // inverted direction
} else { // inverted direction
_cal_min = (axis_settings[axis_index]->steps_per_mm->get() / 100.0);
_cal_max = (axis_settings[axis_index]->max_travel->get() / 100.0);
}
@ -186,5 +185,4 @@ void RcServo::_get_calibration() {
_pwm_pulse_max *= _cal_max;
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo calibration min:%1.2f max %1.2f", _pwm_pulse_min, _pwm_pulse_max);
}

View File

@ -21,25 +21,25 @@
// this is the pulse range of a the servo. Typical servos are 0.001 to 0.002 seconds
// some servos have a wider range. You can adjust this here or in the calibration feature
#define SERVO_MIN_PULSE_SEC 0.001 // min pulse in seconds
#define SERVO_MAX_PULSE_SEC 0.002 // max pulse in seconds
#define SERVO_MIN_PULSE_SEC 0.001 // min pulse in seconds
#define SERVO_MAX_PULSE_SEC 0.002 // max pulse in seconds
#define SERVO_POSITION_MIN_DEFAULT 0.0 // mm
#define SERVO_POSITION_MAX_DEFAULT 20.0 // mm
#define SERVO_POSITION_MIN_DEFAULT 0.0 // mm
#define SERVO_POSITION_MAX_DEFAULT 20.0 // mm
#define SERVO_PULSE_FREQ 50 // 50Hz ...This is a standard analog servo value. Digital ones can repeat faster
#define SERVO_PULSE_FREQ 50 // 50Hz ...This is a standard analog servo value. Digital ones can repeat faster
#define SERVO_PULSE_RES_BITS 16 // bits of resolution of PWM (16 is max)
#define SERVO_PULSE_RES_COUNT 65535 // see above TODO...do the math here 2^SERVO_PULSE_RES_BITS
#define SERVO_PULSE_RES_BITS 16 // bits of resolution of PWM (16 is max)
#define SERVO_PULSE_RES_COUNT 65535 // see above TODO...do the math here 2^SERVO_PULSE_RES_BITS
#define SERVO_TIME_PER_BIT ((1.0 / (float)SERVO_PULSE_FREQ) / ((float)SERVO_PULSE_RES_COUNT) ) // seconds
#define SERVO_TIME_PER_BIT ((1.0 / (float)SERVO_PULSE_FREQ) / ((float)SERVO_PULSE_RES_COUNT)) // seconds
#define SERVO_MIN_PULSE (uint16_t)(SERVO_MIN_PULSE_SEC / SERVO_TIME_PER_BIT) // in timer counts
#define SERVO_MAX_PULSE (uint16_t)(SERVO_MAX_PULSE_SEC / SERVO_TIME_PER_BIT) // in timer counts
#define SERVO_MIN_PULSE (uint16_t)(SERVO_MIN_PULSE_SEC / SERVO_TIME_PER_BIT) // in timer counts
#define SERVO_MAX_PULSE (uint16_t)(SERVO_MAX_PULSE_SEC / SERVO_TIME_PER_BIT) // in timer counts
#define SERVO_PULSE_RANGE (SERVO_MAX_PULSE-SERVO_MIN_PULSE)
#define SERVO_PULSE_RANGE (SERVO_MAX_PULSE - SERVO_MIN_PULSE)
#define SERVO_CAL_MIN 20.0 // Percent: the minimum allowable calibration value
#define SERVO_CAL_MAX 180.0 // Percent: the maximum allowable calibration value
#define SERVO_CAL_MIN 20.0 // Percent: the minimum allowable calibration value
#define SERVO_CAL_MAX 180.0 // Percent: the maximum allowable calibration value
#define SERVO_TIMER_INT_FREQ 50.0 // Hz This is the task frequency
#define SERVO_TIMER_INT_FREQ 50.0 // Hz This is the task frequency

View File

@ -21,50 +21,47 @@
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
StandardStepper :: StandardStepper() {
StandardStepper ::StandardStepper() {}
}
StandardStepper :: StandardStepper(uint8_t axis_index, uint8_t step_pin, uint8_t dir_pin, uint8_t disable_pin) {
type_id = STANDARD_MOTOR;
this->axis_index = axis_index % MAX_AXES;
this->dual_axis_index = axis_index < MAX_AXES ? 0 : 1; // 0 = primary 1 = ganged
this->step_pin = step_pin;
this->dir_pin = dir_pin;
this->disable_pin = disable_pin;
StandardStepper ::StandardStepper(uint8_t axis_index, uint8_t step_pin, uint8_t dir_pin, uint8_t disable_pin) {
type_id = STANDARD_MOTOR;
this->axis_index = axis_index % MAX_AXES;
this->dual_axis_index = axis_index < MAX_AXES ? 0 : 1; // 0 = primary 1 = ganged
this->step_pin = step_pin;
this->dir_pin = dir_pin;
this->disable_pin = disable_pin;
init();
}
void StandardStepper :: init() {
void StandardStepper ::init() {
_homing_mask = 0;
is_active = true; // as opposed to NullMotors, this is a real motor
is_active = true; // as opposed to NullMotors, this is a real motor
set_axis_name();
init_step_dir_pins();
config_message();
}
void StandardStepper :: init_step_dir_pins() {
void StandardStepper ::init_step_dir_pins() {
// TODO Step pin, but RMT complicates things
_invert_step_pin = bit_istrue(step_invert_mask->get(), bit(axis_index));
pinMode(dir_pin, OUTPUT);
#ifdef USE_RMT_STEPS
rmtConfig.rmt_mode = RMT_MODE_TX;
rmtConfig.clk_div = 20;
rmtConfig.mem_block_num = 2;
rmtConfig.tx_config.loop_en = false;
rmtConfig.tx_config.carrier_en = false;
rmtConfig.tx_config.carrier_freq_hz = 0;
rmtConfig.rmt_mode = RMT_MODE_TX;
rmtConfig.clk_div = 20;
rmtConfig.mem_block_num = 2;
rmtConfig.tx_config.loop_en = false;
rmtConfig.tx_config.carrier_en = false;
rmtConfig.tx_config.carrier_freq_hz = 0;
rmtConfig.tx_config.carrier_duty_percent = 50;
rmtConfig.tx_config.carrier_level = RMT_CARRIER_LEVEL_LOW;
rmtConfig.tx_config.idle_output_en = true;
rmtConfig.tx_config.carrier_level = RMT_CARRIER_LEVEL_LOW;
rmtConfig.tx_config.idle_output_en = true;
#ifdef STEP_PULSE_DELAY
# ifdef STEP_PULSE_DELAY
rmtItem[0].duration0 = STEP_PULSE_DELAY * 4;
#else
# else
rmtItem[0].duration0 = 1;
#endif
# endif
rmtItem[0].duration1 = 4 * pulse_microseconds->get();
rmtItem[1].duration0 = 0;
@ -72,23 +69,22 @@ void StandardStepper :: init_step_dir_pins() {
rmt_chan_num[axis_index][dual_axis_index] = sys_get_next_RMT_chan_num();
rmt_set_source_clk((rmt_channel_t)rmt_chan_num[axis_index][dual_axis_index], RMT_BASECLK_APB);
rmtConfig.channel = (rmt_channel_t)rmt_chan_num[axis_index][dual_axis_index];
rmtConfig.channel = (rmt_channel_t)rmt_chan_num[axis_index][dual_axis_index];
rmtConfig.tx_config.idle_level = _invert_step_pin ? RMT_IDLE_LEVEL_HIGH : RMT_IDLE_LEVEL_LOW;
rmtConfig.gpio_num = gpio_num_t(step_pin); // c is a wacky lang
rmtItem[0].level0 = rmtConfig.tx_config.idle_level;
rmtItem[0].level1 = !rmtConfig.tx_config.idle_level;
rmtConfig.gpio_num = gpio_num_t(step_pin); // c is a wacky lang
rmtItem[0].level0 = rmtConfig.tx_config.idle_level;
rmtItem[0].level1 = !rmtConfig.tx_config.idle_level;
rmt_config(&rmtConfig);
rmt_fill_tx_items(rmtConfig.channel, &rmtItem[0], rmtConfig.mem_block_num, 0);
#else
pinMode(step_pin, OUTPUT);
#endif // USE_RMT_STEPS
#endif // USE_RMT_STEPS
pinMode(disable_pin, OUTPUT);
}
void StandardStepper :: config_message() {
void StandardStepper ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"%s Axis standard stepper motor Step:%s Dir:%s Disable:%s",
@ -98,10 +94,10 @@ void StandardStepper :: config_message() {
pinName(disable_pin).c_str());
}
void StandardStepper :: set_direction_pins(uint8_t onMask) {
void StandardStepper ::set_direction_pins(uint8_t onMask) {
digitalWrite(dir_pin, (onMask & bit(axis_index)));
}
void StandardStepper :: set_disable(bool disable) {
void StandardStepper ::set_disable(bool disable) {
digitalWrite(disable_pin, disable);
}

View File

@ -20,27 +20,27 @@
#include <TMCStepper.h>
#include "TrinamicDriverClass.h"
TrinamicDriver :: TrinamicDriver(uint8_t axis_index,
uint8_t step_pin,
uint8_t dir_pin,
uint8_t disable_pin,
uint8_t cs_pin,
uint16_t driver_part_number,
float r_sense,
int8_t spi_index) {
type_id = TRINAMIC_SPI_MOTOR;
this->axis_index = axis_index % MAX_AXES;
this->dual_axis_index = axis_index < 6 ? 0 : 1; // 0 = primary 1 = ganged
_driver_part_number = driver_part_number;
_r_sense = r_sense;
this->step_pin = step_pin;
this->dir_pin = dir_pin;
this->disable_pin = disable_pin;
this->cs_pin = cs_pin;
this->spi_index = spi_index;
TrinamicDriver ::TrinamicDriver(uint8_t axis_index,
uint8_t step_pin,
uint8_t dir_pin,
uint8_t disable_pin,
uint8_t cs_pin,
uint16_t driver_part_number,
float r_sense,
int8_t spi_index) {
type_id = TRINAMIC_SPI_MOTOR;
this->axis_index = axis_index % MAX_AXES;
this->dual_axis_index = axis_index < 6 ? 0 : 1; // 0 = primary 1 = ganged
_driver_part_number = driver_part_number;
_r_sense = r_sense;
this->step_pin = step_pin;
this->dir_pin = dir_pin;
this->disable_pin = disable_pin;
this->cs_pin = cs_pin;
this->spi_index = spi_index;
_homing_mode = TRINAMIC_HOMING_MODE;
_homing_mask = 0; // no axes homing
_homing_mode = TRINAMIC_HOMING_MODE;
_homing_mask = 0; // no axes homing
if (_driver_part_number == 2130)
tmcstepper = new TMC2130Stepper(cs_pin, _r_sense, spi_index);
@ -53,7 +53,7 @@ TrinamicDriver :: TrinamicDriver(uint8_t axis_index,
set_axis_name();
init_step_dir_pins(); // from StandardStepper
init_step_dir_pins(); // from StandardStepper
digitalWrite(cs_pin, HIGH);
pinMode(cs_pin, OUTPUT);
@ -67,23 +67,22 @@ TrinamicDriver :: TrinamicDriver(uint8_t axis_index,
// init() must be called later, after all TMC drivers have CS pins setup.
}
void TrinamicDriver :: init() {
void TrinamicDriver ::init() {
SPI.begin(); // this will get called for each motor, but does not seem to hurt anything
tmcstepper->begin();
test(); // Try communicating with motor. Prints an error if there is a problem.
read_settings(); // pull info from settings
test(); // Try communicating with motor. Prints an error if there is a problem.
read_settings(); // pull info from settings
set_mode(false);
_homing_mask = 0;
is_active = true; // as opposed to NullMotors, this is a real motor
is_active = true; // as opposed to NullMotors, this is a real motor
}
/*
This is the startup message showing the basic definition
*/
void TrinamicDriver :: config_message() {
void TrinamicDriver ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"%s Axis Trinamic TMC%d Step:%s Dir:%s CS:%s Disable:%s Index:%d",
@ -96,30 +95,25 @@ void TrinamicDriver :: config_message() {
spi_index);
}
bool TrinamicDriver :: test() {
bool TrinamicDriver ::test() {
switch (tmcstepper->test_connection()) {
case 1:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test failed. Check connection", _axis_name);
return false;
case 2:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test failed. Check motor power", _axis_name);
return false;
default:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test passed", _axis_name);
return true;
case 1: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test failed. Check connection", _axis_name); return false;
case 2:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test failed. Check motor power", _axis_name);
return false;
default: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test passed", _axis_name); return true;
}
}
/*
Read setting and send them to the driver. Called at init() and whenever related settings change
both are stored as float Amps, but TMCStepper library expects...
uint16_t run (mA)
float hold (as a percentage of run)
*/
void TrinamicDriver :: read_settings() {
void TrinamicDriver ::read_settings() {
uint16_t run_i_ma = (uint16_t)(axis_settings[axis_index]->run_current->get() * 1000.0);
float hold_i_percent;
float hold_i_percent;
if (axis_settings[axis_index]->run_current->get() == 0)
hold_i_percent = 0;
@ -132,10 +126,9 @@ void TrinamicDriver :: read_settings() {
tmcstepper->microsteps(axis_settings[axis_index]->microsteps->get());
tmcstepper->rms_current(run_i_ma, hold_i_percent);
}
void TrinamicDriver :: set_homing_mode(uint8_t homing_mask, bool isHoming) {
void TrinamicDriver ::set_homing_mode(uint8_t homing_mask, bool isHoming) {
_homing_mask = homing_mask;
set_mode(isHoming);
}
@ -145,8 +138,7 @@ void TrinamicDriver :: set_homing_mode(uint8_t homing_mask, bool isHoming) {
Many people will want quiet and stallgaurd homing. Stallguard only run in
Coolstep mode, so it will need to switch to Coolstep when homing
*/
void TrinamicDriver :: set_mode(bool isHoming) {
void TrinamicDriver ::set_mode(bool isHoming) {
if (isHoming)
_mode = TRINAMIC_HOMING_MODE;
else
@ -157,45 +149,42 @@ void TrinamicDriver :: set_mode(bool isHoming) {
_lastMode = _mode;
switch (_mode) {
case TRINAMIC_MODE_STEALTHCHOP:
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "TRINAMIC_MODE_STEALTHCHOP");
tmcstepper->en_pwm_mode(true);
tmcstepper->pwm_autoscale(true);
tmcstepper->diag1_stall(false);
break;
case TRINAMIC_MODE_COOLSTEP:
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "TRINAMIC_MODE_COOLSTEP");
tmcstepper->en_pwm_mode(false);
tmcstepper->pwm_autoscale(false);
tmcstepper->TCOOLTHRS(NORMAL_TCOOLTHRS); // when to turn on coolstep
tmcstepper->THIGH(NORMAL_THIGH);
break;
case TRINAMIC_MODE_STALLGUARD:
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "TRINAMIC_MODE_STALLGUARD");
tmcstepper->en_pwm_mode(false);
tmcstepper->pwm_autoscale(false);
tmcstepper->TCOOLTHRS(calc_tstep(homing_feed_rate->get(), 150.0));
tmcstepper->THIGH(calc_tstep(homing_feed_rate->get(), 60.0));
tmcstepper->sfilt(1);
tmcstepper->diag1_stall(true); // stallguard i/o is on diag1
tmcstepper->sgt(axis_settings[axis_index]->stallguard->get());
break;
default:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "TRINAMIC_MODE_UNDEFINED");
case TRINAMIC_MODE_STEALTHCHOP:
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "TRINAMIC_MODE_STEALTHCHOP");
tmcstepper->en_pwm_mode(true);
tmcstepper->pwm_autoscale(true);
tmcstepper->diag1_stall(false);
break;
case TRINAMIC_MODE_COOLSTEP:
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "TRINAMIC_MODE_COOLSTEP");
tmcstepper->en_pwm_mode(false);
tmcstepper->pwm_autoscale(false);
tmcstepper->TCOOLTHRS(NORMAL_TCOOLTHRS); // when to turn on coolstep
tmcstepper->THIGH(NORMAL_THIGH);
break;
case TRINAMIC_MODE_STALLGUARD:
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "TRINAMIC_MODE_STALLGUARD");
tmcstepper->en_pwm_mode(false);
tmcstepper->pwm_autoscale(false);
tmcstepper->TCOOLTHRS(calc_tstep(homing_feed_rate->get(), 150.0));
tmcstepper->THIGH(calc_tstep(homing_feed_rate->get(), 60.0));
tmcstepper->sfilt(1);
tmcstepper->diag1_stall(true); // stallguard i/o is on diag1
tmcstepper->sgt(axis_settings[axis_index]->stallguard->get());
break;
default: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "TRINAMIC_MODE_UNDEFINED");
}
}
/*
This is the stallguard tuning info. It is call debug, so it could be generic across all classes.
*/
void TrinamicDriver :: debug_message() {
void TrinamicDriver ::debug_message() {
uint32_t tstep = tmcstepper->TSTEP();
if (tstep == 0xFFFFF || tstep < 1) // if axis is not moving return
if (tstep == 0xFFFFF || tstep < 1) // if axis is not moving return
return;
float feedrate = st_get_realtime_rate(); //* settings.microsteps[axis_index] / 60.0 ; // convert mm/min to Hz
float feedrate = st_get_realtime_rate(); //* settings.microsteps[axis_index] / 60.0 ; // convert mm/min to Hz
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
@ -211,17 +200,16 @@ void TrinamicDriver :: debug_message() {
// tstep = TRINAMIC_FCLK / (time between 1/256 steps)
// This is used to set the stallguard window from the homing speed.
// The percent is the offset on the window
uint32_t TrinamicDriver :: calc_tstep(float speed, float percent) {
uint32_t TrinamicDriver ::calc_tstep(float speed, float percent) {
float tstep = speed / 60.0 * axis_settings[axis_index]->steps_per_mm->get() * (float)(256 / axis_settings[axis_index]->microsteps->get());
tstep = TRINAMIC_FCLK / tstep * percent / 100.0;
tstep = TRINAMIC_FCLK / tstep * percent / 100.0;
return (uint32_t)tstep;
}
// this can use the enable feature over SPI. The dedicated pin must be in the enable mode,
// but that can be hardwired that way.
void TrinamicDriver :: set_disable(bool disable) {
void TrinamicDriver ::set_disable(bool disable) {
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Axis disable %d", _axis_name, disable);
digitalWrite(disable_pin, disable);
@ -239,4 +227,3 @@ void TrinamicDriver :: set_disable(bool disable) {
// the pin based enable could be added here.
// This would be for individual motors, not the single pin for all motors.
}

View File

@ -19,43 +19,40 @@
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#define TRINAMIC_MODE_STEALTHCHOP 0 // very quiet
#define TRINAMIC_MODE_COOLSTEP 1 // everything runs cooler so higher current possible
#define TRINAMIC_MODE_STALLGUARD 2 // coolstep plus generates stall indication
#define TRINAMIC_MODE_STEALTHCHOP 0 // very quiet
#define TRINAMIC_MODE_COOLSTEP 1 // everything runs cooler so higher current possible
#define TRINAMIC_MODE_STALLGUARD 2 // coolstep plus generates stall indication
#define NORMAL_TCOOLTHRS 0xFFFFF // 20 bit is max
#define NORMAL_THIGH 0
#define NORMAL_TCOOLTHRS 0xFFFFF // 20 bit is max
#define NORMAL_THIGH 0
#define TMC2130_RSENSE_DEFAULT 0.11f
#define TMC5160_RSENSE_DEFAULT 0.075f
#define TMC2130_RSENSE_DEFAULT 0.11f
#define TMC5160_RSENSE_DEFAULT 0.075f
#define TRINAMIC_SPI_FREQ 100000
#define TRINAMIC_FCLK 12700000.0 // Internal clock Approx (Hz) used to calculate TSTEP from homing rate
#define TRINAMIC_FCLK 12700000.0 // Internal clock Approx (Hz) used to calculate TSTEP from homing rate
// ==== defaults OK to define them in your machine definition ====
#ifndef TRINAMIC_RUN_MODE
#define TRINAMIC_RUN_MODE TRINAMIC_MODE_COOLSTEP
# define TRINAMIC_RUN_MODE TRINAMIC_MODE_COOLSTEP
#endif
#ifndef TRINAMIC_HOMING_MODE
#define TRINAMIC_HOMING_MODE TRINAMIC_RUN_MODE
# define TRINAMIC_HOMING_MODE TRINAMIC_RUN_MODE
#endif
#ifndef TRINAMIC_TOFF_DISABLE
#define TRINAMIC_TOFF_DISABLE 0
# define TRINAMIC_TOFF_DISABLE 0
#endif
#ifndef TRINAMIC_TOFF_STEALTHCHOP
#define TRINAMIC_TOFF_STEALTHCHOP 5
# define TRINAMIC_TOFF_STEALTHCHOP 5
#endif
#ifndef TRINAMIC_TOFF_COOLSTEP
#define TRINAMIC_TOFF_COOLSTEP 3
# define TRINAMIC_TOFF_COOLSTEP 3
#endif
#include "MotorClass.h"
#include <TMCStepper.h> // https://github.com/teemuatlut/TMCStepper
#include <TMCStepper.h> // https://github.com/teemuatlut/TMCStepper

View File

@ -1,25 +1,22 @@
UnipolarMotor :: UnipolarMotor() {
UnipolarMotor ::UnipolarMotor() {}
}
UnipolarMotor ::UnipolarMotor(uint8_t axis_index, uint8_t pin_phase0, uint8_t pin_phase1, uint8_t pin_phase2, uint8_t pin_phase3) {
type_id = UNIPOLAR_MOTOR;
this->axis_index = axis_index % MAX_AXES;
this->dual_axis_index = axis_index < MAX_AXES ? 0 : 1; // 0 = primary 1 = ganged
_pin_phase0 = pin_phase0;
_pin_phase1 = pin_phase1;
_pin_phase2 = pin_phase2;
_pin_phase3 = pin_phase3;
UnipolarMotor :: UnipolarMotor(uint8_t axis_index, uint8_t pin_phase0, uint8_t pin_phase1, uint8_t pin_phase2, uint8_t pin_phase3) {
type_id = UNIPOLAR_MOTOR;
this->axis_index = axis_index % MAX_AXES;
this->dual_axis_index = axis_index < MAX_AXES ? 0 : 1; // 0 = primary 1 = ganged
_pin_phase0 = pin_phase0;
_pin_phase1 = pin_phase1;
_pin_phase2 = pin_phase2;
_pin_phase3 = pin_phase3;
_half_step = true; // TODO read from settings ... microstep > 1 = half step
_half_step = true; // TODO read from settings ... microstep > 1 = half step
set_axis_name();
init();
config_message();
}
void UnipolarMotor :: init() {
void UnipolarMotor ::init() {
pinMode(_pin_phase0, OUTPUT);
pinMode(_pin_phase1, OUTPUT);
pinMode(_pin_phase2, OUTPUT);
@ -27,7 +24,7 @@ void UnipolarMotor :: init() {
_current_phase = 0;
}
void UnipolarMotor :: config_message() {
void UnipolarMotor ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"%s Axis unipolar stepper motor Ph0:%s Ph1:%s Ph2:%s Ph3:%s",
@ -38,7 +35,7 @@ void UnipolarMotor :: config_message() {
pinName(_pin_phase3).c_str());
}
void UnipolarMotor :: set_disable(bool disable) {
void UnipolarMotor ::set_disable(bool disable) {
if (disable) {
digitalWrite(_pin_phase0, 0);
digitalWrite(_pin_phase1, 0);
@ -49,26 +46,26 @@ void UnipolarMotor :: set_disable(bool disable) {
}
void UnipolarMotor::step(uint8_t step_mask, uint8_t dir_mask) {
uint8_t _phase[8] = {0, 0, 0, 0, 0, 0, 0, 0}; // temporary phase values...all start as off
uint8_t _phase[8] = { 0, 0, 0, 0, 0, 0, 0, 0 }; // temporary phase values...all start as off
uint8_t phase_max;
if (!(step_mask & bit(axis_index)))
return; // a step is not required on this interrupt
return; // a step is not required on this interrupt
if (!_enabled)
return; // don't do anything, phase is not changed or lost
return; // don't do anything, phase is not changed or lost
if (_half_step)
phase_max = 7;
else
phase_max = 3;
if (dir_mask & bit(axis_index)) { // count up
if (dir_mask & bit(axis_index)) { // count up
if (_current_phase == phase_max)
_current_phase = 0;
else
_current_phase++;
} else { // count down
} else { // count down
if (_current_phase == 0)
_current_phase = phase_max;
else
@ -90,53 +87,45 @@ void UnipolarMotor::step(uint8_t step_mask, uint8_t dir_mask) {
*/
if (_half_step) {
switch (_current_phase) {
case 0:
_phase[0] = 1;
break;
case 1:
_phase[0] = 1;
_phase[1] = 1;
break;
case 2:
_phase[1] = 1;
break;
case 3:
_phase[1] = 1;
_phase[2] = 1;
break;
case 4:
_phase[2] = 1;
break;
case 5:
_phase[2] = 1;
_phase[3] = 1;
break;
case 6:
_phase[3] = 1;
break;
case 7:
_phase[3] = 1;
_phase[0] = 1;
break;
case 0: _phase[0] = 1; break;
case 1:
_phase[0] = 1;
_phase[1] = 1;
break;
case 2: _phase[1] = 1; break;
case 3:
_phase[1] = 1;
_phase[2] = 1;
break;
case 4: _phase[2] = 1; break;
case 5:
_phase[2] = 1;
_phase[3] = 1;
break;
case 6: _phase[3] = 1; break;
case 7:
_phase[3] = 1;
_phase[0] = 1;
break;
}
} else {
switch (_current_phase) {
case 0:
_phase[0] = 1;
_phase[1] = 1;
break;
case 1:
_phase[1] = 1;
_phase[2] = 1;
break;
case 2:
_phase[2] = 1;
_phase[3] = 1;
break;
case 3:
_phase[3] = 1;
_phase[0] = 1;
break;
case 0:
_phase[0] = 1;
_phase[1] = 1;
break;
case 1:
_phase[1] = 1;
_phase[2] = 1;
break;
case 2:
_phase[2] = 1;
_phase[3] = 1;
break;
case 3:
_phase[3] = 1;
_phase[0] = 1;
break;
}
}
digitalWrite(_pin_phase0, _phase[0]);

View File

@ -6,7 +6,7 @@
#define I2S_OUT_PIN_BASE 128
extern "C" int __digitalRead(uint8_t pin);
extern "C" int __digitalRead(uint8_t pin);
extern "C" void __pinMode(uint8_t pin, uint8_t mode);
extern "C" void __digitalWrite(uint8_t pin, uint8_t val);

View File

@ -9,17 +9,16 @@
bool auth_failed(Word* w, const char* value, auth_t auth_level) {
permissions_t permissions = w->getPermissions();
switch (auth_level) {
case LEVEL_ADMIN: // Admin can do anything
return false; // Nothing is an Admin auth fail
case LEVEL_GUEST: // Guest can only access open settings
case LEVEL_ADMIN: // Admin can do anything
return false; // Nothing is an Admin auth fail
case LEVEL_GUEST: // Guest can only access open settings
return permissions != WG; // Anything other than RG is Guest auth fail
case LEVEL_USER: // User is complicated...
if (!value) { // User can read anything
return false; // No read is a User auth fail
case LEVEL_USER: // User is complicated...
if (!value) { // User can read anything
return false; // No read is a User auth fail
}
return permissions == WA; // User cannot write WA
default:
return true;
default: return true;
}
}
@ -32,45 +31,45 @@ void show_setting(const char* name, const char* value, const char* description,
}
void settings_restore(uint8_t restore_flag) {
#ifdef WIFI_OR_BLUETOOTH
if (restore_flag & SETTINGS_RESTORE_WIFI_SETTINGS) {
#ifdef ENABLE_WIFI
wifi_config.reset_settings();
#endif
#ifdef ENABLE_BLUETOOTH
bt_config.reset_settings();
#endif
}
#endif
#ifdef WIFI_OR_BLUETOOTH
if (restore_flag & SETTINGS_RESTORE_WIFI_SETTINGS) {
# ifdef ENABLE_WIFI
wifi_config.reset_settings();
# endif
# ifdef ENABLE_BLUETOOTH
bt_config.reset_settings();
# endif
}
#endif
if (restore_flag & SETTINGS_RESTORE_DEFAULTS) {
bool restore_startup = restore_flag & SETTINGS_RESTORE_STARTUP_LINES;
for (Setting* s = Setting::List; s; s = s->next()) {
if (!s->getDescription()) {
const char* name = s->getName();
if (restore_startup) // all settings get restored
s->setDefault();
else if ((strcmp(name, "Line0") != 0) && (strcmp(name, "Line1") != 0)) // non startup settings get restored
if (restore_startup) // all settings get restored
s->setDefault();
else if ((strcmp(name, "Line0") != 0) && (strcmp(name, "Line1") != 0)) // non startup settings get restored
s->setDefault();
}
}
}
if (restore_flag & SETTINGS_RESTORE_PARAMETERS) {
uint8_t idx;
float coord_data[N_AXIS];
float coord_data[N_AXIS];
memset(&coord_data, 0, sizeof(coord_data));
for (idx = 0; idx <= SETTING_INDEX_NCOORD; idx++) settings_write_coord_data(idx, coord_data);
for (idx = 0; idx <= SETTING_INDEX_NCOORD; idx++)
settings_write_coord_data(idx, coord_data);
}
if (restore_flag & SETTINGS_RESTORE_BUILD_INFO) {
EEPROM.write(EEPROM_ADDR_BUILD_INFO, 0);
EEPROM.write(EEPROM_ADDR_BUILD_INFO + 1, 0); // Checksum
EEPROM.write(EEPROM_ADDR_BUILD_INFO + 1, 0); // Checksum
EEPROM.commit();
}
}
// Get settings values from non volatile storage into memory
void load_settings()
{
for (Setting *s = Setting::List; s; s = s->next()) {
void load_settings() {
for (Setting* s = Setting::List; s; s = s->next()) {
s->load();
}
}
@ -78,8 +77,7 @@ void load_settings()
extern void make_settings();
extern void make_grbl_commands();
extern void make_web_settings();
void settings_init()
{
void settings_init() {
EEPROM.begin(EEPROM_SIZE);
make_settings();
make_web_settings();
@ -92,17 +90,18 @@ void settings_init()
// sent to gc_execute_line. It is probably also more time-critical
// than actual settings, which change infrequently, so handling
// it early is probably prudent.
uint8_t jog_set(uint8_t *value, auth_t auth_level, ESPResponseStream* out) {
uint8_t jog_set(uint8_t* value, auth_t auth_level, ESPResponseStream* out) {
// Execute only if in IDLE or JOG states.
if (sys.state != STATE_IDLE && sys.state != STATE_JOG) return STATUS_IDLE_ERROR;
if (sys.state != STATE_IDLE && sys.state != STATE_JOG)
return STATUS_IDLE_ERROR;
// restore the $J= prefix because gc_execute_line() expects it
// restore the $J= prefix because gc_execute_line() expects it
#define MAXLINE 128
char line[MAXLINE];
strcpy(line, "$J=");
strncat(line, (char *)value, MAXLINE-strlen("$J=")-1);
strncat(line, (char*)value, MAXLINE - strlen("$J=") - 1);
return gc_execute_line(line, out->client()); // NOTE: $J= is ignored inside g-code parser and used to detect jog motions.
return gc_execute_line(line, out->client()); // NOTE: $J= is ignored inside g-code parser and used to detect jog motions.
}
err_t show_grbl_help(const char* value, auth_t auth_level, ESPResponseStream* out) {
@ -110,13 +109,13 @@ err_t show_grbl_help(const char* value, auth_t auth_level, ESPResponseStream* ou
return STATUS_OK;
}
err_t report_gcode(const char *value, auth_t auth_level, ESPResponseStream* out) {
err_t report_gcode(const char* value, auth_t auth_level, ESPResponseStream* out) {
report_gcode_modes(out->client());
return STATUS_OK;
}
void show_grbl_settings(ESPResponseStream* out, type_t type, bool wantAxis) {
for (Setting *s = Setting::List; s; s = s->next()) {
for (Setting* s = Setting::List; s; s = s->next()) {
if (s->getType() == type && s->getGrblName()) {
bool isAxis = s->getAxis() != NO_AXIS;
// The following test could be expressed more succinctly with XOR,
@ -128,20 +127,19 @@ void show_grbl_settings(ESPResponseStream* out, type_t type, bool wantAxis) {
}
}
err_t report_normal_settings(const char* value, auth_t auth_level, ESPResponseStream* out) {
show_grbl_settings(out, GRBL, false); // GRBL non-axis settings
show_grbl_settings(out, GRBL, true); // GRBL axis settings
show_grbl_settings(out, GRBL, false); // GRBL non-axis settings
show_grbl_settings(out, GRBL, true); // GRBL axis settings
return STATUS_OK;
}
err_t report_extended_settings(const char* value, auth_t auth_level, ESPResponseStream* out) {
show_grbl_settings(out, GRBL, false); // GRBL non-axis settings
show_grbl_settings(out, EXTENDED, false); // Extended non-axis settings
show_grbl_settings(out, GRBL, true); // GRBL axis settings
show_grbl_settings(out, EXTENDED, true); // Extended axis settings
show_grbl_settings(out, GRBL, false); // GRBL non-axis settings
show_grbl_settings(out, EXTENDED, false); // Extended non-axis settings
show_grbl_settings(out, GRBL, true); // GRBL axis settings
show_grbl_settings(out, EXTENDED, true); // Extended axis settings
return STATUS_OK;
}
err_t list_grbl_names(const char* value, auth_t auth_level, ESPResponseStream* out)
{
for (Setting *s = Setting::List; s; s = s->next()) {
err_t list_grbl_names(const char* value, auth_t auth_level, ESPResponseStream* out) {
for (Setting* s = Setting::List; s; s = s->next()) {
const char* gn = s->getGrblName();
if (gn) {
grbl_sendf(out->client(), "$%s => $%s\r\n", gn, s->getName());
@ -149,20 +147,16 @@ err_t list_grbl_names(const char* value, auth_t auth_level, ESPResponseStream* o
}
return STATUS_OK;
}
err_t list_settings(const char* value, auth_t auth_level, ESPResponseStream* out)
{
for (Setting *s = Setting::List; s; s = s->next()) {
const char *displayValue = auth_failed(s, value, auth_level)
? "<Authentication required>"
: s->getStringValue();
err_t list_settings(const char* value, auth_t auth_level, ESPResponseStream* out) {
for (Setting* s = Setting::List; s; s = s->next()) {
const char* displayValue = auth_failed(s, value, auth_level) ? "<Authentication required>" : s->getStringValue();
show_setting(s->getName(), displayValue, NULL, out);
}
return STATUS_OK;
}
err_t list_commands(const char* value, auth_t auth_level, ESPResponseStream* out)
{
for (Command *cp = Command::List; cp; cp = cp->next()) {
const char* name = cp->getName();
err_t list_commands(const char* value, auth_t auth_level, ESPResponseStream* out) {
for (Command* cp = Command::List; cp; cp = cp->next()) {
const char* name = cp->getName();
const char* oldName = cp->getGrblName();
if (oldName) {
grbl_sendf(out->client(), "$%s or $%s", name, oldName);
@ -185,7 +179,8 @@ err_t toggle_check_mode(const char* value, auth_t auth_level, ESPResponseStream*
mc_reset();
report_feedback_message(MESSAGE_DISABLED);
} else {
if (sys.state) return (STATUS_IDLE_ERROR); // Requires no alarm mode.
if (sys.state)
return (STATUS_IDLE_ERROR); // Requires no alarm mode.
sys.state = STATE_CHECK_MODE;
report_feedback_message(MESSAGE_ENABLED);
}
@ -199,7 +194,7 @@ err_t disable_alarm_lock(const char* value, auth_t auth_level, ESPResponseStream
report_feedback_message(MESSAGE_ALARM_UNLOCK);
sys.state = STATE_IDLE;
// Don't run startup script. Prevents stored moves in startup from causing accidents.
} // Otherwise, no effect.
} // Otherwise, no effect.
return STATUS_OK;
}
err_t report_ngc(const char* value, auth_t auth_level, ESPResponseStream* out) {
@ -210,12 +205,12 @@ err_t home(int cycle) {
if (homing_enable->get() == false)
return (STATUS_SETTING_DISABLED);
if (system_check_safety_door_ajar())
return (STATUS_CHECK_DOOR); // Block if safety door is ajar.
sys.state = STATE_HOMING; // Set system state variable
return (STATUS_CHECK_DOOR); // Block if safety door is ajar.
sys.state = STATE_HOMING; // Set system state variable
mc_homing_cycle(cycle);
if (!sys.abort) { // Execute startup scripts after successful homing.
sys.state = STATE_IDLE; // Set to IDLE when complete.
st_go_idle(); // Set steppers to the settings idle state before returning.
if (!sys.abort) { // Execute startup scripts after successful homing.
sys.state = STATE_IDLE; // Set to IDLE when complete.
st_go_idle(); // Set steppers to the settings idle state before returning.
if (cycle == HOMING_CYCLE_ALL) {
char line[128];
system_execute_startup(line);
@ -255,12 +250,12 @@ err_t get_report_build_info(const char* value, auth_t auth_level, ESPResponseStr
report_build_info(line, out->client());
return STATUS_OK;
}
#ifdef ENABLE_BUILD_INFO_WRITE_COMMAND
settings_store_build_info(value);
return STATUS_OK;
#else
return STATUS_INVALID_STATEMENT;
#endif
#ifdef ENABLE_BUILD_INFO_WRITE_COMMAND
settings_store_build_info(value);
return STATUS_OK;
#else
return STATUS_INVALID_STATEMENT;
#endif
}
err_t report_startup_lines(const char* value, auth_t auth_level, ESPResponseStream* out) {
report_startup_line(0, startup_line_0->get(), out->client());
@ -269,20 +264,16 @@ err_t report_startup_lines(const char* value, auth_t auth_level, ESPResponseStre
}
std::map<const char*, uint8_t, cmp_str> restoreCommands = {
#ifdef ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS
{ "$", SETTINGS_RESTORE_DEFAULTS },
{ "settings", SETTINGS_RESTORE_DEFAULTS },
#endif
#ifdef ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS
{ "#", SETTINGS_RESTORE_PARAMETERS },
{ "gcode", SETTINGS_RESTORE_PARAMETERS },
#endif
#ifdef ENABLE_RESTORE_EEPROM_WIPE_ALL
{ "*", SETTINGS_RESTORE_ALL },
{ "all", SETTINGS_RESTORE_ALL },
#endif
{ "@", SETTINGS_RESTORE_WIFI_SETTINGS },
{ "wifi", SETTINGS_RESTORE_WIFI_SETTINGS },
#ifdef ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS
{ "$", SETTINGS_RESTORE_DEFAULTS }, { "settings", SETTINGS_RESTORE_DEFAULTS },
#endif
#ifdef ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS
{ "#", SETTINGS_RESTORE_PARAMETERS }, { "gcode", SETTINGS_RESTORE_PARAMETERS },
#endif
#ifdef ENABLE_RESTORE_EEPROM_WIPE_ALL
{ "*", SETTINGS_RESTORE_ALL }, { "all", SETTINGS_RESTORE_ALL },
#endif
{ "@", SETTINGS_RESTORE_WIFI_SETTINGS }, { "wifi", SETTINGS_RESTORE_WIFI_SETTINGS },
};
err_t restore_settings(const char* value, auth_t auth_level, ESPResponseStream* out) {
if (!value) {
@ -315,61 +306,61 @@ err_t doJog(const char* value, auth_t auth_level, ESPResponseStream* out) {
}
std::map<uint8_t, const char*> ErrorCodes = {
{ STATUS_OK , "No error", },
{ STATUS_EXPECTED_COMMAND_LETTER , "Expected GCodecommand letter", },
{ STATUS_BAD_NUMBER_FORMAT , "Bad GCode number format", },
{ STATUS_INVALID_STATEMENT , "Invalid $ statement", },
{ STATUS_NEGATIVE_VALUE , "Negative value", },
{ STATUS_SETTING_DISABLED , "Setting disabled", },
{ STATUS_SETTING_STEP_PULSE_MIN , "Step pulse too short", },
{ STATUS_SETTING_READ_FAIL , "Failed to read settings", },
{ STATUS_IDLE_ERROR , "Command requires idle state", },
{ STATUS_SYSTEM_GC_LOCK , "GCode cannot be executed in lock or alarm state", },
{ STATUS_SOFT_LIMIT_ERROR , "Soft limit error", },
{ STATUS_OVERFLOW , "Line too long", },
{ STATUS_MAX_STEP_RATE_EXCEEDED , "Max step rate exceeded", },
{ STATUS_CHECK_DOOR , "Check door", },
{ STATUS_LINE_LENGTH_EXCEEDED , "Startup line too long", },
{ STATUS_TRAVEL_EXCEEDED , "Max travel exceeded during jog", },
{ STATUS_INVALID_JOG_COMMAND , "Invalid jog command", },
{ STATUS_SETTING_DISABLED_LASER , "Laser mode requires PWM output", },
{ STATUS_GCODE_UNSUPPORTED_COMMAND , "Unsupported GCode command", },
{ STATUS_GCODE_MODAL_GROUP_VIOLATION , "Gcode modal group violation", },
{ STATUS_GCODE_UNDEFINED_FEED_RATE , "Gcode undefined feed rate", },
{ STATUS_GCODE_COMMAND_VALUE_NOT_INTEGER , "Gcode command value not integer", },
{ STATUS_GCODE_AXIS_COMMAND_CONFLICT , "Gcode axis command conflict", },
{ STATUS_GCODE_WORD_REPEATED , "Gcode word repeated", },
{ STATUS_GCODE_NO_AXIS_WORDS , "Gcode no axis words", },
{ STATUS_GCODE_INVALID_LINE_NUMBER , "Gcode invalid line number", },
{ STATUS_GCODE_VALUE_WORD_MISSING , "Gcode value word missing", },
{ STATUS_GCODE_UNSUPPORTED_COORD_SYS , "Gcode unsupported coordinate system", },
{ STATUS_GCODE_G53_INVALID_MOTION_MODE , "Gcode G53 invalid motion mode", },
{ STATUS_GCODE_AXIS_WORDS_EXIST , "Gcode extra axis words", },
{ STATUS_GCODE_NO_AXIS_WORDS_IN_PLANE , "Gcode no axis words in plane", },
{ STATUS_GCODE_INVALID_TARGET , "Gcode invalid target", },
{ STATUS_GCODE_ARC_RADIUS_ERROR , "Gcode arc radius error", },
{ STATUS_GCODE_NO_OFFSETS_IN_PLANE , "Gcode no offsets in plane", },
{ STATUS_GCODE_UNUSED_WORDS , "Gcode unused words", },
{ STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR , "Gcode G43 dynamic axis error", },
{ STATUS_GCODE_MAX_VALUE_EXCEEDED , "Gcode max value exceeded", },
{ STATUS_P_PARAM_MAX_EXCEEDED , "P param max exceeded", },
{ STATUS_SD_FAILED_MOUNT , "SD failed mount", },
{ STATUS_SD_FAILED_READ , "SD failed read", },
{ STATUS_SD_FAILED_OPEN_DIR , "SD failed to open directory", },
{ STATUS_SD_DIR_NOT_FOUND , "SD directory not found", },
{ STATUS_SD_FILE_EMPTY , "SD file empty", },
{ STATUS_SD_FILE_NOT_FOUND , "SD file not found", },
{ STATUS_SD_FAILED_OPEN_FILE , "SD failed to open file", },
{ STATUS_SD_FAILED_BUSY , "SD is busy", },
{ STATUS_SD_FAILED_DEL_DIR, "SD failed to delete directory", },
{ STATUS_SD_FAILED_DEL_FILE, "SD failed to delete file", },
{ STATUS_BT_FAIL_BEGIN , "Bluetooth failed to start", },
{ STATUS_WIFI_FAIL_BEGIN , "WiFi failed to start", },
{ STATUS_NUMBER_RANGE , "Number out of range for setting", },
{ STATUS_INVALID_VALUE , "Invalid value for setting", },
{ STATUS_MESSAGE_FAILED , "Failed to send message", },
{ STATUS_NVS_SET_FAILED , "Failed to store setting", },
{ STATUS_AUTHENTICATION_FAILED, "Authentication failed!", },
{ STATUS_OK, "No error" },
{ STATUS_EXPECTED_COMMAND_LETTER, "Expected GCodecommand letter" },
{ STATUS_BAD_NUMBER_FORMAT, "Bad GCode number format" },
{ STATUS_INVALID_STATEMENT, "Invalid $ statement" },
{ STATUS_NEGATIVE_VALUE, "Negative value" },
{ STATUS_SETTING_DISABLED, "Setting disabled" },
{ STATUS_SETTING_STEP_PULSE_MIN, "Step pulse too short" },
{ STATUS_SETTING_READ_FAIL, "Failed to read settings" },
{ STATUS_IDLE_ERROR, "Command requires idle state" },
{ STATUS_SYSTEM_GC_LOCK, "GCode cannot be executed in lock or alarm state" },
{ STATUS_SOFT_LIMIT_ERROR, "Soft limit error" },
{ STATUS_OVERFLOW, "Line too long" },
{ STATUS_MAX_STEP_RATE_EXCEEDED, "Max step rate exceeded" },
{ STATUS_CHECK_DOOR, "Check door" },
{ STATUS_LINE_LENGTH_EXCEEDED, "Startup line too long" },
{ STATUS_TRAVEL_EXCEEDED, "Max travel exceeded during jog" },
{ STATUS_INVALID_JOG_COMMAND, "Invalid jog command" },
{ STATUS_SETTING_DISABLED_LASER, "Laser mode requires PWM output" },
{ STATUS_GCODE_UNSUPPORTED_COMMAND, "Unsupported GCode command" },
{ STATUS_GCODE_MODAL_GROUP_VIOLATION, "Gcode modal group violation" },
{ STATUS_GCODE_UNDEFINED_FEED_RATE, "Gcode undefined feed rate" },
{ STATUS_GCODE_COMMAND_VALUE_NOT_INTEGER, "Gcode command value not integer" },
{ STATUS_GCODE_AXIS_COMMAND_CONFLICT, "Gcode axis command conflict" },
{ STATUS_GCODE_WORD_REPEATED, "Gcode word repeated" },
{ STATUS_GCODE_NO_AXIS_WORDS, "Gcode no axis words" },
{ STATUS_GCODE_INVALID_LINE_NUMBER, "Gcode invalid line number" },
{ STATUS_GCODE_VALUE_WORD_MISSING, "Gcode value word missing" },
{ STATUS_GCODE_UNSUPPORTED_COORD_SYS, "Gcode unsupported coordinate system" },
{ STATUS_GCODE_G53_INVALID_MOTION_MODE, "Gcode G53 invalid motion mode" },
{ STATUS_GCODE_AXIS_WORDS_EXIST, "Gcode extra axis words" },
{ STATUS_GCODE_NO_AXIS_WORDS_IN_PLANE, "Gcode no axis words in plane" },
{ STATUS_GCODE_INVALID_TARGET, "Gcode invalid target" },
{ STATUS_GCODE_ARC_RADIUS_ERROR, "Gcode arc radius error" },
{ STATUS_GCODE_NO_OFFSETS_IN_PLANE, "Gcode no offsets in plane" },
{ STATUS_GCODE_UNUSED_WORDS, "Gcode unused words" },
{ STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR, "Gcode G43 dynamic axis error" },
{ STATUS_GCODE_MAX_VALUE_EXCEEDED, "Gcode max value exceeded" },
{ STATUS_P_PARAM_MAX_EXCEEDED, "P param max exceeded" },
{ STATUS_SD_FAILED_MOUNT, "SD failed mount" },
{ STATUS_SD_FAILED_READ, "SD failed read" },
{ STATUS_SD_FAILED_OPEN_DIR, "SD failed to open directory" },
{ STATUS_SD_DIR_NOT_FOUND, "SD directory not found" },
{ STATUS_SD_FILE_EMPTY, "SD file empty" },
{ STATUS_SD_FILE_NOT_FOUND, "SD file not found" },
{ STATUS_SD_FAILED_OPEN_FILE, "SD failed to open file" },
{ STATUS_SD_FAILED_BUSY, "SD is busy" },
{ STATUS_SD_FAILED_DEL_DIR, "SD failed to delete directory" },
{ STATUS_SD_FAILED_DEL_FILE, "SD failed to delete file" },
{ STATUS_BT_FAIL_BEGIN, "Bluetooth failed to start" },
{ STATUS_WIFI_FAIL_BEGIN, "WiFi failed to start" },
{ STATUS_NUMBER_RANGE, "Number out of range for setting" },
{ STATUS_INVALID_VALUE, "Invalid value for setting" },
{ STATUS_MESSAGE_FAILED, "Failed to send message" },
{ STATUS_NVS_SET_FAILED, "Failed to store setting" },
{ STATUS_AUTHENTICATION_FAILED, "Authentication failed!" },
};
const char* errorString(err_t errorNumber) {
@ -379,7 +370,7 @@ const char* errorString(err_t errorNumber) {
err_t listErrorCodes(const char* value, auth_t auth_level, ESPResponseStream* out) {
if (value) {
char* endptr = NULL;
char* endptr = NULL;
uint8_t errorNumber = strtol(value, &endptr, 10);
if (*endptr) {
grbl_sendf(out->client(), "Malformed error number: %s\r\n", value);
@ -395,55 +386,52 @@ err_t listErrorCodes(const char* value, auth_t auth_level, ESPResponseStream* ou
}
}
for (auto it = ErrorCodes.begin();
it != ErrorCodes.end();
it++) {
for (auto it = ErrorCodes.begin(); it != ErrorCodes.end(); it++) {
grbl_sendf(out->client(), "%d: %s\r\n", it->first, it->second);
}
return STATUS_OK;
}
// Commands use the same syntax as Settings, but instead of setting or
// displaying a persistent value, a command causes some action to occur.
// That action could be anything, from displaying a run-time parameter
// to performing some system state change. Each command is responsible
// for decoding its own value string, if it needs one.
void make_grbl_commands() {
new GrblCommand("", "Help", show_grbl_help, ANY_STATE);
new GrblCommand("T", "State", showState, ANY_STATE);
new GrblCommand("J", "Jog", doJog, IDLE_OR_JOG);
new GrblCommand("", "Help", show_grbl_help, ANY_STATE);
new GrblCommand("T", "State", showState, ANY_STATE);
new GrblCommand("J", "Jog", doJog, IDLE_OR_JOG);
new GrblCommand("$", "GrblSettings/List", report_normal_settings, NOT_CYCLE_OR_HOLD);
new GrblCommand("+", "ExtendedSettings/List", report_extended_settings, NOT_CYCLE_OR_HOLD);
new GrblCommand("L", "GrblNames/List", list_grbl_names, NOT_CYCLE_OR_HOLD);
new GrblCommand("S", "Settings/List", list_settings, NOT_CYCLE_OR_HOLD);
new GrblCommand("CMD", "Commands/List", list_commands, NOT_CYCLE_OR_HOLD);
new GrblCommand("E", "ErrorCodes/List",listErrorCodes, ANY_STATE);
new GrblCommand("G", "GCode/Modes", report_gcode, ANY_STATE);
new GrblCommand("C", "GCode/Check", toggle_check_mode, ANY_STATE);
new GrblCommand("X", "Alarm/Disable", disable_alarm_lock, ANY_STATE);
new GrblCommand("$", "GrblSettings/List", report_normal_settings, NOT_CYCLE_OR_HOLD);
new GrblCommand("+", "ExtendedSettings/List", report_extended_settings, NOT_CYCLE_OR_HOLD);
new GrblCommand("L", "GrblNames/List", list_grbl_names, NOT_CYCLE_OR_HOLD);
new GrblCommand("S", "Settings/List", list_settings, NOT_CYCLE_OR_HOLD);
new GrblCommand("CMD", "Commands/List", list_commands, NOT_CYCLE_OR_HOLD);
new GrblCommand("E", "ErrorCodes/List", listErrorCodes, ANY_STATE);
new GrblCommand("G", "GCode/Modes", report_gcode, ANY_STATE);
new GrblCommand("C", "GCode/Check", toggle_check_mode, ANY_STATE);
new GrblCommand("X", "Alarm/Disable", disable_alarm_lock, ANY_STATE);
new GrblCommand("NVX", "Settings/Erase", Setting::eraseNVS, IDLE_OR_ALARM, WA);
new GrblCommand("V", "Settings/Stats", Setting::report_nvs_stats, IDLE_OR_ALARM);
new GrblCommand("#", "GCode/Offsets", report_ngc, IDLE_OR_ALARM);
new GrblCommand("H", "Home", home_all, IDLE_OR_ALARM);
#ifdef HOMING_SINGLE_AXIS_COMMANDS
new GrblCommand("HX", "Home/X", home_x, IDLE_OR_ALARM);
new GrblCommand("HY", "Home/Y", home_y, IDLE_OR_ALARM);
new GrblCommand("HZ", "Home/Z", home_z, IDLE_OR_ALARM);
#if (N_AXIS > 3)
new GrblCommand("HA", "Home/A", home_a, IDLE_OR_ALARM);
#endif
#if (N_AXIS > 4)
new GrblCommand("HB", "Home/B", home_b, IDLE_OR_ALARM);
#endif
#if (N_AXIS > 5)
new GrblCommand("HC", "Home/C", home_c, IDLE_OR_ALARM);
#endif
#endif
new GrblCommand("V", "Settings/Stats", Setting::report_nvs_stats, IDLE_OR_ALARM);
new GrblCommand("#", "GCode/Offsets", report_ngc, IDLE_OR_ALARM);
new GrblCommand("H", "Home", home_all, IDLE_OR_ALARM);
#ifdef HOMING_SINGLE_AXIS_COMMANDS
new GrblCommand("HX", "Home/X", home_x, IDLE_OR_ALARM);
new GrblCommand("HY", "Home/Y", home_y, IDLE_OR_ALARM);
new GrblCommand("HZ", "Home/Z", home_z, IDLE_OR_ALARM);
# if (N_AXIS > 3)
new GrblCommand("HA", "Home/A", home_a, IDLE_OR_ALARM);
# endif
# if (N_AXIS > 4)
new GrblCommand("HB", "Home/B", home_b, IDLE_OR_ALARM);
# endif
# if (N_AXIS > 5)
new GrblCommand("HC", "Home/C", home_c, IDLE_OR_ALARM);
# endif
#endif
new GrblCommand("SLP", "System/Sleep", sleep_grbl, IDLE_OR_ALARM);
new GrblCommand("I", "Build/Info", get_report_build_info, IDLE_OR_ALARM);
new GrblCommand("N", "GCode/StartupLines", report_startup_lines, IDLE_OR_ALARM);
new GrblCommand("I", "Build/Info", get_report_build_info, IDLE_OR_ALARM);
new GrblCommand("N", "GCode/StartupLines", report_startup_lines, IDLE_OR_ALARM);
new GrblCommand("RST", "Settings/Restore", restore_settings, IDLE_OR_ALARM, WA);
};
@ -452,7 +440,7 @@ void make_grbl_commands() {
// start points to a null-terminated string.
// Returns the first substring that does not contain whitespace.
// Case is unchanged because comparisons are case-insensitive.
char *normalize_key(char *start) {
char* normalize_key(char* start) {
char c;
// In the usual case, this loop will exit on the very first test,
@ -469,9 +457,8 @@ char *normalize_key(char *start) {
// Having found the beginning of the printable string,
// we now scan forward until we find a space character.
char *end;
for (end = start; (c = *end) != '\0' && !isspace(c); end++) {
}
char* end;
for (end = start; (c = *end) != '\0' && !isspace(c); end++) {}
// end now points to either a whitespace character of end of string
// In either case it is okay to place a null there
@ -482,7 +469,7 @@ char *normalize_key(char *start) {
// This is the handler for all forms of settings commands,
// $..= and [..], with and without a value.
err_t do_command_or_setting(const char *key, char *value, auth_t auth_level, ESPResponseStream* out) {
err_t do_command_or_setting(const char* key, char* value, auth_t auth_level, ESPResponseStream* out) {
// If value is NULL, it means that there was no value string, i.e.
// $key without =, or [key] with nothing following.
// If value is not NULL, but the string is empty, that is the form
@ -491,7 +478,7 @@ err_t do_command_or_setting(const char *key, char *value, auth_t auth_level, ESP
// First search the settings list by text name. If found, set a new
// value if one is given, otherwise display the current value
for (Setting *s = Setting::List; s; s = s->next()) {
for (Setting* s = Setting::List; s; s = s->next()) {
if (strcasecmp(s->getName(), key) == 0) {
if (auth_failed(s, value, auth_level)) {
return STATUS_AUTHENTICATION_FAILED;
@ -507,7 +494,7 @@ err_t do_command_or_setting(const char *key, char *value, auth_t auth_level, ESP
// Then search the setting list by compatible name. If found, set a new
// value if one is given, otherwise display the current value in compatible mode
for (Setting *s = Setting::List; s; s = s->next()) {
for (Setting* s = Setting::List; s; s = s->next()) {
if (s->getGrblName() && strcasecmp(s->getGrblName(), key) == 0) {
if (auth_failed(s, value, auth_level)) {
return STATUS_AUTHENTICATION_FAILED;
@ -523,12 +510,8 @@ err_t do_command_or_setting(const char *key, char *value, auth_t auth_level, ESP
// If we did not find a setting, look for a command. Commands
// handle values internally; you cannot determine whether to set
// or display solely based on the presence of a value.
for (Command *cp = Command::List; cp; cp = cp->next()) {
if ( (strcasecmp(cp->getName(), key) == 0)
|| (cp->getGrblName()
&& strcasecmp(cp->getGrblName(), key) == 0
)
) {
for (Command* cp = Command::List; cp; cp = cp->next()) {
if ((strcasecmp(cp->getName(), key) == 0) || (cp->getGrblName() && strcasecmp(cp->getGrblName(), key) == 0)) {
if (auth_failed(cp, value, auth_level)) {
return STATUS_AUTHENTICATION_FAILED;
}
@ -547,18 +530,16 @@ err_t do_command_or_setting(const char *key, char *value, auth_t auth_level, ESP
// This lets us look at X axis settings with $*x.
// $x by itself is the disable alarm lock command
if (lcKey.startsWith("*")) {
lcKey.remove(0,1);
lcKey.remove(0, 1);
}
lcKey.toLowerCase();
bool found = false;
for (Setting *s = Setting::List; s; s = s->next()) {
for (Setting* s = Setting::List; s; s = s->next()) {
auto lcTest = String(s->getName());
lcTest.toLowerCase();
if (lcTest.indexOf(lcKey) >= 0) {
const char *displayValue = auth_failed(s, value, auth_level)
? "<Authentication required>"
: s->getStringValue();
const char* displayValue = auth_failed(s, value, auth_level) ? "<Authentication required>" : s->getStringValue();
show_setting(s->getName(), displayValue, NULL, out);
found = true;
}
@ -573,8 +554,8 @@ err_t do_command_or_setting(const char *key, char *value, auth_t auth_level, ESP
uint8_t system_execute_line(char* line, ESPResponseStream* out, auth_t auth_level) {
remove_password(line, auth_level);
char *value;
if (*line++ == '[') { // [ESPxxx] form
char* value;
if (*line++ == '[') { // [ESPxxx] form
value = strrchr(line, ']');
if (!value) {
// Missing ] is an error in this form
@ -595,7 +576,7 @@ uint8_t system_execute_line(char* line, ESPResponseStream* out, auth_t auth_leve
}
}
char *key = normalize_key(line);
char* key = normalize_key(line);
// At this point there are three possibilities for value
// NULL - $xxx without =
@ -610,7 +591,7 @@ uint8_t system_execute_line(char* line, uint8_t client, auth_t auth_level) {
void system_execute_startup(char* line) {
err_t status_code;
char gcline[256];
char gcline[256];
strncpy(gcline, startup_line_0->get(), 255);
if (*gcline) {
status_code = gc_execute_line(gcline, CLIENT_SERIAL);
@ -622,4 +603,3 @@ void system_execute_startup(char* line) {
report_execute_startup_message(gcline, status_code, CLIENT_SERIAL);
}
}

View File

@ -3,29 +3,23 @@
#include <map>
#include "nvs.h"
Word::Word(type_t type, permissions_t permissions, const char* description, const char* grblName, const char* fullName)
: _description(description)
, _grblName(grblName)
, _fullName(fullName)
, _type(type)
, _permissions(permissions)
{}
Word::Word(type_t type, permissions_t permissions, const char* description, const char* grblName, const char* fullName) :
_description(description), _grblName(grblName), _fullName(fullName), _type(type), _permissions(permissions) {}
Command* Command::List = NULL;
Command::Command(const char* description, type_t type, permissions_t permissions, const char* grblName, const char* fullName)
: Word(type, permissions, description, grblName, fullName)
{
Command::Command(const char* description, type_t type, permissions_t permissions, const char* grblName, const char* fullName) :
Word(type, permissions, description, grblName, fullName) {
link = List;
List = this;
}
Setting* Setting::List = NULL;
Setting::Setting(const char* description, type_t type, permissions_t permissions, const char* grblName, const char* fullName, bool (*checker)(char *))
: Word(type, permissions, description, grblName, fullName)
, _checker(checker)
{
Setting::Setting(
const char* description, type_t type, permissions_t permissions, const char* grblName, const char* fullName, bool (*checker)(char*)) :
Word(type, permissions, description, grblName, fullName),
_checker(checker) {
link = List;
List = this;
@ -36,9 +30,9 @@ Setting::Setting(const char* description, type_t type, permissions_t permissions
_keyName = _fullName;
} else {
// This is Donald Knuth's hash function from Vol 3, chapter 6.4
char *hashName = (char *)malloc(16);
uint32_t hash = len;
for (const char *s = fullName; *s; s++) {
char* hashName = (char*)malloc(16);
uint32_t hash = len;
for (const char* s = fullName; *s; s++) {
hash = ((hash << 5) ^ (hash >> 27)) ^ (*s);
}
sprintf(hashName, "%.7s%08x", fullName, hash);
@ -46,7 +40,7 @@ Setting::Setting(const char* description, type_t type, permissions_t permissions
}
}
err_t Setting::check(char *s) {
err_t Setting::check(char* s) {
if (sys.state != STATE_IDLE && !(sys.state & STATE_ALARM)) {
return STATUS_IDLE_ERROR;
}
@ -66,18 +60,22 @@ void Setting::init() {
}
}
IntSetting::IntSetting(const char *description, type_t type, permissions_t permissions, const char* grblName, const char* name, int32_t defVal, int32_t minVal, int32_t maxVal, bool (*checker)(char *) = NULL)
: Setting(description, type, permissions, grblName, name, checker)
, _defaultValue(defVal)
, _currentValue(defVal)
, _minValue(minVal)
, _maxValue(maxVal)
{ }
IntSetting::IntSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
int32_t defVal,
int32_t minVal,
int32_t maxVal,
bool (*checker)(char*) = NULL) :
Setting(description, type, permissions, grblName, name, checker),
_defaultValue(defVal), _currentValue(defVal), _minValue(minVal), _maxValue(maxVal) {}
void IntSetting::load() {
esp_err_t err = nvs_get_i32(_handle, _keyName, &_storedValue);
if (err) {
_storedValue = std::numeric_limits<int32_t>::min();
_storedValue = std::numeric_limits<int32_t>::min();
_currentValue = _defaultValue;
} else {
_currentValue = _storedValue;
@ -96,7 +94,7 @@ err_t IntSetting::setStringValue(char* s) {
if (err_t err = check(s)) {
return err;
}
char* endptr;
char* endptr;
int32_t convertedValue = strtol(s, &endptr, 10);
if (endptr == s || *endptr != '\0') {
return STATUS_BAD_NUMBER_FORMAT;
@ -124,23 +122,27 @@ const char* IntSetting::getStringValue() {
return strval;
}
void IntSetting::addWebui(JSONencoder *j) {
void IntSetting::addWebui(JSONencoder* j) {
if (getDescription()) {
j->begin_webui(getName(), getDescription(), "I", getStringValue(), _minValue, _maxValue);
j->end_object();
}
}
AxisMaskSetting::AxisMaskSetting(const char *description, type_t type, permissions_t permissions, const char* grblName, const char* name, int32_t defVal, bool (*checker)(char *) = NULL)
: Setting(description, type, permissions, grblName, name, checker)
, _defaultValue(defVal)
, _currentValue(defVal)
{ }
AxisMaskSetting::AxisMaskSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
int32_t defVal,
bool (*checker)(char*) = NULL) :
Setting(description, type, permissions, grblName, name, checker),
_defaultValue(defVal), _currentValue(defVal) {}
void AxisMaskSetting::load() {
esp_err_t err = nvs_get_i32(_handle, _keyName, &_storedValue);
if (err) {
_storedValue = -1;
_storedValue = -1;
_currentValue = _defaultValue;
} else {
_currentValue = _storedValue;
@ -160,7 +162,7 @@ err_t AxisMaskSetting::setStringValue(char* s) {
return err;
}
int32_t convertedValue;
char* endptr;
char* endptr;
if (*s == '\0') {
convertedValue = 0;
} else {
@ -200,8 +202,8 @@ const char* AxisMaskSetting::getCompatibleValue() {
const char* AxisMaskSetting::getStringValue() {
static char strval[32];
char *s = strval;
uint32_t mask = get();
char* s = strval;
uint32_t mask = get();
for (int i = 0; i < MAX_N_AXIS; i++) {
if (mask & bit(i)) {
*s++ = "XYZABC"[i];
@ -211,20 +213,24 @@ const char* AxisMaskSetting::getStringValue() {
return strval;
}
void AxisMaskSetting::addWebui(JSONencoder *j) {
void AxisMaskSetting::addWebui(JSONencoder* j) {
if (getDescription()) {
j->begin_webui(getName(), getDescription(), "I", getStringValue(), 0, (1<<MAX_N_AXIS)-1);
j->begin_webui(getName(), getDescription(), "I", getStringValue(), 0, (1 << MAX_N_AXIS) - 1);
j->end_object();
}
}
FloatSetting::FloatSetting(const char *description, type_t type, permissions_t permissions, const char* grblName, const char* name, float defVal, float minVal, float maxVal, bool (*checker)(char *) = NULL)
: Setting(description, type, permissions, grblName, name, checker)
, _defaultValue(defVal)
, _currentValue(defVal)
, _minValue(minVal)
, _maxValue(maxVal)
{ }
FloatSetting::FloatSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
float defVal,
float minVal,
float maxVal,
bool (*checker)(char*) = NULL) :
Setting(description, type, permissions, grblName, name, checker),
_defaultValue(defVal), _currentValue(defVal), _minValue(minVal), _maxValue(maxVal) {}
void FloatSetting::load() {
union {
@ -251,12 +257,10 @@ err_t FloatSetting::setStringValue(char* s) {
return err;
}
float convertedValue;
uint8_t len = strlen(s);
float convertedValue;
uint8_t len = strlen(s);
uint8_t retlen = 0;
if (!read_float(s, &retlen, &convertedValue)
|| retlen != len)
{
if (!read_float(s, &retlen, &convertedValue) || retlen != len) {
return STATUS_BAD_NUMBER_FORMAT;
}
if (convertedValue < _minValue || convertedValue > _maxValue) {
@ -299,31 +303,38 @@ const char* FloatSetting::getStringValue() {
return strval;
}
StringSetting::StringSetting(const char *description, type_t type, permissions_t permissions, const char* grblName, const char* name, const char* defVal, int min, int max, bool (*checker)(char *))
: Setting(description, type, permissions, grblName, name, checker)
{
StringSetting::StringSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
const char* defVal,
int min,
int max,
bool (*checker)(char*)) :
Setting(description, type, permissions, grblName, name, checker) {
_defaultValue = defVal;
_currentValue = defVal;
_minLength = min;
_maxLength = max;
};
_minLength = min;
_maxLength = max;
};
void StringSetting::load() {
size_t len = 0;
size_t len = 0;
esp_err_t err = nvs_get_str(_handle, _keyName, NULL, &len);
if(err) {
_storedValue = _defaultValue;
if (err) {
_storedValue = _defaultValue;
_currentValue = _defaultValue;
return;
}
char buf[len];
err = nvs_get_str(_handle, _keyName, buf, &len);
if (err) {
_storedValue = _defaultValue;
_storedValue = _defaultValue;
_currentValue = _defaultValue;
return;
}
_storedValue = String(buf);
_storedValue = String(buf);
_currentValue = _storedValue;
}
@ -341,7 +352,7 @@ err_t StringSetting::setStringValue(char* s) {
if (err_t err = check(s)) {
return err;
}
_currentValue = s;
_currentValue = s;
if (_storedValue != _currentValue) {
if (_currentValue == _defaultValue) {
nvs_erase_key(_handle, _keyName);
@ -358,41 +369,37 @@ err_t StringSetting::setStringValue(char* s) {
const char* StringSetting::getStringValue() {
// If the string is a password do not display it
if (_checker &&
(
#ifdef ENABLE_WIFI
_checker == (bool (*)(char *))WiFiConfig::isPasswordValid
||
#endif
_checker == (bool (*)(char *))COMMANDS::isLocalPasswordValid
)) {
if (_checker && (
#ifdef ENABLE_WIFI
_checker == (bool (*)(char*))WiFiConfig::isPasswordValid ||
#endif
_checker == (bool (*)(char*))COMMANDS::isLocalPasswordValid)) {
return "******";
}
return _currentValue.c_str();
}
void StringSetting::addWebui(JSONencoder *j) {
void StringSetting::addWebui(JSONencoder* j) {
if (!getDescription()) {
return;
}
j->begin_webui(
getName(), getDescription(), "S", getStringValue(), _minLength, _maxLength);
j->begin_webui(getName(), getDescription(), "S", getStringValue(), _minLength, _maxLength);
j->end_object();
}
typedef std::map<const char *, int8_t, cmp_str> enum_opt_t;
typedef std::map<const char*, int8_t, cmp_str> enum_opt_t;
EnumSetting::EnumSetting(const char *description, type_t type, permissions_t permissions, const char* grblName, const char* name, int8_t defVal, enum_opt_t *opts)
EnumSetting::EnumSetting(
const char* description, type_t type, permissions_t permissions, const char* grblName, const char* name, int8_t defVal, enum_opt_t* opts)
// No checker function because enumerations have an exact set of value
: Setting(description, type, permissions, grblName, name, NULL)
, _defaultValue(defVal)
, _options(opts)
{ }
:
Setting(description, type, permissions, grblName, name, NULL),
_defaultValue(defVal), _options(opts) {}
void EnumSetting::load() {
esp_err_t err = nvs_get_i8(_handle, _keyName, &_storedValue);
if (err) {
_storedValue = -1;
_storedValue = -1;
_currentValue = _defaultValue;
} else {
_currentValue = _storedValue;
@ -411,7 +418,7 @@ void EnumSetting::setDefault() {
// This is necessary for WebUI, which uses the number
// for setting.
err_t EnumSetting::setStringValue(char* s) {
s = trim(s);
s = trim(s);
enum_opt_t::iterator it = _options->find(s);
if (it == _options->end()) {
// If we don't find the value in keys, look for it in the numeric values
@ -420,7 +427,7 @@ err_t EnumSetting::setStringValue(char* s) {
if (!s || !*s) {
return STATUS_BAD_NUMBER_FORMAT;
}
char *endptr;
char* endptr;
uint8_t num = strtol(s, &endptr, 10);
// Disallow non-numeric characters in string
if (*endptr) {
@ -450,9 +457,7 @@ err_t EnumSetting::setStringValue(char* s) {
}
const char* EnumSetting::getStringValue() {
for (enum_opt_t::iterator it = _options->begin();
it != _options->end();
it++) {
for (enum_opt_t::iterator it = _options->begin(); it != _options->end(); it++) {
if (it->second == _currentValue) {
return it->first;
}
@ -460,32 +465,35 @@ const char* EnumSetting::getStringValue() {
return "???";
}
void EnumSetting::addWebui(JSONencoder *j) {
void EnumSetting::addWebui(JSONencoder* j) {
if (!getDescription()) {
return;
return;
}
j->begin_webui(getName(), getDescription(), "B", String(get()).c_str());
j->begin_array("O");
for (enum_opt_t::iterator it = _options->begin();
it != _options->end();
it++) {
for (enum_opt_t::iterator it = _options->begin(); it != _options->end(); it++) {
j->begin_object();
j->member(it->first, it->second);
j->end_object();
}
}
j->end_array();
j->end_object();
}
FlagSetting::FlagSetting(const char *description, type_t type, permissions_t permissions, const char * grblName, const char* name, bool defVal, bool (*checker)(char *) = NULL) :
FlagSetting::FlagSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
bool defVal,
bool (*checker)(char*) = NULL) :
Setting(description, type, permissions, grblName, name, checker),
_defaultValue(defVal)
{ }
_defaultValue(defVal) {}
void FlagSetting::load() {
esp_err_t err = nvs_get_i8(_handle, _keyName, &_storedValue);
if (err) {
_storedValue = -1; // Neither well-formed false (0) nor true (1)
_storedValue = -1; // Neither well-formed false (0) nor true (1)
_currentValue = _defaultValue;
} else {
_currentValue = !!_storedValue;
@ -499,12 +507,9 @@ void FlagSetting::setDefault() {
}
err_t FlagSetting::setStringValue(char* s) {
s = trim(s);
_currentValue = (strcasecmp(s, "on") == 0)
|| (strcasecmp(s, "true") == 0)
|| (strcasecmp(s, "enabled") == 0)
|| (strcasecmp(s, "yes") == 0)
|| (strcasecmp(s, "1") == 0);
s = trim(s);
_currentValue = (strcasecmp(s, "on") == 0) || (strcasecmp(s, "true") == 0) || (strcasecmp(s, "enabled") == 0) ||
(strcasecmp(s, "yes") == 0) || (strcasecmp(s, "1") == 0);
// _storedValue is -1, 0, or 1
// _currentValue is 0 or 1
if (_storedValue != (int8_t)_currentValue) {
@ -526,18 +531,27 @@ const char* FlagSetting::getCompatibleValue() {
return get() ? "1" : "0";
}
#include <WiFi.h>
IPaddrSetting::IPaddrSetting(const char *description, type_t type, permissions_t permissions, const char * grblName, const char* name, uint32_t defVal, bool (*checker)(char *) = NULL)
: Setting(description, type, permissions, grblName, name, checker) // There are no GRBL IP settings.
, _defaultValue(defVal)
, _currentValue(defVal)
{ }
IPaddrSetting::IPaddrSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
uint32_t defVal,
bool (*checker)(char*) = NULL) :
Setting(description, type, permissions, grblName, name, checker) // There are no GRBL IP settings.
,
_defaultValue(defVal), _currentValue(defVal) {}
IPaddrSetting::IPaddrSetting(const char *description, type_t type, permissions_t permissions, const char * grblName, const char* name, const char *defVal, bool (*checker)(char *) = NULL)
: Setting(description, type, permissions, grblName, name, checker)
{
IPaddrSetting::IPaddrSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
const char* defVal,
bool (*checker)(char*) = NULL) :
Setting(description, type, permissions, grblName, name, checker) {
IPAddress ipaddr;
if (ipaddr.fromString(defVal)) {
_defaultValue = ipaddr;
@ -548,9 +562,9 @@ IPaddrSetting::IPaddrSetting(const char *description, type_t type, permissions_t
}
void IPaddrSetting::load() {
esp_err_t err = nvs_get_i32(_handle, _keyName, (int32_t *)&_storedValue);
esp_err_t err = nvs_get_i32(_handle, _keyName, (int32_t*)&_storedValue);
if (err) {
_storedValue = 0x000000ff; // Unreasonable value for any IP thing
_storedValue = 0x000000ff; // Unreasonable value for any IP thing
_currentValue = _defaultValue;
} else {
_currentValue = _storedValue;
@ -589,21 +603,19 @@ err_t IPaddrSetting::setStringValue(char* s) {
const char* IPaddrSetting::getStringValue() {
static String s;
IPAddress ipaddr(get());
IPAddress ipaddr(get());
s = ipaddr.toString();
return s.c_str();
}
void IPaddrSetting::addWebui(JSONencoder *j) {
void IPaddrSetting::addWebui(JSONencoder* j) {
if (getDescription()) {
j->begin_webui(getName(), getDescription(), "A", getStringValue());
j->end_object();
}
}
AxisSettings::AxisSettings(const char *axisName) :
name(axisName)
{}
AxisSettings::AxisSettings(const char* axisName) : name(axisName) {}
err_t GrblCommand::action(char* value, auth_t auth_type, ESPResponseStream* out) {
if (sys.state & _disallowedStates) {

View File

@ -39,35 +39,36 @@ typedef uint8_t axis_t;
class Word {
protected:
const char* _description;
const char* _grblName;
const char* _fullName;
type_t _type;
const char* _description;
const char* _grblName;
const char* _fullName;
type_t _type;
permissions_t _permissions;
public:
Word(type_t type, permissions_t permissions, const char *description, const char * grblName, const char* fullName);
type_t getType() { return _type; }
Word(type_t type, permissions_t permissions, const char* description, const char* grblName, const char* fullName);
type_t getType() { return _type; }
permissions_t getPermissions() { return _permissions; }
const char* getName() { return _fullName; }
const char* getGrblName() { return _grblName; }
const char* getDescription() { return _description; }
const char* getName() { return _fullName; }
const char* getGrblName() { return _grblName; }
const char* getDescription() { return _description; }
};
class Command : public Word {
protected:
Command *link; // linked list of setting objects
Command* link; // linked list of setting objects
public:
static Command* List;
Command* next() { return link; }
Command* next() { return link; }
~Command() {}
Command(const char *description, type_t type, permissions_t permissions, const char * grblName, const char* fullName);
Command(const char* description, type_t type, permissions_t permissions, const char* grblName, const char* fullName);
// The default implementation of addWebui() does nothing.
// Derived classes may override it to do something.
virtual void addWebui(JSONencoder *) {};
virtual void addWebui(JSONencoder*) {};
virtual err_t action(char* value, auth_t auth_level, ESPResponseStream* out) =0;
virtual err_t action(char* value, auth_t auth_level, ESPResponseStream* out) = 0;
};
class Setting : public Word {
@ -75,24 +76,24 @@ private:
protected:
static nvs_handle _handle;
// group_t _group;
axis_t _axis = NO_AXIS;
Setting *link; // linked list of setting objects
axis_t _axis = NO_AXIS;
Setting* link; // linked list of setting objects
bool (*_checker)(char *);
bool (*_checker)(char*);
const char* _keyName;
public:
static void init();
static Setting* List;
Setting* next() { return link; }
err_t check(char *s);
public:
static void init();
static Setting* List;
Setting* next() { return link; }
err_t check(char* s);
static err_t report_nvs_stats(const char* value, auth_t auth_level, ESPResponseStream* out) {
nvs_stats_t stats;
if (err_t err = nvs_get_stats(NULL, &stats))
return err;
grbl_sendf(out->client(), "[MSG: NVS Used: %d Free: %d Total: %d]\r\n",
stats.used_entries, stats.free_entries, stats.total_entries);
grbl_sendf(out->client(), "[MSG: NVS Used: %d Free: %d Total: %d]\r\n", stats.used_entries, stats.free_entries, stats.total_entries);
#if 0 // The SDK we use does not have this yet
nvs_iterator_t it = nvs_entry_find(NULL, NULL, NVS_TYPE_ANY);
while (it != NULL) {
@ -113,9 +114,9 @@ public:
~Setting() {}
// Setting(const char *description, group_t group, const char * grblName, const char* fullName, bool (*checker)(char *));
Setting(const char *description, type_t type, permissions_t permissions, const char * grblName, const char* fullName, bool (*checker)(char *));
Setting(const char* description, type_t type, permissions_t permissions, const char* grblName, const char* fullName, bool (*checker)(char*));
axis_t getAxis() { return _axis; }
void setAxis(axis_t axis) { _axis = axis; }
void setAxis(axis_t axis) { _axis = axis; }
// load() reads the backing store to get the current
// value of the setting. This could be slow so it
@ -125,11 +126,11 @@ public:
// The default implementation of addWebui() does nothing.
// Derived classes may override it to do something.
virtual void addWebui(JSONencoder *) {};
virtual void addWebui(JSONencoder*) {};
virtual err_t setStringValue(char* value) =0;
err_t setStringValue(String s) { return setStringValue(s.c_str()); }
virtual const char* getStringValue() =0;
virtual err_t setStringValue(char* value) = 0;
err_t setStringValue(String s) { return setStringValue(s.c_str()); }
virtual const char* getStringValue() = 0;
virtual const char* getCompatibleValue() { return getStringValue(); }
};
@ -142,19 +143,33 @@ private:
int32_t _maxValue;
public:
IntSetting(const char *description, type_t type, permissions_t permissions, const char* grblName, const char* name, int32_t defVal, int32_t minVal, int32_t maxVal, bool (*checker)(char *));
IntSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
int32_t defVal,
int32_t minVal,
int32_t maxVal,
bool (*checker)(char*));
IntSetting(type_t type, permissions_t permissions, const char* grblName, const char* name, int32_t defVal, int32_t minVal, int32_t maxVal, bool (*checker)(char *) = NULL)
: IntSetting(NULL, type, permissions, grblName, name, defVal, minVal, maxVal, checker)
{ }
IntSetting(type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
int32_t defVal,
int32_t minVal,
int32_t maxVal,
bool (*checker)(char*) = NULL) :
IntSetting(NULL, type, permissions, grblName, name, defVal, minVal, maxVal, checker) {}
void load();
void setDefault();
void addWebui(JSONencoder *);
err_t setStringValue(char* value);
void load();
void setDefault();
void addWebui(JSONencoder*);
err_t setStringValue(char* value);
const char* getStringValue();
int32_t get() { return _currentValue; }
int32_t get() { return _currentValue; }
};
class AxisMaskSetting : public Setting {
@ -164,20 +179,26 @@ private:
int32_t _storedValue;
public:
AxisMaskSetting(const char *description, type_t type, permissions_t permissions, const char* grblName, const char* name, int32_t defVal, bool (*checker)(char *));
AxisMaskSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
int32_t defVal,
bool (*checker)(char*));
AxisMaskSetting(type_t type, permissions_t permissions, const char* grblName, const char* name, int32_t defVal, bool (*checker)(char *) = NULL)
: AxisMaskSetting(NULL, type, permissions, grblName, name, defVal, checker)
{ }
AxisMaskSetting(
type_t type, permissions_t permissions, const char* grblName, const char* name, int32_t defVal, bool (*checker)(char*) = NULL) :
AxisMaskSetting(NULL, type, permissions, grblName, name, defVal, checker) {}
void load();
void setDefault();
void addWebui(JSONencoder *);
err_t setStringValue(char* value);
void load();
void setDefault();
void addWebui(JSONencoder*);
err_t setStringValue(char* value);
const char* getCompatibleValue();
const char* getStringValue();
int32_t get() { return _currentValue; }
int32_t get() { return _currentValue; }
};
class FloatSetting : public Setting {
@ -187,21 +208,36 @@ private:
float _storedValue;
float _minValue;
float _maxValue;
public:
FloatSetting(const char *description, type_t type, permissions_t permissions, const char* grblName, const char* name, float defVal, float minVal, float maxVal, bool (*checker)(char *));
FloatSetting(type_t type, permissions_t permissions, const char* grblName, const char* name, float defVal, float minVal, float maxVal, bool (*checker)(char *) = NULL)
: FloatSetting(NULL, type, permissions, grblName, name, defVal, minVal, maxVal, checker)
{ }
public:
FloatSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
float defVal,
float minVal,
float maxVal,
bool (*checker)(char*));
FloatSetting(type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
float defVal,
float minVal,
float maxVal,
bool (*checker)(char*) = NULL) :
FloatSetting(NULL, type, permissions, grblName, name, defVal, minVal, maxVal, checker) {}
void load();
void setDefault();
// There are no Float settings in WebUI
void addWebui(JSONencoder *) {}
err_t setStringValue(char* value);
void addWebui(JSONencoder*) {}
err_t setStringValue(char* value);
const char* getStringValue();
float get() { return _currentValue; }
float get() { return _currentValue; }
};
#define MAX_SETTING_STRING 256
@ -210,76 +246,93 @@ private:
String _defaultValue;
String _currentValue;
String _storedValue;
int _minLength;
int _maxLength;
void _setStoredValue(const char *s);
int _minLength;
int _maxLength;
void _setStoredValue(const char* s);
public:
StringSetting(const char *description, type_t type, permissions_t permissions, const char* grblName, const char* name, const char* defVal, int min, int max, bool (*checker)(char *));
StringSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
const char* defVal,
int min,
int max,
bool (*checker)(char*));
StringSetting(type_t type, permissions_t permissions, const char* grblName, const char* name, const char* defVal, bool (*checker)(char *) = NULL)
: StringSetting(NULL, type, permissions, grblName, name, defVal, 0, 0, checker)
{ };
StringSetting(
type_t type, permissions_t permissions, const char* grblName, const char* name, const char* defVal, bool (*checker)(char*) = NULL) :
StringSetting(NULL, type, permissions, grblName, name, defVal, 0, 0, checker) {};
void load();
void setDefault();
void addWebui(JSONencoder *);
err_t setStringValue(char* value);
void load();
void setDefault();
void addWebui(JSONencoder*);
err_t setStringValue(char* value);
const char* getStringValue();
const char* get() { return _currentValue.c_str(); }
const char* get() { return _currentValue.c_str(); }
};
struct cmp_str
{
bool operator()(char const *a, char const *b) const
{
return strcasecmp(a, b) < 0;
}
struct cmp_str {
bool operator()(char const* a, char const* b) const { return strcasecmp(a, b) < 0; }
};
typedef std::map<const char *, int8_t, cmp_str> enum_opt_t;
typedef std::map<const char*, int8_t, cmp_str> enum_opt_t;
class EnumSetting : public Setting {
private:
int8_t _defaultValue;
int8_t _storedValue;
int8_t _currentValue;
std::map<const char *, int8_t, cmp_str>* _options;
int8_t _defaultValue;
int8_t _storedValue;
int8_t _currentValue;
std::map<const char*, int8_t, cmp_str>* _options;
public:
EnumSetting(const char *description, type_t type, permissions_t permissions, const char* grblName, const char* name, int8_t defVal, enum_opt_t* opts);
EnumSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
int8_t defVal,
enum_opt_t* opts);
EnumSetting(type_t type, permissions_t permissions, const char* grblName, const char* name, int8_t defVal, enum_opt_t* opts) :
EnumSetting(NULL, type, permissions, grblName, name, defVal, opts)
{ }
EnumSetting(NULL, type, permissions, grblName, name, defVal, opts) {}
void load();
void setDefault();
void addWebui(JSONencoder *);
err_t setStringValue(char* value);
void load();
void setDefault();
void addWebui(JSONencoder*);
err_t setStringValue(char* value);
const char* getStringValue();
int8_t get() { return _currentValue; }
int8_t get() { return _currentValue; }
};
class FlagSetting : public Setting {
private:
bool _defaultValue;
bool _defaultValue;
int8_t _storedValue;
bool _currentValue;
bool _currentValue;
public:
FlagSetting(const char *description, type_t type, permissions_t permissions, const char* grblName, const char* name, bool defVal, bool (*checker)(char *));
FlagSetting(type_t type, permissions_t permissions, const char* grblName, const char* name, bool defVal, bool (*checker)(char *) = NULL)
: FlagSetting(NULL, type, permissions, grblName, name, defVal, checker)
{ }
FlagSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
bool defVal,
bool (*checker)(char*));
FlagSetting(type_t type, permissions_t permissions, const char* grblName, const char* name, bool defVal, bool (*checker)(char*) = NULL) :
FlagSetting(NULL, type, permissions, grblName, name, defVal, checker) {}
void load();
void setDefault();
// There are no Flag settings in WebUI
// The booleans are expressed as Enums
void addWebui(JSONencoder *) {}
err_t setStringValue(char* value);
void addWebui(JSONencoder*) {}
err_t setStringValue(char* value);
const char* getCompatibleValue();
const char* getStringValue();
bool get() { return _currentValue; }
bool get() { return _currentValue; }
};
class IPaddrSetting : public Setting {
@ -289,64 +342,83 @@ private:
uint32_t _storedValue;
public:
IPaddrSetting(const char *description, type_t type, permissions_t permissions, const char * grblName, const char* name, uint32_t defVal, bool (*checker)(char *));
IPaddrSetting(const char *description, type_t type, permissions_t permissions, const char * grblName, const char* name, const char *defVal, bool (*checker)(char *));
IPaddrSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
uint32_t defVal,
bool (*checker)(char*));
IPaddrSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
const char* defVal,
bool (*checker)(char*));
void load();
void setDefault();
void addWebui(JSONencoder *);
err_t setStringValue(char* value);
void load();
void setDefault();
void addWebui(JSONencoder*);
err_t setStringValue(char* value);
const char* getStringValue();
uint32_t get() { return _currentValue; }
uint32_t get() { return _currentValue; }
};
class AxisSettings {
public:
const char* name;
FloatSetting *steps_per_mm;
FloatSetting *max_rate;
FloatSetting *acceleration;
FloatSetting *max_travel;
FloatSetting *run_current;
FloatSetting *hold_current;
IntSetting *microsteps;
IntSetting *stallguard;
const char* name;
FloatSetting* steps_per_mm;
FloatSetting* max_rate;
FloatSetting* acceleration;
FloatSetting* max_travel;
FloatSetting* run_current;
FloatSetting* hold_current;
IntSetting* microsteps;
IntSetting* stallguard;
AxisSettings(const char *axisName);
AxisSettings(const char* axisName);
};
class WebCommand : public Command {
private:
err_t (*_action)(char *, auth_t);
const char* password;
public:
WebCommand(const char* description, type_t type, permissions_t permissions, const char * grblName, const char* name, err_t (*action)(char *, auth_t)) :
private:
err_t (*_action)(char*, auth_t);
const char* password;
public:
WebCommand(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
err_t (*action)(char*, auth_t)) :
Command(description, type, permissions, grblName, name),
_action(action)
{}
_action(action) {}
err_t action(char* value, auth_t auth_level, ESPResponseStream* response);
};
enum : uint8_t {
ANY_STATE = 0,
IDLE_OR_ALARM = 0xff & ~STATE_ALARM,
IDLE_OR_JOG = 0xff & ~STATE_JOG,
ANY_STATE = 0,
IDLE_OR_ALARM = 0xff & ~STATE_ALARM,
IDLE_OR_JOG = 0xff & ~STATE_JOG,
NOT_CYCLE_OR_HOLD = STATE_CYCLE | STATE_HOLD,
};
class GrblCommand : public Command {
private:
err_t (*_action)(const char *, auth_t, ESPResponseStream*);
uint8_t _disallowedStates;
public:
GrblCommand(const char * grblName, const char* name, err_t (*action)(const char*, auth_t, ESPResponseStream*), uint8_t disallowedStates, permissions_t auth)
: Command(NULL, GRBLCMD, auth, grblName, name)
, _action(action)
, _disallowedStates(disallowedStates)
{}
private:
err_t (*_action)(const char*, auth_t, ESPResponseStream*);
uint8_t _disallowedStates;
GrblCommand(const char * grblName, const char* name, err_t (*action)(const char*, auth_t, ESPResponseStream*), uint8_t disallowedStates)
: GrblCommand(grblName, name, action, disallowedStates, WG)
{}
public:
GrblCommand(const char* grblName,
const char* name,
err_t (*action)(const char*, auth_t, ESPResponseStream*),
uint8_t disallowedStates,
permissions_t auth) :
Command(NULL, GRBLCMD, auth, grblName, name),
_action(action), _disallowedStates(disallowedStates) {}
GrblCommand(const char* grblName, const char* name, err_t (*action)(const char*, auth_t, ESPResponseStream*), uint8_t disallowedStates) :
GrblCommand(grblName, name, action, disallowedStates, WG) {}
err_t action(char* value, auth_t auth_level, ESPResponseStream* response);
};

View File

@ -28,7 +28,7 @@ FlagSetting* homing_enable;
FlagSetting* laser_mode;
// TODO Settings - also need to call my_spindle->init;
IntSetting* status_mask;
IntSetting* status_mask;
FloatSetting* junction_deviation;
FloatSetting* arc_tolerance;
@ -45,19 +45,21 @@ FloatSetting* spindle_delay_spindown;
FloatSetting* spindle_pwm_off_value;
FloatSetting* spindle_pwm_min_value;
FloatSetting* spindle_pwm_max_value;
IntSetting* spindle_pwm_bit_precision;
IntSetting* spindle_pwm_bit_precision;
EnumSetting* spindle_type;
enum_opt_t spindleTypes = {
{ "NONE", SPINDLE_TYPE_NONE, },
{ "PWM", SPINDLE_TYPE_PWM, },
{ "RELAY", SPINDLE_TYPE_RELAY, },
{ "LASER", SPINDLE_TYPE_LASER, },
{ "DAC", SPINDLE_TYPE_DAC, },
{ "HUANYANG", SPINDLE_TYPE_HUANYANG, },
{ "BESC", SPINDLE_TYPE_BESC, },
{ "10V", SPINDLE_TYPE_10V, },
// clang-format off
{ "NONE", SPINDLE_TYPE_NONE },
{ "PWM", SPINDLE_TYPE_PWM },
{ "RELAY", SPINDLE_TYPE_RELAY },
{ "LASER", SPINDLE_TYPE_LASER },
{ "DAC", SPINDLE_TYPE_DAC },
{ "HUANYANG", SPINDLE_TYPE_HUANYANG },
{ "BESC", SPINDLE_TYPE_BESC },
{ "10V", SPINDLE_TYPE_10V },
// clang-format on
};
AxisSettings* x_axis_settings;
@ -71,89 +73,75 @@ AxisSettings* axis_settings[MAX_N_AXIS];
typedef struct {
const char* name;
float steps_per_mm;
float max_rate;
float acceleration;
float max_travel;
float run_current;
float hold_current;
uint16_t microsteps;
uint16_t stallguard;
float steps_per_mm;
float max_rate;
float acceleration;
float max_travel;
float run_current;
float hold_current;
uint16_t microsteps;
uint16_t stallguard;
} axis_defaults_t;
axis_defaults_t axis_defaults[] = {
{
"X",
DEFAULT_X_STEPS_PER_MM,
DEFAULT_X_MAX_RATE,
DEFAULT_X_ACCELERATION,
DEFAULT_X_MAX_TRAVEL,
DEFAULT_X_CURRENT,
DEFAULT_X_HOLD_CURRENT,
DEFAULT_X_MICROSTEPS,
DEFAULT_X_STALLGUARD
},
{
"Y",
DEFAULT_Y_STEPS_PER_MM,
DEFAULT_Y_MAX_RATE,
DEFAULT_Y_ACCELERATION,
DEFAULT_Y_MAX_TRAVEL,
DEFAULT_Y_CURRENT,
DEFAULT_Y_HOLD_CURRENT,
DEFAULT_Y_MICROSTEPS,
DEFAULT_Y_STALLGUARD
},
{
"Z",
DEFAULT_Z_STEPS_PER_MM,
DEFAULT_Z_MAX_RATE,
DEFAULT_Z_ACCELERATION,
DEFAULT_Z_MAX_TRAVEL,
DEFAULT_Z_CURRENT,
DEFAULT_Z_HOLD_CURRENT,
DEFAULT_Z_MICROSTEPS,
DEFAULT_Z_STALLGUARD
},
{
"A",
DEFAULT_A_STEPS_PER_MM,
DEFAULT_A_MAX_RATE,
DEFAULT_A_ACCELERATION,
DEFAULT_A_MAX_TRAVEL,
DEFAULT_A_CURRENT,
DEFAULT_A_HOLD_CURRENT,
DEFAULT_A_MICROSTEPS,
DEFAULT_A_STALLGUARD
},
{
"B",
DEFAULT_B_STEPS_PER_MM,
DEFAULT_B_MAX_RATE,
DEFAULT_B_ACCELERATION,
DEFAULT_B_MAX_TRAVEL,
DEFAULT_B_CURRENT,
DEFAULT_B_HOLD_CURRENT,
DEFAULT_B_MICROSTEPS,
DEFAULT_B_STALLGUARD
},
{
"C",
DEFAULT_C_STEPS_PER_MM,
DEFAULT_C_MAX_RATE,
DEFAULT_C_ACCELERATION,
DEFAULT_C_MAX_TRAVEL,
DEFAULT_C_CURRENT,
DEFAULT_C_HOLD_CURRENT,
DEFAULT_C_MICROSTEPS,
DEFAULT_C_STALLGUARD
}
};
axis_defaults_t axis_defaults[] = { { "X",
DEFAULT_X_STEPS_PER_MM,
DEFAULT_X_MAX_RATE,
DEFAULT_X_ACCELERATION,
DEFAULT_X_MAX_TRAVEL,
DEFAULT_X_CURRENT,
DEFAULT_X_HOLD_CURRENT,
DEFAULT_X_MICROSTEPS,
DEFAULT_X_STALLGUARD },
{ "Y",
DEFAULT_Y_STEPS_PER_MM,
DEFAULT_Y_MAX_RATE,
DEFAULT_Y_ACCELERATION,
DEFAULT_Y_MAX_TRAVEL,
DEFAULT_Y_CURRENT,
DEFAULT_Y_HOLD_CURRENT,
DEFAULT_Y_MICROSTEPS,
DEFAULT_Y_STALLGUARD },
{ "Z",
DEFAULT_Z_STEPS_PER_MM,
DEFAULT_Z_MAX_RATE,
DEFAULT_Z_ACCELERATION,
DEFAULT_Z_MAX_TRAVEL,
DEFAULT_Z_CURRENT,
DEFAULT_Z_HOLD_CURRENT,
DEFAULT_Z_MICROSTEPS,
DEFAULT_Z_STALLGUARD },
{ "A",
DEFAULT_A_STEPS_PER_MM,
DEFAULT_A_MAX_RATE,
DEFAULT_A_ACCELERATION,
DEFAULT_A_MAX_TRAVEL,
DEFAULT_A_CURRENT,
DEFAULT_A_HOLD_CURRENT,
DEFAULT_A_MICROSTEPS,
DEFAULT_A_STALLGUARD },
{ "B",
DEFAULT_B_STEPS_PER_MM,
DEFAULT_B_MAX_RATE,
DEFAULT_B_ACCELERATION,
DEFAULT_B_MAX_TRAVEL,
DEFAULT_B_CURRENT,
DEFAULT_B_HOLD_CURRENT,
DEFAULT_B_MICROSTEPS,
DEFAULT_B_STALLGUARD },
{ "C",
DEFAULT_C_STEPS_PER_MM,
DEFAULT_C_MAX_RATE,
DEFAULT_C_ACCELERATION,
DEFAULT_C_MAX_TRAVEL,
DEFAULT_C_CURRENT,
DEFAULT_C_HOLD_CURRENT,
DEFAULT_C_MICROSTEPS,
DEFAULT_C_STALLGUARD } };
// Construct e.g. X_MAX_RATE from axisName "X" and tail "_MAX_RATE"
// in dynamically allocated memory that will not be freed.
static const char *makename(const char *axisName, const char *tail) {
char* retval = (char *)malloc(strlen(axisName) + strlen(tail) + 2);
static const char* makename(const char* axisName, const char* tail) {
char* retval = (char*)malloc(strlen(axisName) + strlen(tail) + 2);
strcpy(retval, axisName);
strcat(retval, "/");
@ -186,7 +174,6 @@ static bool checkHoldcurrent(char* value) {
return true;
}
static bool checkStallguardDebugMask(char* val) {
motorSettingChanged = true;
return true;
@ -207,10 +194,10 @@ void make_settings() {
// Create the axis settings in the order that people are
// accustomed to seeing.
int axis;
int axis;
axis_defaults_t* def;
for (axis = 0; axis < N_AXIS; axis++) {
def = &axis_defaults[axis];
def = &axis_defaults[axis];
axis_settings[axis] = new AxisSettings(def->name);
}
x_axis_settings = axis_settings[X_AXIS];
@ -220,50 +207,56 @@ void make_settings() {
b_axis_settings = axis_settings[B_AXIS];
c_axis_settings = axis_settings[C_AXIS];
for (axis = N_AXIS - 1; axis >= 0; axis--) {
def = &axis_defaults[axis];
auto setting = new IntSetting(EXTENDED, WG, makeGrblName(axis, 170), makename(def->name, "StallGuard"), def->stallguard, -64, 63, checkStallguard);
def = &axis_defaults[axis];
auto setting = new IntSetting(
EXTENDED, WG, makeGrblName(axis, 170), makename(def->name, "StallGuard"), def->stallguard, -64, 63, checkStallguard);
setting->setAxis(axis);
axis_settings[axis]->stallguard = setting;
}
for (axis = N_AXIS - 1; axis >= 0; axis--) {
def = &axis_defaults[axis];
auto setting = new IntSetting(EXTENDED, WG, makeGrblName(axis, 160), makename(def->name, "Microsteps"), def->microsteps, 0, 256, checkMicrosteps);
def = &axis_defaults[axis];
auto setting = new IntSetting(
EXTENDED, WG, makeGrblName(axis, 160), makename(def->name, "Microsteps"), def->microsteps, 0, 256, checkMicrosteps);
setting->setAxis(axis);
axis_settings[axis]->microsteps = setting;
}
for (axis = N_AXIS - 1; axis >= 0; axis--) {
def = &axis_defaults[axis];
auto setting = new FloatSetting(EXTENDED, WG, makeGrblName(axis, 150), makename(def->name, "Current/Hold"), def->hold_current, 0.05, 20.0, checkHoldcurrent); // Amps
def = &axis_defaults[axis];
auto setting = new FloatSetting(
EXTENDED, WG, makeGrblName(axis, 150), makename(def->name, "Current/Hold"), def->hold_current, 0.05, 20.0, checkHoldcurrent); // Amps
setting->setAxis(axis);
axis_settings[axis]->hold_current = setting;
}
for (axis = N_AXIS - 1; axis >= 0; axis--) {
def = &axis_defaults[axis];
auto setting = new FloatSetting(EXTENDED, WG, makeGrblName(axis, 140), makename(def->name, "Current/Run"), def->run_current, 0.0, 20.0, checkRunCurrent); // Amps
def = &axis_defaults[axis];
auto setting = new FloatSetting(
EXTENDED, WG, makeGrblName(axis, 140), makename(def->name, "Current/Run"), def->run_current, 0.0, 20.0, checkRunCurrent); // Amps
setting->setAxis(axis);
axis_settings[axis]->run_current = setting;
}
for (axis = N_AXIS - 1; axis >= 0; axis--) {
def = &axis_defaults[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);
setting->setAxis(axis);
axis_settings[axis]->max_travel = setting;
}
for (axis = N_AXIS - 1; axis >= 0; axis--) {
def = &axis_defaults[axis];
auto setting = new FloatSetting(GRBL, WG, makeGrblName(axis, 120), makename(def->name, "Acceleration"), def->acceleration, 1.0, 100000.0);
auto setting =
new FloatSetting(GRBL, WG, makeGrblName(axis, 120), makename(def->name, "Acceleration"), def->acceleration, 1.0, 100000.0);
setting->setAxis(axis);
axis_settings[axis]->acceleration = setting;
}
for (axis = N_AXIS - 1; axis >= 0; axis--) {
def = &axis_defaults[axis];
def = &axis_defaults[axis];
auto setting = new FloatSetting(GRBL, WG, makeGrblName(axis, 110), makename(def->name, "MaxRate"), def->max_rate, 1.0, 100000.0);
setting->setAxis(axis);
axis_settings[axis]->max_rate = setting;
}
for (axis = N_AXIS - 1; axis >= 0; axis--) {
def = &axis_defaults[axis];
auto setting = new FloatSetting(GRBL, WG, makeGrblName(axis, 100), makename(def->name, "StepsPerMm"), def->steps_per_mm, 1.0, 100000.0);
auto setting =
new FloatSetting(GRBL, WG, makeGrblName(axis, 100), makename(def->name, "StepsPerMm"), def->steps_per_mm, 1.0, 100000.0);
setting->setAxis(axis);
axis_settings[axis]->steps_per_mm = setting;
}
@ -271,10 +264,11 @@ void make_settings() {
// Spindle Settings
spindle_pwm_max_value = new FloatSetting(EXTENDED, WG, "36", "Spindle/PWM/Max", DEFAULT_SPINDLE_MAX_VALUE, 0.0, 100.0);
spindle_pwm_min_value = new FloatSetting(EXTENDED, WG, "35", "Spindle/PWM/Min", DEFAULT_SPINDLE_MIN_VALUE, 0.0, 100.0);
spindle_pwm_off_value = new FloatSetting(EXTENDED, WG, "34", "Spindle/PWM/Off", DEFAULT_SPINDLE_OFF_VALUE, 0.0, 100.0); // these are percentages
spindle_pwm_off_value =
new FloatSetting(EXTENDED, WG, "34", "Spindle/PWM/Off", DEFAULT_SPINDLE_OFF_VALUE, 0.0, 100.0); // these are percentages
// IntSetting spindle_pwm_bit_precision(EXTENDED, WG, "Spindle/PWM/Precision", DEFAULT_SPINDLE_BIT_PRECISION, 1, 16);
spindle_pwm_freq = new FloatSetting(EXTENDED, WG, "33", "Spindle/PWM/Frequency", DEFAULT_SPINDLE_FREQ, 0, 100000);
spindle_delay_spinup = new FloatSetting(EXTENDED, WG, NULL, "Spindle/Delay/SpinUp", DEFAULT_SPINDLE_DELAY_SPINUP, 0, 30);
spindle_pwm_freq = new FloatSetting(EXTENDED, WG, "33", "Spindle/PWM/Frequency", DEFAULT_SPINDLE_FREQ, 0, 100000);
spindle_delay_spinup = new FloatSetting(EXTENDED, WG, NULL, "Spindle/Delay/SpinUp", DEFAULT_SPINDLE_DELAY_SPINUP, 0, 30);
spindle_delay_spindown = new FloatSetting(EXTENDED, WG, NULL, "Spindle/Delay/SpinDown", DEFAULT_SPINDLE_DELAY_SPINUP, 0, 30);
// GRBL Non-numbered settings
@ -287,9 +281,8 @@ void make_settings() {
rpm_min = new FloatSetting(GRBL, WG, "31", "GCode/MinS", DEFAULT_SPINDLE_RPM_MIN, 0, 100000);
rpm_max = new FloatSetting(GRBL, WG, "30", "GCode/MaxS", DEFAULT_SPINDLE_RPM_MAX, 0, 100000);
homing_pulloff = new FloatSetting(GRBL, WG, "27", "Homing/Pulloff", DEFAULT_HOMING_PULLOFF, 0, 1000);
homing_debounce = new FloatSetting(GRBL, WG, "26", "Homing/Debounce", DEFAULT_HOMING_DEBOUNCE_DELAY, 0, 10000);
homing_pulloff = new FloatSetting(GRBL, WG, "27", "Homing/Pulloff", DEFAULT_HOMING_PULLOFF, 0, 1000);
homing_debounce = new FloatSetting(GRBL, WG, "26", "Homing/Debounce", DEFAULT_HOMING_DEBOUNCE_DELAY, 0, 10000);
homing_seek_rate = new FloatSetting(GRBL, WG, "25", "Homing/Seek", DEFAULT_HOMING_SEEK_RATE, 0, 10000);
homing_feed_rate = new FloatSetting(GRBL, WG, "24", "Homing/Feed", DEFAULT_HOMING_FEED_RATE, 0, 10000);
@ -304,17 +297,17 @@ void make_settings() {
report_inches = new FlagSetting(GRBL, WG, "13", "Report/Inches", DEFAULT_REPORT_INCHES);
// TODO Settings - also need to clear, but not set, soft_limits
arc_tolerance = new FloatSetting(GRBL, WG, "12", "GCode/ArcTolerance", DEFAULT_ARC_TOLERANCE, 0, 1);
arc_tolerance = new FloatSetting(GRBL, WG, "12", "GCode/ArcTolerance", DEFAULT_ARC_TOLERANCE, 0, 1);
junction_deviation = new FloatSetting(GRBL, WG, "11", "GCode/JunctionDeviation", DEFAULT_JUNCTION_DEVIATION, 0, 10);
status_mask = new IntSetting(GRBL, WG, "10", "Report/Status", DEFAULT_STATUS_REPORT_MASK, 0, 2);
status_mask = new IntSetting(GRBL, WG, "10", "Report/Status", DEFAULT_STATUS_REPORT_MASK, 0, 2);
probe_invert = new FlagSetting(GRBL, WG, "6", "Probe/Invert", DEFAULT_INVERT_PROBE_PIN);
limit_invert = new FlagSetting(GRBL, WG, "5", "Limits/Invert", DEFAULT_INVERT_LIMIT_PINS);
step_enable_invert = new FlagSetting(GRBL, WG, "4", "Stepper/EnableInvert", DEFAULT_INVERT_ST_ENABLE);
dir_invert_mask = new AxisMaskSetting(GRBL, WG, "3", "Stepper/DirInvert", DEFAULT_DIRECTION_INVERT_MASK);
step_invert_mask = new AxisMaskSetting(GRBL, WG, "2", "Stepper/StepInvert", DEFAULT_STEPPING_INVERT_MASK);
probe_invert = new FlagSetting(GRBL, WG, "6", "Probe/Invert", DEFAULT_INVERT_PROBE_PIN);
limit_invert = new FlagSetting(GRBL, WG, "5", "Limits/Invert", DEFAULT_INVERT_LIMIT_PINS);
step_enable_invert = new FlagSetting(GRBL, WG, "4", "Stepper/EnableInvert", DEFAULT_INVERT_ST_ENABLE);
dir_invert_mask = new AxisMaskSetting(GRBL, WG, "3", "Stepper/DirInvert", DEFAULT_DIRECTION_INVERT_MASK);
step_invert_mask = new AxisMaskSetting(GRBL, WG, "2", "Stepper/StepInvert", DEFAULT_STEPPING_INVERT_MASK);
stepper_idle_lock_time = new IntSetting(GRBL, WG, "1", "Stepper/IdleTime", DEFAULT_STEPPER_IDLE_LOCK_TIME, 0, 255);
pulse_microseconds = new IntSetting(GRBL, WG, "0", "Stepper/Pulse", DEFAULT_STEP_PULSE_MICROSECONDS, 3, 1000);
spindle_type = new EnumSetting(NULL, EXTENDED, WG, NULL, "Spindle/Type", SPINDLE_TYPE, &spindleTypes);
stallguard_debug_mask = new AxisMaskSetting(EXTENDED, WG, NULL, "Report/StallGuard", 0, checkStallguardDebugMask);
pulse_microseconds = new IntSetting(GRBL, WG, "0", "Stepper/Pulse", DEFAULT_STEP_PULSE_MICROSECONDS, 3, 1000);
spindle_type = new EnumSetting(NULL, EXTENDED, WG, NULL, "Spindle/Type", SPINDLE_TYPE, &spindleTypes);
stallguard_debug_mask = new AxisMaskSetting(EXTENDED, WG, NULL, "Report/StallGuard", 0, checkStallguardDebugMask);
}

View File

@ -30,7 +30,7 @@ extern FlagSetting* hard_limits;
extern FlagSetting* homing_enable;
extern FlagSetting* laser_mode;
extern IntSetting* status_mask;
extern IntSetting* status_mask;
extern FloatSetting* junction_deviation;
extern FloatSetting* arc_tolerance;
@ -47,7 +47,7 @@ extern FloatSetting* spindle_delay_spindown;
extern FloatSetting* spindle_pwm_off_value;
extern FloatSetting* spindle_pwm_min_value;
extern FloatSetting* spindle_pwm_max_value;
extern IntSetting* spindle_pwm_bit_precision;
extern IntSetting* spindle_pwm_bit_precision;
extern EnumSetting* spindle_type;

View File

@ -29,11 +29,8 @@
*/
#include "SpindleClass.h"
void _10vSpindle :: init() {
get_pins_and_settings(); // these gets the standard PWM settings, but many need to be changed for BESC
void _10vSpindle ::init() {
get_pins_and_settings(); // these gets the standard PWM settings, but many need to be changed for BESC
// a couple more pins not inherited from PWM Spindle
#ifdef SPINDLE_FORWARD_PIN
@ -48,14 +45,13 @@ void _10vSpindle :: init() {
_reverse_pin = UNDEFINED_PIN;
#endif
if (_output_pin == UNDEFINED_PIN) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: BESC output pin not defined");
return; // We cannot continue without the output pin
return; // We cannot continue without the output pin
}
ledcSetup(_spindle_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
ledcAttachPin(_output_pin, _spindle_pwm_chan_num); // attach the PWM to the pin
ledcSetup(_spindle_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
ledcAttachPin(_output_pin, _spindle_pwm_chan_num); // attach the PWM to the pin
pinMode(_enable_pin, OUTPUT);
pinMode(_direction_pin, OUTPUT);
@ -66,13 +62,12 @@ void _10vSpindle :: init() {
config_message();
is_reversable = true; // these VFDs are always reversable
use_delays = true;
is_reversable = true; // these VFDs are always reversable
use_delays = true;
}
// prints the startup message of the spindle config
void _10vSpindle :: config_message() {
void _10vSpindle ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"0-10V spindle Out:%s Enbl:%s, Dir:%s, Fwd:%s, Rev:%s, Freq:%dHz Res:%dbits",
@ -92,7 +87,7 @@ uint32_t _10vSpindle::set_rpm(uint32_t rpm) {
return rpm;
// apply speed overrides
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (percent)
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (percent)
// apply limits limits
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm))
@ -130,9 +125,8 @@ void _10vSpindle::set_state(uint8_t state, uint32_t rpm) {
*/
uint8_t _10vSpindle::get_state() {
if (_current_pwm_duty == 0 || _output_pin == UNDEFINED_PIN)
if (_current_pwm_duty == 0 || _output_pin == UNDEFINED_PIN)
return (SPINDLE_STATE_DISABLE);
if (_direction_pin != UNDEFINED_PIN)
return digitalRead(_direction_pin) ? SPINDLE_STATE_CW : SPINDLE_STATE_CCW;
@ -147,7 +141,7 @@ void _10vSpindle::stop() {
void _10vSpindle::set_enable_pin(bool enable) {
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "_10vSpindle::set_enable_pin");
if (_off_with_zero_speed && sys.spindle_speed == 0)
if (_off_with_zero_speed && sys.spindle_speed == 0)
enable = false;
#ifdef INVERT_SPINDLE_ENABLE_PIN
@ -167,6 +161,5 @@ void _10vSpindle::set_spindle_dir_pin(bool Clockwise) {
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "_10vSpindle::set_spindle_dir_pin");
digitalWrite(_direction_pin, Clockwise);
digitalWrite(_forward_pin, Clockwise);
digitalWrite(_reverse_pin, ! Clockwise);
digitalWrite(_reverse_pin, !Clockwise);
}

View File

@ -32,37 +32,35 @@
*/
#include "SpindleClass.h"
// don't change these
#define BESC_PWM_FREQ 50.0f // Hz
#define BESC_PWM_BIT_PRECISION 16 // bits
#define BESC_PULSE_PERIOD (1.0 / BESC_PWM_FREQ)
#define BESC_PWM_FREQ 50.0f // Hz
#define BESC_PWM_BIT_PRECISION 16 // bits
#define BESC_PULSE_PERIOD (1.0 / BESC_PWM_FREQ)
// Ok to tweak. These are the pulse lengths in seconds
// #define them in your machine definition file if you want different values
#ifndef BESC_MIN_PULSE_SECS
#define BESC_MIN_PULSE_SECS 0.0009f // in seconds
# define BESC_MIN_PULSE_SECS 0.0009f // in seconds
#endif
#ifndef BESC_MAX_PULSE_SECS
#define BESC_MAX_PULSE_SECS 0.0022f // in seconds
# define BESC_MAX_PULSE_SECS 0.0022f // in seconds
#endif
//calculations...don't change
#define BESC_MIN_PULSE_CNT (uint16_t)(BESC_MIN_PULSE_SECS / BESC_PULSE_PERIOD * 65535.0)
#define BESC_MAX_PULSE_CNT (uint16_t)(BESC_MAX_PULSE_SECS / BESC_PULSE_PERIOD * 65535.0)
#define BESC_MIN_PULSE_CNT (uint16_t)(BESC_MIN_PULSE_SECS / BESC_PULSE_PERIOD * 65535.0)
#define BESC_MAX_PULSE_CNT (uint16_t)(BESC_MAX_PULSE_SECS / BESC_PULSE_PERIOD * 65535.0)
void BESCSpindle :: init() {
get_pins_and_settings(); // these gets the standard PWM settings, but many need to be changed for BESC
void BESCSpindle ::init() {
get_pins_and_settings(); // these gets the standard PWM settings, but many need to be changed for BESC
if (_output_pin == UNDEFINED_PIN) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: BESC output pin not defined");
return; // We cannot continue without the output pin
return; // We cannot continue without the output pin
}
// override some settings to what is required for a BESC
_pwm_freq = (uint32_t)BESC_PWM_FREQ;
_pwm_freq = (uint32_t)BESC_PWM_FREQ;
_pwm_precision = 16;
// override these settings
@ -70,8 +68,8 @@ void BESCSpindle :: init() {
_pwm_min_value = _pwm_off_value;
_pwm_max_value = BESC_MAX_PULSE_CNT;
ledcSetup(_spindle_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
ledcAttachPin(_output_pin, _spindle_pwm_chan_num); // attach the PWM to the pin
ledcSetup(_spindle_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
ledcAttachPin(_output_pin, _spindle_pwm_chan_num); // attach the PWM to the pin
pinMode(_enable_pin, OUTPUT);
@ -83,13 +81,13 @@ void BESCSpindle :: init() {
}
// prints the startup message of the spindle config
void BESCSpindle :: config_message() {
void BESCSpindle ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"BESC spindle on Pin:%s Min:%0.2fms Max:%0.2fms Freq:%dHz Res:%dbits",
pinName(_output_pin).c_str(),
BESC_MIN_PULSE_SECS * 1000.0, // convert to milliseconds
BESC_MAX_PULSE_SECS * 1000.0, // convert to milliseconds
BESC_MIN_PULSE_SECS * 1000.0, // convert to milliseconds
BESC_MAX_PULSE_SECS * 1000.0, // convert to milliseconds
_pwm_freq,
_pwm_precision);
}
@ -101,7 +99,7 @@ uint32_t BESCSpindle::set_rpm(uint32_t rpm) {
return rpm;
// apply speed overrides
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (percent)
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (percent)
// apply limits limits
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm))
@ -111,7 +109,7 @@ uint32_t BESCSpindle::set_rpm(uint32_t rpm) {
sys.spindle_speed = rpm;
// determine the pwm value
if (rpm == 0) {
if (rpm == 0) {
pwm_value = _pwm_off_value;
} else {
pwm_value = map_uint32_t(rpm, _min_rpm, _max_rpm, _pwm_min_value, _pwm_max_value);

View File

@ -24,19 +24,19 @@
#include "SpindleClass.h"
// ======================================== DacSpindle ======================================
void DacSpindle :: init() {
void DacSpindle ::init() {
get_pins_and_settings();
if (_output_pin == UNDEFINED_PIN)
return;
_min_rpm = rpm_min->get();
_max_rpm = rpm_max->get();
_pwm_min_value = 0; // not actually PWM...DAC counts
_pwm_max_value = 255; // not actually PWM...DAC counts
_gpio_ok = true;
_min_rpm = rpm_min->get();
_max_rpm = rpm_max->get();
_pwm_min_value = 0; // not actually PWM...DAC counts
_pwm_max_value = 255; // not actually PWM...DAC counts
_gpio_ok = true;
if (_output_pin != GPIO_NUM_25 && _output_pin != GPIO_NUM_26) { // DAC can only be used on these pins
if (_output_pin != GPIO_NUM_25 && _output_pin != GPIO_NUM_26) { // DAC can only be used on these pins
_gpio_ok = false;
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "DAC spindle pin invalid GPIO_NUM_%d (pin 25 or 26 only)", _output_pin);
return;
@ -46,12 +46,12 @@ void DacSpindle :: init() {
pinMode(_direction_pin, OUTPUT);
is_reversable = (_direction_pin != UNDEFINED_PIN);
use_delays = true;
use_delays = true;
config_message();
}
void DacSpindle :: config_message() {
void DacSpindle ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"DAC spindle Output:%s, Enbl:%s, Dir:%s, Res:8bits",
@ -67,38 +67,38 @@ uint32_t DacSpindle::set_rpm(uint32_t rpm) {
uint32_t pwm_value;
// apply overrides and limits
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (percent)
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (percent)
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm)) {
// No PWM range possible. Set simple on/off spindle control pin state.
sys.spindle_speed = _max_rpm;
pwm_value = _pwm_max_value;
pwm_value = _pwm_max_value;
} else if (rpm <= _min_rpm) {
if (rpm == 0) { // S0 disables spindle
if (rpm == 0) { // S0 disables spindle
sys.spindle_speed = 0;
pwm_value = 0;
} else { // Set minimum PWM output
rpm = _min_rpm;
pwm_value = 0;
} else { // Set minimum PWM output
rpm = _min_rpm;
sys.spindle_speed = rpm;
pwm_value = 0;
pwm_value = 0;
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Spindle RPM less than min RPM:%5.2f %d", rpm, pwm_value);
}
} else {
// Compute intermediate PWM value with linear spindle speed model.
// NOTE: A nonlinear model could be installed here, if required, but keep it VERY light-weight.
sys.spindle_speed = rpm;
pwm_value = map_uint32_t(rpm, _min_rpm, _max_rpm, _pwm_min_value, _pwm_max_value);
}
set_output(pwm_value);
return rpm;
}
void DacSpindle :: set_output(uint32_t duty) {
void DacSpindle ::set_output(uint32_t duty) {
if (_gpio_ok) {
dacWrite(_output_pin, (uint8_t)duty);
dacWrite(_output_pin, (uint8_t)duty);
}
}

View File

@ -113,41 +113,41 @@
#include "driver/uart.h"
#define HUANYANG_UART_PORT UART_NUM_2 // hard coded for this port right now
#define ECHO_TEST_CTS UART_PIN_NO_CHANGE // CTS pin is not used
#define HUANYANG_BUF_SIZE 127
#define HUANYANG_QUEUE_SIZE 10 // numv\ber of commands that can be queued up.
#define RESPONSE_WAIT_TICKS 50 // how long to wait for a response
#define HUANYANG_MAX_MSG_SIZE 16 // more than enough for a modbus message
#define HUANYANG_POLL_RATE 200 // in milliseconds betwwen commands
#define HUANYANG_UART_PORT UART_NUM_2 // hard coded for this port right now
#define ECHO_TEST_CTS UART_PIN_NO_CHANGE // CTS pin is not used
#define HUANYANG_BUF_SIZE 127
#define HUANYANG_QUEUE_SIZE 10 // numv\ber of commands that can be queued up.
#define RESPONSE_WAIT_TICKS 50 // how long to wait for a response
#define HUANYANG_MAX_MSG_SIZE 16 // more than enough for a modbus message
#define HUANYANG_POLL_RATE 200 // in milliseconds betwwen commands
// OK to change these
// #define them in your machine definition file if you want different values
#ifndef HUANYANG_ADDR
#define HUANYANG_ADDR 0x01
# define HUANYANG_ADDR 0x01
#endif
#ifndef HUANYANG_BAUD_RATE
#define HUANYANG_BAUD_RATE 9600 // PD164 setting
# define HUANYANG_BAUD_RATE 9600 // PD164 setting
#endif
// communication task and queue stuff
typedef struct {
uint8_t tx_length;
uint8_t rx_length;
bool critical;
char msg[HUANYANG_MAX_MSG_SIZE];
bool critical;
char msg[HUANYANG_MAX_MSG_SIZE];
} hy_command_t;
typedef enum : uint8_t {
READ_SET_FREQ = 0, // The set frequency
READ_OUTPUT_FREQ = 1, // The current operating frequency
READ_OUTPUT_AMPS = 2, //
READ_SET_RPM = 3, // This is the last requested freq even in off mode
READ_DC_VOLTAGE = 4, //
READ_AC_VOLTAGE = 5, //
READ_CONT = 6, // counting value???
READ_TEMP = 7, //
READ_SET_FREQ = 0, // The set frequency
READ_OUTPUT_FREQ = 1, // The current operating frequency
READ_OUTPUT_AMPS = 2, //
READ_SET_RPM = 3, // This is the last requested freq even in off mode
READ_DC_VOLTAGE = 4, //
READ_AC_VOLTAGE = 5, //
READ_CONT = 6, // counting value???
READ_TEMP = 7, //
} read_register_t;
QueueHandle_t hy_cmd_queue;
@ -158,14 +158,13 @@ bool hy_spindle_ok = true;
// The communications task
void vfd_cmd_task(void* pvParameters) {
static bool unresponsive = false; // to pop off a message once each time it becomes unresponsive
uint8_t reg_item = 0x00;
static bool unresponsive = false; // to pop off a message once each time it becomes unresponsive
uint8_t reg_item = 0x00;
hy_command_t next_cmd;
uint8_t rx_message[HUANYANG_MAX_MSG_SIZE];
uint8_t rx_message[HUANYANG_MAX_MSG_SIZE];
while (true) {
if (xQueueReceive(hy_cmd_queue, &next_cmd, 0) == pdTRUE) {
uart_flush(HUANYANG_UART_PORT);
//report_hex_msg(next_cmd.msg, "Tx: ", next_cmd.tx_length);
uart_write_bytes(HUANYANG_UART_PORT, next_cmd.msg, next_cmd.tx_length);
@ -183,29 +182,27 @@ void vfd_cmd_task(void* pvParameters) {
}
} else {
// success
unresponsive = false;
unresponsive = false;
//report_hex_msg(rx_message, "Rx: ", read_length);
uint32_t ret_value = ((uint32_t)rx_message[4] << 8) + rx_message[5];
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Item:%d value:%05d ", rx_message[3], ret_value);
uint32_t ret_value = ((uint32_t)rx_message[4] << 8) + rx_message[5];
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Item:%d value:%05d ", rx_message[3], ret_value);
}
} else {
HuanyangSpindle :: read_value(reg_item); // only this appears to work all the time. Other registers are flakey.
HuanyangSpindle ::read_value(reg_item); // only this appears to work all the time. Other registers are flakey.
if (reg_item < 0x03)
reg_item++;
else
{
reg_item = 0x00;
else {
reg_item = 0x00;
}
}
vTaskDelay(HUANYANG_POLL_RATE); // TODO: What is the best value here?
vTaskDelay(HUANYANG_POLL_RATE); // TODO: What is the best value here?
}
}
// ================== Class methods ==================================
void HuanyangSpindle :: init() {
void HuanyangSpindle ::init() {
hy_spindle_ok = true; // initialize
// fail if required items are not defined
@ -214,55 +211,46 @@ void HuanyangSpindle :: init() {
return;
}
if (! _task_running) { // init can happen many times, we only want to start one task
if (!_task_running) { // init can happen many times, we only want to start one task
hy_cmd_queue = xQueueCreate(HUANYANG_QUEUE_SIZE, sizeof(hy_command_t));
xTaskCreatePinnedToCore(vfd_cmd_task, // task
"vfd_cmdTaskHandle", // name for task
2048, // size of task stack
NULL, // parameters
1, // priority
xTaskCreatePinnedToCore(vfd_cmd_task, // task
"vfd_cmdTaskHandle", // name for task
2048, // size of task stack
NULL, // parameters
1, // priority
&vfd_cmdTaskHandle,
0 // core
);
0 // core
);
_task_running = true;
}
}
// this allows us to init() again later.
// If you change certain settings, init() gets called agian
uart_driver_delete(HUANYANG_UART_PORT);
uart_config_t uart_config = {
.baud_rate = HUANYANG_BAUD_RATE,
.data_bits = UART_DATA_8_BITS,
.parity = UART_PARITY_DISABLE,
.stop_bits = UART_STOP_BITS_1,
.flow_ctrl = UART_HW_FLOWCTRL_DISABLE,
.baud_rate = HUANYANG_BAUD_RATE,
.data_bits = UART_DATA_8_BITS,
.parity = UART_PARITY_DISABLE,
.stop_bits = UART_STOP_BITS_1,
.flow_ctrl = UART_HW_FLOWCTRL_DISABLE,
.rx_flow_ctrl_thresh = 122,
};
uart_param_config(HUANYANG_UART_PORT, &uart_config);
uart_set_pin(HUANYANG_UART_PORT,
_txd_pin,
_rxd_pin,
_rts_pin,
UART_PIN_NO_CHANGE);
uart_set_pin(HUANYANG_UART_PORT, _txd_pin, _rxd_pin, _rts_pin, UART_PIN_NO_CHANGE);
uart_driver_install(HUANYANG_UART_PORT,
HUANYANG_BUF_SIZE * 2,
0,
0,
NULL,
0);
uart_driver_install(HUANYANG_UART_PORT, HUANYANG_BUF_SIZE * 2, 0, 0, NULL, 0);
uart_set_mode(HUANYANG_UART_PORT, UART_MODE_RS485_HALF_DUPLEX);
is_reversable = true; // these VFDs are always reversable
use_delays = true;
is_reversable = true; // these VFDs are always reversable
use_delays = true;
//
_current_rpm = 0;
_state = SPINDLE_DISABLE;
_state = SPINDLE_DISABLE;
config_message();
}
@ -270,9 +258,7 @@ void HuanyangSpindle :: init() {
// Checks for all the required pin definitions
// It returns a message for each missing pin
// Returns true if all pins are defined.
bool HuanyangSpindle :: get_pins_and_settings() {
bool HuanyangSpindle ::get_pins_and_settings() {
#ifdef HUANYANG_TXD_PIN
_txd_pin = HUANYANG_TXD_PIN;
#else
@ -296,16 +282,16 @@ bool HuanyangSpindle :: get_pins_and_settings() {
if (laser_mode->get()) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Huanyang spindle disabled in laser mode. Set $GCode/LaserMode=Off and restart");
hy_spindle_ok = false;
hy_spindle_ok = false;
}
_min_rpm = rpm_min->get();
_max_rpm = rpm_max->get();
_max_rpm = rpm_max->get();
return hy_spindle_ok;
}
void HuanyangSpindle :: config_message() {
void HuanyangSpindle ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"Huanyang Spindle Tx:%s Rx:%s RTS:%s",
@ -314,15 +300,14 @@ void HuanyangSpindle :: config_message() {
pinName(_rts_pin).c_str());
}
void HuanyangSpindle :: set_state(uint8_t state, uint32_t rpm) {
void HuanyangSpindle ::set_state(uint8_t state, uint32_t rpm) {
if (sys.abort)
return; // Block during abort.
return; // Block during abort.
bool critical = (sys.state == STATE_CYCLE || state != SPINDLE_DISABLE);
if (_current_state != state) { // already at the desired state. This function gets called a lot.
set_mode(state, critical); // critical if we are in a job
if (_current_state != state) { // already at the desired state. This function gets called a lot.
set_mode(state, critical); // critical if we are in a job
set_rpm(rpm);
if (state == SPINDLE_DISABLE) {
sys.spindle_speed = 0;
@ -337,16 +322,16 @@ void HuanyangSpindle :: set_state(uint8_t state, uint32_t rpm) {
set_rpm(rpm);
}
_current_state = state; // store locally for faster get_state()
_current_state = state; // store locally for faster get_state()
sys.report_ovr_counter = 0; // Set to report change immediately
sys.report_ovr_counter = 0; // Set to report change immediately
return;
}
bool HuanyangSpindle :: set_mode(uint8_t mode, bool critical) {
if (!hy_spindle_ok) return false;
bool HuanyangSpindle ::set_mode(uint8_t mode, bool critical) {
if (!hy_spindle_ok)
return false;
hy_command_t mode_cmd;
@ -357,14 +342,14 @@ bool HuanyangSpindle :: set_mode(uint8_t mode, bool critical) {
mode_cmd.msg[1] = 0x03;
mode_cmd.msg[2] = 0x01;
if (mode == SPINDLE_ENABLE_CW)
if (mode == SPINDLE_ENABLE_CW)
mode_cmd.msg[3] = 0x01;
else if (mode == SPINDLE_ENABLE_CCW)
mode_cmd.msg[3] = 0x11;
else { //SPINDLE_DISABLE
mode_cmd.msg[3] = 0x08;
if (! xQueueReset(hy_cmd_queue)) {
else { //SPINDLE_DISABLE
mode_cmd.msg[3] = 0x08;
if (!xQueueReset(hy_cmd_queue)) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "VFD spindle off, queue could not be reset");
}
}
@ -379,14 +364,14 @@ bool HuanyangSpindle :: set_mode(uint8_t mode, bool critical) {
return true;
}
uint32_t HuanyangSpindle :: set_rpm(uint32_t rpm) {
if (!hy_spindle_ok) return 0;
uint32_t HuanyangSpindle ::set_rpm(uint32_t rpm) {
if (!hy_spindle_ok)
return 0;
hy_command_t rpm_cmd;
// apply override
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (uint8_t percent)
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (uint8_t percent)
// apply limits
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm))
@ -396,8 +381,8 @@ uint32_t HuanyangSpindle :: set_rpm(uint32_t rpm) {
sys.spindle_speed = rpm;
if (rpm == _current_rpm) // prevent setting same RPM twice
return rpm;
if (rpm == _current_rpm) // prevent setting same RPM twice
return rpm;
_current_rpm = rpm;
@ -410,7 +395,7 @@ uint32_t HuanyangSpindle :: set_rpm(uint32_t rpm) {
rpm_cmd.msg[1] = 0x05;
rpm_cmd.msg[2] = 0x02;
uint16_t data = (uint16_t)(rpm * 100 / 60); // send Hz * 10 (Ex:1500 RPM = 25Hz .... Send 2500)
uint16_t data = (uint16_t)(rpm * 100 / 60); // send Hz * 10 (Ex:1500 RPM = 25Hz .... Send 2500)
rpm_cmd.msg[3] = (data & 0xFF00) >> 8;
rpm_cmd.msg[4] = (data & 0xFF);
@ -425,12 +410,11 @@ uint32_t HuanyangSpindle :: set_rpm(uint32_t rpm) {
return rpm;
}
// This appears to read the control register and will return an RPM running or not.
void HuanyangSpindle :: read_value(uint8_t reg) {
uint16_t ret_value = 0;
void HuanyangSpindle ::read_value(uint8_t reg) {
uint16_t ret_value = 0;
hy_command_t read_cmd;
uint8_t rx_message[HUANYANG_MAX_MSG_SIZE];
uint8_t rx_message[HUANYANG_MAX_MSG_SIZE];
read_cmd.tx_length = 8;
read_cmd.rx_length = 8;
@ -444,7 +428,7 @@ void HuanyangSpindle :: read_value(uint8_t reg) {
read_cmd.msg[4] = 0x00;
read_cmd.msg[5] = 0x00;
read_cmd.critical = (sys.state == STATE_CYCLE); // only critical if running a job TBD.... maybe spindle on?
read_cmd.critical = (sys.state == STATE_CYCLE); // only critical if running a job TBD.... maybe spindle on?
add_ModRTU_CRC(read_cmd.msg, read_cmd.tx_length);
@ -452,12 +436,12 @@ void HuanyangSpindle :: read_value(uint8_t reg) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "VFD Queue Full");
}
void HuanyangSpindle ::stop() {
void HuanyangSpindle ::stop() {
set_mode(SPINDLE_DISABLE, false);
}
// state is cached rather than read right now to prevent delays
uint8_t HuanyangSpindle :: get_state() {
uint8_t HuanyangSpindle ::get_state() {
return _state;
}
@ -465,16 +449,16 @@ uint8_t HuanyangSpindle :: get_state() {
// It then added the CRC to those last 2 bytes
// full_msg_len This is the length of the message including the 2 crc bytes
// Source: https://ctlsys.com/support/how_to_compute_the_modbus_rtu_message_crc/
void HuanyangSpindle :: add_ModRTU_CRC(char* buf, int full_msg_len) {
void HuanyangSpindle ::add_ModRTU_CRC(char* buf, int full_msg_len) {
uint16_t crc = 0xFFFF;
for (int pos = 0; pos < full_msg_len - 2; pos++) {
crc ^= (uint16_t)buf[pos]; // XOR byte into least sig. byte of crc
for (int i = 8; i != 0; i--) { // Loop over each bit
if ((crc & 0x0001) != 0) { // If the LSB is set
crc >>= 1; // Shift right and XOR 0xA001
crc ^= (uint16_t)buf[pos]; // XOR byte into least sig. byte of crc
for (int i = 8; i != 0; i--) { // Loop over each bit
if ((crc & 0x0001) != 0) { // If the LSB is set
crc >>= 1; // Shift right and XOR 0xA001
crc ^= 0xA001;
} else // Else LSB is not set
crc >>= 1; // Just shift right
} else // Else LSB is not set
crc >>= 1; // Just shift right
}
}
// add the calculated Crc to the message

View File

@ -23,12 +23,11 @@
// ===================================== Laser ==============================================
bool Laser :: isRateAdjusted() {
return true; // can use M4 (CCW) laser mode.
bool Laser ::isRateAdjusted() {
return true; // can use M4 (CCW) laser mode.
}
void Laser :: config_message() {
void Laser ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"Laser spindle on Pin:%s, Freq:%.2fHz, Res:%dbits Laser mode:$32=%d",
@ -37,5 +36,5 @@ void Laser :: config_message() {
_pwm_precision,
isRateAdjusted()); // the current mode
use_delays = false; // this will override the value set in PWMSpindle intit()
use_delays = false; // this will override the value set in PWMSpindle intit()
}

View File

@ -24,19 +24,19 @@
// ======================= NullSpindle ==============================
// NullSpindle is just bunch of do nothing (ignore) methods to be used when you don't want a spindle
void NullSpindle :: init() {
void NullSpindle ::init() {
is_reversable = false;
use_delays = false;
use_delays = false;
config_message();
}
uint32_t NullSpindle :: set_rpm(uint32_t rpm) {
uint32_t NullSpindle ::set_rpm(uint32_t rpm) {
return rpm;
}
void NullSpindle :: set_state(uint8_t state, uint32_t rpm) {}
uint8_t NullSpindle :: get_state() {
void NullSpindle ::set_state(uint8_t state, uint32_t rpm) {}
uint8_t NullSpindle ::get_state() {
return (SPINDLE_STATE_DISABLE);
}
void NullSpindle :: stop() {}
void NullSpindle :: config_message() {
void NullSpindle ::stop() {}
void NullSpindle ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No spindle");
}

View File

@ -29,13 +29,12 @@
//#include "grbl.h"
void PWMSpindle :: init() {
void PWMSpindle ::init() {
get_pins_and_settings();
if (_output_pin == UNDEFINED_PIN) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: Spindle output pin not defined");
return; // We cannot continue without the output pin
return; // We cannot continue without the output pin
}
if (_output_pin >= I2S_OUT_PIN_BASE) {
@ -43,55 +42,54 @@ void PWMSpindle :: init() {
return;
}
ledcSetup(_spindle_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
ledcAttachPin(_output_pin, _spindle_pwm_chan_num); // attach the PWM to the pin
ledcSetup(_spindle_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
ledcAttachPin(_output_pin, _spindle_pwm_chan_num); // attach the PWM to the pin
pinMode(_enable_pin, OUTPUT);
pinMode(_direction_pin, OUTPUT);
use_delays = true;
config_message();
}
// Get the GPIO from the machine definition
void PWMSpindle :: get_pins_and_settings() {
void PWMSpindle ::get_pins_and_settings() {
// setup all the pins
#ifdef SPINDLE_OUTPUT_PIN
_output_pin = SPINDLE_OUTPUT_PIN;
#else
_output_pin = UNDEFINED_PIN;
_output_pin = UNDEFINED_PIN;
#endif
#ifdef INVERT_SPINDLE_OUTPUT_PIN
_invert_pwm = true;
#else
_invert_pwm = false;
_invert_pwm = false;
#endif
#ifdef SPINDLE_ENABLE_PIN
_enable_pin = SPINDLE_ENABLE_PIN;
#ifdef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
# ifdef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
_off_with_zero_speed = true;
#endif
# endif
#else
_enable_pin = UNDEFINED_PIN;
_enable_pin = UNDEFINED_PIN;
_off_with_zero_speed = false;
#endif
#ifdef SPINDLE_DIR_PIN
_direction_pin = SPINDLE_DIR_PIN;
#else
_direction_pin = UNDEFINED_PIN;
_direction_pin = UNDEFINED_PIN;
#endif
is_reversable = (_direction_pin != UNDEFINED_PIN);
_pwm_freq = spindle_pwm_freq->get();
_pwm_precision = calc_pwm_precision(_pwm_freq); // detewrmine the best precision
_pwm_period = (1 << _pwm_precision);
_pwm_freq = spindle_pwm_freq->get();
_pwm_precision = calc_pwm_precision(_pwm_freq); // detewrmine the best precision
_pwm_period = (1 << _pwm_precision);
if (spindle_pwm_min_value->get() > spindle_pwm_min_value->get())
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: Spindle min pwm is greater than max. Check $35 and $36");
@ -102,20 +100,18 @@ void PWMSpindle :: get_pins_and_settings() {
_pwm_max_value = (_pwm_period * spindle_pwm_max_value->get() / 100.0);
#ifdef ENABLE_PIECEWISE_LINEAR_SPINDLE
_min_rpm = RPM_MIN;
_max_rpm = RPM_MAX;
_min_rpm = RPM_MIN;
_max_rpm = RPM_MAX;
_piecewide_linear = true;
#else
_min_rpm = rpm_min->get();
_max_rpm = rpm_max->get();
_piecewide_linear = false;
_min_rpm = rpm_min->get();
_max_rpm = rpm_max->get();
_piecewide_linear = false;
#endif
// The pwm_gradient is the pwm duty cycle units per rpm
// _pwm_gradient = (_pwm_max_value - _pwm_min_value) / (_max_rpm - _min_rpm);
_spindle_pwm_chan_num = 0; // Channel 0 is reserved for spindle use
_spindle_pwm_chan_num = 0; // Channel 0 is reserved for spindle use
}
uint32_t PWMSpindle::set_rpm(uint32_t rpm) {
@ -127,7 +123,7 @@ uint32_t PWMSpindle::set_rpm(uint32_t rpm) {
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "set_rpm(%d)", rpm);
// apply override
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (uint8_t percent)
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (uint8_t percent)
// apply limits
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm))
@ -156,9 +152,9 @@ uint32_t PWMSpindle::set_rpm(uint32_t rpm) {
void PWMSpindle::set_state(uint8_t state, uint32_t rpm) {
if (sys.abort)
return; // Block during abort.
return; // Block during abort.
if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
sys.spindle_speed = 0;
stop();
if (use_delays && (_current_state != state)) {
@ -169,7 +165,7 @@ void PWMSpindle::set_state(uint8_t state, uint32_t rpm) {
} else {
set_spindle_dir_pin(state == SPINDLE_ENABLE_CW);
set_rpm(rpm);
set_enable_pin(state != SPINDLE_DISABLE); // must be done after setting rpm for enable features to work
set_enable_pin(state != SPINDLE_DISABLE); // must be done after setting rpm for enable features to work
if (use_delays && (_current_state != state)) {
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "SpinUp Start %d", rpm);
mc_dwell(spindle_delay_spinup->get());
@ -179,11 +175,11 @@ void PWMSpindle::set_state(uint8_t state, uint32_t rpm) {
_current_state = state;
sys.report_ovr_counter = 0; // Set to report change immediately
sys.report_ovr_counter = 0; // Set to report change immediately
}
uint8_t PWMSpindle::get_state() {
if (_current_pwm_duty == 0 || _output_pin == UNDEFINED_PIN)
if (_current_pwm_duty == 0 || _output_pin == UNDEFINED_PIN)
return (SPINDLE_STATE_DISABLE);
if (_direction_pin != UNDEFINED_PIN)
return digitalRead(_direction_pin) ? SPINDLE_STATE_CW : SPINDLE_STATE_CCW;
@ -194,11 +190,10 @@ void PWMSpindle::stop() {
// inverts are delt with in methods
set_enable_pin(false);
set_output(_pwm_off_value);
}
// prints the startup message of the spindle config
void PWMSpindle :: config_message() {
void PWMSpindle ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"PWM spindle Output:%s, Enbl:%s, Dir:%s, Freq:%dHz, Res:%dbits",
@ -209,10 +204,7 @@ void PWMSpindle :: config_message() {
_pwm_precision);
}
void PWMSpindle::set_output(uint32_t duty) {
if (_output_pin == UNDEFINED_PIN)
return;
@ -222,7 +214,7 @@ void PWMSpindle::set_output(uint32_t duty) {
_current_pwm_duty = duty;
if (_invert_pwm)
if (_invert_pwm)
duty = (1 << _pwm_precision) - duty;
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "set_output(%d)", duty);
@ -231,11 +223,10 @@ void PWMSpindle::set_output(uint32_t duty) {
}
void PWMSpindle::set_enable_pin(bool enable) {
if (_enable_pin == UNDEFINED_PIN)
return;
if (_off_with_zero_speed && sys.spindle_speed == 0)
if (_off_with_zero_speed && sys.spindle_speed == 0)
enable = false;
#ifndef INVERT_SPINDLE_ENABLE_PIN
@ -250,14 +241,13 @@ void PWMSpindle::set_spindle_dir_pin(bool Clockwise) {
digitalWrite(_direction_pin, Clockwise);
}
/*
Calculate the highest precision of a PWM based on the frequency in bits
80,000,000 / freq = period
determine the highest precision where (1 << precision) < period
*/
uint8_t PWMSpindle :: calc_pwm_precision(uint32_t freq) {
uint8_t PWMSpindle ::calc_pwm_precision(uint32_t freq) {
uint8_t precision = 0;
// increase the precision (bits) until it exceeds allow by frequency the max or is 16

View File

@ -36,13 +36,13 @@ void RelaySpindle::init() {
pinMode(_direction_pin, OUTPUT);
is_reversable = (_direction_pin != UNDEFINED_PIN);
use_delays = true;
use_delays = true;
config_message();
}
// prints the startup message of the spindle config
void RelaySpindle :: config_message() {
void RelaySpindle ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"Relay spindle Output:%s, Enbl:%s, Dir:%s",
@ -56,15 +56,14 @@ uint32_t RelaySpindle::set_rpm(uint32_t rpm) {
return rpm;
sys.spindle_speed = rpm;
set_output(rpm != 0);
set_output(rpm != 0);
return rpm;
}
void RelaySpindle::set_output(uint32_t duty) {
#ifdef INVERT_SPINDLE_PWM
duty = (duty == 0); // flip duty
duty = (duty == 0); // flip duty
#endif
digitalWrite(_output_pin, duty > 0); // anything greater
digitalWrite(_output_pin, duty > 0); // anything greater
}

View File

@ -36,61 +36,42 @@
#include "BESCSpindle.cpp"
#include "10vSpindle.cpp"
// An instance of each type of spindle is created here.
// This allows the spindle to be dynamicly switched
NullSpindle null_spindle;
PWMSpindle pwm_spindle;
RelaySpindle relay_spindle;
Laser laser;
DacSpindle dac_spindle;
NullSpindle null_spindle;
PWMSpindle pwm_spindle;
RelaySpindle relay_spindle;
Laser laser;
DacSpindle dac_spindle;
HuanyangSpindle huanyang_spindle;
BESCSpindle besc_spindle;
_10vSpindle _10v_spindle;
BESCSpindle besc_spindle;
_10vSpindle _10v_spindle;
void spindle_select() {
switch (spindle_type->get()) {
case SPINDLE_TYPE_PWM:
spindle = &pwm_spindle;
break;
case SPINDLE_TYPE_RELAY:
spindle = &relay_spindle;
break;
case SPINDLE_TYPE_LASER:
spindle = &laser;
break;
case SPINDLE_TYPE_DAC:
spindle = &dac_spindle;
break;
case SPINDLE_TYPE_HUANYANG:
spindle = &huanyang_spindle;
break;
case SPINDLE_TYPE_BESC:
spindle = &besc_spindle;
break;
case SPINDLE_TYPE_10V:
spindle = &_10v_spindle;
break;
case SPINDLE_TYPE_NONE:
default:
spindle = &null_spindle;
break;
case SPINDLE_TYPE_PWM: spindle = &pwm_spindle; break;
case SPINDLE_TYPE_RELAY: spindle = &relay_spindle; break;
case SPINDLE_TYPE_LASER: spindle = &laser; break;
case SPINDLE_TYPE_DAC: spindle = &dac_spindle; break;
case SPINDLE_TYPE_HUANYANG: spindle = &huanyang_spindle; break;
case SPINDLE_TYPE_BESC: spindle = &besc_spindle; break;
case SPINDLE_TYPE_10V: spindle = &_10v_spindle; break;
case SPINDLE_TYPE_NONE:
default: spindle = &null_spindle; break;
}
spindle->init();
}
// ========================= Spindle ==================================
bool Spindle::isRateAdjusted() {
return false; // default for basic spindle is false
return false; // default for basic spindle is false
}
void Spindle :: spindle_sync(uint8_t state, uint32_t rpm) {
void Spindle ::spindle_sync(uint8_t state, uint32_t rpm) {
if (sys.state == STATE_CHECK_MODE)
return;
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
set_state(state, rpm);
}

View File

@ -26,199 +26,190 @@
*/
#define SPINDLE_STATE_DISABLE 0 // Must be zero.
#define SPINDLE_STATE_CW bit(0)
#define SPINDLE_STATE_CCW bit(1)
#define SPINDLE_STATE_DISABLE 0 // Must be zero.
#define SPINDLE_STATE_CW bit(0)
#define SPINDLE_STATE_CCW bit(1)
#define SPINDLE_TYPE_NONE 0
#define SPINDLE_TYPE_PWM 1
#define SPINDLE_TYPE_RELAY 2
#define SPINDLE_TYPE_LASER 3
#define SPINDLE_TYPE_DAC 4
#define SPINDLE_TYPE_HUANYANG 5
#define SPINDLE_TYPE_BESC 6
#define SPINDLE_TYPE_10V 7
#define SPINDLE_TYPE_NONE 0
#define SPINDLE_TYPE_PWM 1
#define SPINDLE_TYPE_RELAY 2
#define SPINDLE_TYPE_LASER 3
#define SPINDLE_TYPE_DAC 4
#define SPINDLE_TYPE_HUANYANG 5
#define SPINDLE_TYPE_BESC 6
#define SPINDLE_TYPE_10V 7
#include "../grbl.h"
#include <driver/dac.h>
#include "driver/uart.h"
// =============== No floats! ===========================
// ================ NO FLOATS! ==========================
// This is the base class. Do not use this as your spindle
class Spindle {
public:
virtual void init(); // not in constructor because this also gets called when $$ settings change
public:
virtual void init(); // not in constructor because this also gets called when $$ settings change
virtual uint32_t set_rpm(uint32_t rpm);
virtual void set_state(uint8_t state, uint32_t rpm);
virtual uint8_t get_state();
virtual void stop();
virtual void config_message();
virtual bool isRateAdjusted();
virtual void spindle_sync(uint8_t state, uint32_t rpm);
virtual void set_state(uint8_t state, uint32_t rpm);
virtual uint8_t get_state();
virtual void stop();
virtual void config_message();
virtual bool isRateAdjusted();
virtual void spindle_sync(uint8_t state, uint32_t rpm);
bool is_reversable;
bool use_delays; // will SpinUp and SpinDown delays be used.
bool is_reversable;
bool use_delays; // will SpinUp and SpinDown delays be used.
uint8_t _current_state;
};
// This is a dummy spindle that has no I/O.
// It is used to ignore spindle commands when no spinde is desired
class NullSpindle : public Spindle {
public:
void init();
public:
void init();
uint32_t set_rpm(uint32_t rpm);
void set_state(uint8_t state, uint32_t rpm);
uint8_t get_state();
void stop();
void config_message();
void set_state(uint8_t state, uint32_t rpm);
uint8_t get_state();
void stop();
void config_message();
};
// This adds support for PWM
class PWMSpindle : public Spindle {
public:
void init();
public:
void init();
virtual uint32_t set_rpm(uint32_t rpm);
void set_state(uint8_t state, uint32_t rpm);
uint8_t get_state();
void stop();
void config_message();
void set_state(uint8_t state, uint32_t rpm);
uint8_t get_state();
void stop();
void config_message();
private:
private:
void set_spindle_dir_pin(bool Clockwise);
protected:
int32_t _current_pwm_duty;
protected:
int32_t _current_pwm_duty;
uint32_t _min_rpm;
uint32_t _max_rpm;
uint32_t _pwm_off_value;
uint32_t _pwm_min_value;
uint32_t _pwm_max_value;
uint8_t _output_pin;
uint8_t _enable_pin;
uint8_t _direction_pin;
uint8_t _spindle_pwm_chan_num;
uint8_t _output_pin;
uint8_t _enable_pin;
uint8_t _direction_pin;
uint8_t _spindle_pwm_chan_num;
uint32_t _pwm_freq;
uint32_t _pwm_period; // how many counts in 1 period
uint8_t _pwm_precision;
bool _piecewide_linear;
bool _off_with_zero_speed;
bool _invert_pwm;
uint32_t _pwm_period; // how many counts in 1 period
uint8_t _pwm_precision;
bool _piecewide_linear;
bool _off_with_zero_speed;
bool _invert_pwm;
//uint32_t _pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
virtual void set_output(uint32_t duty);
void set_enable_pin(bool enable_pin);
void get_pins_and_settings();
uint8_t calc_pwm_precision(uint32_t freq);
void set_enable_pin(bool enable_pin);
void get_pins_and_settings();
uint8_t calc_pwm_precision(uint32_t freq);
};
// This is for an on/off spindle all RPMs above 0 are on
class RelaySpindle : public PWMSpindle {
public:
void init();
void config_message();
public:
void init();
void config_message();
uint32_t set_rpm(uint32_t rpm);
protected:
protected:
void set_output(uint32_t duty);
};
// this is the same as a PWM spindle but the M4 compensation is supported.
class Laser : public PWMSpindle {
public:
public:
bool isRateAdjusted();
void config_message();
};
// This uses one of the (2) DAC pins on ESP32 to output a voltage
class DacSpindle : public PWMSpindle {
public:
void init();
void config_message();
public:
void init();
void config_message();
uint32_t set_rpm(uint32_t rpm);
private:
bool _gpio_ok; // DAC is on a valid pin
protected:
void set_output(uint32_t duty); // sets DAC instead of PWM
private:
bool _gpio_ok; // DAC is on a valid pin
protected:
void set_output(uint32_t duty); // sets DAC instead of PWM
};
class HuanyangSpindle : public Spindle {
private:
uint16_t ModRTU_CRC(char* buf, int len);
private:
uint16_t ModRTU_CRC(char* buf, int len);
bool set_mode(uint8_t mode, bool critical);
bool get_pins_and_settings();
uint32_t _current_rpm;
uint8_t _txd_pin;
uint8_t _rxd_pin;
uint8_t _rts_pin;
uint8_t _state;
bool _task_running;
uint8_t _txd_pin;
uint8_t _rxd_pin;
uint8_t _rts_pin;
uint8_t _state;
bool _task_running;
public:
HuanyangSpindle() {
_task_running = false;
}
void init();
void config_message();
void set_state(uint8_t state, uint32_t rpm);
uint8_t get_state();
uint32_t set_rpm(uint32_t rpm);
void stop();
public:
HuanyangSpindle() { _task_running = false; }
void init();
void config_message();
void set_state(uint8_t state, uint32_t rpm);
uint8_t get_state();
uint32_t set_rpm(uint32_t rpm);
void stop();
static void read_value(uint8_t reg);
static void add_ModRTU_CRC(char* buf, int full_msg_len);
static void add_ModRTU_CRC(char* buf, int full_msg_len);
protected:
protected:
uint32_t _min_rpm;
uint32_t _max_rpm;
};
class BESCSpindle : public PWMSpindle {
public:
void init();
void config_message();
public:
void init();
void config_message();
uint32_t set_rpm(uint32_t rpm);
};
class _10vSpindle : public PWMSpindle {
public:
void init();
void config_message();
public:
void init();
void config_message();
uint32_t set_rpm(uint32_t rpm);
uint8_t _forward_pin;
uint8_t _reverse_pin;
uint8_t _forward_pin;
uint8_t _reverse_pin;
//void set_state(uint8_t state, uint32_t rpm);
uint8_t get_state();
void stop();
protected:
void stop();
protected:
void set_enable_pin(bool enable_pin);
void set_spindle_dir_pin(bool Clockwise);
};
extern Spindle* spindle;
extern NullSpindle null_spindle;
extern PWMSpindle pwm_spindle;
extern RelaySpindle relay_spindle;
extern Laser laser;
extern DacSpindle dac_spindle;
extern NullSpindle null_spindle;
extern PWMSpindle pwm_spindle;
extern RelaySpindle relay_spindle;
extern Laser laser;
extern DacSpindle dac_spindle;
extern HuanyangSpindle huanyang_spindle;
extern BESCSpindle besc_spindle;
extern _10vSpindle _10v_spindle;
extern BESCSpindle besc_spindle;
extern _10vSpindle _10v_spindle;
void spindle_select();

File diff suppressed because it is too large Load Diff

View File

@ -37,10 +37,10 @@ extern IPaddrSetting* wifi_ap_ip;
extern IntSetting* wifi_ap_channel;
extern StringSetting* wifi_hostname;
extern EnumSetting* http_enable;
extern IntSetting* http_port;
extern EnumSetting* telnet_enable;
extern IntSetting* telnet_port;
extern EnumSetting* http_enable;
extern IntSetting* http_port;
extern EnumSetting* telnet_enable;
extern IntSetting* telnet_port;
#endif
#ifdef WIFI_OR_BLUETOOTH
@ -57,7 +57,7 @@ extern StringSetting* admin_password;
#endif
#ifdef ENABLE_NOTIFICATIONS
extern EnumSetting* notification_type;
extern EnumSetting* notification_type;
extern StringSetting* notification_t1;
extern StringSetting* notification_t2;
extern StringSetting* notification_ts;

View File

@ -5,9 +5,9 @@
StringSetting* user_password;
StringSetting* admin_password;
void remove_password(char *str, auth_t& auth_level) {
void remove_password(char* str, auth_t& auth_level) {
String paramStr = String((const char*)str);
int pos = paramStr.indexOf("pwd=");
int pos = paramStr.indexOf("pwd=");
if (pos == -1) {
return;
}
@ -15,7 +15,7 @@ void remove_password(char *str, auth_t& auth_level) {
// Truncate the str string at the pwd= .
// If the pwd= is preceded by a space, take off that space too.
int endpos = pos;
if (endpos && str[endpos-1] == ' ') {
if (endpos && str[endpos - 1] == ' ') {
--endpos;
}
str[endpos] = '\0';
@ -35,7 +35,7 @@ void remove_password(char *str, auth_t& auth_level) {
}
}
#else
void remove_password(char *str, auth_t& auth_level) {
void remove_password(char* str, auth_t& auth_level) {
auth_level = LEVEL_ADMIN;
}
#endif

View File

@ -1,13 +1,9 @@
#pragma once
//Authentication level
typedef enum {
LEVEL_GUEST = 0,
LEVEL_USER = 1,
LEVEL_ADMIN = 2
} auth_t;
typedef enum { LEVEL_GUEST = 0, LEVEL_USER = 1, LEVEL_ADMIN = 2 } auth_t;
#define MIN_LOCAL_PASSWORD_LENGTH 1
#define MAX_LOCAL_PASSWORD_LENGTH 16
#define MIN_LOCAL_PASSWORD_LENGTH 1
#define MAX_LOCAL_PASSWORD_LENGTH 16
void remove_password(char *str, auth_t& auth_level);
void remove_password(char* str, auth_t& auth_level);

View File

@ -34,7 +34,7 @@ bool COMMANDS::restart_ESP_module = false;
*/
void COMMANDS::wait(uint32_t milliseconds) {
uint32_t timeout = millis();
esp_task_wdt_reset(); //for a wait 0;
esp_task_wdt_reset(); //for a wait 0;
//wait feeding WDT
while ((millis() - timeout) < milliseconds)
esp_task_wdt_reset();
@ -69,6 +69,7 @@ void COMMANDS::handle() {
//in case of restart requested
if (restart_ESP_module) {
ESP.restart();
while (1) ;
while (1)
;
}
}

View File

@ -25,11 +25,12 @@
class ESPResponseStream;
class COMMANDS {
public:
public:
static void wait(uint32_t milliseconds);
static void handle();
static void restart_ESP();
static bool isLocalPasswordValid(char* password);
private :
private:
static bool restart_ESP_module;
};

View File

@ -62,7 +62,7 @@ Some features should not be changed. See notes below.
// NOTE: Defaults are set for a traditional 3-axis CNC machine. Z-axis first to clear, followed by X & Y.
// These homing cycle definitions precede the machine.h file so that the machine
// definition can undefine them if necessary.
#define HOMING_CYCLE_0 bit(Z_AXIS) // TYPICALLY REQUIRED: First move Z to clear workspace.
#define HOMING_CYCLE_0 bit(Z_AXIS) // TYPICALLY REQUIRED: First move Z to clear workspace.
#define HOMING_CYCLE_1 bit(X_AXIS)
#define HOMING_CYCLE_2 bit(Y_AXIS)
@ -74,10 +74,10 @@ Some features should not be changed. See notes below.
// normally-closed switches on the specified pins, rather than the default normally-open switches.
// The mask order is Cycle Start | Feed Hold | Reset | Safety Door
// For example B1101 will invert the function of the Reset pin.
#define INVERT_CONTROL_PIN_MASK B1111
#define INVERT_CONTROL_PIN_MASK B1111
#define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
#define CONTROL_SW_DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
#define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
#define CONTROL_SW_DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
#define USE_RMT_STEPS
@ -93,15 +93,15 @@ Some features should not be changed. See notes below.
// Number of axes defined (steppers, servos, etc) (valid range: 3 to 6)
// Even if your machine only uses less than the minimum of 3, you should select 3
#ifndef N_AXIS
#define N_AXIS 3
# define N_AXIS 3
#endif
#ifndef LIMIT_MASK
#define LIMIT_MASK B0
# define LIMIT_MASK B0
#endif
#define VERBOSE_HELP // Currently this doesn't do anything
#define GRBL_MSG_LEVEL MSG_LEVEL_INFO // what level of [MSG:....] do you want to see 0=all off
#define VERBOSE_HELP // Currently this doesn't do anything
#define GRBL_MSG_LEVEL MSG_LEVEL_INFO // what level of [MSG:....] do you want to see 0=all off
// Serial baud rate
// OK to change, but the ESP32 boot text is 115200, so you will not see that is your
@ -112,24 +112,23 @@ Some features should not be changed. See notes below.
//#define CONNECT_TO_SSID "your SSID"
//#define SSID_PASSWORD "your SSID password"
//CONFIGURE_EYECATCH_BEGIN (DO NOT MODIFY THIS LINE)
#define ENABLE_BLUETOOTH // enable bluetooth
#define ENABLE_BLUETOOTH // enable bluetooth
#define ENABLE_SD_CARD // enable use of SD Card to run jobs
#define ENABLE_SD_CARD // enable use of SD Card to run jobs
#define ENABLE_WIFI //enable wifi
#define ENABLE_WIFI //enable wifi
#if defined(ENABLE_WIFI) || defined(ENABLE_BLUETOOTH)
#define WIFI_OR_BLUETOOTH
# define WIFI_OR_BLUETOOTH
#endif
#define ENABLE_HTTP //enable HTTP and all related services
#define ENABLE_OTA //enable OTA
#define ENABLE_TELNET //enable telnet
#define ENABLE_TELNET_WELCOME_MSG //display welcome string when connect to telnet
#define ENABLE_MDNS //enable mDNS discovery
#define ENABLE_SSDP //enable UPNP discovery
#define ENABLE_NOTIFICATIONS //enable notifications
#define ENABLE_HTTP //enable HTTP and all related services
#define ENABLE_OTA //enable OTA
#define ENABLE_TELNET //enable telnet
#define ENABLE_TELNET_WELCOME_MSG //display welcome string when connect to telnet
#define ENABLE_MDNS //enable mDNS discovery
#define ENABLE_SSDP //enable UPNP discovery
#define ENABLE_NOTIFICATIONS //enable notifications
#define ENABLE_SERIAL2SOCKET_IN
#define ENABLE_SERIAL2SOCKET_OUT
@ -150,32 +149,32 @@ Some features should not be changed. See notes below.
#define NAMESPACE "GRBL"
#ifdef ENABLE_AUTHENTICATION
#define DEFAULT_ADMIN_PWD "admin"
#define DEFAULT_USER_PWD "user"
#define DEFAULT_ADMIN_LOGIN "admin"
#define DEFAULT_USER_LOGIN "user"
# define DEFAULT_ADMIN_PWD "admin"
# define DEFAULT_USER_PWD "user"
# define DEFAULT_ADMIN_LOGIN "admin"
# define DEFAULT_USER_LOGIN "user"
#endif
//Radio Mode
#define ESP_RADIO_OFF 0
#define ESP_WIFI_STA 1
#define ESP_WIFI_AP 2
#define ESP_BT 3
#define ESP_WIFI_AP 2
#define ESP_BT 3
//Default mode
#ifdef ENABLE_WIFI
#ifdef CONNECT_TO_SSID
#define DEFAULT_RADIO_MODE ESP_WIFI_STA
#else
#define DEFAULT_RADIO_MODE ESP_WIFI_AP
#endif //CONNECT_TO_SSID
# ifdef CONNECT_TO_SSID
# define DEFAULT_RADIO_MODE ESP_WIFI_STA
# else
# define DEFAULT_RADIO_MODE ESP_WIFI_AP
# endif //CONNECT_TO_SSID
#else
#undef ENABLE_NOTIFICATIONS
#ifdef ENABLE_BLUETOOTH
#define DEFAULT_RADIO_MODE ESP_BT
#else
#define DEFAULT_RADIO_MODE ESP_RADIO_OFF
#endif
# undef ENABLE_NOTIFICATIONS
# ifdef ENABLE_BLUETOOTH
# define DEFAULT_RADIO_MODE ESP_BT
# else
# define DEFAULT_RADIO_MODE ESP_RADIO_OFF
# endif
#endif
// Define realtime command special characters. These characters are 'picked-off' directly from the
@ -185,7 +184,7 @@ Some features should not be changed. See notes below.
// g-code programs, maybe selected for interface programs.
// NOTE: If changed, manually update help message in report.c.
#define CMD_RESET 0x18 // ctrl-x.
#define CMD_RESET 0x18 // ctrl-x.
#define CMD_STATUS_REPORT '?'
#define CMD_CYCLE_START '~'
#define CMD_FEED_HOLD '!'
@ -199,19 +198,19 @@ Some features should not be changed. See notes below.
// #define CMD_CYCLE_START 0x82
// #define CMD_FEED_HOLD 0x83
#define CMD_SAFETY_DOOR 0x84
#define CMD_JOG_CANCEL 0x85
#define CMD_DEBUG_REPORT 0x86 // Only when DEBUG enabled, sends debug report in '{}' braces.
#define CMD_FEED_OVR_RESET 0x90 // Restores feed override value to 100%.
#define CMD_JOG_CANCEL 0x85
#define CMD_DEBUG_REPORT 0x86 // Only when DEBUG enabled, sends debug report in '{}' braces.
#define CMD_FEED_OVR_RESET 0x90 // Restores feed override value to 100%.
#define CMD_FEED_OVR_COARSE_PLUS 0x91
#define CMD_FEED_OVR_COARSE_MINUS 0x92
#define CMD_FEED_OVR_FINE_PLUS 0x93
#define CMD_FEED_OVR_FINE_MINUS 0x94
#define CMD_RAPID_OVR_RESET 0x95 // Restores rapid override value to 100%.
#define CMD_FEED_OVR_FINE_PLUS 0x93
#define CMD_FEED_OVR_FINE_MINUS 0x94
#define CMD_RAPID_OVR_RESET 0x95 // Restores rapid override value to 100%.
#define CMD_RAPID_OVR_MEDIUM 0x96
#define CMD_RAPID_OVR_LOW 0x97
// #define CMD_RAPID_OVR_EXTRA_LOW 0x98 // *NOT SUPPORTED*
#define CMD_SPINDLE_OVR_RESET 0x99 // Restores spindle override value to 100%.
#define CMD_SPINDLE_OVR_COARSE_PLUS 0x9A // 154
#define CMD_SPINDLE_OVR_RESET 0x99 // Restores spindle override value to 100%.
#define CMD_SPINDLE_OVR_COARSE_PLUS 0x9A // 154
#define CMD_SPINDLE_OVR_COARSE_MINUS 0x9B
#define CMD_SPINDLE_OVR_FINE_PLUS 0x9C
#define CMD_SPINDLE_OVR_FINE_MINUS 0x9D
@ -222,18 +221,18 @@ Some features should not be changed. See notes below.
// If homing is enabled, homing init lock sets Grbl into an alarm state upon power up. This forces
// the user to perform the homing cycle (or override the locks) before doing anything else. This is
// mainly a safety feature to remind the user to home, since position is unknown to Grbl.
#define HOMING_INIT_LOCK // Comment to disable
#define HOMING_INIT_LOCK // Comment to disable
// Number of homing cycles performed after when the machine initially jogs to limit switches.
// This help in preventing overshoot and should improve repeatability. This value should be one or
// greater.
#define N_HOMING_LOCATE_CYCLE 1 // Integer (1-128)
#define N_HOMING_LOCATE_CYCLE 1 // Integer (1-128)
// Enables single axis homing commands. $HX, $HY, and $HZ for X, Y, and Z-axis homing. The full homing
// cycle is still invoked by the $H command. This is disabled by default. It's here only to address
// users that need to switch between a two-axis and three-axis machine. This is actually very rare.
// If you have a two-axis machine, DON'T USE THIS. Instead, just alter the homing cycle for two-axes.
#define HOMING_SINGLE_AXIS_COMMANDS // Default disabled. Uncomment to enable.
#define HOMING_SINGLE_AXIS_COMMANDS // Default disabled. Uncomment to enable.
// After homing, Grbl will set by default the entire machine space into negative space, as is typical
// for professional CNC machines, regardless of where the limit switches are located. Uncomment this
@ -250,7 +249,7 @@ Some features should not be changed. See notes below.
// and addresses are defined in settings.h. With the current settings, up to 2 startup blocks may
// be stored and executed in order. These startup blocks would typically be used to set the g-code
// parser state depending on user preferences.
#define N_STARTUP_LINE 2 // Integer (1-2)
#define N_STARTUP_LINE 2 // Integer (1-2)
// Number of floating decimal points printed by Grbl for certain value types. These settings are
// determined by realistic and commonly observed values in CNC machines. For example, position
@ -258,12 +257,12 @@ Some features should not be changed. See notes below.
// precise this. So, there is likely no need to change these, but you can if you need to here.
// NOTE: Must be an integer value from 0 to ~4. More than 4 may exhibit round-off errors.
// ESP32 Note: These are mostly hard coded, so these values will not change anything
#define N_DECIMAL_COORDVALUE_INCH 4 // Coordinate or position value in inches
#define N_DECIMAL_COORDVALUE_MM 3 // Coordinate or position value in mm
#define N_DECIMAL_RATEVALUE_INCH 1 // Rate or velocity value in in/min
#define N_DECIMAL_RATEVALUE_MM 0 // Rate or velocity value in mm/min
#define N_DECIMAL_SETTINGVALUE 3 // Decimals for floating point setting values
#define N_DECIMAL_RPMVALUE 0 // RPM value in rotations per min.
#define N_DECIMAL_COORDVALUE_INCH 4 // Coordinate or position value in inches
#define N_DECIMAL_COORDVALUE_MM 3 // Coordinate or position value in mm
#define N_DECIMAL_RATEVALUE_INCH 1 // Rate or velocity value in in/min
#define N_DECIMAL_RATEVALUE_MM 0 // Rate or velocity value in mm/min
#define N_DECIMAL_SETTINGVALUE 3 // Decimals for floating point setting values
#define N_DECIMAL_RPMVALUE 0 // RPM value in rotations per min.
// If your machine has two limits switches wired in parallel to one axis, you will need to enable
// this feature. Since the two switches are sharing a single pin, there is no way for Grbl to tell
@ -280,7 +279,7 @@ Some features should not be changed. See notes below.
// Upon a successful probe cycle, this option provides immediately feedback of the probe coordinates
// through an automatically generated message. If disabled, users can still access the last probe
// coordinates through Grbl '$#' print parameters.
#define MESSAGE_PROBE_COORDINATES // Enabled by default. Comment to disable.
#define MESSAGE_PROBE_COORDINATES // Enabled by default. Comment to disable.
// Enables a second coolant control pin via the mist coolant g-code command M7 on the Arduino Uno
// analog pin 4. Only use this option if you require a second coolant control pin.
@ -293,12 +292,12 @@ Some features should not be changed. See notes below.
// immediately forces a feed hold and then safely de-energizes the machine. Resuming is blocked until
// the safety door is re-engaged. When it is, Grbl will re-energize the machine and then resume on the
// previous tool path, as if nothing happened.
#define ENABLE_SAFETY_DOOR_INPUT_PIN // ESP32 Leave this enabled for now .. code for undefined not ready
#define ENABLE_SAFETY_DOOR_INPUT_PIN // ESP32 Leave this enabled for now .. code for undefined not ready
// After the safety door switch has been toggled and restored, this setting sets the power-up delay
// between restoring the spindle and coolant and resuming the cycle.
#define SAFETY_DOOR_SPINDLE_DELAY 4.0 // Float (seconds)
#define SAFETY_DOOR_COOLANT_DELAY 1.0 // Float (seconds)
#define SAFETY_DOOR_SPINDLE_DELAY 4.0 // Float (seconds)
#define SAFETY_DOOR_COOLANT_DELAY 1.0 // Float (seconds)
// Enable CoreXY kinematics. Use ONLY with CoreXY machines.
// IMPORTANT: If homing is enabled, you must reconfigure the homing cycle #defines above to
@ -352,27 +351,27 @@ Some features should not be changed. See notes below.
// Configure rapid, feed, and spindle override settings. These values define the max and min
// allowable override values and the coarse and fine increments per command received. Please
// note the allowable values in the descriptions following each define.
#define DEFAULT_FEED_OVERRIDE 100 // 100%. Don't change this value.
#define MAX_FEED_RATE_OVERRIDE 200 // Percent of programmed feed rate (100-255). Usually 120% or 200%
#define MIN_FEED_RATE_OVERRIDE 10 // Percent of programmed feed rate (1-100). Usually 50% or 1%
#define FEED_OVERRIDE_COARSE_INCREMENT 10 // (1-99). Usually 10%.
#define FEED_OVERRIDE_FINE_INCREMENT 1 // (1-99). Usually 1%.
#define DEFAULT_FEED_OVERRIDE 100 // 100%. Don't change this value.
#define MAX_FEED_RATE_OVERRIDE 200 // Percent of programmed feed rate (100-255). Usually 120% or 200%
#define MIN_FEED_RATE_OVERRIDE 10 // Percent of programmed feed rate (1-100). Usually 50% or 1%
#define FEED_OVERRIDE_COARSE_INCREMENT 10 // (1-99). Usually 10%.
#define FEED_OVERRIDE_FINE_INCREMENT 1 // (1-99). Usually 1%.
#define DEFAULT_RAPID_OVERRIDE 100 // 100%. Don't change this value.
#define RAPID_OVERRIDE_MEDIUM 50 // Percent of rapid (1-99). Usually 50%.
#define RAPID_OVERRIDE_LOW 25 // Percent of rapid (1-99). Usually 25%.
#define DEFAULT_RAPID_OVERRIDE 100 // 100%. Don't change this value.
#define RAPID_OVERRIDE_MEDIUM 50 // Percent of rapid (1-99). Usually 50%.
#define RAPID_OVERRIDE_LOW 25 // Percent of rapid (1-99). Usually 25%.
// #define RAPID_OVERRIDE_EXTRA_LOW 5 // *NOT SUPPORTED* Percent of rapid (1-99). Usually 5%.
#define DEFAULT_SPINDLE_SPEED_OVERRIDE 100 // 100%. Don't change this value.
#define MAX_SPINDLE_SPEED_OVERRIDE 200 // Percent of programmed spindle speed (100-255). Usually 200%.
#define MIN_SPINDLE_SPEED_OVERRIDE 10 // Percent of programmed spindle speed (1-100). Usually 10%.
#define SPINDLE_OVERRIDE_COARSE_INCREMENT 10 // (1-99). Usually 10%.
#define SPINDLE_OVERRIDE_FINE_INCREMENT 1 // (1-99). Usually 1%.
#define DEFAULT_SPINDLE_SPEED_OVERRIDE 100 // 100%. Don't change this value.
#define MAX_SPINDLE_SPEED_OVERRIDE 200 // Percent of programmed spindle speed (100-255). Usually 200%.
#define MIN_SPINDLE_SPEED_OVERRIDE 10 // Percent of programmed spindle speed (1-100). Usually 10%.
#define SPINDLE_OVERRIDE_COARSE_INCREMENT 10 // (1-99). Usually 10%.
#define SPINDLE_OVERRIDE_FINE_INCREMENT 1 // (1-99). Usually 1%.
// When a M2 or M30 program end command is executed, most g-code states are restored to their defaults.
// This compile-time option includes the restoring of the feed, rapid, and spindle speed override values
// to their default values at program end.
#define RESTORE_OVERRIDES_AFTER_PROGRAM_END // Default enabled. Comment to disable.
#define RESTORE_OVERRIDES_AFTER_PROGRAM_END // Default enabled. Comment to disable.
// The status report change for Grbl v1.1 and after also removed the ability to disable/enable most data
// fields from the report. This caused issues for GUI developers, who've had to manage several scenarios
@ -380,12 +379,12 @@ Some features should not be changed. See notes below.
// be sent without potential performance issues.
// NOTE: The options below are here only provide a way to disable certain data fields if a unique
// situation demands it, but be aware GUIs may depend on this data. If disabled, it may not be compatible.
#define REPORT_FIELD_BUFFER_STATE // Default enabled. Comment to disable.
#define REPORT_FIELD_PIN_STATE // Default enabled. Comment to disable.
#define REPORT_FIELD_CURRENT_FEED_SPEED // Default enabled. Comment to disable.
#define REPORT_FIELD_WORK_COORD_OFFSET // Default enabled. Comment to disable.
#define REPORT_FIELD_OVERRIDES // Default enabled. Comment to disable.
#define REPORT_FIELD_LINE_NUMBERS // Default enabled. Comment to disable.
#define REPORT_FIELD_BUFFER_STATE // Default enabled. Comment to disable.
#define REPORT_FIELD_PIN_STATE // Default enabled. Comment to disable.
#define REPORT_FIELD_CURRENT_FEED_SPEED // Default enabled. Comment to disable.
#define REPORT_FIELD_WORK_COORD_OFFSET // Default enabled. Comment to disable.
#define REPORT_FIELD_OVERRIDES // Default enabled. Comment to disable.
#define REPORT_FIELD_LINE_NUMBERS // Default enabled. Comment to disable.
// Some status report data isn't necessary for realtime, only intermittently, because the values don't
// change often. The following macros configures how many times a status report needs to be called before
@ -444,14 +443,14 @@ Some features should not be changed. See notes below.
// Sets which axis the tool length offset is applied. Assumes the spindle is always parallel with
// the selected axis with the tool oriented toward the negative direction. In other words, a positive
// tool length offset value is subtracted from the current location.
#define TOOL_LENGTH_OFFSET_AXIS Z_AXIS // Default z-axis. Valid values are X_AXIS, Y_AXIS, or Z_AXIS.
#define TOOL_LENGTH_OFFSET_AXIS Z_AXIS // Default z-axis. Valid values are X_AXIS, Y_AXIS, or Z_AXIS.
// Alters the behavior of the spindle enable pin. By default Grbl will not disable the enable pin if
// spindle speed is zero and M3/4 is active, but still sets the PWM output to zero. This allows the users
// to know if the spindle is active and use it as an additional control input.
// However, in some use cases, user may want the enable pin to disable with a zero spindle speed and
// re-enable when spindle speed is greater than zero. This option does that.
#define SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED // Default enabled. Comment to disable.
#define SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED // Default enabled. Comment to disable.
// With this enabled, Grbl sends back an echo of the line it has received, which has been pre-parsed (spaces
// removed, capitalized letters, no comments) and is to be immediately executed by Grbl. Echoes will not be
@ -474,19 +473,19 @@ Some features should not be changed. See notes below.
// limits or angle between neighboring block line move directions. This is useful for machines that can't
// tolerate the tool dwelling for a split second, i.e. 3d printers or laser cutters. If used, this value
// should not be much greater than zero or to the minimum value necessary for the machine to work.
#define MINIMUM_JUNCTION_SPEED 0.0 // (mm/min)
#define MINIMUM_JUNCTION_SPEED 0.0 // (mm/min)
// Sets the minimum feed rate the planner will allow. Any value below it will be set to this minimum
// value. This also ensures that a planned motion always completes and accounts for any floating-point
// round-off errors. Although not recommended, a lower value than 1.0 mm/min will likely work in smaller
// machines, perhaps to 0.1mm/min, but your success may vary based on multiple factors.
#define MINIMUM_FEED_RATE 1.0 // (mm/min)
#define MINIMUM_FEED_RATE 1.0 // (mm/min)
// Number of arc generation iterations by small angle approximation before exact arc trajectory
// correction with expensive sin() and cos() calcualtions. This parameter maybe decreased if there
// are issues with the accuracy of the arc generations, or increased if arc execution is getting
// bogged down by too many trig calculations.
#define N_ARC_CORRECTION 12 // Integer (1-255)
#define N_ARC_CORRECTION 12 // Integer (1-255)
// The arc G2/3 g-code standard is problematic by definition. Radius-based arcs have horrible numerical
// errors when arc at semi-circles(pi) or full-circles(2*pi). Offset-based arcs are much more accurate
@ -496,15 +495,14 @@ Some features should not be changed. See notes below.
// This define value sets the machine epsilon cutoff to determine if the arc is a full-circle or not.
// NOTE: Be very careful when adjusting this value. It should always be greater than 1.2e-7 but not too
// much greater than this. The default setting should capture most, if not all, full arc error situations.
#define ARC_ANGULAR_TRAVEL_EPSILON 5E-7 // Float (radians)
#define ARC_ANGULAR_TRAVEL_EPSILON 5E-7 // Float (radians)
// Time delay increments performed during a dwell. The default value is set at 50ms, which provides
// a maximum time delay of roughly 55 minutes, more than enough for most any application. Increasing
// this delay will increase the maximum dwell time linearly, but also reduces the responsiveness of
// run-time command executions, like status reports, since these are performed between each dwell
// time step. Also, keep in mind that the Arduino delay timer is not very accurate for long delays.
#define DWELL_TIME_STEP 50 // Integer (1-255) (milliseconds)
#define DWELL_TIME_STEP 50 // Integer (1-255) (milliseconds)
// For test use only. This uses the ESP32's RMT peripheral to generate step pulses
// It allows the use of the STEP_PULSE_DELAY (see below) and it automatically ends the
@ -568,7 +566,7 @@ Some features should not be changed. See notes below.
// switch interrupt unblock a waiting task which will recheck the limit switch pins after
// a short delay. Default disabled
//#define ENABLE_SOFTWARE_DEBOUNCE // Default disabled. Uncomment to enable.
#define DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
#define DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
// Configures the position after a probing cycle during Grbl's check mode. Disabled sets
// the position to the probe target, when enabled sets the position to the start position.
@ -597,9 +595,9 @@ Some features should not be changed. See notes below.
// Enable the '$RST=*', '$RST=$', and '$RST=#' eeprom restore commands. There are cases where
// these commands may be undesirable. Simply comment the desired macro to disable it.
// NOTE: See SETTINGS_RESTORE_ALL macro for customizing the `$RST=*` command.
#define ENABLE_RESTORE_EEPROM_WIPE_ALL // '$RST=*' Default enabled. Comment to disable.
#define ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS // '$RST=$' Default enabled. Comment to disable.
#define ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS // '$RST=#' Default enabled. Comment to disable.
#define ENABLE_RESTORE_EEPROM_WIPE_ALL // '$RST=*' Default enabled. Comment to disable.
#define ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS // '$RST=$' Default enabled. Comment to disable.
#define ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS // '$RST=#' Default enabled. Comment to disable.
// Defines the EEPROM data restored upon a settings version change and `$RST=*` command. Whenever the
// the settings or other EEPROM data structure changes between Grbl versions, Grbl will automatically
@ -622,7 +620,7 @@ Some features should not be changed. See notes below.
// NOTE: If disabled and to ensure Grbl can never alter the build info line, you'll also need to enable
// the SETTING_RESTORE_ALL macro above and remove SETTINGS_RESTORE_BUILD_INFO from the mask.
// NOTE: See the included grblWrite_BuildInfo.ino example file to write this string seperately.
#define ENABLE_BUILD_INFO_WRITE_COMMAND // '$I=' Default enabled. Comment to disable.
#define ENABLE_BUILD_INFO_WRITE_COMMAND // '$I=' Default enabled. Comment to disable.
// AVR processors require all interrupts to be disabled during an EEPROM write. This includes both
// the stepper ISRs and serial comm ISRs. In the event of a long EEPROM write, this ISR pause can
@ -636,7 +634,7 @@ Some features should not be changed. See notes below.
// NOTE: Most EEPROM write commands are implicitly blocked during a job (all '$' commands). However,
// coordinate set g-code commands (G10,G28/30.1) are not, since they are part of an active streaming
// job. At this time, this option only forces a planner buffer sync with these g-code commands.
#define FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE // Default enabled. Comment to disable.
#define FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE // Default enabled. Comment to disable.
// In Grbl v0.9 and prior, there is an old outstanding bug where the `WPos:` work position reported
// may not correlate to what is executing, because `WPos:` is based on the g-code parser state, which
@ -644,7 +642,7 @@ Some features should not be changed. See notes below.
// motion whenever there is a command that alters the work coordinate offsets `G10,G43.1,G92,G54-59`.
// This is the simplest way to ensure `WPos:` is always correct. Fortunately, it's exceedingly rare
// that any of these commands are used need continuous motions through them.
#define FORCE_BUFFER_SYNC_DURING_WCO_CHANGE // Default enabled. Comment to disable.
#define FORCE_BUFFER_SYNC_DURING_WCO_CHANGE // Default enabled. Comment to disable.
// By default, Grbl disables feed rate overrides for all G38.x probe cycle commands. Although this
// may be different than some pro-class machine control, it's arguable that it should be this way.
@ -669,11 +667,11 @@ Some features should not be changed. See notes below.
//#define PARKING_ENABLE // Default disabled. Uncomment to enable
// Configure options for the parking motion, if enabled.
#define PARKING_AXIS Z_AXIS // Define which axis that performs the parking motion
#define PARKING_TARGET -5.0 // Parking axis target. In mm, as machine coordinate [-max_travel,0].
#define PARKING_RATE 500.0 // Parking fast rate after pull-out in mm/min.
#define PARKING_PULLOUT_RATE 100.0 // Pull-out/plunge slow feed rate in mm/min.
#define PARKING_PULLOUT_INCREMENT 5.0 // Spindle pull-out and plunge distance in mm. Incremental distance.
#define PARKING_AXIS Z_AXIS // Define which axis that performs the parking motion
#define PARKING_TARGET -5.0 // Parking axis target. In mm, as machine coordinate [-max_travel,0].
#define PARKING_RATE 500.0 // Parking fast rate after pull-out in mm/min.
#define PARKING_PULLOUT_RATE 100.0 // Pull-out/plunge slow feed rate in mm/min.
#define PARKING_PULLOUT_INCREMENT 5.0 // Spindle pull-out and plunge distance in mm. Incremental distance.
// Must be positive value or equal to zero.
// Enables a special set of M-code commands that enables and disables the parking motion.
@ -689,7 +687,7 @@ Some features should not be changed. See notes below.
// override immediately after coming to a stop. However, this also means that the laser still may
// be reenabled by disabling the spindle stop override, if needed. This is purely a safety feature
// to ensure the laser doesn't inadvertently remain powered while at a stop and cause a fire.
#define DISABLE_LASER_DURING_HOLD // Default enabled. Comment to disable.
#define DISABLE_LASER_DURING_HOLD // Default enabled. Comment to disable.
// Enables a piecewise linear model of the spindle PWM/speed output. Requires a solution by the
// 'fit_nonlinear_spindle.py' script in the /doc/script folder of the repo. See file comments

View File

@ -23,7 +23,6 @@
#include "grbl.h"
void coolant_init() {
#ifdef COOLANT_FLOOD_PIN
pinMode(COOLANT_FLOOD_PIN, OUTPUT);
@ -34,88 +33,86 @@ void coolant_init() {
coolant_stop();
}
// Returns current coolant output state. Overrides may alter it from programmed state.
uint8_t coolant_get_state() {
uint8_t cl_state = COOLANT_STATE_DISABLE;
#ifdef COOLANT_FLOOD_PIN
#ifdef INVERT_COOLANT_FLOOD_PIN
if (! digitalRead(COOLANT_FLOOD_PIN)) {
#else
# ifdef INVERT_COOLANT_FLOOD_PIN
if (!digitalRead(COOLANT_FLOOD_PIN)) {
# else
if (digitalRead(COOLANT_FLOOD_PIN)) {
#endif
# endif
cl_state |= COOLANT_STATE_FLOOD;
}
#endif
#ifdef COOLANT_MIST_PIN
#ifdef INVERT_COOLANT_MIST_PIN
if (! digitalRead(COOLANT_MIST_PIN)) {
#else
# ifdef INVERT_COOLANT_MIST_PIN
if (!digitalRead(COOLANT_MIST_PIN)) {
# else
if (digitalRead(COOLANT_MIST_PIN)) {
#endif
# endif
cl_state |= COOLANT_STATE_MIST;
}
#endif
return (cl_state);
}
// Directly called by coolant_init(), coolant_set_state(), and mc_reset(), which can be at
// an interrupt-level. No report flag set, but only called by routines that don't need it.
void coolant_stop() {
#ifdef COOLANT_FLOOD_PIN
#ifdef INVERT_COOLANT_FLOOD_PIN
# ifdef INVERT_COOLANT_FLOOD_PIN
digitalWrite(COOLANT_FLOOD_PIN, 1);
#else
# else
digitalWrite(COOLANT_FLOOD_PIN, 0);
#endif
# endif
#endif
#ifdef COOLANT_MIST_PIN
#ifdef INVERT_COOLANT_MIST_PIN
# ifdef INVERT_COOLANT_MIST_PIN
digitalWrite(COOLANT_MIST_PIN, 1);
#else
# else
digitalWrite(COOLANT_MIST_PIN, 0);
#endif
# endif
#endif
}
// Main program only. Immediately sets flood coolant running state and also mist coolant,
// if enabled. Also sets a flag to report an update to a coolant state.
// Called by coolant toggle override, parking restore, parking retract, sleep mode, g-code
// parser program end, and g-code parser coolant_sync().
void coolant_set_state(uint8_t mode) {
if (sys.abort) return; // Block during abort.
if (sys.abort)
return; // Block during abort.
if (mode == COOLANT_DISABLE)
coolant_stop();
else {
#ifdef COOLANT_FLOOD_PIN
if (mode & COOLANT_FLOOD_ENABLE) {
#ifdef INVERT_COOLANT_FLOOD_PIN
# ifdef INVERT_COOLANT_FLOOD_PIN
digitalWrite(COOLANT_FLOOD_PIN, 0);
#else
# else
digitalWrite(COOLANT_FLOOD_PIN, 1);
#endif
# endif
}
#endif
#ifdef COOLANT_MIST_PIN
if (mode & COOLANT_MIST_ENABLE) {
#ifdef INVERT_COOLANT_MIST_PIN
# ifdef INVERT_COOLANT_MIST_PIN
digitalWrite(COOLANT_MIST_PIN, 0);
#else
# else
digitalWrite(COOLANT_MIST_PIN, 1);
#endif
# endif
}
#endif
}
sys.report_ovr_counter = 0; // Set to report change immediately
sys.report_ovr_counter = 0; // Set to report change immediately
}
// G-code parser entry-point for setting coolant state. Forces a planner buffer sync and bails
// if an abort or check-mode is active.
void coolant_sync(uint8_t mode) {
if (sys.state == STATE_CHECK_MODE) return;
protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
if (sys.state == STATE_CHECK_MODE)
return;
protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
coolant_set_state(mode);
}

View File

@ -23,13 +23,12 @@
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#define COOLANT_NO_SYNC false
#define COOLANT_FORCE_SYNC true
#define COOLANT_STATE_DISABLE 0 // Must be zero
#define COOLANT_STATE_FLOOD bit(0)
#define COOLANT_STATE_MIST bit(1)
#define COOLANT_NO_SYNC false
#define COOLANT_FORCE_SYNC true
#define COOLANT_STATE_DISABLE 0 // Must be zero
#define COOLANT_STATE_FLOOD bit(0)
#define COOLANT_STATE_MIST bit(1)
// Initializes coolant control pins.
void coolant_init();

View File

@ -4,5 +4,5 @@
#include "grbl.h"
#ifdef CUSTOM_CODE_FILENAME
#include CUSTOM_CODE_FILENAME
# include CUSTOM_CODE_FILENAME
#endif

View File

@ -30,406 +30,403 @@
your nefarious needs.
NOTE: Ensure one and only one of these DEFAULTS_XXX values is defined in config.h */
/*
/*
All of these settings check to see if they have been defined already
before defining them. This allows to to easily set them eslewhere.
You only need to set ones that are important or unique to your
machine. The rest will be pulled from here.
*/
// Grbl generic default settings. Should work across different machines.
#ifndef DEFAULT_STEP_PULSE_MICROSECONDS
#define DEFAULT_STEP_PULSE_MICROSECONDS 3 // $0
#endif
// Grbl generic default settings. Should work across different machines.
#ifndef DEFAULT_STEP_PULSE_MICROSECONDS
# define DEFAULT_STEP_PULSE_MICROSECONDS 3 // $0
#endif
#ifndef DEFAULT_STEPPER_IDLE_LOCK_TIME
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // $1 msec (0-254, 255 keeps steppers enabled)
#endif
#ifndef DEFAULT_STEPPER_IDLE_LOCK_TIME
# define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // $1 msec (0-254, 255 keeps steppers enabled)
#endif
#ifndef DEFAULT_STEPPING_INVERT_MASK
#define DEFAULT_STEPPING_INVERT_MASK 0 // $2 uint8_t
#endif
#ifndef DEFAULT_STEPPING_INVERT_MASK
# define DEFAULT_STEPPING_INVERT_MASK 0 // $2 uint8_t
#endif
#ifndef DEFAULT_DIRECTION_INVERT_MASK
#define DEFAULT_DIRECTION_INVERT_MASK 0 // $3 uint8_
#endif
#ifndef DEFAULT_DIRECTION_INVERT_MASK
# define DEFAULT_DIRECTION_INVERT_MASK 0 // $3 uint8_
#endif
#ifndef DEFAULT_INVERT_ST_ENABLE
#define DEFAULT_INVERT_ST_ENABLE 0 // $4 boolean
#endif
#ifndef DEFAULT_INVERT_ST_ENABLE
# define DEFAULT_INVERT_ST_ENABLE 0 // $4 boolean
#endif
#ifndef DEFAULT_INVERT_LIMIT_PINS
#define DEFAULT_INVERT_LIMIT_PINS 1 // $5 boolean
#endif
#ifndef DEFAULT_INVERT_LIMIT_PINS
# define DEFAULT_INVERT_LIMIT_PINS 1 // $5 boolean
#endif
#ifndef DEFAULT_INVERT_PROBE_PIN
#define DEFAULT_INVERT_PROBE_PIN 0 // $6 boolean
#endif
#ifndef DEFAULT_INVERT_PROBE_PIN
# define DEFAULT_INVERT_PROBE_PIN 0 // $6 boolean
#endif
#ifndef DEFAULT_STATUS_REPORT_MASK
#define DEFAULT_STATUS_REPORT_MASK 1 // $10
#endif
#ifndef DEFAULT_STATUS_REPORT_MASK
# define DEFAULT_STATUS_REPORT_MASK 1 // $10
#endif
#ifndef DEFAULT_JUNCTION_DEVIATION
#define DEFAULT_JUNCTION_DEVIATION 0.01 // $11 mm
#endif
#ifndef DEFAULT_JUNCTION_DEVIATION
# define DEFAULT_JUNCTION_DEVIATION 0.01 // $11 mm
#endif
#ifndef DEFAULT_ARC_TOLERANCE
#define DEFAULT_ARC_TOLERANCE 0.002 // $12 mm
#endif
#ifndef DEFAULT_ARC_TOLERANCE
# define DEFAULT_ARC_TOLERANCE 0.002 // $12 mm
#endif
#ifndef DEFAULT_REPORT_INCHES
#define DEFAULT_REPORT_INCHES 0 // $13 false
#endif
#ifndef DEFAULT_REPORT_INCHES
# define DEFAULT_REPORT_INCHES 0 // $13 false
#endif
#ifndef DEFAULT_SOFT_LIMIT_ENABLE
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // $20 false
#endif
#ifndef DEFAULT_SOFT_LIMIT_ENABLE
# define DEFAULT_SOFT_LIMIT_ENABLE 0 // $20 false
#endif
#ifndef DEFAULT_HARD_LIMIT_ENABLE
#define DEFAULT_HARD_LIMIT_ENABLE 0 // $21 false
#endif
#ifndef DEFAULT_HARD_LIMIT_ENABLE
# define DEFAULT_HARD_LIMIT_ENABLE 0 // $21 false
#endif
#ifndef DEFAULT_HOMING_ENABLE
#define DEFAULT_HOMING_ENABLE 0 // $22 false
#endif
#ifndef DEFAULT_HOMING_ENABLE
# define DEFAULT_HOMING_ENABLE 0 // $22 false
#endif
#ifndef DEFAULT_HOMING_DIR_MASK
#define DEFAULT_HOMING_DIR_MASK 3 // $23 move positive dir Z, negative X,Y
#endif
#ifndef DEFAULT_HOMING_DIR_MASK
# define DEFAULT_HOMING_DIR_MASK 3 // $23 move positive dir Z, negative X,Y
#endif
#ifndef DEFAULT_HOMING_FEED_RATE
#define DEFAULT_HOMING_FEED_RATE 200.0 // $24 mm/min
#endif
#ifndef DEFAULT_HOMING_FEED_RATE
# define DEFAULT_HOMING_FEED_RATE 200.0 // $24 mm/min
#endif
#ifndef DEFAULT_HOMING_SEEK_RATE
#define DEFAULT_HOMING_SEEK_RATE 2000.0 // $25 mm/min
#endif
#ifndef DEFAULT_HOMING_SEEK_RATE
# define DEFAULT_HOMING_SEEK_RATE 2000.0 // $25 mm/min
#endif
#ifndef DEFAULT_HOMING_DEBOUNCE_DELAY
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // $26 msec (0-65k)
#endif
#ifndef DEFAULT_HOMING_DEBOUNCE_DELAY
# define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // $26 msec (0-65k)
#endif
#ifndef DEFAULT_HOMING_PULLOFF
#define DEFAULT_HOMING_PULLOFF 1.0 // $27 mm
#endif
#ifndef DEFAULT_HOMING_PULLOFF
# define DEFAULT_HOMING_PULLOFF 1.0 // $27 mm
#endif
// ======== SPINDLE STUFF ====================
#ifndef SPINDLE_TYPE
#define SPINDLE_TYPE SPINDLE_TYPE_NONE
#endif
// ======== SPINDLE STUFF ====================
#ifndef SPINDLE_TYPE
# define SPINDLE_TYPE SPINDLE_TYPE_NONE
#endif
#ifndef DEFAULT_SPINDLE_RPM_MIN // $31
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#endif
#ifndef DEFAULT_SPINDLE_RPM_MIN // $31
# define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#endif
#ifndef DEFAULT_LASER_MODE // $32
#define DEFAULT_LASER_MODE 0 // false
#endif
#ifndef DEFAULT_LASER_MODE // $32
# define DEFAULT_LASER_MODE 0 // false
#endif
#ifndef DEFAULT_SPINDLE_RPM_MAX // $30
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
#endif
#ifndef DEFAULT_SPINDLE_RPM_MAX // $30
# define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
#endif
#ifndef DEFAULT_SPINDLE_FREQ
#define DEFAULT_SPINDLE_FREQ 5000.0 // $33 Hz (extended set)
#endif
#ifndef DEFAULT_SPINDLE_FREQ
# define DEFAULT_SPINDLE_FREQ 5000.0 // $33 Hz (extended set)
#endif
#ifndef DEFAULT_SPINDLE_OFF_VALUE
#define DEFAULT_SPINDLE_OFF_VALUE 0.0 // $34 Percent of full period(extended set)
#endif
#ifndef DEFAULT_SPINDLE_OFF_VALUE
# define DEFAULT_SPINDLE_OFF_VALUE 0.0 // $34 Percent of full period(extended set)
#endif
#ifndef DEFAULT_SPINDLE_MIN_VALUE
#define DEFAULT_SPINDLE_MIN_VALUE 0.0 // $35 Percent of full period (extended set)
#endif
#ifndef DEFAULT_SPINDLE_MIN_VALUE
# define DEFAULT_SPINDLE_MIN_VALUE 0.0 // $35 Percent of full period (extended set)
#endif
#ifndef DEFAULT_SPINDLE_MAX_VALUE
#define DEFAULT_SPINDLE_MAX_VALUE 100.0 // $36 Percent of full period (extended set)
#endif
#ifndef DEFAULT_SPINDLE_MAX_VALUE
# define DEFAULT_SPINDLE_MAX_VALUE 100.0 // $36 Percent of full period (extended set)
#endif
#ifndef DEFAULT_SPINDLE_DELAY_SPINUP
#define DEFAULT_SPINDLE_DELAY_SPINUP 0
#endif
#ifndef DEFAULT_SPINDLE_DELAY_SPINUP
# define DEFAULT_SPINDLE_DELAY_SPINUP 0
#endif
#ifndef DEFAULT_SPINDLE_DELAY_SPINDOWN
#define DEFAULT_SPINDLE_DELAY_SPINDOWN 0
#endif
#ifndef DEFAULT_SPINDLE_DELAY_SPINDOWN
# define DEFAULT_SPINDLE_DELAY_SPINDOWN 0
#endif
// ================ user settings =====================
#ifndef DEFAULT_USER_INT_80
#define DEFAULT_USER_INT_80 0 // $80 User integer setting
#endif
// ================ user settings =====================
#ifndef DEFAULT_USER_INT_80
# define DEFAULT_USER_INT_80 0 // $80 User integer setting
#endif
#ifndef DEFAULT_USER_INT_81
#define DEFAULT_USER_INT_81 0 // $81 User integer setting
#endif
#ifndef DEFAULT_USER_INT_81
# define DEFAULT_USER_INT_81 0 // $81 User integer setting
#endif
#ifndef DEFAULT_USER_INT_82
#define DEFAULT_USER_INT_82 0 // $82 User integer setting
#endif
#ifndef DEFAULT_USER_INT_82
# define DEFAULT_USER_INT_82 0 // $82 User integer setting
#endif
#ifndef DEFAULT_USER_INT_83
#define DEFAULT_USER_INT_83 0 // $83 User integer setting
#endif
#ifndef DEFAULT_USER_INT_83
# define DEFAULT_USER_INT_83 0 // $83 User integer setting
#endif
#ifndef DEFAULT_USER_INT_84
#define DEFAULT_USER_INT_84 0 // $84 User integer setting
#endif
#ifndef DEFAULT_USER_INT_84
# define DEFAULT_USER_INT_84 0 // $84 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_90
#define DEFAULT_USER_FLOAT_90 0.0 // $90 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_90
# define DEFAULT_USER_FLOAT_90 0.0 // $90 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_91
#define DEFAULT_USER_FLOAT_91 0.0 // $92 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_91
# define DEFAULT_USER_FLOAT_91 0.0 // $92 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_92
#define DEFAULT_USER_FLOAT_92 0.0 // $92 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_92
# define DEFAULT_USER_FLOAT_92 0.0 // $92 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_93
#define DEFAULT_USER_FLOAT_93 0.0 // $93 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_93
# define DEFAULT_USER_FLOAT_93 0.0 // $93 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_94
#define DEFAULT_USER_FLOAT_94 0.0 // $94 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_94
# define DEFAULT_USER_FLOAT_94 0.0 // $94 User integer setting
#endif
// =========== AXIS RESOLUTION ======
// =========== AXIS RESOLUTION ======
#ifndef DEFAULT_X_STEPS_PER_MM
# define DEFAULT_X_STEPS_PER_MM 100.0
#endif
#ifndef DEFAULT_Y_STEPS_PER_MM
# define DEFAULT_Y_STEPS_PER_MM 100.0
#endif
#ifndef DEFAULT_Z_STEPS_PER_MM
# define DEFAULT_Z_STEPS_PER_MM 100.0
#endif
#ifndef DEFAULT_A_STEPS_PER_MM
# define DEFAULT_A_STEPS_PER_MM 100.0
#endif
#ifndef DEFAULT_B_STEPS_PER_MM
# define DEFAULT_B_STEPS_PER_MM 100.0
#endif
#ifndef DEFAULT_C_STEPS_PER_MM
# define DEFAULT_C_STEPS_PER_MM 100.0
#endif
#ifndef DEFAULT_X_STEPS_PER_MM
#define DEFAULT_X_STEPS_PER_MM 100.0
#endif
#ifndef DEFAULT_Y_STEPS_PER_MM
#define DEFAULT_Y_STEPS_PER_MM 100.0
#endif
#ifndef DEFAULT_Z_STEPS_PER_MM
#define DEFAULT_Z_STEPS_PER_MM 100.0
#endif
#ifndef DEFAULT_A_STEPS_PER_MM
#define DEFAULT_A_STEPS_PER_MM 100.0
#endif
#ifndef DEFAULT_B_STEPS_PER_MM
#define DEFAULT_B_STEPS_PER_MM 100.0
#endif
#ifndef DEFAULT_C_STEPS_PER_MM
#define DEFAULT_C_STEPS_PER_MM 100.0
#endif
// ============ AXIS MAX SPPED =========
// ============ AXIS MAX SPPED =========
#ifndef DEFAULT_X_MAX_RATE
# define DEFAULT_X_MAX_RATE 1000.0 // mm/min
#endif
#ifndef DEFAULT_Y_MAX_RATE
# define DEFAULT_Y_MAX_RATE 1000.0 // mm/min
#endif
#ifndef DEFAULT_Z_MAX_RATE
# define DEFAULT_Z_MAX_RATE 1000.0 // mm/min
#endif
#ifndef DEFAULT_A_MAX_RATE
# define DEFAULT_A_MAX_RATE 1000.0 // mm/min
#endif
#ifndef DEFAULT_B_MAX_RATE
# define DEFAULT_B_MAX_RATE 1000.0 // mm/min
#endif
#ifndef DEFAULT_C_MAX_RATE
# define DEFAULT_C_MAX_RATE 1000.0 // mm/min
#endif
#ifndef DEFAULT_X_MAX_RATE
#define DEFAULT_X_MAX_RATE 1000.0 // mm/min
#endif
#ifndef DEFAULT_Y_MAX_RATE
#define DEFAULT_Y_MAX_RATE 1000.0 // mm/min
#endif
#ifndef DEFAULT_Z_MAX_RATE
#define DEFAULT_Z_MAX_RATE 1000.0 // mm/min
#endif
#ifndef DEFAULT_A_MAX_RATE
#define DEFAULT_A_MAX_RATE 1000.0 // mm/min
#endif
#ifndef DEFAULT_B_MAX_RATE
#define DEFAULT_B_MAX_RATE 1000.0 // mm/min
#endif
#ifndef DEFAULT_C_MAX_RATE
#define DEFAULT_C_MAX_RATE 1000.0 // mm/min
#endif
// ============== Axis Acceleration =========
#define SEC_PER_MIN_SQ (60.0 * 60.0) // Seconds Per Minute Squared, for acceleration conversion
// Default accelerations are expressed in mm/sec^2
#ifndef DEFAULT_X_ACCELERATION
# define DEFAULT_X_ACCELERATION 200.0
#endif
#ifndef DEFAULT_Y_ACCELERATION
# define DEFAULT_Y_ACCELERATION 200.0
#endif
#ifndef DEFAULT_Z_ACCELERATION
# define DEFAULT_Z_ACCELERATION 200.0
#endif
#ifndef DEFAULT_A_ACCELERATION
# define DEFAULT_A_ACCELERATION 200.0
#endif
#ifndef DEFAULT_B_ACCELERATION
# define DEFAULT_B_ACCELERATION 200.0
#endif
#ifndef DEFAULT_C_ACCELERATION
# define DEFAULT_C_ACCELERATION 200.0
#endif
// ============== Axis Acceleration =========
#define SEC_PER_MIN_SQ (60.0*60.0) // Seconds Per Minute Squared, for acceleration conversion
// Default accelerations are expressed in mm/sec^2
#ifndef DEFAULT_X_ACCELERATION
#define DEFAULT_X_ACCELERATION 200.0
#endif
#ifndef DEFAULT_Y_ACCELERATION
#define DEFAULT_Y_ACCELERATION 200.0
#endif
#ifndef DEFAULT_Z_ACCELERATION
#define DEFAULT_Z_ACCELERATION 200.0
#endif
#ifndef DEFAULT_A_ACCELERATION
#define DEFAULT_A_ACCELERATION 200.0
#endif
#ifndef DEFAULT_B_ACCELERATION
#define DEFAULT_B_ACCELERATION 200.0
#endif
#ifndef DEFAULT_C_ACCELERATION
#define DEFAULT_C_ACCELERATION 200.0
#endif
// ========= AXIS MAX TRAVEL ============
// ========= AXIS MAX TRAVEL ============
#ifndef DEFAULT_X_MAX_TRAVEL
# define DEFAULT_X_MAX_TRAVEL 300.0 // $130 mm NOTE: Must be a positive value.
#endif
#ifndef DEFAULT_Y_MAX_TRAVEL
# define DEFAULT_Y_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#endif
#ifndef DEFAULT_Z_MAX_TRAVEL
# define DEFAULT_Z_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#endif
#ifndef DEFAULT_A_MAX_TRAVEL
# define DEFAULT_A_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#endif
#ifndef DEFAULT_B_MAX_TRAVEL
# define DEFAULT_B_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#endif
#ifndef DEFAULT_C_MAX_TRAVEL
# define DEFAULT_C_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#endif
#ifndef DEFAULT_X_MAX_TRAVEL
#define DEFAULT_X_MAX_TRAVEL 300.0 // $130 mm NOTE: Must be a positive value.
#endif
#ifndef DEFAULT_Y_MAX_TRAVEL
#define DEFAULT_Y_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#endif
#ifndef DEFAULT_Z_MAX_TRAVEL
#define DEFAULT_Z_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#endif
#ifndef DEFAULT_A_MAX_TRAVEL
#define DEFAULT_A_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#endif
#ifndef DEFAULT_B_MAX_TRAVEL
#define DEFAULT_B_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#endif
#ifndef DEFAULT_C_MAX_TRAVEL
#define DEFAULT_C_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#endif
// ========== Motor current (SPI Drivers ) =============
#ifndef DEFAULT_X_CURRENT
# define DEFAULT_X_CURRENT 0.25 // $140 current in amps (extended set)
#endif
#ifndef DEFAULT_Y_CURRENT
# define DEFAULT_Y_CURRENT 0.25 // $141 current in amps (extended set)
#endif
#ifndef DEFAULT_Z_CURRENT
# define DEFAULT_Z_CURRENT 0.25 // $142 current in amps (extended set)
#endif
#ifndef DEFAULT_A_CURRENT
# define DEFAULT_A_CURRENT 0.25 // $143 current in amps (extended set)
#endif
#ifndef DEFAULT_B_CURRENT
# define DEFAULT_B_CURRENT 0.25 // $144 current in amps (extended set)
#endif
#ifndef DEFAULT_C_CURRENT
# define DEFAULT_C_CURRENT 0.25 // $145 current in amps (extended set)
#endif
// ========== Motor current (SPI Drivers ) =============
#ifndef DEFAULT_X_CURRENT
#define DEFAULT_X_CURRENT 0.25 // $140 current in amps (extended set)
#endif
#ifndef DEFAULT_Y_CURRENT
#define DEFAULT_Y_CURRENT 0.25 // $141 current in amps (extended set)
#endif
#ifndef DEFAULT_Z_CURRENT
#define DEFAULT_Z_CURRENT 0.25 // $142 current in amps (extended set)
#endif
#ifndef DEFAULT_A_CURRENT
#define DEFAULT_A_CURRENT 0.25 // $143 current in amps (extended set)
#endif
#ifndef DEFAULT_B_CURRENT
#define DEFAULT_B_CURRENT 0.25 // $144 current in amps (extended set)
#endif
#ifndef DEFAULT_C_CURRENT
#define DEFAULT_C_CURRENT 0.25 // $145 current in amps (extended set)
#endif
// ========== Motor hold current (SPI Drivers ) =============
// ========== Motor hold current (SPI Drivers ) =============
#ifndef DEFAULT_X_HOLD_CURRENT
# define DEFAULT_X_HOLD_CURRENT 0.125 // $150 current in amps (extended set)
#endif
#ifndef DEFAULT_Y_HOLD_CURRENT
# define DEFAULT_Y_HOLD_CURRENT 0.125 // $151 current in amps (extended set)
#endif
#ifndef DEFAULT_Z_HOLD_CURRENT
# define DEFAULT_Z_HOLD_CURRENT 0.125 // $152 current in amps (extended set)
#endif
#ifndef DEFAULT_A_HOLD_CURRENT
# define DEFAULT_A_HOLD_CURRENT 0.125 // $153 current in amps (extended set)
#endif
#ifndef DEFAULT_B_HOLD_CURRENT
# define DEFAULT_B_HOLD_CURRENT 0.125 // $154 current in amps (extended set)
#endif
#ifndef DEFAULT_C_HOLD_CURRENT
# define DEFAULT_C_HOLD_CURRENT 0.125 // $154 current in amps (extended set)
#endif
#ifndef DEFAULT_X_HOLD_CURRENT
#define DEFAULT_X_HOLD_CURRENT 0.125 // $150 current in amps (extended set)
#endif
#ifndef DEFAULT_Y_HOLD_CURRENT
#define DEFAULT_Y_HOLD_CURRENT 0.125 // $151 current in amps (extended set)
#endif
#ifndef DEFAULT_Z_HOLD_CURRENT
#define DEFAULT_Z_HOLD_CURRENT 0.125 // $152 current in amps (extended set)
#endif
#ifndef DEFAULT_A_HOLD_CURRENT
#define DEFAULT_A_HOLD_CURRENT 0.125 // $153 current in amps (extended set)
#endif
#ifndef DEFAULT_B_HOLD_CURRENT
#define DEFAULT_B_HOLD_CURRENT 0.125 // $154 current in amps (extended set)
#endif
#ifndef DEFAULT_C_HOLD_CURRENT
#define DEFAULT_C_HOLD_CURRENT 0.125 // $154 current in amps (extended set)
#endif
// ========== Microsteps (SPI Drivers ) ================
// ========== Microsteps (SPI Drivers ) ================
#ifndef DEFAULT_X_MICROSTEPS
# define DEFAULT_X_MICROSTEPS 16 // $160 micro steps (extended set)
#endif
#ifndef DEFAULT_Y_MICROSTEPS
# define DEFAULT_Y_MICROSTEPS 16 // $161 micro steps (extended set)
#endif
#ifndef DEFAULT_Z_MICROSTEPS
# define DEFAULT_Z_MICROSTEPS 16 // $162 micro steps (extended set)
#endif
#ifndef DEFAULT_A_MICROSTEPS
# define DEFAULT_A_MICROSTEPS 16 // $163 micro steps (extended set)
#endif
#ifndef DEFAULT_B_MICROSTEPS
# define DEFAULT_B_MICROSTEPS 16 // $164 micro steps (extended set)
#endif
#ifndef DEFAULT_C_MICROSTEPS
# define DEFAULT_C_MICROSTEPS 16 // $165 micro steps (extended set)
#endif
#ifndef DEFAULT_X_MICROSTEPS
#define DEFAULT_X_MICROSTEPS 16 // $160 micro steps (extended set)
#endif
#ifndef DEFAULT_Y_MICROSTEPS
#define DEFAULT_Y_MICROSTEPS 16 // $161 micro steps (extended set)
#endif
#ifndef DEFAULT_Z_MICROSTEPS
#define DEFAULT_Z_MICROSTEPS 16 // $162 micro steps (extended set)
#endif
#ifndef DEFAULT_A_MICROSTEPS
#define DEFAULT_A_MICROSTEPS 16 // $163 micro steps (extended set)
#endif
#ifndef DEFAULT_B_MICROSTEPS
#define DEFAULT_B_MICROSTEPS 16 // $164 micro steps (extended set)
#endif
#ifndef DEFAULT_C_MICROSTEPS
#define DEFAULT_C_MICROSTEPS 16 // $165 micro steps (extended set)
#endif
// ========== Stallguard (SPI Drivers ) ================
// ========== Stallguard (SPI Drivers ) ================
#ifndef DEFAULT_X_STALLGUARD
# define DEFAULT_X_STALLGUARD 16 // $170 stallguard (extended set)
#endif
#ifndef DEFAULT_Y_STALLGUARD
# define DEFAULT_Y_STALLGUARD 16 // $171 stallguard (extended set)
#endif
#ifndef DEFAULT_Z_STALLGUARD
# define DEFAULT_Z_STALLGUARD 16 // $172 stallguard (extended set)
#endif
#ifndef DEFAULT_A_STALLGUARD
# define DEFAULT_A_STALLGUARD 16 // $173 stallguard (extended set)
#endif
#ifndef DEFAULT_B_STALLGUARD
# define DEFAULT_B_STALLGUARD 16 // $174 stallguard (extended set)
#endif
#ifndef DEFAULT_C_STALLGUARD
# define DEFAULT_C_STALLGUARD 16 // $175 stallguard (extended set)
#endif
#ifndef DEFAULT_X_STALLGUARD
#define DEFAULT_X_STALLGUARD 16 // $170 stallguard (extended set)
#endif
#ifndef DEFAULT_Y_STALLGUARD
#define DEFAULT_Y_STALLGUARD 16 // $171 stallguard (extended set)
#endif
#ifndef DEFAULT_Z_STALLGUARD
#define DEFAULT_Z_STALLGUARD 16 // $172 stallguard (extended set)
#endif
#ifndef DEFAULT_A_STALLGUARD
#define DEFAULT_A_STALLGUARD 16 // $173 stallguard (extended set)
#endif
#ifndef DEFAULT_B_STALLGUARD
#define DEFAULT_B_STALLGUARD 16 // $174 stallguard (extended set)
#endif
#ifndef DEFAULT_C_STALLGUARD
#define DEFAULT_C_STALLGUARD 16 // $175 stallguard (extended set)
#endif
// ================== pin defaults ========================
// Here is a place to default pins to UNDEFINED_PIN.
// This can eliminate checking to see if the pin is defined because
// the overridden pinMode and digitalWrite functions will deal with it.
#ifndef STEPPERS_DISABLE_PIN
#define STEPPERS_DISABLE_PIN UNDEFINED_PIN
# define STEPPERS_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef X_DISABLE_PIN
#define X_DISABLE_PIN UNDEFINED_PIN
# define X_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef Y_DISABLE_PIN
#define Y_DISABLE_PIN UNDEFINED_PIN
# define Y_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef Z_DISABLE_PIN
#define Z_DISABLE_PIN UNDEFINED_PIN
# define Z_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef A_DISABLE_PIN
#define A_DISABLE_PIN UNDEFINED_PIN
# define A_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef B_DISABLE_PIN
#define B_DISABLE_PIN UNDEFINED_PIN
# define B_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef C_DISABLE_PIN
#define C_DISABLE_PIN UNDEFINED_PIN
# define C_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef X2_DISABLE_PIN
#define X2_DISABLE_PIN UNDEFINED_PIN
# define X2_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef Y2_DISABLE_PIN
#define Y2_DISABLE_PIN UNDEFINED_PIN
# define Y2_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef Z2_DISABLE_PIN
#define Z2_DISABLE_PIN UNDEFINED_PIN
# define Z2_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef A2_DISABLE_PIN
#define A2_DISABLE_PIN UNDEFINED_PIN
# define A2_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef B2_DISABLE_PIN
#define B2_DISABLE_PIN UNDEFINED_PIN
# define B2_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef C2_DISABLE_PIN
#define C2_DISABLE_PIN UNDEFINED_PIN
# define C2_DISABLE_PIN UNDEFINED_PIN
#endif
#ifndef X_LIMIT_PIN
#define X_LIMIT_PIN UNDEFINED_PIN
# define X_LIMIT_PIN UNDEFINED_PIN
#endif
#ifndef Y_LIMIT_PIN
#define Y_LIMIT_PIN UNDEFINED_PIN
# define Y_LIMIT_PIN UNDEFINED_PIN
#endif
#ifndef Z_LIMIT_PIN
#define Z_LIMIT_PIN UNDEFINED_PIN
# define Z_LIMIT_PIN UNDEFINED_PIN
#endif
#ifndef A_LIMIT_PIN
#define A_LIMIT_PIN UNDEFINED_PIN
# define A_LIMIT_PIN UNDEFINED_PIN
#endif
#ifndef B_LIMIT_PIN
#define B_LIMIT_PIN UNDEFINED_PIN
# define B_LIMIT_PIN UNDEFINED_PIN
#endif
#ifndef C_LIMIT_PIN
#define C_LIMIT_PIN UNDEFINED_PIN
# define C_LIMIT_PIN UNDEFINED_PIN
#endif

View File

@ -19,40 +19,42 @@
*/
#include "grbl.h"
#include "espresponse.h"
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
#include "web_server.h"
#include <WebServer.h>
#if defined(ENABLE_HTTP) && defined(ENABLE_WIFI)
# include "web_server.h"
# include <WebServer.h>
#endif
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
#if defined(ENABLE_HTTP) && defined(ENABLE_WIFI)
ESPResponseStream::ESPResponseStream(WebServer* webserver) {
_header_sent = false;
_webserver = webserver;
_client = CLIENT_WEBUI;
_webserver = webserver;
_client = CLIENT_WEBUI;
}
#endif
ESPResponseStream::ESPResponseStream() {
_client = CLIENT_INPUT;
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
#if defined(ENABLE_HTTP) && defined(ENABLE_WIFI)
_header_sent = false;
_webserver = NULL;
_webserver = NULL;
#endif
}
ESPResponseStream::ESPResponseStream(uint8_t client, bool byid) {
(void)byid; //fake parameter to avoid confusion with pointer one (NULL == 0)
(void)byid; //fake parameter to avoid confusion with pointer one (NULL == 0)
_client = client;
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
#if defined(ENABLE_HTTP) && defined(ENABLE_WIFI)
_header_sent = false;
_webserver = NULL;
_webserver = NULL;
#endif
}
void ESPResponseStream::println(const char* data) {
print(data);
if (_client == CLIENT_TELNET) print("\r\n");
else print("\n");
if (_client == CLIENT_TELNET)
print("\r\n");
else
print("\n");
}
//helper to format size to readable string
@ -68,8 +70,9 @@ String ESPResponseStream::formatBytes(uint64_t bytes) {
}
void ESPResponseStream::print(const char* data) {
if (_client == CLIENT_INPUT) return;
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
if (_client == CLIENT_INPUT)
return;
#if defined(ENABLE_HTTP) && defined(ENABLE_WIFI)
if (_webserver) {
if (!_header_sent) {
_webserver->setContentLength(CONTENT_LENGTH_UNKNOWN);
@ -88,21 +91,23 @@ void ESPResponseStream::print(const char* data) {
return;
}
#endif
if (_client == CLIENT_WEBUI) return; //this is sanity check
if (_client == CLIENT_WEBUI)
return; //this is sanity check
grbl_send(_client, data);
}
void ESPResponseStream::flush() {
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
#if defined(ENABLE_HTTP) && defined(ENABLE_WIFI)
if (_webserver) {
if (_header_sent) {
//send data
if (_buffer.length() > 0)_webserver->sendContent(_buffer);
if (_buffer.length() > 0)
_webserver->sendContent(_buffer);
//close connection
_webserver->sendContent("");
}
_header_sent = false;
_buffer = "";
_buffer = "";
}
#endif
}

View File

@ -20,28 +20,29 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
class WebServer;
#if defined(ENABLE_HTTP) && defined(ENABLE_WIFI)
class WebServer;
#endif
class ESPResponseStream {
public:
void print(const char* data);
void println(const char* data);
void flush();
bool anyOutput() { return _header_sent; }
public:
void print(const char* data);
void println(const char* data);
void flush();
bool anyOutput() { return _header_sent; }
static String formatBytes(uint64_t bytes);
uint8_t client() {return _client;}
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
uint8_t client() { return _client; }
#if defined(ENABLE_HTTP) && defined(ENABLE_WIFI)
ESPResponseStream(WebServer* webserver);
#endif
ESPResponseStream(uint8_t client, bool byid = true);
ESPResponseStream();
private:
private:
uint8_t _client;
bool _header_sent;
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
bool _header_sent;
#if defined(ENABLE_HTTP) && defined(ENABLE_WIFI)
WebServer* _webserver;
String _buffer;
String _buffer;
#endif
};

File diff suppressed because it is too large Load Diff

View File

@ -30,24 +30,24 @@
// a unique motion. These are defined in the NIST RS274-NGC v3 g-code standard, available online,
// and are similar/identical to other g-code interpreters by manufacturers (Haas,Fanuc,Mazak,etc).
// NOTE: Modal group define values must be sequential and starting from zero.
#define MODAL_GROUP_G0 0 // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal
#define MODAL_GROUP_G1 1 // [G0,G1,G2,G3,G38.2,G38.3,G38.4,G38.5,G80] Motion
#define MODAL_GROUP_G2 2 // [G17,G18,G19] Plane selection
#define MODAL_GROUP_G3 3 // [G90,G91] Distance mode
#define MODAL_GROUP_G4 4 // [G91.1] Arc IJK distance mode
#define MODAL_GROUP_G5 5 // [G93,G94] Feed rate mode
#define MODAL_GROUP_G6 6 // [G20,G21] Units
#define MODAL_GROUP_G7 7 // [G40] Cutter radius compensation mode. G41/42 NOT SUPPORTED.
#define MODAL_GROUP_G8 8 // [G43.1,G49] Tool length offset
#define MODAL_GROUP_G12 9 // [G54,G55,G56,G57,G58,G59] Coordinate system selection
#define MODAL_GROUP_G13 10 // [G61] Control mode
#define MODAL_GROUP_G0 0 // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal
#define MODAL_GROUP_G1 1 // [G0,G1,G2,G3,G38.2,G38.3,G38.4,G38.5,G80] Motion
#define MODAL_GROUP_G2 2 // [G17,G18,G19] Plane selection
#define MODAL_GROUP_G3 3 // [G90,G91] Distance mode
#define MODAL_GROUP_G4 4 // [G91.1] Arc IJK distance mode
#define MODAL_GROUP_G5 5 // [G93,G94] Feed rate mode
#define MODAL_GROUP_G6 6 // [G20,G21] Units
#define MODAL_GROUP_G7 7 // [G40] Cutter radius compensation mode. G41/42 NOT SUPPORTED.
#define MODAL_GROUP_G8 8 // [G43.1,G49] Tool length offset
#define MODAL_GROUP_G12 9 // [G54,G55,G56,G57,G58,G59] Coordinate system selection
#define MODAL_GROUP_G13 10 // [G61] Control mode
#define MODAL_GROUP_M4 11 // [M0,M1,M2,M30] Stopping
#define MODAL_GROUP_M6 14 // [M6] Tool change
#define MODAL_GROUP_M7 12 // [M3,M4,M5] Spindle turning
#define MODAL_GROUP_M8 13 // [M7,M8,M9] Coolant control
#define MODAL_GROUP_M9 14 // [M56] Override control
#define MODAL_GROUP_M10 15 // [M62, M63] User Defined http://linuxcnc.org/docs/html/gcode/overview.html#_modal_groups
#define MODAL_GROUP_M4 11 // [M0,M1,M2,M30] Stopping
#define MODAL_GROUP_M6 14 // [M6] Tool change
#define MODAL_GROUP_M7 12 // [M3,M4,M5] Spindle turning
#define MODAL_GROUP_M8 13 // [M7,M8,M9] Coolant control
#define MODAL_GROUP_M9 14 // [M56] Override control
#define MODAL_GROUP_M10 15 // [M62, M63] User Defined http://linuxcnc.org/docs/html/gcode/overview.html#_modal_groups
// #define OTHER_INPUT_F 14
// #define OTHER_INPUT_S 15
@ -61,88 +61,88 @@
// to see how they are used, if you need to alter them.
// Modal Group G0: Non-modal actions
#define NON_MODAL_NO_ACTION 0 // (Default: Must be zero)
#define NON_MODAL_DWELL 4 // G4 (Do not alter value)
#define NON_MODAL_SET_COORDINATE_DATA 10 // G10 (Do not alter value)
#define NON_MODAL_GO_HOME_0 28 // G28 (Do not alter value)
#define NON_MODAL_SET_HOME_0 38 // G28.1 (Do not alter value)
#define NON_MODAL_GO_HOME_1 30 // G30 (Do not alter value)
#define NON_MODAL_SET_HOME_1 40 // G30.1 (Do not alter value)
#define NON_MODAL_ABSOLUTE_OVERRIDE 53 // G53 (Do not alter value)
#define NON_MODAL_SET_COORDINATE_OFFSET 92 // G92 (Do not alter value)
#define NON_MODAL_RESET_COORDINATE_OFFSET 102 //G92.1 (Do not alter value)
#define NON_MODAL_NO_ACTION 0 // (Default: Must be zero)
#define NON_MODAL_DWELL 4 // G4 (Do not alter value)
#define NON_MODAL_SET_COORDINATE_DATA 10 // G10 (Do not alter value)
#define NON_MODAL_GO_HOME_0 28 // G28 (Do not alter value)
#define NON_MODAL_SET_HOME_0 38 // G28.1 (Do not alter value)
#define NON_MODAL_GO_HOME_1 30 // G30 (Do not alter value)
#define NON_MODAL_SET_HOME_1 40 // G30.1 (Do not alter value)
#define NON_MODAL_ABSOLUTE_OVERRIDE 53 // G53 (Do not alter value)
#define NON_MODAL_SET_COORDINATE_OFFSET 92 // G92 (Do not alter value)
#define NON_MODAL_RESET_COORDINATE_OFFSET 102 //G92.1 (Do not alter value)
// Modal Group G1: Motion modes
#define MOTION_MODE_SEEK 0 // G0 (Default: Must be zero)
#define MOTION_MODE_LINEAR 1 // G1 (Do not alter value)
#define MOTION_MODE_CW_ARC 2 // G2 (Do not alter value)
#define MOTION_MODE_CCW_ARC 3 // G3 (Do not alter value)
#define MOTION_MODE_PROBE_TOWARD 140 // G38.2 (Do not alter value)
#define MOTION_MODE_PROBE_TOWARD_NO_ERROR 141 // G38.3 (Do not alter value)
#define MOTION_MODE_PROBE_AWAY 142 // G38.4 (Do not alter value)
#define MOTION_MODE_PROBE_AWAY_NO_ERROR 143 // G38.5 (Do not alter value)
#define MOTION_MODE_NONE 80 // G80 (Do not alter value)
#define MOTION_MODE_SEEK 0 // G0 (Default: Must be zero)
#define MOTION_MODE_LINEAR 1 // G1 (Do not alter value)
#define MOTION_MODE_CW_ARC 2 // G2 (Do not alter value)
#define MOTION_MODE_CCW_ARC 3 // G3 (Do not alter value)
#define MOTION_MODE_PROBE_TOWARD 140 // G38.2 (Do not alter value)
#define MOTION_MODE_PROBE_TOWARD_NO_ERROR 141 // G38.3 (Do not alter value)
#define MOTION_MODE_PROBE_AWAY 142 // G38.4 (Do not alter value)
#define MOTION_MODE_PROBE_AWAY_NO_ERROR 143 // G38.5 (Do not alter value)
#define MOTION_MODE_NONE 80 // G80 (Do not alter value)
// Modal Group G2: Plane select
#define PLANE_SELECT_XY 0 // G17 (Default: Must be zero)
#define PLANE_SELECT_ZX 1 // G18 (Do not alter value)
#define PLANE_SELECT_YZ 2 // G19 (Do not alter value)
#define PLANE_SELECT_XY 0 // G17 (Default: Must be zero)
#define PLANE_SELECT_ZX 1 // G18 (Do not alter value)
#define PLANE_SELECT_YZ 2 // G19 (Do not alter value)
// Modal Group G3: Distance mode
#define DISTANCE_MODE_ABSOLUTE 0 // G90 (Default: Must be zero)
#define DISTANCE_MODE_INCREMENTAL 1 // G91 (Do not alter value)
#define DISTANCE_MODE_ABSOLUTE 0 // G90 (Default: Must be zero)
#define DISTANCE_MODE_INCREMENTAL 1 // G91 (Do not alter value)
// Modal Group G4: Arc IJK distance mode
#define DISTANCE_ARC_MODE_INCREMENTAL 0 // G91.1 (Default: Must be zero)
#define DISTANCE_ARC_MODE_INCREMENTAL 0 // G91.1 (Default: Must be zero)
// Modal Group M4: Program flow
#define PROGRAM_FLOW_RUNNING 0 // (Default: Must be zero)
#define PROGRAM_FLOW_PAUSED 3 // M0
#define PROGRAM_FLOW_OPTIONAL_STOP 1 // M1 NOTE: Not supported, but valid and ignored.
#define PROGRAM_FLOW_COMPLETED_M2 2 // M2 (Do not alter value)
#define PROGRAM_FLOW_COMPLETED_M30 30 // M30 (Do not alter value)
#define PROGRAM_FLOW_RUNNING 0 // (Default: Must be zero)
#define PROGRAM_FLOW_PAUSED 3 // M0
#define PROGRAM_FLOW_OPTIONAL_STOP 1 // M1 NOTE: Not supported, but valid and ignored.
#define PROGRAM_FLOW_COMPLETED_M2 2 // M2 (Do not alter value)
#define PROGRAM_FLOW_COMPLETED_M30 30 // M30 (Do not alter value)
// Modal Group G5: Feed rate mode
#define FEED_RATE_MODE_UNITS_PER_MIN 0 // G94 (Default: Must be zero)
#define FEED_RATE_MODE_INVERSE_TIME 1 // G93 (Do not alter value)
#define FEED_RATE_MODE_UNITS_PER_MIN 0 // G94 (Default: Must be zero)
#define FEED_RATE_MODE_INVERSE_TIME 1 // G93 (Do not alter value)
// Modal Group G6: Units mode
#define UNITS_MODE_MM 0 // G21 (Default: Must be zero)
#define UNITS_MODE_INCHES 1 // G20 (Do not alter value)
#define UNITS_MODE_MM 0 // G21 (Default: Must be zero)
#define UNITS_MODE_INCHES 1 // G20 (Do not alter value)
// Modal Group G7: Cutter radius compensation mode
#define CUTTER_COMP_DISABLE 0 // G40 (Default: Must be zero)
#define CUTTER_COMP_DISABLE 0 // G40 (Default: Must be zero)
// Modal Group G13: Control mode
#define CONTROL_MODE_EXACT_PATH 0 // G61 (Default: Must be zero)
#define CONTROL_MODE_EXACT_PATH 0 // G61 (Default: Must be zero)
// Modal Group M7: Spindle control
#define SPINDLE_DISABLE 0 // M5 (Default: Must be zero)
#define SPINDLE_ENABLE_CW PL_COND_FLAG_SPINDLE_CW // M3 (NOTE: Uses planner condition bit flag)
#define SPINDLE_ENABLE_CCW PL_COND_FLAG_SPINDLE_CCW // M4 (NOTE: Uses planner condition bit flag)
#define SPINDLE_DISABLE 0 // M5 (Default: Must be zero)
#define SPINDLE_ENABLE_CW PL_COND_FLAG_SPINDLE_CW // M3 (NOTE: Uses planner condition bit flag)
#define SPINDLE_ENABLE_CCW PL_COND_FLAG_SPINDLE_CCW // M4 (NOTE: Uses planner condition bit flag)
// Modal Group M8: Coolant control
#define COOLANT_DISABLE 0 // M9 (Default: Must be zero)
#define COOLANT_FLOOD_ENABLE PL_COND_FLAG_COOLANT_FLOOD // M8 (NOTE: Uses planner condition bit flag)
#define COOLANT_MIST_ENABLE PL_COND_FLAG_COOLANT_MIST // M7 (NOTE: Uses planner condition bit flag)
#define COOLANT_DISABLE 0 // M9 (Default: Must be zero)
#define COOLANT_FLOOD_ENABLE PL_COND_FLAG_COOLANT_FLOOD // M8 (NOTE: Uses planner condition bit flag)
#define COOLANT_MIST_ENABLE PL_COND_FLAG_COOLANT_MIST // M7 (NOTE: Uses planner condition bit flag)
// Modal Group M9: Override control
#ifdef DEACTIVATE_PARKING_UPON_INIT
#define OVERRIDE_DISABLED 0 // (Default: Must be zero)
#define OVERRIDE_PARKING_MOTION 1 // M56
# define OVERRIDE_DISABLED 0 // (Default: Must be zero)
# define OVERRIDE_PARKING_MOTION 1 // M56
#else
#define OVERRIDE_PARKING_MOTION 0 // M56 (Default: Must be zero)
#define OVERRIDE_DISABLED 1 // Parking disabled.
# define OVERRIDE_PARKING_MOTION 0 // M56 (Default: Must be zero)
# define OVERRIDE_DISABLED 1 // Parking disabled.
#endif
// modal Group M10: User I/O control
#define NON_MODAL_IO_ENABLE 1
#define NON_MODAL_IO_DISABLE 2
#define MAX_USER_DIGITAL_PIN 4
#define NON_MODAL_IO_ENABLE 1
#define NON_MODAL_IO_DISABLE 2
#define MAX_USER_DIGITAL_PIN 4
// Modal Group G8: Tool length offset
#define TOOL_LENGTH_OFFSET_CANCEL 0 // G49 (Default: Must be zero)
#define TOOL_LENGTH_OFFSET_ENABLE_DYNAMIC 1 // G43.1
#define TOOL_LENGTH_OFFSET_CANCEL 0 // G49 (Default: Must be zero)
#define TOOL_LENGTH_OFFSET_ENABLE_DYNAMIC 1 // G43.1
#define TOOL_CHANGE 1
@ -150,111 +150,107 @@
// N/A: Stores coordinate system value (54-59) to change to.
// Define parameter word mapping.
#define WORD_F 0
#define WORD_I 1
#define WORD_J 2
#define WORD_K 3
#define WORD_L 4
#define WORD_N 5
#define WORD_P 6
#define WORD_R 7
#define WORD_S 8
#define WORD_T 9
#define WORD_X 10
#define WORD_Y 11
#define WORD_Z 12
#define WORD_A 13
#define WORD_B 14
#define WORD_C 15
#define WORD_F 0
#define WORD_I 1
#define WORD_J 2
#define WORD_K 3
#define WORD_L 4
#define WORD_N 5
#define WORD_P 6
#define WORD_R 7
#define WORD_S 8
#define WORD_T 9
#define WORD_X 10
#define WORD_Y 11
#define WORD_Z 12
#define WORD_A 13
#define WORD_B 14
#define WORD_C 15
// Define g-code parser position updating flags
#define GC_UPDATE_POS_TARGET 0 // Must be zero
#define GC_UPDATE_POS_SYSTEM 1
#define GC_UPDATE_POS_NONE 2
#define GC_UPDATE_POS_TARGET 0 // Must be zero
#define GC_UPDATE_POS_SYSTEM 1
#define GC_UPDATE_POS_NONE 2
// Define probe cycle exit states and assign proper position updating.
#define GC_PROBE_FOUND GC_UPDATE_POS_SYSTEM
#define GC_PROBE_ABORT GC_UPDATE_POS_NONE
#define GC_PROBE_FAIL_INIT GC_UPDATE_POS_NONE
#define GC_PROBE_FAIL_END GC_UPDATE_POS_TARGET
#define GC_PROBE_FOUND GC_UPDATE_POS_SYSTEM
#define GC_PROBE_ABORT GC_UPDATE_POS_NONE
#define GC_PROBE_FAIL_INIT GC_UPDATE_POS_NONE
#define GC_PROBE_FAIL_END GC_UPDATE_POS_TARGET
#ifdef SET_CHECK_MODE_PROBE_TO_START
#define GC_PROBE_CHECK_MODE GC_UPDATE_POS_NONE
# define GC_PROBE_CHECK_MODE GC_UPDATE_POS_NONE
#else
#define GC_PROBE_CHECK_MODE GC_UPDATE_POS_TARGET
# define GC_PROBE_CHECK_MODE GC_UPDATE_POS_TARGET
#endif
// Define gcode parser flags for handling special cases.
#define GC_PARSER_NONE 0 // Must be zero.
#define GC_PARSER_JOG_MOTION bit(0)
#define GC_PARSER_CHECK_MANTISSA bit(1)
#define GC_PARSER_ARC_IS_CLOCKWISE bit(2)
#define GC_PARSER_PROBE_IS_AWAY bit(3)
#define GC_PARSER_PROBE_IS_NO_ERROR bit(4)
#define GC_PARSER_LASER_FORCE_SYNC bit(5)
#define GC_PARSER_LASER_DISABLE bit(6)
#define GC_PARSER_LASER_ISMOTION bit(7)
#define GC_PARSER_NONE 0 // Must be zero.
#define GC_PARSER_JOG_MOTION bit(0)
#define GC_PARSER_CHECK_MANTISSA bit(1)
#define GC_PARSER_ARC_IS_CLOCKWISE bit(2)
#define GC_PARSER_PROBE_IS_AWAY bit(3)
#define GC_PARSER_PROBE_IS_NO_ERROR bit(4)
#define GC_PARSER_LASER_FORCE_SYNC bit(5)
#define GC_PARSER_LASER_DISABLE bit(6)
#define GC_PARSER_LASER_ISMOTION bit(7)
// NOTE: When this struct is zeroed, the above defines set the defaults for the system.
typedef struct {
uint8_t motion; // {G0,G1,G2,G3,G38.2,G80}
uint8_t feed_rate; // {G93,G94}
uint8_t units; // {G20,G21}
uint8_t distance; // {G90,G91}
uint8_t motion; // {G0,G1,G2,G3,G38.2,G80}
uint8_t feed_rate; // {G93,G94}
uint8_t units; // {G20,G21}
uint8_t distance; // {G90,G91}
// uint8_t distance_arc; // {G91.1} NOTE: Don't track. Only default supported.
uint8_t plane_select; // {G17,G18,G19}
uint8_t plane_select; // {G17,G18,G19}
// uint8_t cutter_comp; // {G40} NOTE: Don't track. Only default supported.
uint8_t tool_length; // {G43.1,G49}
uint8_t coord_select; // {G54,G55,G56,G57,G58,G59}
uint8_t tool_length; // {G43.1,G49}
uint8_t coord_select; // {G54,G55,G56,G57,G58,G59}
// uint8_t control; // {G61} NOTE: Don't track. Only default supported.
uint8_t program_flow; // {M0,M1,M2,M30}
uint8_t coolant; // {M7,M8,M9}
uint8_t spindle; // {M3,M4,M5}
uint8_t tool_change; // {M6}
uint8_t io_control; // {M62, M63}
uint8_t override; // {M56}
uint8_t program_flow; // {M0,M1,M2,M30}
uint8_t coolant; // {M7,M8,M9}
uint8_t spindle; // {M3,M4,M5}
uint8_t tool_change; // {M6}
uint8_t io_control; // {M62, M63}
uint8_t override; // {M56}
} gc_modal_t;
typedef struct {
float f; // Feed
float ijk[N_AXIS]; // I,J,K Axis arc offsets
uint8_t l; // G10 or canned cycles parameters
int32_t n; // Line number
float p; // G10 or dwell parameters
float f; // Feed
float ijk[N_AXIS]; // I,J,K Axis arc offsets
uint8_t l; // G10 or canned cycles parameters
int32_t n; // Line number
float p; // G10 or dwell parameters
// float q; // G82 peck drilling
float r; // Arc radius
float s; // Spindle speed
uint8_t t; // Tool selection
float xyz[N_AXIS]; // X,Y,Z Translational axes
float r; // Arc radius
float s; // Spindle speed
uint8_t t; // Tool selection
float xyz[N_AXIS]; // X,Y,Z Translational axes
} gc_values_t;
typedef struct {
gc_modal_t modal;
float spindle_speed; // RPM
float feed_rate; // Millimeters/min
uint8_t tool; // Tracks tool number. NOT USED.
int32_t line_number; // Last line number sent
float spindle_speed; // RPM
float feed_rate; // Millimeters/min
uint8_t tool; // Tracks tool number. NOT USED.
int32_t line_number; // Last line number sent
float position[N_AXIS]; // Where the interpreter considers the tool to be at this point in the code
float position[N_AXIS]; // Where the interpreter considers the tool to be at this point in the code
float coord_system[N_AXIS]; // Current work coordinate system (G54+). Stores offset from absolute machine
float coord_system[N_AXIS]; // Current work coordinate system (G54+). Stores offset from absolute machine
// position in mm. Loaded from EEPROM when called.
float coord_offset[N_AXIS]; // Retains the G92 coordinate offset (work coordinates) relative to
float coord_offset[N_AXIS]; // Retains the G92 coordinate offset (work coordinates) relative to
// machine zero in mm. Non-persistent. Cleared upon reset and boot.
float tool_length_offset; // Tracks tool length offset value when enabled.
float tool_length_offset; // Tracks tool length offset value when enabled.
} parser_state_t;
extern parser_state_t gc_state;
typedef struct {
uint8_t non_modal_command;
gc_modal_t modal;
uint8_t non_modal_command;
gc_modal_t modal;
gc_values_t values;
} parser_block_t;
// Initialize the parser
void gc_init();

View File

@ -25,7 +25,6 @@
#define GRBL_VERSION "1.3a"
#define GRBL_VERSION_BUILD "20200727"
//#include <sdkconfig.h>
#include <Arduino.h>
#include <EEPROM.h>
@ -52,7 +51,6 @@
#include "gcode.h"
#include "grbl_limits.h"
#include "motion_control.h"
#include "print.h"
#include "probe.h"
#include "protocol.h"
#include "report.h"
@ -72,34 +70,34 @@
#include "grbl_sd.h"
#ifdef ENABLE_BLUETOOTH
#include "BTconfig.h"
# include "BTconfig.h"
#endif
#ifdef ENABLE_WIFI
#include "wificonfig.h"
#ifdef ENABLE_HTTP
#include "serial2socket.h"
#endif
#ifdef ENABLE_TELNET
#include "telnet_server.h"
#endif
#ifdef ENABLE_NOTIFICATIONS
#include "notifications_service.h"
#endif
# include "wificonfig.h"
# ifdef ENABLE_HTTP
# include "serial2socket.h"
# endif
# ifdef ENABLE_TELNET
# include "telnet_server.h"
# endif
# ifdef ENABLE_NOTIFICATIONS
# include "notifications_service.h"
# endif
#endif
#include "solenoid_pen.h"
#ifdef USE_SERVO_AXES
#include "servo_axis.h"
# include "servo_axis.h"
#endif
#ifdef USE_UNIPOLAR
#include "grbl_unipolar.h"
# include "grbl_unipolar.h"
#endif
#ifdef USE_I2S_OUT
#include "i2s_out.h"
# include "i2s_out.h"
#endif
// Called if USE_MACHINE_INIT is defined

View File

@ -34,7 +34,7 @@ void memcpy_to_eeprom_with_checksum(unsigned int destination, const char* source
int memcpy_from_eeprom_with_checksum(char* destination, unsigned int source, unsigned int size) {
unsigned char data, checksum = 0;
for (; size > 0; size--) {
data = EEPROM.read(source++);
data = EEPROM.read(source++);
checksum = (checksum << 1) || (checksum >> 7);
checksum += data;
*(destination++) = data;

View File

@ -25,4 +25,4 @@
//unsigned char eeprom_get_char(unsigned int addr);
//void eeprom_put_char(unsigned int addr, unsigned char new_value);
void memcpy_to_eeprom_with_checksum(unsigned int destination, const char* source, unsigned int size);
int memcpy_from_eeprom_with_checksum(char* destination, unsigned int source, unsigned int size);
int memcpy_from_eeprom_with_checksum(char* destination, unsigned int source, unsigned int size);

View File

@ -33,10 +33,10 @@ xQueueHandle limit_sw_queue; // used by limit switch debouncing
// Homing axis search distance multiplier. Computed by this value times the cycle travel.
#ifndef HOMING_AXIS_SEARCH_SCALAR
#define HOMING_AXIS_SEARCH_SCALAR 1.1 // Must be > 1 to ensure limit switch will be engaged.
# define HOMING_AXIS_SEARCH_SCALAR 1.1 // Must be > 1 to ensure limit switch will be engaged.
#endif
#ifndef HOMING_AXIS_LOCATE_SCALAR
#define HOMING_AXIS_LOCATE_SCALAR 5.0 // Must be > 1 to ensure limit switch is cleared.
# define HOMING_AXIS_LOCATE_SCALAR 5.0 // Must be > 1 to ensure limit switch is cleared.
#endif
void IRAM_ATTR isr_limit_switches() {
@ -52,16 +52,16 @@ void IRAM_ATTR isr_limit_switches() {
int evt;
xQueueSendFromISR(limit_sw_queue, &evt, NULL);
#else
#ifdef HARD_LIMIT_FORCE_STATE_CHECK
# ifdef HARD_LIMIT_FORCE_STATE_CHECK
// Check limit pin state.
if (limits_get_state()) {
mc_reset(); // Initiate system kill.
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
mc_reset(); // Initiate system kill.
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
}
#else
mc_reset(); // Initiate system kill.
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
#endif
# else
mc_reset(); // Initiate system kill.
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
# endif
#endif
}
}
@ -75,10 +75,11 @@ void IRAM_ATTR isr_limit_switches() {
// NOTE: Only the abort realtime command can interrupt this process.
// TODO: Move limit pin-specific calls to a general function for portability.
void limits_go_home(uint8_t cycle_mask) {
if (sys.abort) return; // Block if system reset has been issued.
if (sys.abort)
return; // Block if system reset has been issued.
// Initialize plan data struct for homing motion. Spindle and coolant are disabled.
motors_set_homing_mode(cycle_mask, true); // tell motors homing is about to start
plan_line_data_t plan_data;
motors_set_homing_mode(cycle_mask, true); // tell motors homing is about to start
plan_line_data_t plan_data;
plan_line_data_t* pl_data = &plan_data;
memset(pl_data, 0, sizeof(plan_line_data_t));
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION | PL_COND_FLAG_NO_FEED_OVERRIDE);
@ -88,28 +89,29 @@ void limits_go_home(uint8_t cycle_mask) {
// Initialize variables used for homing computations.
uint8_t n_cycle = (2 * n_homing_locate_cycle + 1);
uint8_t step_pin[N_AXIS];
float target[N_AXIS];
float max_travel = 0.0;
float target[N_AXIS];
float max_travel = 0.0;
uint8_t idx;
for (idx = 0; idx < N_AXIS; idx++) {
// Initialize step pin masks
step_pin[idx] = get_step_pin_mask(idx);
#ifdef COREXY
if ((idx == A_MOTOR) || (idx == B_MOTOR)) step_pin[idx] = (get_step_pin_mask(X_AXIS) | get_step_pin_mask(Y_AXIS));
if ((idx == A_MOTOR) || (idx == B_MOTOR))
step_pin[idx] = (get_step_pin_mask(X_AXIS) | get_step_pin_mask(Y_AXIS));
#endif
if (bit_istrue(cycle_mask, bit(idx))) {
// Set target based on max_travel setting. Ensure homing switches engaged with search scalar.
max_travel = MAX(max_travel, (HOMING_AXIS_SEARCH_SCALAR) * axis_settings[idx]->max_travel->get());
max_travel = MAX(max_travel, (HOMING_AXIS_SEARCH_SCALAR)*axis_settings[idx]->max_travel->get());
}
}
// Set search mode with approach at seek rate to quickly engage the specified cycle_mask limit switches.
bool approach = true;
float homing_rate = homing_seek_rate->get();
bool approach = true;
float homing_rate = homing_seek_rate->get();
uint8_t limit_state, axislock, n_active_axis;
do {
system_convert_array_steps_to_mpos(target, sys_position);
// Initialize and declare variables needed for homing routine.
axislock = 0;
axislock = 0;
n_active_axis = 0;
for (idx = 0; idx < N_AXIS; idx++) {
// Set target location for active axes and setup computation for homing rate.
@ -132,24 +134,28 @@ void limits_go_home(uint8_t cycle_mask) {
// NOTE: This happens to compile smaller than any other implementation tried.
auto mask = homing_dir_mask->get();
if (bit_istrue(mask, bit(idx))) {
if (approach) target[idx] = -max_travel;
else target[idx] = max_travel;
if (approach)
target[idx] = -max_travel;
else
target[idx] = max_travel;
} else {
if (approach) target[idx] = max_travel;
else target[idx] = -max_travel;
if (approach)
target[idx] = max_travel;
else
target[idx] = -max_travel;
}
// Apply axislock to the step port pins active in this cycle.
axislock |= step_pin[idx];
}
}
homing_rate *= sqrt(n_active_axis); // [sqrt(N_AXIS)] Adjust so individual axes all move at homing rate.
homing_rate *= sqrt(n_active_axis); // [sqrt(N_AXIS)] Adjust so individual axes all move at homing rate.
sys.homing_axis_lock = axislock;
// Perform homing cycle. Planner buffer should be empty, as required to initiate the homing cycle.
pl_data->feed_rate = homing_rate; // Set current homing rate.
plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
sys.step_control = STEP_CONTROL_EXECUTE_SYS_MOTION; // Set to execute homing motion and clear existing flags.
st_prep_buffer(); // Prep and fill segment buffer from newly planned block.
st_wake_up(); // Initiate motion
pl_data->feed_rate = homing_rate; // Set current homing rate.
plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
sys.step_control = STEP_CONTROL_EXECUTE_SYS_MOTION; // Set to execute homing motion and clear existing flags.
st_prep_buffer(); // Prep and fill segment buffer from newly planned block.
st_wake_up(); // Initiate motion
do {
if (approach) {
// Check limit state. Lock out cycle axes when they change.
@ -158,8 +164,10 @@ void limits_go_home(uint8_t cycle_mask) {
if (axislock & step_pin[idx]) {
if (limit_state & bit(idx)) {
#ifdef COREXY
if (idx == Z_AXIS) axislock &= ~(step_pin[Z_AXIS]);
else axislock &= ~(step_pin[A_MOTOR] | step_pin[B_MOTOR]);
if (idx == Z_AXIS)
axislock &= ~(step_pin[Z_AXIS]);
else
axislock &= ~(step_pin[A_MOTOR] | step_pin[B_MOTOR]);
#else
axislock &= ~(step_pin[idx]);
#endif
@ -168,21 +176,25 @@ void limits_go_home(uint8_t cycle_mask) {
}
sys.homing_axis_lock = axislock;
}
st_prep_buffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us.
st_prep_buffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us.
// Exit routines: No time to run protocol_execute_realtime() in this loop.
if (sys_rt_exec_state & (EXEC_SAFETY_DOOR | EXEC_RESET | EXEC_CYCLE_STOP)) {
uint8_t rt_exec = sys_rt_exec_state;
// Homing failure condition: Reset issued during cycle.
if (rt_exec & EXEC_RESET) system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_RESET);
if (rt_exec & EXEC_RESET)
system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_RESET);
// Homing failure condition: Safety door was opened.
if (rt_exec & EXEC_SAFETY_DOOR) system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_DOOR);
if (rt_exec & EXEC_SAFETY_DOOR)
system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_DOOR);
// Homing failure condition: Limit switch still engaged after pull-off motion
if (!approach && (limits_get_state() & cycle_mask)) system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_PULLOFF);
if (!approach && (limits_get_state() & cycle_mask))
system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_PULLOFF);
// Homing failure condition: Limit switch not found during approach.
if (approach && (rt_exec & EXEC_CYCLE_STOP)) system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_APPROACH);
if (sys_rt_exec_alarm) {
motors_set_homing_mode(cycle_mask, false); // tell motors homing is done...failed
mc_reset(); // Stop motors, if they are running.
if (approach && (rt_exec & EXEC_CYCLE_STOP))
system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_APPROACH);
if (sys_rt_exec_alarm) {
motors_set_homing_mode(cycle_mask, false); // tell motors homing is done...failed
mc_reset(); // Stop motors, if they are running.
protocol_execute_realtime();
return;
} else {
@ -197,16 +209,16 @@ void limits_go_home(uint8_t cycle_mask) {
delay_ms(I2S_OUT_DELAY_MS);
}
#endif
st_reset(); // Immediately force kill steppers and reset step segment buffer.
delay_ms(homing_debounce->get()); // Delay to allow transient dynamics to dissipate.
st_reset(); // Immediately force kill steppers and reset step segment buffer.
delay_ms(homing_debounce->get()); // Delay to allow transient dynamics to dissipate.
// Reverse direction and reset homing rate for locate cycle(s).
approach = !approach;
// After first cycle, homing enters locating phase. Shorten search to pull-off distance.
if (approach) {
max_travel = homing_pulloff->get() * HOMING_AXIS_LOCATE_SCALAR;
max_travel = homing_pulloff->get() * HOMING_AXIS_LOCATE_SCALAR;
homing_rate = homing_feed_rate->get();
} else {
max_travel = homing_pulloff->get();
max_travel = homing_pulloff->get();
homing_rate = homing_seek_rate->get();
}
} while (n_cycle-- > 0);
@ -218,7 +230,7 @@ void limits_go_home(uint8_t cycle_mask) {
// triggering when hard limits are enabled or when more than one axes shares a limit pin.
int32_t set_axis_position;
// Set machine positions for homed limit switches. Don't update non-homed axes.
auto mask = homing_dir_mask->get();
auto mask = homing_dir_mask->get();
auto pulloff = homing_pulloff->get();
for (idx = 0; idx < N_AXIS; idx++) {
auto steps = axis_settings[idx]->steps_per_mm->get();
@ -228,28 +240,28 @@ void limits_go_home(uint8_t cycle_mask) {
#else
auto travel = axis_settings[idx]->max_travel->get();
if (bit_istrue(mask, bit(idx))) {
#ifdef HOMING_FORCE_POSITIVE_SPACE
set_axis_position = 0; //lround(settings.homing_pulloff*settings.steps_per_mm[idx]);
#else
# ifdef HOMING_FORCE_POSITIVE_SPACE
set_axis_position = 0; //lround(settings.homing_pulloff*settings.steps_per_mm[idx]);
# else
set_axis_position = lround((-travel + pulloff) * steps);
#endif
# endif
} else {
#ifdef HOMING_FORCE_POSITIVE_SPACE
# ifdef HOMING_FORCE_POSITIVE_SPACE
set_axis_position = lround((-travel - pulloff) * steps);
#else
# else
set_axis_position = lround(-pulloff * steps);
#endif
# endif
}
#endif
#ifdef COREXY
if (idx == X_AXIS) {
int32_t off_axis_position = system_convert_corexy_to_y_axis_steps(sys_position);
sys_position[A_MOTOR] = set_axis_position + off_axis_position;
sys_position[B_MOTOR] = set_axis_position - off_axis_position;
sys_position[A_MOTOR] = set_axis_position + off_axis_position;
sys_position[B_MOTOR] = set_axis_position - off_axis_position;
} else if (idx == Y_AXIS) {
int32_t off_axis_position = system_convert_corexy_to_x_axis_steps(sys_position);
sys_position[A_MOTOR] = off_axis_position + set_axis_position;
sys_position[B_MOTOR] = off_axis_position - set_axis_position;
sys_position[A_MOTOR] = off_axis_position + set_axis_position;
sys_position[B_MOTOR] = off_axis_position - set_axis_position;
} else
sys_position[idx] = set_axis_position;
#else
@ -257,28 +269,23 @@ void limits_go_home(uint8_t cycle_mask) {
#endif
}
}
sys.step_control = STEP_CONTROL_NORMAL_OP; // Return step control to normal operation.
motors_set_homing_mode(cycle_mask, false); // tell motors homing is done
sys.step_control = STEP_CONTROL_NORMAL_OP; // Return step control to normal operation.
motors_set_homing_mode(cycle_mask, false); // tell motors homing is done
}
uint8_t limit_pins[] = {
X_LIMIT_PIN,
Y_LIMIT_PIN,
Z_LIMIT_PIN,
A_LIMIT_PIN,
B_LIMIT_PIN,
C_LIMIT_PIN,
X_LIMIT_PIN, Y_LIMIT_PIN, Z_LIMIT_PIN, A_LIMIT_PIN, B_LIMIT_PIN, C_LIMIT_PIN,
};
uint8_t limit_mask = 0;
void limits_init() {
limit_mask = 0;
int mode = INPUT_PULLUP;
int mode = INPUT_PULLUP;
#ifdef DISABLE_LIMIT_PIN_PULL_UP
mode = INPUT;
#endif
for (int i=0; i<N_AXIS; i++) {
for (int i = 0; i < N_AXIS; i++) {
uint8_t pin;
if ((pin = limit_pins[i]) != UNDEFINED_PIN) {
limit_mask |= bit(i);
@ -297,13 +304,13 @@ void limits_init() {
"limitCheckTask",
2048,
NULL,
5, // priority
5, // priority
NULL);
}
// Disables hard limits.
void limits_disable() {
for (int i=0; i<N_AXIS; i++) {
for (int i = 0; i < N_AXIS; i++) {
if (limit_pins[i] != UNDEFINED_PIN) {
detachInterrupt(i);
}
@ -315,14 +322,14 @@ void limits_disable() {
// number in bit position, i.e. Z_AXIS is bit(2), and Y_AXIS is bit(1).
uint8_t limits_get_state() {
uint8_t pinMask = 0;
for (int i=0; i<N_AXIS; i++) {
for (int i = 0; i < N_AXIS; i++) {
uint8_t pin;
if ((pin = limit_pins[i]) != UNDEFINED_PIN) {
pinMask += digitalRead(pin) << i;
}
}
#ifdef INVERT_LIMIT_PIN_MASK // not normally used..unless you have both normal and inverted switches
#ifdef INVERT_LIMIT_PIN_MASK // not normally used..unless you have both normal and inverted switches
pinMask ^= INVERT_LIMIT_PIN_MASK;
#endif
if (limit_invert->get()) {
@ -338,11 +345,11 @@ void limits_soft_check(float* target) {
if (system_check_travel_limits(target)) {
// TODO for debugging only 3 axes right now
grbl_msg_sendf(CLIENT_SERIAL,
MSG_LEVEL_INFO,
"Soft limit error target WPOS X:%5.2f Y:%5.2f Z:%5.2f",
target[X_AXIS] - gc_state.coord_system[X_AXIS],
target[Y_AXIS] - gc_state.coord_system[Y_AXIS],
target[Z_AXIS] - gc_state.coord_system[Z_AXIS]);
MSG_LEVEL_INFO,
"Soft limit error target WPOS X:%5.2f Y:%5.2f Z:%5.2f",
target[X_AXIS] - gc_state.coord_system[X_AXIS],
target[Y_AXIS] - gc_state.coord_system[Y_AXIS],
target[Z_AXIS] - gc_state.coord_system[Z_AXIS]);
sys.soft_limit = true;
// Force feed hold if cycle is active. All buffered blocks are guaranteed to be within
@ -352,12 +359,13 @@ void limits_soft_check(float* target) {
system_set_exec_state_flag(EXEC_FEED_HOLD);
do {
protocol_execute_realtime();
if (sys.abort) return;
if (sys.abort)
return;
} while (sys.state != STATE_IDLE);
}
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
system_set_exec_alarm(EXEC_ALARM_SOFT_LIMIT); // Indicate soft limit critical event
protocol_execute_realtime(); // Execute to enter critical event loop and system abort
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
system_set_exec_alarm(EXEC_ALARM_SOFT_LIMIT); // Indicate soft limit critical event
protocol_execute_realtime(); // Execute to enter critical event loop and system abort
return;
}
}
@ -366,14 +374,14 @@ void limits_soft_check(float* target) {
void limitCheckTask(void* pvParameters) {
while (true) {
int evt;
xQueueReceive(limit_sw_queue, &evt, portMAX_DELAY); // block until receive queue
vTaskDelay(DEBOUNCE_PERIOD / portTICK_PERIOD_MS); // delay a while
xQueueReceive(limit_sw_queue, &evt, portMAX_DELAY); // block until receive queue
vTaskDelay(DEBOUNCE_PERIOD / portTICK_PERIOD_MS); // delay a while
uint8_t switch_state;
switch_state = limits_get_state();
if (switch_state) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Limit Switch State %08d", switch_state);
mc_reset(); // Initiate system kill.
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
mc_reset(); // Initiate system kill.
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
}
}
}
@ -398,17 +406,17 @@ bool axis_is_squared(uint8_t axis_mask) {
return true;
#endif
}
if (axis_mask == (1 << A_AXIS)) {
if (axis_mask == (1 << A_AXIS)) {
#ifdef A_AXIS_SQUARING
return true;
#endif
}
if (axis_mask == (1 << B_AXIS)) {
if (axis_mask == (1 << B_AXIS)) {
#ifdef B_AXIS_SQUARING
return true;
#endif
}
if (axis_mask == (1 << C_AXIS)) {
if (axis_mask == (1 << C_AXIS)) {
#ifdef C_AXIS_SQUARING
return true;
#endif

View File

@ -29,9 +29,9 @@
extern uint8_t n_homing_locate_cycle;
#define SQUARING_MODE_DUAL 0 // both motors run
#define SQUARING_MODE_A 1 // A motor runs
#define SQUARING_MODE_B 2 // B motor runs
#define SQUARING_MODE_DUAL 0 // both motors run
#define SQUARING_MODE_A 1 // A motor runs
#define SQUARING_MODE_B 2 // B motor runs
// Initialize the limits module
void limits_init();

View File

@ -20,11 +20,11 @@
#include "grbl_sd.h"
File myFile;
bool SD_ready_next = false; // Grbl has processed a line and is waiting for another
uint8_t SD_client = CLIENT_SERIAL;
uint32_t sd_current_line_number; // stores the most recent line number read from the SD
static char comment[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
File myFile;
bool SD_ready_next = false; // Grbl has processed a line and is waiting for another
uint8_t SD_client = CLIENT_SERIAL;
uint32_t sd_current_line_number; // stores the most recent line number read from the SD
static char comment[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
// attempt to mount the SD card
/*bool sd_mount()
@ -65,7 +65,7 @@ boolean openFile(fs::FS& fs, const char* path) {
return false;
}
set_sd_state(SDCARD_BUSY_PRINTING);
SD_ready_next = false; // this will get set to true when Grbl issues "ok" message
SD_ready_next = false; // this will get set to true when Grbl issues "ok" message
sd_current_line_number = 0;
return true;
}
@ -74,7 +74,7 @@ boolean closeFile() {
if (!myFile)
return false;
set_sd_state(SDCARD_IDLE);
SD_ready_next = false;
SD_ready_next = false;
sd_current_line_number = 0;
myFile.close();
return true;
@ -119,7 +119,6 @@ uint32_t sd_get_current_line_number() {
return sd_current_line_number;
}
uint8_t sd_state = SDCARD_IDLE;
uint8_t get_sd_state(bool refresh) {
@ -142,13 +141,14 @@ uint8_t get_sd_state(bool refresh) {
//using default value for speed ? should be parameter
//refresh content if card was removed
if (SD.begin((GRBL_SPI_SS == -1) ? SS : GRBL_SPI_SS, SPI, GRBL_SPI_FREQ)) {
if (SD.cardSize() > 0)sd_state = SDCARD_IDLE;
if (SD.cardSize() > 0)
sd_state = SDCARD_IDLE;
}
return sd_state;
}
uint8_t set_sd_state(uint8_t flag) {
sd_state = flag;
sd_state = flag;
return sd_state;
}
@ -158,5 +158,3 @@ void sd_get_current_filename(char* name) {
else
name[0] = 0;
}

View File

@ -20,7 +20,7 @@
#include "SD.h"
#include "SPI.h"
#define FILE_TYPE_COUNT 5 // number of acceptable gcode file types in array
#define FILE_TYPE_COUNT 5 // number of acceptable gcode file types in array
#define SDCARD_DET_PIN -1
#define SDCARD_DET_VAL 0
@ -31,19 +31,17 @@
#define SDCARD_BUSY_UPLOADING 4
#define SDCARD_BUSY_PARSING 8
extern bool SD_ready_next; // Grbl has processed a line and is waiting for another
extern uint8_t SD_client;
extern bool SD_ready_next; // Grbl has processed a line and is waiting for another
extern uint8_t SD_client;
//bool sd_mount();
uint8_t get_sd_state(bool refresh);
uint8_t set_sd_state(uint8_t flag);
void listDir(fs::FS& fs, const char* dirname, uint8_t levels, uint8_t client);
boolean openFile(fs::FS& fs, const char* path);
boolean closeFile();
boolean readFileLine(char* line, int len);
void readFile(fs::FS& fs, const char* path);
float sd_report_perc_complete();
uint8_t get_sd_state(bool refresh);
uint8_t set_sd_state(uint8_t flag);
void listDir(fs::FS& fs, const char* dirname, uint8_t levels, uint8_t client);
boolean openFile(fs::FS& fs, const char* path);
boolean closeFile();
boolean readFileLine(char* line, int len);
void readFile(fs::FS& fs, const char* path);
float sd_report_perc_complete();
uint32_t sd_get_current_line_number();
void sd_get_current_filename(char* name);
void sd_get_current_filename(char* name);

File diff suppressed because it is too large Load Diff

View File

@ -45,34 +45,34 @@
// but the prerequisite USE_I2S_OUT is not defined,
// it is forced to be defined.
#ifdef USE_I2S_OUT_STREAM
#ifndef USE_I2S_OUT
#define USE_I2S_OUT
#endif
# ifndef USE_I2S_OUT
# define USE_I2S_OUT
# endif
#endif
#ifdef USE_I2S_OUT
#include <stdint.h>
# include <stdint.h>
/* Assert */
#if defined(I2S_OUT_NUM_BITS)
#if (I2S_OUT_NUM_BITS != 16) && (I2S_OUT_NUM_BITS != 32)
#error "I2S_OUT_NUM_BITS should be 16 or 32"
#endif
#else
#define I2S_OUT_NUM_BITS 32
#endif
# if defined(I2S_OUT_NUM_BITS)
# if (I2S_OUT_NUM_BITS != 16) && (I2S_OUT_NUM_BITS != 32)
# error "I2S_OUT_NUM_BITS should be 16 or 32"
# endif
# else
# define I2S_OUT_NUM_BITS 32
# endif
#define I2SO(n) (I2S_OUT_PIN_BASE + n)
# define I2SO(n) (I2S_OUT_PIN_BASE + n)
/* 16-bit mode: 1000000 usec / ((160000000 Hz) / 10 / 2) x 16 bit/pulse x 2(stereo) = 4 usec/pulse */
/* 32-bit mode: 1000000 usec / ((160000000 Hz) / 5 / 2) x 32 bit/pulse x 2(stereo) = 4 usec/pulse */
#define I2S_OUT_USEC_PER_PULSE 4
# define I2S_OUT_USEC_PER_PULSE 4
#define I2S_OUT_DMABUF_COUNT 5 /* number of DMA buffers to store data */
#define I2S_OUT_DMABUF_LEN 2000 /* maximum size in bytes (4092 is DMA's limit) */
# define I2S_OUT_DMABUF_COUNT 5 /* number of DMA buffers to store data */
# define I2S_OUT_DMABUF_LEN 2000 /* maximum size in bytes (4092 is DMA's limit) */
#define I2S_OUT_DELAY_DMABUF_MS (I2S_OUT_DMABUF_LEN / sizeof(uint32_t) * I2S_OUT_USEC_PER_PULSE / 1000)
#define I2S_OUT_DELAY_MS (I2S_OUT_DELAY_DMABUF_MS * (I2S_OUT_DMABUF_COUNT + 1))
# define I2S_OUT_DELAY_DMABUF_MS (I2S_OUT_DMABUF_LEN / sizeof(uint32_t) * I2S_OUT_USEC_PER_PULSE / 1000)
# define I2S_OUT_DELAY_MS (I2S_OUT_DELAY_DMABUF_MS * (I2S_OUT_DMABUF_COUNT + 1))
typedef void (*i2s_out_pulse_func_t)(void);
@ -90,19 +90,19 @@ typedef struct {
If I2S_OUT_PIN_BASE is set to 128,
bit0:Expanded GPIO 128, 1: Expanded GPIO 129, ..., v: Expanded GPIO 159
*/
uint8_t ws_pin;
uint8_t bck_pin;
uint8_t data_pin;
uint8_t ws_pin;
uint8_t bck_pin;
uint8_t data_pin;
i2s_out_pulse_func_t pulse_func;
uint32_t pulse_period; // aka step rate.
uint32_t init_val;
uint32_t pulse_period; // aka step rate.
uint32_t init_val;
} i2s_out_init_t;
/*
Initialize I2S out by parameters.
return -1 ... already initialized
*/
int i2s_out_init(i2s_out_init_t &init_param);
int i2s_out_init(i2s_out_init_t& init_param);
/*
Initialize I2S out by default parameters.

View File

@ -18,31 +18,27 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifdef ARDUINO_ARCH_ESP32
#include "config.h"
#include "inputbuffer.h"
InputBuffer inputBuffer;
InputBuffer::InputBuffer() {
_RXbufferSize = 0;
_RXbufferpos = 0;
_RXbufferpos = 0;
}
InputBuffer::~InputBuffer() {
_RXbufferSize = 0;
_RXbufferpos = 0;
_RXbufferpos = 0;
}
void InputBuffer::begin() {
_RXbufferSize = 0;
_RXbufferpos = 0;
_RXbufferpos = 0;
}
void InputBuffer::end() {
_RXbufferSize = 0;
_RXbufferpos = 0;
_RXbufferpos = 0;
}
InputBuffer::operator bool() const {
@ -65,7 +61,7 @@ size_t InputBuffer::write(uint8_t c) {
if (current > (RXBUFFERSIZE - 1))
current = 0;
_RXbuffer[current] = c;
current ++;
current++;
_RXbufferSize += 1;
return 1;
}
@ -79,19 +75,23 @@ size_t InputBuffer::write(const uint8_t* buffer, size_t size) {
}
int InputBuffer::peek(void) {
if (_RXbufferSize > 0)return _RXbuffer[_RXbufferpos];
else return -1;
if (_RXbufferSize > 0)
return _RXbuffer[_RXbufferpos];
else
return -1;
}
bool InputBuffer::push(const char* data) {
int data_size = strlen(data);
if ((data_size + _RXbufferSize) <= RXBUFFERSIZE) {
int current = _RXbufferpos + _RXbufferSize;
if (current > RXBUFFERSIZE) current = current - RXBUFFERSIZE;
if (current > RXBUFFERSIZE)
current = current - RXBUFFERSIZE;
for (int i = 0; i < data_size; i++) {
if (current > (RXBUFFERSIZE - 1)) current = 0;
if (current > (RXBUFFERSIZE - 1))
current = 0;
_RXbuffer[current] = data[i];
current ++;
current++;
}
_RXbufferSize += strlen(data);
return true;
@ -103,16 +103,15 @@ int InputBuffer::read(void) {
if (_RXbufferSize > 0) {
int v = _RXbuffer[_RXbufferpos];
_RXbufferpos++;
if (_RXbufferpos > (RXBUFFERSIZE - 1))_RXbufferpos = 0;
if (_RXbufferpos > (RXBUFFERSIZE - 1))
_RXbufferpos = 0;
_RXbufferSize--;
return v;
} else return -1;
} else
return -1;
}
void InputBuffer::flush(void) {
//No need currently
//keep for compatibility
}
#endif // ARDUINO_ARCH_ESP32

View File

@ -20,45 +20,34 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "Print.h"
#include <print.h>
#define RXBUFFERSIZE 128
class InputBuffer: public Print {
public:
class InputBuffer : public Print {
public:
InputBuffer();
~InputBuffer();
size_t write(uint8_t c);
size_t write(const uint8_t* buffer, size_t size);
inline size_t write(const char* s) {
return write((uint8_t*) s, strlen(s));
}
inline size_t write(unsigned long n) {
return write((uint8_t) n);
}
inline size_t write(long n) {
return write((uint8_t) n);
}
inline size_t write(unsigned int n) {
return write((uint8_t) n);
}
inline size_t write(int n) {
return write((uint8_t) n);
}
void begin();
void end();
int available();
int availableforwrite();
int peek(void);
int read(void);
bool push(const char* data);
void flush(void);
operator bool() const;
private:
uint8_t _RXbuffer[RXBUFFERSIZE];
inline size_t write(const char* s) { return write((uint8_t*)s, strlen(s)); }
inline size_t write(unsigned long n) { return write((uint8_t)n); }
inline size_t write(long n) { return write((uint8_t)n); }
inline size_t write(unsigned int n) { return write((uint8_t)n); }
inline size_t write(int n) { return write((uint8_t)n); }
void begin();
void end();
int available();
int availableforwrite();
int peek(void);
int read(void);
bool push(const char* data);
void flush(void);
operator bool() const;
private:
uint8_t _RXbuffer[RXBUFFERSIZE];
uint16_t _RXbufferSize;
uint16_t _RXbufferpos;
};
extern InputBuffer inputBuffer;

View File

@ -23,7 +23,6 @@
#include "grbl.h"
// Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog.
uint8_t jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block) {
// Initialize planner data struct for jogging motions.
@ -34,12 +33,13 @@ uint8_t jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block) {
pl_data->line_number = gc_block->values.n;
#endif
if (soft_limits->get()) {
if (system_check_travel_limits(gc_block->values.xyz)) return (STATUS_TRAVEL_EXCEEDED);
if (system_check_travel_limits(gc_block->values.xyz))
return (STATUS_TRAVEL_EXCEEDED);
}
// Valid jog command. Plan, set state, and execute.
mc_line(gc_block->values.xyz, pl_data);
if (sys.state == STATE_IDLE) {
if (plan_get_current_block() != NULL) { // Check if there is a block to execute.
if (plan_get_current_block() != NULL) { // Check if there is a block to execute.
sys.state = STATE_JOG;
st_prep_buffer();
st_wake_up(); // NOTE: Manual start. No state machine required.

View File

@ -24,9 +24,8 @@
#include "grbl.h"
// System motion line numbers must be zero.
#define JOG_LINE_NUMBER 0
// Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog.
uint8_t jog_execute(plan_line_data_t *pl_data, parser_block_t *gc_block);
uint8_t jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block);

View File

@ -1,5 +1,4 @@
#pragma once
// clang-format off
// This file is where you choose the machine type, by including
// one or more machine definition files as described below.
@ -17,7 +16,7 @@ PWM
// !!! For initial testing, start with test_drive.h which disables
// all I/O pins
// #include "Machines/atari_1020.h"
#include "Machines/test_drive.h"
# include "Machines/test_drive.h"
// !!! For actual use, change the line above to select a board
// from Machines/, for example:
@ -48,8 +47,8 @@ PWM
// supplied automatically.
// MACHINE_PATHNAME_QUOTED constructs a path that is suitable for #include
#define MACHINE_PATHNAME_QUOTED(name) <Machines/name>
# define MACHINE_PATHNAME_QUOTED(name) <Machines/name>
#include MACHINE_PATHNAME_QUOTED(MACHINE_FILENAME)
# include MACHINE_PATHNAME_QUOTED(MACHINE_FILENAME)
#endif // MACHINE_FILENAME
#endif // MACHINE_FILENAME

View File

@ -1,28 +1,28 @@
#pragma once
#ifndef SPINDLE_TYPE
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
# define SPINDLE_TYPE SPINDLE_TYPE_PWM
#endif
// Grbl setting that are common to all machines
// It should not be necessary to change anything herein
#ifndef GRBL_SPI_FREQ
// You can override these by defining them in a board file.
// To override, you must set all of them
//-1 means use the default board pin
#define GRBL_SPI_SS -1
#define GRBL_SPI_MOSI -1
#define GRBL_SPI_MISO -1
#define GRBL_SPI_SCK -1
#define GRBL_SPI_FREQ 4000000
// You can override these by defining them in a board file.
// To override, you must set all of them
//-1 means use the default board pin
# define GRBL_SPI_SS -1
# define GRBL_SPI_MOSI -1
# define GRBL_SPI_MISO -1
# define GRBL_SPI_SCK -1
# define GRBL_SPI_FREQ 4000000
#endif
// ESP32 CPU Settings
#define F_TIMERS 80000000 // a reference to the speed of ESP32 timers
#define F_STEPPER_TIMER 20000000 // frequency of step pulse timer
#define STEPPER_OFF_TIMER_PRESCALE 8 // gives a frequency of 10MHz
#define STEPPER_OFF_PERIOD_uSEC 3 // each tick is
#define F_TIMERS 80000000 // a reference to the speed of ESP32 timers
#define F_STEPPER_TIMER 20000000 // frequency of step pulse timer
#define STEPPER_OFF_TIMER_PRESCALE 8 // gives a frequency of 10MHz
#define STEPPER_OFF_PERIOD_uSEC 3 // each tick is
#define STEP_PULSE_MIN 2 // uSeconds
#define STEP_PULSE_MAX 10 // uSeconds

View File

@ -28,17 +28,16 @@
// support it anyway. The following suppresses Intellisense
// problem reports.
#ifndef M_PI
#define M_PI 3.14159265358979323846
# define M_PI 3.14159265358979323846
#endif
uint8_t ganged_mode = SQUARING_MODE_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
#else // else use kinematics
inverse_kinematics(target, pl_data, position);
#endif
}
@ -55,10 +54,12 @@ void mc_line(float* target, plan_line_data_t* pl_data) {
// from everywhere in Grbl.
if (soft_limits->get()) {
// NOTE: Block jog state. Jogging is a special case and soft limits are handled independently.
if (sys.state != STATE_JOG) limits_soft_check(target);
if (sys.state != STATE_JOG)
limits_soft_check(target);
}
// If in check gcode mode, prevent motion by blocking planner. Soft limits still work.
if (sys.state == STATE_CHECK_MODE) return;
if (sys.state == STATE_CHECK_MODE)
return;
// 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
// plan_check_full_buffer() and check for system abort loop. Also for position reporting
@ -75,17 +76,19 @@ void mc_line(float* target, plan_line_data_t* pl_data) {
// If the buffer is full: good! That means we are well ahead of the robot.
// Remain in this loop until there is room in the buffer.
do {
protocol_execute_realtime(); // Check for any run-time commands
if (sys.abort) return; // Bail, if system abort.
if (plan_check_full_buffer()) protocol_auto_cycle_start(); // Auto-cycle start when buffer is full.
else break;
protocol_execute_realtime(); // Check for any run-time commands
if (sys.abort)
return; // Bail, if system abort.
if (plan_check_full_buffer())
protocol_auto_cycle_start(); // Auto-cycle start when buffer is full.
else
break;
} while (1);
// Plan and queue motion into planner buffer
// uint8_t plan_status; // Not used in normal operation.
plan_buffer_line(target, pl_data);
}
// 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
@ -93,42 +96,50 @@ void mc_line(float* target, plan_line_data_t* pl_data) {
// The arc is approximated by generating a huge number of tiny, linear segments. The chordal tolerance
// of each segment is configured in the arc_tolerance setting, which is defined to be the maximum normal
// distance from segment to the circle when the end points both lie on the circle.
void mc_arc(float* target, plan_line_data_t* pl_data, float* position, float* offset, float radius,
uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc) {
void mc_arc(float* target,
plan_line_data_t* pl_data,
float* position,
float* offset,
float radius,
uint8_t axis_0,
uint8_t axis_1,
uint8_t axis_linear,
uint8_t is_clockwise_arc) {
float center_axis0 = position[axis_0] + offset[axis_0];
float center_axis1 = position[axis_1] + offset[axis_1];
float r_axis0 = -offset[axis_0]; // Radius vector from center to current location
float r_axis1 = -offset[axis_1];
float rt_axis0 = target[axis_0] - center_axis0;
float rt_axis1 = target[axis_1] - center_axis1;
float r_axis0 = -offset[axis_0]; // Radius vector from center to current location
float r_axis1 = -offset[axis_1];
float rt_axis0 = target[axis_0] - center_axis0;
float rt_axis1 = target[axis_1] - center_axis1;
#ifdef USE_KINEMATICS
float previous_position[N_AXIS];
float previous_position[N_AXIS];
uint16_t n;
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
if (angular_travel >= -ARC_ANGULAR_TRAVEL_EPSILON) angular_travel -= 2 * M_PI;
if (is_clockwise_arc) { // Correct atan2 output per direction
if (angular_travel >= -ARC_ANGULAR_TRAVEL_EPSILON)
angular_travel -= 2 * M_PI;
} else {
if (angular_travel <= ARC_ANGULAR_TRAVEL_EPSILON) angular_travel += 2 * M_PI;
if (angular_travel <= ARC_ANGULAR_TRAVEL_EPSILON)
angular_travel += 2 * M_PI;
}
// NOTE: Segment end points are on the arc, which can lead to the arc diameter being smaller by up to
// (2x) arc_tolerance. For 99% of users, this is just fine. If a different arc segment fit
// is desired, i.e. least-squares, midpoint on arc, just change the mm_per_arc_segment calculation.
// For the intended uses of Grbl, this value shouldn't exceed 2000 for the strictest of cases.
uint16_t segments = floor(fabs(0.5 * angular_travel * radius) /
sqrt(arc_tolerance->get() * (2 * radius - arc_tolerance->get())));
uint16_t segments = floor(fabs(0.5 * angular_travel * radius) / sqrt(arc_tolerance->get() * (2 * radius - arc_tolerance->get())));
if (segments) {
// Multiply inverse feed_rate to compensate for the fact that this movement is approximated
// by a number of discrete segments. The inverse feed_rate should be correct for the sum of
// all segments.
if (pl_data->condition & PL_COND_FLAG_INVERSE_TIME) {
pl_data->feed_rate *= segments;
bit_false(pl_data->condition, PL_COND_FLAG_INVERSE_TIME); // Force as feed absolute mode over arc segments.
bit_false(pl_data->condition, PL_COND_FLAG_INVERSE_TIME); // Force as feed absolute mode over arc segments.
}
float theta_per_segment = angular_travel / segments;
float theta_per_segment = angular_travel / segments;
float linear_per_segment = (target[axis_linear] - position[axis_linear]) / segments;
/* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector,
and phi is the angle of rotation. Solution approach by Jens Geisler.
@ -159,12 +170,12 @@ void mc_arc(float* target, plan_line_data_t* pl_data, float* position, float* of
float cos_T = 2.0 - theta_per_segment * theta_per_segment;
float sin_T = theta_per_segment * 0.16666667 * (cos_T + 4.0);
cos_T *= 0.5;
float sin_Ti;
float cos_Ti;
float r_axisi;
float sin_Ti;
float cos_Ti;
float r_axisi;
uint16_t i;
uint8_t count = 0;
for (i = 1; i < segments; i++) { // Increment (segments-1).
uint8_t count = 0;
for (i = 1; i < segments; i++) { // Increment (segments-1).
if (count < N_ARC_CORRECTION) {
// Apply vector rotation matrix. ~40 usec
r_axisi = r_axis0 * sin_T + r_axis1 * cos_T;
@ -174,11 +185,11 @@ void mc_arc(float* target, plan_line_data_t* pl_data, float* position, float* of
} else {
// Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments. ~375 usec
// Compute exact location by applying transformation matrix from initial radius vector(=-offset).
cos_Ti = cos(i * theta_per_segment);
sin_Ti = sin(i * theta_per_segment);
cos_Ti = cos(i * theta_per_segment);
sin_Ti = sin(i * theta_per_segment);
r_axis0 = -offset[axis_0] * cos_Ti + offset[axis_1] * sin_Ti;
r_axis1 = -offset[axis_0] * sin_Ti - offset[axis_1] * cos_Ti;
count = 0;
count = 0;
}
// Update arc_target location
position[axis_0] = center_axis0 + r_axis0;
@ -186,14 +197,15 @@ void mc_arc(float* target, plan_line_data_t* pl_data, float* position, float* of
position[axis_linear] += linear_per_segment;
#ifdef USE_KINEMATICS
mc_line_kins(position, pl_data, previous_position);
previous_position[axis_0] = position[axis_0];
previous_position[axis_1] = position[axis_1];
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;
if (sys.abort)
return;
}
}
// Ensure last segment arrives at target location.
@ -204,15 +216,14 @@ void mc_arc(float* target, plan_line_data_t* pl_data, float* position, float* of
#endif
}
// Execute dwell in seconds.
void mc_dwell(float seconds) {
if (sys.state == STATE_CHECK_MODE) return;
if (sys.state == STATE_CHECK_MODE)
return;
protocol_buffer_synchronize();
delay_sec(seconds, DELAY_MODE_DWELL);
}
// Perform homing cycle to locate and set machine zero. Only '$H' executes this command.
// NOTE: There should be no motions in the buffer and Grbl must be in an idle state before
// executing the homing cycle. This prevents incorrect buffered plans after homing.
@ -221,23 +232,23 @@ void mc_homing_cycle(uint8_t cycle_mask) {
if (user_defined_homing())
return;
#endif
// This give kinematics a chance to do something before normal homing
// if it returns true, the homing is canceled.
// 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.c as a function.
// 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.c as a function.
#ifdef LIMITS_TWO_SWITCHES_ON_AXES
if (limits_get_state()) {
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT);
return;
}
#endif
limits_disable(); // Disable hard limits pin change register for cycle duration
limits_disable(); // Disable hard limits pin change register for cycle duration
// -------------------------------------------------------------------------------------
// Perform homing routine. NOTE: Special motion case. Only system reset works.
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE;
@ -247,65 +258,65 @@ void mc_homing_cycle(uint8_t cycle_mask) {
else
*/
if (cycle_mask) {
if (! axis_is_squared(cycle_mask))
if (!axis_is_squared(cycle_mask))
limits_go_home(cycle_mask); // Homing cycle 0
else {
ganged_mode = SQUARING_MODE_DUAL;
n_homing_locate_cycle = 0; // don't do a second touch cycle
ganged_mode = SQUARING_MODE_DUAL;
n_homing_locate_cycle = 0; // don't do a second touch cycle
limits_go_home(cycle_mask);
ganged_mode = SQUARING_MODE_A;
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
ganged_mode = SQUARING_MODE_A;
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
limits_go_home(cycle_mask);
ganged_mode = SQUARING_MODE_B;
limits_go_home(cycle_mask);
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
}
} // Perform homing cycle based on mask.
} // Perform homing cycle based on mask.
else
#endif
{
// Search to engage all axes limit switches at faster homing seek rate.
if (! axis_is_squared(HOMING_CYCLE_0))
if (!axis_is_squared(HOMING_CYCLE_0))
limits_go_home(HOMING_CYCLE_0); // Homing cycle 0
else {
ganged_mode = SQUARING_MODE_DUAL;
n_homing_locate_cycle = 0; // don't do a second touch cycle
ganged_mode = SQUARING_MODE_DUAL;
n_homing_locate_cycle = 0; // don't do a second touch cycle
limits_go_home(HOMING_CYCLE_0);
ganged_mode = SQUARING_MODE_A;
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
ganged_mode = SQUARING_MODE_A;
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
limits_go_home(HOMING_CYCLE_0);
ganged_mode = SQUARING_MODE_B;
limits_go_home(HOMING_CYCLE_0);
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
}
#ifdef HOMING_CYCLE_1
if (! axis_is_squared(HOMING_CYCLE_1))
if (!axis_is_squared(HOMING_CYCLE_1))
limits_go_home(HOMING_CYCLE_1);
else {
ganged_mode = SQUARING_MODE_DUAL;
n_homing_locate_cycle = 0; // don't do a second touch cycle
ganged_mode = SQUARING_MODE_DUAL;
n_homing_locate_cycle = 0; // don't do a second touch cycle
limits_go_home(HOMING_CYCLE_1);
ganged_mode = SQUARING_MODE_A;
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
ganged_mode = SQUARING_MODE_A;
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
limits_go_home(HOMING_CYCLE_1);
ganged_mode = SQUARING_MODE_B;
limits_go_home(HOMING_CYCLE_1);
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
}
#endif
#ifdef HOMING_CYCLE_2
if (! axis_is_squared(HOMING_CYCLE_2))
if (!axis_is_squared(HOMING_CYCLE_2))
limits_go_home(HOMING_CYCLE_2);
else {
ganged_mode = SQUARING_MODE_DUAL;
n_homing_locate_cycle = 0; // don't do a second touch cycle
ganged_mode = SQUARING_MODE_DUAL;
n_homing_locate_cycle = 0; // don't do a second touch cycle
limits_go_home(HOMING_CYCLE_2);
ganged_mode = SQUARING_MODE_A;
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
ganged_mode = SQUARING_MODE_A;
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
limits_go_home(HOMING_CYCLE_2);
ganged_mode = SQUARING_MODE_B;
limits_go_home(HOMING_CYCLE_2);
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
}
#endif
#ifdef HOMING_CYCLE_3
@ -318,15 +329,15 @@ void mc_homing_cycle(uint8_t cycle_mask) {
limits_go_home(HOMING_CYCLE_5); // Homing cycle 5
#endif
}
protocol_execute_realtime(); // Check for reset and set system abort.
if (sys.abort) {
return; // Did not complete. Alarm state set by mc_alarm.
protocol_execute_realtime(); // Check for reset and set system abort.
if (sys.abort) {
return; // Did not complete. Alarm state set by mc_alarm.
}
// Homing cycle complete! Setup system for normal operation.
// -------------------------------------------------------------------------------------
// Sync gcode parser and planner positions to homed position.
gc_sync_position();
plan_sync_position();
plan_sync_position();
#ifdef USE_KINEMATICS
// This give kinematics a chance to do something after normal homing
kinematics_post_homing();
@ -335,27 +346,28 @@ void mc_homing_cycle(uint8_t cycle_mask) {
limits_init();
}
// Perform tool length probe cycle. Requires probe switch.
// NOTE: Upon probe failure, the program will be stopped and placed into ALARM state.
uint8_t mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_flags) {
// TODO: Need to update this cycle so it obeys a non-auto cycle start.
if (sys.state == STATE_CHECK_MODE) return (GC_PROBE_CHECK_MODE);
if (sys.state == STATE_CHECK_MODE)
return (GC_PROBE_CHECK_MODE);
// Finish all queued commands and empty planner buffer before starting probe cycle.
protocol_buffer_synchronize();
if (sys.abort) return (GC_PROBE_ABORT); // Return if system reset has been issued.
if (sys.abort)
return (GC_PROBE_ABORT); // Return if system reset has been issued.
// Initialize probing control variables
uint8_t is_probe_away = bit_istrue(parser_flags, GC_PARSER_PROBE_IS_AWAY);
uint8_t is_no_error = bit_istrue(parser_flags, GC_PARSER_PROBE_IS_NO_ERROR);
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
uint8_t is_no_error = bit_istrue(parser_flags, GC_PARSER_PROBE_IS_NO_ERROR);
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
probe_configure_invert_mask(is_probe_away);
// After syncing, check if probe is already triggered. If so, halt and issue alarm.
// NOTE: This probe initialization error applies to all probing cycles.
if (probe_get_state()) { // Check probe pin state.
if (probe_get_state()) { // Check probe pin state.
system_set_exec_alarm(EXEC_ALARM_PROBE_FAIL_INITIAL);
protocol_execute_realtime();
probe_configure_invert_mask(false); // Re-initialize invert mask before returning.
return (GC_PROBE_FAIL_INIT); // Nothing else to do but bail.
probe_configure_invert_mask(false); // Re-initialize invert mask before returning.
return (GC_PROBE_FAIL_INIT); // Nothing else to do but bail.
}
// Setup and queue probing motion. Auto cycle-start should not start the cycle.
mc_line(target, pl_data);
@ -365,48 +377,54 @@ uint8_t mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_
system_set_exec_state_flag(EXEC_CYCLE_START);
do {
protocol_execute_realtime();
if (sys.abort) return (GC_PROBE_ABORT); // Check for system abort
if (sys.abort)
return (GC_PROBE_ABORT); // Check for system abort
} while (sys.state != STATE_IDLE);
// Probing cycle complete!
// Set state variables and error out, if the probe failed and cycle with error is enabled.
if (sys_probe_state == PROBE_ACTIVE) {
if (is_no_error) memcpy(sys_probe_position, sys_position, sizeof(sys_position));
else system_set_exec_alarm(EXEC_ALARM_PROBE_FAIL_CONTACT);
if (is_no_error)
memcpy(sys_probe_position, sys_position, sizeof(sys_position));
else
system_set_exec_alarm(EXEC_ALARM_PROBE_FAIL_CONTACT);
} else {
sys.probe_succeeded = true; // Indicate to system the probing cycle completed successfully.
sys.probe_succeeded = true; // Indicate to system the probing cycle completed successfully.
}
sys_probe_state = PROBE_OFF; // Ensure probe state monitor is disabled.
probe_configure_invert_mask(false); // Re-initialize invert mask.
protocol_execute_realtime(); // Check and execute run-time commands
sys_probe_state = PROBE_OFF; // Ensure probe state monitor is disabled.
probe_configure_invert_mask(false); // Re-initialize invert mask.
protocol_execute_realtime(); // Check and execute run-time commands
// Reset the stepper and planner buffers to remove the remainder of the probe motion.
st_reset(); // Reset step segment buffer.
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
plan_sync_position(); // Sync planner position to current machine position.
st_reset(); // Reset step segment buffer.
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
plan_sync_position(); // Sync planner position to current machine position.
#ifdef MESSAGE_PROBE_COORDINATES
// All done! Output the probe position as message.
report_probe_parameters(CLIENT_ALL);
#endif
if (sys.probe_succeeded) return (GC_PROBE_FOUND); // Successful probe cycle.
else return (GC_PROBE_FAIL_END); // Failed to trigger probe within travel. With or without error.
if (sys.probe_succeeded)
return (GC_PROBE_FOUND); // Successful probe cycle.
else
return (GC_PROBE_FAIL_END); // Failed to trigger probe within travel. With or without error.
}
// Plans and executes the single special motion case for parking. Independent of main planner buffer.
// NOTE: Uses the always free planner ring buffer head to store motion parameters for execution.
void mc_parking_motion(float* parking_target, plan_line_data_t* pl_data) {
if (sys.abort) return; // Block during abort.
if (sys.abort)
return; // Block during abort.
uint8_t plan_status = plan_buffer_line(parking_target, pl_data);
if (plan_status) {
bit_true(sys.step_control, STEP_CONTROL_EXECUTE_SYS_MOTION);
bit_false(sys.step_control, STEP_CONTROL_END_MOTION); // Allow parking motion to execute, if feed hold is active.
st_parking_setup_buffer(); // Setup step segment buffer for special parking motion case
bit_false(sys.step_control, STEP_CONTROL_END_MOTION); // Allow parking motion to execute, if feed hold is active.
st_parking_setup_buffer(); // Setup step segment buffer for special parking motion case
st_prep_buffer();
st_wake_up();
do {
protocol_exec_rt_system();
if (sys.abort) return;
if (sys.abort)
return;
} while (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION);
st_parking_restore_buffer(); // Restore step segment buffer to normal run state.
st_parking_restore_buffer(); // Restore step segment buffer to normal run state.
} else {
bit_false(sys.step_control, STEP_CONTROL_EXECUTE_SYS_MOTION);
protocol_exec_rt_system();
@ -417,12 +435,12 @@ void mc_parking_motion(float* parking_target, plan_line_data_t* pl_data) {
void mc_override_ctrl_update(uint8_t override_state) {
// Finish all queued commands before altering override control state
protocol_buffer_synchronize();
if (sys.abort) return;
if (sys.abort)
return;
sys.override_ctrl = override_state;
}
#endif
// Method to ready the system to reset by setting the realtime reset command and killing any
// active processes in the system. This also checks if a system reset is issued while Grbl
// is in a motion state. If so, kills the steppers and sets the system alarm to flag position
@ -434,7 +452,7 @@ void mc_reset() {
system_set_exec_state_flag(EXEC_RESET);
// Kill spindle and coolant.
spindle->stop();
coolant_stop();
coolant_stop();
// turn off all digital I/O immediately
fast_sys_io_control(0xFF, false);
@ -451,18 +469,18 @@ void mc_reset() {
// the steppers enabled by avoiding the go_idle call altogether, unless the motion state is
// violated, by which, all bets are off.
if ((sys.state & (STATE_CYCLE | STATE_HOMING | STATE_JOG)) ||
(sys.step_control & (STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_SYS_MOTION))) {
(sys.step_control & (STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_SYS_MOTION))) {
if (sys.state == STATE_HOMING) {
if (!sys_rt_exec_alarm) system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_RESET);
} else system_set_exec_alarm(EXEC_ALARM_ABORT_CYCLE);
st_go_idle(); // Force kill steppers. Position has likely been lost.
if (!sys_rt_exec_alarm)
system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_RESET);
} else
system_set_exec_alarm(EXEC_ALARM_ABORT_CYCLE);
st_go_idle(); // Force kill steppers. Position has likely been lost.
}
ganged_mode = SQUARING_MODE_DUAL; // in case an error occurred during squaring
ganged_mode = SQUARING_MODE_DUAL; // in case an error occurred during squaring
#ifdef USE_I2S_OUT_STREAM
i2s_out_reset();
#endif
}
}

View File

@ -26,19 +26,17 @@
#include "grbl.h"
// System motion commands must have a line number of zero.
#define HOMING_CYCLE_LINE_NUMBER 0
#define PARKING_MOTION_LINE_NUMBER 0
#define HOMING_CYCLE_ALL 0 // Must be zero.
#define HOMING_CYCLE_X bit(X_AXIS)
#define HOMING_CYCLE_Y bit(Y_AXIS)
#define HOMING_CYCLE_Z bit(Z_AXIS)
#define HOMING_CYCLE_A bit(A_AXIS)
#define HOMING_CYCLE_B bit(B_AXIS)
#define HOMING_CYCLE_C bit(C_AXIS)
#define HOMING_CYCLE_ALL 0 // Must be zero.
#define HOMING_CYCLE_X bit(X_AXIS)
#define HOMING_CYCLE_Y bit(Y_AXIS)
#define HOMING_CYCLE_Z bit(Z_AXIS)
#define HOMING_CYCLE_A bit(A_AXIS)
#define HOMING_CYCLE_B bit(B_AXIS)
#define HOMING_CYCLE_C bit(C_AXIS)
// 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
@ -50,8 +48,15 @@ void mc_line(float* target, plan_line_data_t* pl_data);
// offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is
// the direction of helical travel, radius == circle radius, is_clockwise_arc boolean. Used
// for vector transformation direction.
void mc_arc(float* target, plan_line_data_t* pl_data, float* position, float* offset, float radius,
uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc);
void mc_arc(float* target,
plan_line_data_t* pl_data,
float* position,
float* offset,
float radius,
uint8_t axis_0,
uint8_t axis_1,
uint8_t axis_linear,
uint8_t is_clockwise_arc);
// Dwell for a specific number of seconds
void mc_dwell(float seconds);

View File

@ -1,4 +1,5 @@
#pragma once
// clang-format off
/*
nofile.h - ESP3D data file

View File

@ -30,25 +30,25 @@
#include "grbl.h"
#ifdef ENABLE_NOTIFICATIONS
#include "notifications_service.h"
#include <WiFiClientSecure.h>
#include <base64.h>
# include "notifications_service.h"
# include <WiFiClientSecure.h>
# include <base64.h>
#define PUSHOVERTIMEOUT 5000
#define PUSHOVERSERVER "api.pushover.net"
#define PUSHOVERPORT 443
# define PUSHOVERTIMEOUT 5000
# define PUSHOVERSERVER "api.pushover.net"
# define PUSHOVERPORT 443
#define LINETIMEOUT 5000
#define LINESERVER "notify-api.line.me"
#define LINEPORT 443
# define LINETIMEOUT 5000
# define LINESERVER "notify-api.line.me"
# define LINEPORT 443
#define EMAILTIMEOUT 5000
# define EMAILTIMEOUT 5000
NotificationsService notificationsservice;
bool Wait4Answer(WiFiClientSecure& client, const char* linetrigger, const char* expected_answer, uint32_t timeout) {
bool Wait4Answer(WiFiClientSecure& client, const char* linetrigger, const char* expected_answer, uint32_t timeout) {
if (client.connected()) {
String answer;
String answer;
uint32_t starttimeout = millis();
while (client.connected() && ((millis() - starttimeout) < timeout)) {
answer = client.readStringUntil('\n');
@ -74,11 +74,11 @@ bool Wait4Answer(WiFiClientSecure& client, const char* linetrigger, const char*
}
NotificationsService::NotificationsService() {
_started = false;
_started = false;
_notificationType = 0;
_token1 = "";
_token1 = "";
_settings = "";
_token1 = "";
_token1 = "";
_settings = "";
}
NotificationsService::~NotificationsService() {
end();
@ -90,33 +90,23 @@ bool NotificationsService::started() {
const char* NotificationsService::getTypeString() {
switch (_notificationType) {
case ESP_PUSHOVER_NOTIFICATION:
return "Pushover";
case ESP_EMAIL_NOTIFICATION:
return "Email";
case ESP_LINE_NOTIFICATION:
return "Line";
default:
break;
case ESP_PUSHOVER_NOTIFICATION: return "Pushover";
case ESP_EMAIL_NOTIFICATION: return "Email";
case ESP_LINE_NOTIFICATION: return "Line";
default: break;
}
return "None";
}
bool NotificationsService::sendMSG(const char* title, const char* message) {
if (!_started) return false;
if (!_started)
return false;
if (!((strlen(title) == 0) && (strlen(message) == 0))) {
switch (_notificationType) {
case ESP_PUSHOVER_NOTIFICATION:
return sendPushoverMSG(title, message);
break;
case ESP_EMAIL_NOTIFICATION:
return sendEmailMSG(title, message);
break;
case ESP_LINE_NOTIFICATION :
return sendLineMSG(title, message);
break;
default:
break;
case ESP_PUSHOVER_NOTIFICATION: return sendPushoverMSG(title, message); break;
case ESP_EMAIL_NOTIFICATION: return sendEmailMSG(title, message); break;
case ESP_LINE_NOTIFICATION: return sendLineMSG(title, message); break;
default: break;
}
}
return false;
@ -124,9 +114,9 @@ bool NotificationsService::sendMSG(const char* title, const char* message) {
//Messages are currently limited to 1024 4-byte UTF-8 characters
//but we do not do any check
bool NotificationsService::sendPushoverMSG(const char* title, const char* message) {
String data;
String postcmd;
bool res;
String data;
String postcmd;
bool res;
WiFiClientSecure Notificationclient;
if (!Notificationclient.connect(_serveraddress.c_str(), _port)) {
log_d("Error connecting server %s:%d", _serveraddress.c_str(), _port);
@ -136,7 +126,8 @@ bool NotificationsService::sendPushoverMSG(const char* title, const char* messag
data = "user=";
data += _token1;
data += "&token=";
data += _token2;;
data += _token2;
;
data += "&title=";
data += title;
data += "&message=";
@ -144,14 +135,15 @@ bool NotificationsService::sendPushoverMSG(const char* title, const char* messag
data += "&device=";
data += wifi_config.Hostname();
//build post query
postcmd = "POST /1/messages.json HTTP/1.1\r\nHost: api.pushover.net\r\nConnection: close\r\nCache-Control: no-cache\r\nUser-Agent: ESP3D\r\nAccept: text/html,application/xhtml+xml,application/xml;q=0.9,*/*;q=0.8\r\nContent-Length: ";
postcmd += data.length();
postcmd += "\r\n\r\n";
postcmd += data;
postcmd = "POST /1/messages.json HTTP/1.1\r\nHost: api.pushover.net\r\nConnection: close\r\nCache-Control: no-cache\r\nUser-Agent: "
"ESP3D\r\nAccept: text/html,application/xhtml+xml,application/xml;q=0.9,*/*;q=0.8\r\nContent-Length: ";
postcmd += data.length();
postcmd += "\r\n\r\n";
postcmd += data;
log_d("Query: %s", postcmd.c_str());
//send query
Notificationclient.print(postcmd);
res = Wait4Answer(Notificationclient, "{", "\"status\":1", PUSHOVERTIMEOUT);
res = Wait4Answer(Notificationclient, "{", "\"status\":1", PUSHOVERTIMEOUT);
Notificationclient.stop();
return res;
}
@ -240,9 +232,9 @@ bool NotificationsService::sendEmailMSG(const char* title, const char* message)
return true;
}
bool NotificationsService::sendLineMSG(const char* title, const char* message) {
String data;
String postcmd;
bool res;
String data;
String postcmd;
bool res;
WiFiClientSecure Notificationclient;
(void)title;
if (!Notificationclient.connect(_serveraddress.c_str(), _port)) {
@ -253,24 +245,26 @@ bool NotificationsService::sendLineMSG(const char* title, const char* message) {
data = "message=";
data += message;
//build post query
postcmd = "POST /api/notify HTTP/1.1\r\nHost: notify-api.line.me\r\nConnection: close\r\nCache-Control: no-cache\r\nUser-Agent: ESP3D\r\nAccept: text/html,application/xhtml+xml,application/xml;q=0.9,*/*;q=0.8\r\nContent-Type: application/x-www-form-urlencoded\r\n";
postcmd += "Authorization: Bearer ";
postcmd += _token1 + "\r\n";
postcmd += "Content-Length: ";
postcmd += data.length();
postcmd += "\r\n\r\n";
postcmd += data;
postcmd = "POST /api/notify HTTP/1.1\r\nHost: notify-api.line.me\r\nConnection: close\r\nCache-Control: no-cache\r\nUser-Agent: "
"ESP3D\r\nAccept: text/html,application/xhtml+xml,application/xml;q=0.9,*/*;q=0.8\r\nContent-Type: "
"application/x-www-form-urlencoded\r\n";
postcmd += "Authorization: Bearer ";
postcmd += _token1 + "\r\n";
postcmd += "Content-Length: ";
postcmd += data.length();
postcmd += "\r\n\r\n";
postcmd += data;
log_d("Query: %s", postcmd.c_str());
//send query
Notificationclient.print(postcmd);
res = Wait4Answer(Notificationclient, "{", "\"status\":200", LINETIMEOUT);
res = Wait4Answer(Notificationclient, "{", "\"status\":200", LINETIMEOUT);
Notificationclient.stop();
return res;
}
//Email#serveraddress:port
bool NotificationsService::getPortFromSettings() {
String tmp = notification_ts->get();
int pos = tmp.lastIndexOf(':');
int pos = tmp.lastIndexOf(':');
if (pos == -1)
return false;
_port = tmp.substring(pos + 1).toInt();
@ -279,9 +273,9 @@ bool NotificationsService::getPortFromSettings() {
}
//Email#serveraddress:port
bool NotificationsService::getServerAddressFromSettings() {
String tmp = notification_ts->get();
int pos1 = tmp.indexOf('#');
int pos2 = tmp.lastIndexOf(':');
String tmp = notification_ts->get();
int pos1 = tmp.indexOf('#');
int pos2 = tmp.lastIndexOf(':');
if ((pos1 == -1) || (pos2 == -1))
return false;
//TODO add a check for valid email ?
@ -292,7 +286,7 @@ bool NotificationsService::getServerAddressFromSettings() {
//Email#serveraddress:port
bool NotificationsService::getEmailFromSettings() {
String tmp = notification_ts->get();
int pos = tmp.indexOf('#');
int pos = tmp.indexOf('#');
if (pos == -1)
return false;
_settings = tmp.substring(0, pos);
@ -301,34 +295,31 @@ bool NotificationsService::getEmailFromSettings() {
return true;
}
bool NotificationsService::begin() {
end();
_notificationType = notification_type->get();
switch (_notificationType) {
case 0: //no notification = no error but no start
return true;
case ESP_PUSHOVER_NOTIFICATION:
_token1 = notification_t1->get();
_token2 = notification_t2->get();
_port = PUSHOVERPORT;
_serveraddress = PUSHOVERSERVER;
break;
case ESP_LINE_NOTIFICATION:
_token1 = notification_t1->get();
_port = LINEPORT;
_serveraddress = LINESERVER;
break;
case ESP_EMAIL_NOTIFICATION:
_token1 = base64::encode(notification_t1->get());
_token2 = base64::encode(notification_t2->get());
if (!getEmailFromSettings() || !getPortFromSettings() || !getServerAddressFromSettings()) {
return false;
}
break;
default:
return false;
break;
case 0: //no notification = no error but no start
return true;
case ESP_PUSHOVER_NOTIFICATION:
_token1 = notification_t1->get();
_token2 = notification_t2->get();
_port = PUSHOVERPORT;
_serveraddress = PUSHOVERSERVER;
break;
case ESP_LINE_NOTIFICATION:
_token1 = notification_t1->get();
_port = LINEPORT;
_serveraddress = LINESERVER;
break;
case ESP_EMAIL_NOTIFICATION:
_token1 = base64::encode(notification_t1->get());
_token2 = base64::encode(notification_t2->get());
if (!getEmailFromSettings() || !getPortFromSettings() || !getServerAddressFromSettings()) {
return false;
}
break;
default: return false; break;
}
bool res = true;
if (WiFi.getMode() != WIFI_STA)
@ -341,18 +332,17 @@ bool NotificationsService::begin() {
void NotificationsService::end() {
if (!_started)
return;
_started = false;
_started = false;
_notificationType = 0;
_token1 = "";
_token1 = "";
_settings = "";
_serveraddress = "";
_port = 0;
_token1 = "";
_token1 = "";
_settings = "";
_serveraddress = "";
_port = 0;
}
void NotificationsService::handle() {
if (_started) {
}
if (_started) {}
}
#endif //ENABLE_NOTIFICATIONS
#endif //ENABLE_NOTIFICATIONS

View File

@ -21,29 +21,30 @@
*/
class NotificationsService {
public:
public:
NotificationsService();
~NotificationsService();
bool begin();
void end();
void handle();
bool sendMSG(const char* title, const char* message);
bool begin();
void end();
void handle();
bool sendMSG(const char* title, const char* message);
const char* getTypeString();
bool started();
private:
bool _started;
uint8_t _notificationType;
String _token1;
String _token2;
String _settings;
String _serveraddress;
bool started();
private:
bool _started;
uint8_t _notificationType;
String _token1;
String _token2;
String _settings;
String _serveraddress;
uint16_t _port;
bool sendPushoverMSG(const char* title, const char* message);
bool sendEmailMSG(const char* title, const char* message);
bool sendLineMSG(const char* title, const char* message);
bool getPortFromSettings();
bool getServerAddressFromSettings();
bool getEmailFromSettings();
bool sendPushoverMSG(const char* title, const char* message);
bool sendEmailMSG(const char* title, const char* message);
bool sendLineMSG(const char* title, const char* message);
bool getPortFromSettings();
bool getServerAddressFromSettings();
bool getEmailFromSettings();
};
extern NotificationsService notificationsservice;

View File

@ -24,10 +24,7 @@
#include "grbl.h"
#define MAX_INT_DIGITS 8 // Maximum number of digits in int32 (and float)
#define MAX_INT_DIGITS 8 // Maximum number of digits in int32 (and float)
// Extracts a floating point value from a string. The following code is based loosely on
// the avr-libc strtod() function by Michael Stumpf and Dmitry Xmelkov and many freely
@ -37,7 +34,7 @@
// be a g-code word on some CNC systems. So, 'E' notation will not be recognized.
// NOTE: Thanks to Radu-Eosif Mihailescu for identifying the issues with using strtod().
uint8_t read_float(const char* line, uint8_t* char_counter, float* float_ptr) {
const char* ptr = line + *char_counter;
const char* ptr = line + *char_counter;
unsigned char c;
// Grab first character and increment pointer. No spaces assumed in line.
c = *ptr++;
@ -45,32 +42,36 @@ uint8_t read_float(const char* line, uint8_t* char_counter, float* float_ptr) {
bool isnegative = false;
if (c == '-') {
isnegative = true;
c = *ptr++;
c = *ptr++;
} else if (c == '+')
c = *ptr++;
// Extract number into fast integer. Track decimal in terms of exponent value.
uint32_t intval = 0;
int8_t exp = 0;
uint8_t ndigit = 0;
bool isdecimal = false;
uint32_t intval = 0;
int8_t exp = 0;
uint8_t ndigit = 0;
bool isdecimal = false;
while (1) {
c -= '0';
if (c <= 9) {
ndigit++;
if (ndigit <= MAX_INT_DIGITS) {
if (isdecimal) exp--;
intval = (((intval << 2) + intval) << 1) + c; // intval*10 + c
if (isdecimal)
exp--;
intval = (((intval << 2) + intval) << 1) + c; // intval*10 + c
} else {
if (!(isdecimal)) exp++; // Drop overflow digits
if (!(isdecimal))
exp++; // Drop overflow digits
}
} else if (c == (('.' - '0') & 0xff) && !(isdecimal))
} else if (c == (('.' - '0') & 0xff) && !(isdecimal))
isdecimal = true;
else
break;
c = *ptr++;
}
// Return if no digits have been read.
if (!ndigit) return (false); ;
if (!ndigit)
return (false);
;
// Convert integer into floating point.
float fval;
fval = (float)intval;
@ -94,7 +95,7 @@ uint8_t read_float(const char* line, uint8_t* char_counter, float* float_ptr) {
*float_ptr = -fval;
else
*float_ptr = fval;
*char_counter = ptr - line - 1; // Set char_counter to next statement
*char_counter = ptr - line - 1; // Set char_counter to next statement
return (true);
}
@ -106,40 +107,44 @@ void delay_ms(uint16_t ms) {
void delay_sec(float seconds, uint8_t mode) {
uint16_t i = ceil(1000 / DWELL_TIME_STEP * seconds);
while (i-- > 0) {
if (sys.abort) return;
if (sys.abort)
return;
if (mode == DELAY_MODE_DWELL)
protocol_execute_realtime();
else { // DELAY_MODE_SYS_SUSPEND
else { // DELAY_MODE_SYS_SUSPEND
// Execute rt_system() only to avoid nesting suspend loops.
protocol_exec_rt_system();
if (sys.suspend & SUSPEND_RESTART_RETRACT) return; // Bail, if safety door reopens.
if (sys.suspend & SUSPEND_RESTART_RETRACT)
return; // Bail, if safety door reopens.
}
delay(DWELL_TIME_STEP); // Delay DWELL_TIME_STEP increment
delay(DWELL_TIME_STEP); // Delay DWELL_TIME_STEP increment
}
}
// Simple hypotenuse computation function.
float hypot_f(float x, float y) { return (sqrt(x * x + y * y)); }
float hypot_f(float x, float y) {
return (sqrt(x * x + y * y));
}
float convert_delta_vector_to_unit_vector(float* vector) {
uint8_t idx;
float magnitude = 0.0;
float magnitude = 0.0;
for (idx = 0; idx < N_AXIS; idx++) {
if (vector[idx] != 0.0)
magnitude += vector[idx] * vector[idx];
}
magnitude = sqrt(magnitude);
magnitude = sqrt(magnitude);
float inv_magnitude = 1.0 / magnitude;
for (idx = 0; idx < N_AXIS; idx++) vector[idx] *= inv_magnitude;
for (idx = 0; idx < N_AXIS; idx++)
vector[idx] *= inv_magnitude;
return (magnitude);
}
float limit_acceleration_by_axis_maximum(float* unit_vec) {
uint8_t idx;
float limit_value = SOME_LARGE_VALUE;
float limit_value = SOME_LARGE_VALUE;
for (idx = 0; idx < N_AXIS; idx++) {
if (unit_vec[idx] != 0) // Avoid divide by zero.
if (unit_vec[idx] != 0) // Avoid divide by zero.
limit_value = MIN(limit_value, fabs(axis_settings[idx]->acceleration->get() / unit_vec[idx]));
}
// The acceleration setting is stored and displayed in units of mm/sec^2,
@ -151,15 +156,15 @@ float limit_acceleration_by_axis_maximum(float* unit_vec) {
float limit_rate_by_axis_maximum(float* unit_vec) {
uint8_t idx;
float limit_value = SOME_LARGE_VALUE;
float limit_value = SOME_LARGE_VALUE;
for (idx = 0; idx < N_AXIS; idx++) {
if (unit_vec[idx] != 0) // Avoid divide by zero.
if (unit_vec[idx] != 0) // Avoid divide by zero.
limit_value = MIN(limit_value, fabs(axis_settings[idx]->max_rate->get() / unit_vec[idx]));
}
return (limit_value);
}
float map_float(float x, float in_min, float in_max, float out_min, float out_max) { // DrawBot_Badge
float map_float(float x, float in_min, float in_max, float out_min, float out_max) { // DrawBot_Badge
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
@ -167,7 +172,7 @@ uint32_t map_uint32_t(uint32_t x, uint32_t in_min, uint32_t in_max, uint32_t out
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
float constrain_float(float in, float min, float max) { // DrawBot_Badge
float constrain_float(float in, float min, float max) { // DrawBot_Badge
if (in < min)
return min;
if (in > max)
@ -181,7 +186,5 @@ float mapConstrain(float x, float in_min, float in_max, float out_min, float out
}
bool char_is_numeric(char value) {
return (value >= '0' && value <='9');
return (value >= '0' && value <= '9');
}

View File

@ -30,7 +30,7 @@
// Axis array index values. Must start with 0 and be continuous.
// Note: You set the number of axes used by changing N_AXIS.
// Be sure to define pins or servos in the machine definition file.
#define X_AXIS 0 // Axis indexing value.
#define X_AXIS 0 // Axis indexing value.
#define Y_AXIS 1
#define Z_AXIS 2
#define A_AXIS 3
@ -40,8 +40,8 @@
#define MAX_AXES 6
#define MAX_GANGED 2
#define PRIMARY_MOTOR 0
#define GANGED_MOTOR 1
#define PRIMARY_MOTOR 0
#define GANGED_MOTOR 1
#define X2_AXIS (X_AXIS + MAX_AXES)
#define Y2_AXIS (Y_AXIS + MAX_AXES)
@ -52,34 +52,32 @@
// CoreXY motor assignments. DO NOT ALTER.
// NOTE: If the A and B motor axis bindings are changed, this effects the CoreXY equations.
#define A_MOTOR X_AXIS // Must be X_AXIS
#define B_MOTOR Y_AXIS // Must be Y_AXIS
#define A_MOTOR X_AXIS // Must be X_AXIS
#define B_MOTOR Y_AXIS // Must be Y_AXIS
// Conversions
#define MM_PER_INCH (25.40)
#define INCH_PER_MM (0.0393701)
#define TICKS_PER_MICROSECOND (F_STEPPER_TIMER/1000000) // Different from AVR version
#define TICKS_PER_MICROSECOND (F_STEPPER_TIMER / 1000000) // Different from AVR version
#define DELAY_MODE_DWELL 0
#define DELAY_MODE_DWELL 0
#define DELAY_MODE_SYS_SUSPEND 1
// Useful macros
#define clear_vector(a) memset(a, 0, sizeof(a))
#define clear_vector_float(a) memset(a, 0.0, sizeof(float)*N_AXIS)
#define clear_vector_float(a) memset(a, 0.0, sizeof(float) * N_AXIS)
// #define clear_vector_long(a) memset(a, 0.0, sizeof(long)*N_AXIS)
#define MAX(a,b) (((a) > (b)) ? (a) : (b)) // changed to upper case to remove conflicts with other libraries
#define MIN(a,b) (((a) < (b)) ? (a) : (b)) // changed to upper case to remove conflicts with other libraries
#define isequal_position_vector(a,b) !(memcmp(a, b, sizeof(float)*N_AXIS))
#define MAX(a, b) (((a) > (b)) ? (a) : (b)) // changed to upper case to remove conflicts with other libraries
#define MIN(a, b) (((a) < (b)) ? (a) : (b)) // changed to upper case to remove conflicts with other libraries
#define isequal_position_vector(a, b) !(memcmp(a, b, sizeof(float) * N_AXIS))
// Bit field and masking macros
//Arduino.h:104:0: note: this is the location of the previous definition
//#define bit(n) (1 << n)
#define bit_true(x,mask) (x) |= (mask)
#define bit_false(x,mask) (x) &= ~(mask)
#define bit_istrue(x,mask) ((x & mask) != 0)
#define bit_isfalse(x,mask) ((x & mask) == 0)
#define bit_true(x, mask) (x) |= (mask)
#define bit_false(x, mask) (x) &= ~(mask)
#define bit_istrue(x, mask) ((x & mask) != 0)
#define bit_isfalse(x, mask) ((x & mask) == 0)
// Read a floating point value from a string. Line points to the input buffer, char_counter
// is the indexer pointing to the current character of the line, while float_ptr is
@ -99,13 +97,16 @@ float convert_delta_vector_to_unit_vector(float* vector);
float limit_acceleration_by_axis_maximum(float* unit_vec);
float limit_rate_by_axis_maximum(float* unit_vec);
float mapConstrain(float x, float in_min, float in_max, float out_min, float out_max);
float map_float(float x, float in_min, float in_max, float out_min, float out_max);
float mapConstrain(float x, float in_min, float in_max, float out_min, float out_max);
float map_float(float x, float in_min, float in_max, float out_min, float out_max);
uint32_t map_uint32_t(uint32_t x, uint32_t in_min, uint32_t in_max, uint32_t out_min, uint32_t out_max);
float constrain_float(float in, float min, float max);
bool char_is_numeric(char value);
char* trim(char* value);
float constrain_float(float in, float min, float max);
bool char_is_numeric(char value);
char* trim(char* value);
template <class T> void swap(T& a, T& b) {
T c(a); a = b; b = c;
template <class T>
void swap(T& a, T& b) {
T c(a);
a = b;
b = c;
}

View File

@ -24,42 +24,40 @@
*/
#include "grbl.h"
#include <stdlib.h> // PSoc Required for labs
#include <stdlib.h> // PSoc Required for labs
static plan_block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for motion instructions
static uint8_t block_buffer_tail; // Index of the block to process now
static uint8_t block_buffer_head; // Index of the next block to be pushed
static uint8_t next_buffer_head; // Index of the next buffer head
static uint8_t block_buffer_planned; // Index of the optimally planned block
static uint8_t block_buffer_tail; // Index of the block to process now
static uint8_t block_buffer_head; // Index of the next block to be pushed
static uint8_t next_buffer_head; // Index of the next buffer head
static uint8_t block_buffer_planned; // Index of the optimally planned block
// Define planner variables
typedef struct {
int32_t position[N_AXIS]; // The planner position of the tool in absolute steps. Kept separate
int32_t position[N_AXIS]; // The planner position of the tool in absolute steps. Kept separate
// from g-code position for movements requiring multiple line motions,
// i.e. arcs, canned cycles, and backlash compensation.
float previous_unit_vec[N_AXIS]; // Unit vector of previous path line segment
float previous_nominal_speed; // Nominal speed of previous path line segment
float previous_unit_vec[N_AXIS]; // Unit vector of previous path line segment
float previous_nominal_speed; // Nominal speed of previous path line segment
} planner_t;
static planner_t pl;
// Returns the index of the next block in the ring buffer. Also called by stepper segment buffer.
uint8_t plan_next_block_index(uint8_t block_index) {
block_index++;
if (block_index == BLOCK_BUFFER_SIZE) block_index = 0;
if (block_index == BLOCK_BUFFER_SIZE)
block_index = 0;
return (block_index);
}
// Returns the index of the previous block in the ring buffer
static uint8_t plan_prev_block_index(uint8_t block_index) {
if (block_index == 0) block_index = BLOCK_BUFFER_SIZE;
if (block_index == 0)
block_index = BLOCK_BUFFER_SIZE;
block_index--;
return (block_index);
}
/* PLANNER SPEED DEFINITION
+--------+ <- current->nominal_speed
/ \
@ -129,26 +127,29 @@ static void planner_recalculate() {
// Initialize block index to the last block in the planner buffer.
uint8_t block_index = plan_prev_block_index(block_buffer_head);
// Bail. Can't do anything with one only one plan-able block.
if (block_index == block_buffer_planned) return;
if (block_index == block_buffer_planned)
return;
// Reverse Pass: Coarsely maximize all possible deceleration curves back-planning from the last
// block in buffer. Cease planning when the last optimal planned or tail pointer is reached.
// NOTE: Forward pass will later refine and correct the reverse pass to create an optimal plan.
float entry_speed_sqr;
float entry_speed_sqr;
plan_block_t* next;
plan_block_t* current = &block_buffer[block_index];
// Calculate maximum entry speed for last block in buffer, where the exit speed is always zero.
current->entry_speed_sqr = MIN(current->max_entry_speed_sqr, 2 * current->acceleration * current->millimeters);
block_index = plan_prev_block_index(block_index);
if (block_index == block_buffer_planned) { // Only two plannable blocks in buffer. Reverse pass complete.
block_index = plan_prev_block_index(block_index);
if (block_index == block_buffer_planned) { // Only two plannable blocks in buffer. Reverse pass complete.
// Check if the first block is the tail. If so, notify stepper to update its current parameters.
if (block_index == block_buffer_tail) st_update_plan_block_parameters();
} else { // Three or more plan-able blocks
if (block_index == block_buffer_tail)
st_update_plan_block_parameters();
} else { // Three or more plan-able blocks
while (block_index != block_buffer_planned) {
next = current;
current = &block_buffer[block_index];
next = current;
current = &block_buffer[block_index];
block_index = plan_prev_block_index(block_index);
// Check if next block is the tail block(=planned block). If so, update current stepper parameters.
if (block_index == block_buffer_tail) st_update_plan_block_parameters();
if (block_index == block_buffer_tail)
st_update_plan_block_parameters();
// Compute maximum entry speed decelerating over the current block from its exit speed.
if (current->entry_speed_sqr != current->max_entry_speed_sqr) {
entry_speed_sqr = next->entry_speed_sqr + 2 * current->acceleration * current->millimeters;
@ -161,11 +162,11 @@ static void planner_recalculate() {
}
// Forward Pass: Forward plan the acceleration curve from the planned pointer onward.
// Also scans for optimal plan breakpoints and appropriately updates the planned pointer.
next = &block_buffer[block_buffer_planned]; // Begin at buffer planned pointer
next = &block_buffer[block_buffer_planned]; // Begin at buffer planned pointer
block_index = plan_next_block_index(block_buffer_planned);
while (block_index != block_buffer_head) {
current = next;
next = &block_buffer[block_index];
next = &block_buffer[block_index];
// Any acceleration detected in the forward pass automatically moves the optimal planned
// pointer forward, since everything before this is all optimal. In other words, nothing
// can improve the plan from the buffer tail to the planned pointer by logic.
@ -173,117 +174,118 @@ static void planner_recalculate() {
entry_speed_sqr = current->entry_speed_sqr + 2 * current->acceleration * current->millimeters;
// If true, current block is full-acceleration and we can move the planned pointer forward.
if (entry_speed_sqr < next->entry_speed_sqr) {
next->entry_speed_sqr = entry_speed_sqr; // Always <= max_entry_speed_sqr. Backward pass sets this.
block_buffer_planned = block_index; // Set optimal plan pointer.
next->entry_speed_sqr = entry_speed_sqr; // Always <= max_entry_speed_sqr. Backward pass sets this.
block_buffer_planned = block_index; // Set optimal plan pointer.
}
}
// Any block set at its maximum entry speed also creates an optimal plan up to this
// point in the buffer. When the plan is bracketed by either the beginning of the
// buffer and a maximum entry speed or two maximum entry speeds, every block in between
// cannot logically be further improved. Hence, we don't have to recompute them anymore.
if (next->entry_speed_sqr == next->max_entry_speed_sqr) block_buffer_planned = block_index;
if (next->entry_speed_sqr == next->max_entry_speed_sqr)
block_buffer_planned = block_index;
block_index = plan_next_block_index(block_index);
}
}
void plan_reset() {
memset(&pl, 0, sizeof(planner_t)); // Clear planner struct
memset(&pl, 0, sizeof(planner_t)); // Clear planner struct
plan_reset_buffer();
}
void plan_reset_buffer() {
block_buffer_tail = 0;
block_buffer_head = 0; // Empty = tail
next_buffer_head = 1; // plan_next_block_index(block_buffer_head)
block_buffer_planned = 0; // = block_buffer_tail;
block_buffer_tail = 0;
block_buffer_head = 0; // Empty = tail
next_buffer_head = 1; // plan_next_block_index(block_buffer_head)
block_buffer_planned = 0; // = block_buffer_tail;
}
void plan_discard_current_block() {
if (block_buffer_head != block_buffer_tail) { // Discard non-empty buffer.
if (block_buffer_head != block_buffer_tail) { // Discard non-empty buffer.
uint8_t block_index = plan_next_block_index(block_buffer_tail);
// Push block_buffer_planned pointer, if encountered.
if (block_buffer_tail == block_buffer_planned) block_buffer_planned = block_index;
if (block_buffer_tail == block_buffer_planned)
block_buffer_planned = block_index;
block_buffer_tail = block_index;
}
}
// Returns address of planner buffer block used by system motions. Called by segment generator.
plan_block_t* plan_get_system_motion_block() {
return (&block_buffer[block_buffer_head]);
}
// Returns address of first planner block, if available. Called by various main program functions.
plan_block_t* plan_get_current_block() {
if (block_buffer_head == block_buffer_tail) return (NULL); // Buffer empty
if (block_buffer_head == block_buffer_tail)
return (NULL); // Buffer empty
return (&block_buffer[block_buffer_tail]);
}
float plan_get_exec_block_exit_speed_sqr() {
uint8_t block_index = plan_next_block_index(block_buffer_tail);
if (block_index == block_buffer_head) return (0.0);
if (block_index == block_buffer_head)
return (0.0);
return (block_buffer[block_index].entry_speed_sqr);
}
// Returns the availability status of the block ring buffer. True, if full.
uint8_t plan_check_full_buffer() {
if (block_buffer_tail == next_buffer_head) return (true);
if (block_buffer_tail == next_buffer_head)
return (true);
return (false);
}
// Computes and returns block nominal speed based on running condition and override values.
// NOTE: All system motion commands, such as homing/parking, are not subject to overrides.
float plan_compute_profile_nominal_speed(plan_block_t* block) {
float nominal_speed = block->programmed_rate;
if (block->condition & PL_COND_FLAG_RAPID_MOTION) nominal_speed *= (0.01 * sys.r_override);
if (block->condition & PL_COND_FLAG_RAPID_MOTION)
nominal_speed *= (0.01 * sys.r_override);
else {
if (!(block->condition & PL_COND_FLAG_NO_FEED_OVERRIDE)) nominal_speed *= (0.01 * sys.f_override);
if (nominal_speed > block->rapid_rate) nominal_speed = block->rapid_rate;
if (!(block->condition & PL_COND_FLAG_NO_FEED_OVERRIDE))
nominal_speed *= (0.01 * sys.f_override);
if (nominal_speed > block->rapid_rate)
nominal_speed = block->rapid_rate;
}
if (nominal_speed > MINIMUM_FEED_RATE) return (nominal_speed);
if (nominal_speed > MINIMUM_FEED_RATE)
return (nominal_speed);
return (MINIMUM_FEED_RATE);
}
// Computes and updates the max entry speed (sqr) of the block, based on the minimum of the junction's
// previous and current nominal speeds and max junction speed.
static void plan_compute_profile_parameters(plan_block_t* block, float nominal_speed, float prev_nominal_speed) {
// Compute the junction maximum entry based on the minimum of the junction speed and neighboring nominal speeds.
if (nominal_speed > prev_nominal_speed) block->max_entry_speed_sqr = prev_nominal_speed * prev_nominal_speed;
else block->max_entry_speed_sqr = nominal_speed * nominal_speed;
if (block->max_entry_speed_sqr > block->max_junction_speed_sqr) block->max_entry_speed_sqr = block->max_junction_speed_sqr;
if (nominal_speed > prev_nominal_speed)
block->max_entry_speed_sqr = prev_nominal_speed * prev_nominal_speed;
else
block->max_entry_speed_sqr = nominal_speed * nominal_speed;
if (block->max_entry_speed_sqr > block->max_junction_speed_sqr)
block->max_entry_speed_sqr = block->max_junction_speed_sqr;
}
// Re-calculates buffered motions profile parameters upon a motion-based override change.
void plan_update_velocity_profile_parameters() {
uint8_t block_index = block_buffer_tail;
uint8_t block_index = block_buffer_tail;
plan_block_t* block;
float nominal_speed;
float prev_nominal_speed = SOME_LARGE_VALUE; // Set high for first block nominal speed calculation.
float nominal_speed;
float prev_nominal_speed = SOME_LARGE_VALUE; // Set high for first block nominal speed calculation.
while (block_index != block_buffer_head) {
block = &block_buffer[block_index];
block = &block_buffer[block_index];
nominal_speed = plan_compute_profile_nominal_speed(block);
plan_compute_profile_parameters(block, nominal_speed, prev_nominal_speed);
prev_nominal_speed = nominal_speed;
block_index = plan_next_block_index(block_index);
block_index = plan_next_block_index(block_index);
}
pl.previous_nominal_speed = prev_nominal_speed; // Update prev nominal speed for next incoming block.
pl.previous_nominal_speed = prev_nominal_speed; // Update prev nominal speed for next incoming block.
}
uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
// Prepare and initialize new block. Copy relevant pl_data for block execution.
plan_block_t* block = &block_buffer[block_buffer_head];
memset(block, 0, sizeof(plan_block_t)); // Zero all block values.
block->condition = pl_data->condition;
memset(block, 0, sizeof(plan_block_t)); // Zero all block values.
block->condition = pl_data->condition;
block->spindle_speed = pl_data->spindle_speed;
#ifdef USE_LINE_NUMBERS
@ -291,7 +293,7 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
#endif
// Compute and store initial move distance data.
int32_t target_steps[N_AXIS], position_steps[N_AXIS];
float unit_vec[N_AXIS], delta_mm;
float unit_vec[N_AXIS], delta_mm;
uint8_t idx;
// Copy position data based on type of motion being planned.
if (block->condition & PL_COND_FLAG_SYSTEM_MOTION) {
@ -302,7 +304,8 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
#else
memcpy(position_steps, sys_position, sizeof(sys_position));
#endif
} else memcpy(position_steps, pl.position, sizeof(pl.position));
} else
memcpy(position_steps, pl.position, sizeof(pl.position));
#ifdef COREXY
target_steps[A_MOTOR] = lround(target[A_MOTOR] * axis_settings[A_MOTOR]->steps_per_mm->get());
target_steps[B_MOTOR] = lround(target[B_MOTOR] * axis_settings[B_MOTOR]->steps_per_mm->get());
@ -320,42 +323,48 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
}
block->step_event_count = MAX(block->step_event_count, block->steps[idx]);
if (idx == A_MOTOR)
delta_mm = (target_steps[X_AXIS] - position_steps[X_AXIS] + target_steps[Y_AXIS] - position_steps[Y_AXIS]) / axis_settings[idx]->steps_per_mm->get();
delta_mm = (target_steps[X_AXIS] - position_steps[X_AXIS] + target_steps[Y_AXIS] - position_steps[Y_AXIS]) /
axis_settings[idx]->steps_per_mm->get();
else if (idx == B_MOTOR)
delta_mm = (target_steps[X_AXIS] - position_steps[X_AXIS] - target_steps[Y_AXIS] + position_steps[Y_AXIS]) / axis_settings[idx]->steps_per_mm->get();
delta_mm = (target_steps[X_AXIS] - position_steps[X_AXIS] - target_steps[Y_AXIS] + position_steps[Y_AXIS]) /
axis_settings[idx]->steps_per_mm->get();
else
delta_mm = (target_steps[idx] - position_steps[idx]) / axis_settings[idx]->steps_per_mm->get();
#else
target_steps[idx] = lround(target[idx] * axis_settings[idx]->steps_per_mm->get());
block->steps[idx] = labs(target_steps[idx] - position_steps[idx]);
target_steps[idx] = lround(target[idx] * axis_settings[idx]->steps_per_mm->get());
block->steps[idx] = labs(target_steps[idx] - position_steps[idx]);
block->step_event_count = MAX(block->step_event_count, block->steps[idx]);
delta_mm = (target_steps[idx] - position_steps[idx]) / axis_settings[idx]->steps_per_mm->get();
delta_mm = (target_steps[idx] - position_steps[idx]) / axis_settings[idx]->steps_per_mm->get();
#endif
unit_vec[idx] = delta_mm; // Store unit vector numerator
unit_vec[idx] = delta_mm; // Store unit vector numerator
// Set direction bits. Bit enabled always means direction is negative.
if (delta_mm < 0.0) block->direction_bits |= get_direction_pin_mask(idx);
if (delta_mm < 0.0)
block->direction_bits |= get_direction_pin_mask(idx);
}
// Bail if this is a zero-length block. Highly unlikely to occur.
if (block->step_event_count == 0) return (PLAN_EMPTY_BLOCK);
if (block->step_event_count == 0)
return (PLAN_EMPTY_BLOCK);
// Calculate the unit vector of the line move and the block maximum feed rate and acceleration scaled
// down such that no individual axes maximum values are exceeded with respect to the line direction.
// NOTE: This calculation assumes all axes are orthogonal (Cartesian) and works with ABC-axes,
// if they are also orthogonal/independent. Operates on the absolute value of the unit vector.
block->millimeters = convert_delta_vector_to_unit_vector(unit_vec);
block->millimeters = convert_delta_vector_to_unit_vector(unit_vec);
block->acceleration = limit_acceleration_by_axis_maximum(unit_vec);
block->rapid_rate = limit_rate_by_axis_maximum(unit_vec);
block->rapid_rate = limit_rate_by_axis_maximum(unit_vec);
// Store programmed rate.
if (block->condition & PL_COND_FLAG_RAPID_MOTION) block->programmed_rate = block->rapid_rate;
if (block->condition & PL_COND_FLAG_RAPID_MOTION)
block->programmed_rate = block->rapid_rate;
else {
block->programmed_rate = pl_data->feed_rate;
if (block->condition & PL_COND_FLAG_INVERSE_TIME) block->programmed_rate *= block->millimeters;
if (block->condition & PL_COND_FLAG_INVERSE_TIME)
block->programmed_rate *= block->millimeters;
}
// TODO: Need to check this method handling zero junction speeds when starting from rest.
if ((block_buffer_head == block_buffer_tail) || (block->condition & PL_COND_FLAG_SYSTEM_MOTION)) {
// Initialize block entry speed as zero. Assume it will be starting from rest. Planner will correct this later.
// If system motion, the system motion block always is assumed to start from rest and end at a complete stop.
block->entry_speed_sqr = 0.0;
block->max_junction_speed_sqr = 0.0; // Starting from rest. Enforce start from zero velocity.
block->entry_speed_sqr = 0.0;
block->max_junction_speed_sqr = 0.0; // Starting from rest. Enforce start from zero velocity.
} else {
// Compute maximum allowable entry speed at junction by centripetal acceleration approximation.
// Let a circle be tangent to both previous and current path line segments, where the junction
@ -395,9 +404,10 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
} else {
convert_delta_vector_to_unit_vector(junction_unit_vec);
float junction_acceleration = limit_acceleration_by_axis_maximum(junction_unit_vec);
float sin_theta_d2 = sqrt(0.5 * (1.0 - junction_cos_theta)); // Trig half angle identity. Always positive.
block->max_junction_speed_sqr = MAX(MINIMUM_JUNCTION_SPEED * MINIMUM_JUNCTION_SPEED,
(junction_acceleration * junction_deviation->get() * sin_theta_d2) / (1.0 - sin_theta_d2));
float sin_theta_d2 = sqrt(0.5 * (1.0 - junction_cos_theta)); // Trig half angle identity. Always positive.
block->max_junction_speed_sqr =
MAX(MINIMUM_JUNCTION_SPEED * MINIMUM_JUNCTION_SPEED,
(junction_acceleration * junction_deviation->get() * sin_theta_d2) / (1.0 - sin_theta_d2));
}
}
}
@ -407,11 +417,11 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
plan_compute_profile_parameters(block, nominal_speed, pl.previous_nominal_speed);
pl.previous_nominal_speed = nominal_speed;
// Update previous path unit_vector and planner position.
memcpy(pl.previous_unit_vec, unit_vec, sizeof(unit_vec)); // pl.previous_unit_vec[] = unit_vec[]
memcpy(pl.position, target_steps, sizeof(target_steps)); // pl.position[] = target_steps[]
memcpy(pl.previous_unit_vec, unit_vec, sizeof(unit_vec)); // pl.previous_unit_vec[] = unit_vec[]
memcpy(pl.position, target_steps, sizeof(target_steps)); // pl.position[] = target_steps[]
// New block is all set. Update buffer head and next buffer head indices.
block_buffer_head = next_buffer_head;
next_buffer_head = plan_next_block_index(block_buffer_head);
next_buffer_head = plan_next_block_index(block_buffer_head);
// Finish up by recalculating the plan with the new block.
planner_recalculate();
}
@ -432,27 +442,26 @@ void plan_sync_position() {
else
pl.position[idx] = sys_position[idx];
#else
pl.position[idx] = sys_position[idx];
pl.position[idx] = sys_position[idx];
#endif
}
}
// Returns the number of available blocks are in the planner buffer.
uint8_t plan_get_block_buffer_available() {
if (block_buffer_head >= block_buffer_tail) return ((BLOCK_BUFFER_SIZE - 1) - (block_buffer_head - block_buffer_tail));
if (block_buffer_head >= block_buffer_tail)
return ((BLOCK_BUFFER_SIZE - 1) - (block_buffer_head - block_buffer_tail));
return ((block_buffer_tail - block_buffer_head - 1));
}
// Returns the number of active blocks are in the planner buffer.
// NOTE: Deprecated. Not used unless classic status reports are enabled in config.h
uint8_t plan_get_block_buffer_count() {
if (block_buffer_head >= block_buffer_tail) return (block_buffer_head - block_buffer_tail);
if (block_buffer_head >= block_buffer_tail)
return (block_buffer_head - block_buffer_tail);
return (BLOCK_BUFFER_SIZE - (block_buffer_tail - block_buffer_head));
}
// Re-initialize buffer plan with a partially completed block, assumed to exist at the buffer tail.
// Called after a steppers have come to a complete stop for a feed hold and the cycle is stopped.
void plan_cycle_reinitialize() {

View File

@ -26,11 +26,11 @@
// The number of linear motions that can be in the plan at any give time
#ifndef BLOCK_BUFFER_SIZE
#ifdef USE_LINE_NUMBERS
#define BLOCK_BUFFER_SIZE 15
#else
#define BLOCK_BUFFER_SIZE 16
#endif
# ifdef USE_LINE_NUMBERS
# define BLOCK_BUFFER_SIZE 15
# else
# define BLOCK_BUFFER_SIZE 16
# endif
#endif
// Returned status message from planner.
@ -38,69 +38,64 @@
#define PLAN_EMPTY_BLOCK false
// Define planner data condition flags. Used to denote running conditions of a block.
#define PL_COND_FLAG_RAPID_MOTION bit(0)
#define PL_COND_FLAG_SYSTEM_MOTION bit(1) // Single motion. Circumvents planner state. Used by home/park.
#define PL_COND_FLAG_NO_FEED_OVERRIDE bit(2) // Motion does not honor feed override.
#define PL_COND_FLAG_INVERSE_TIME bit(3) // Interprets feed rate value as inverse time when set.
#define PL_COND_FLAG_SPINDLE_CW bit(4)
#define PL_COND_FLAG_SPINDLE_CCW bit(5)
#define PL_COND_FLAG_COOLANT_FLOOD bit(6)
#define PL_COND_FLAG_COOLANT_MIST bit(7)
#define PL_COND_MOTION_MASK (PL_COND_FLAG_RAPID_MOTION|PL_COND_FLAG_SYSTEM_MOTION|PL_COND_FLAG_NO_FEED_OVERRIDE)
#define PL_COND_ACCESSORY_MASK (PL_COND_FLAG_SPINDLE_CW|PL_COND_FLAG_SPINDLE_CCW|PL_COND_FLAG_COOLANT_FLOOD|PL_COND_FLAG_COOLANT_MIST)
#define PL_COND_FLAG_RAPID_MOTION bit(0)
#define PL_COND_FLAG_SYSTEM_MOTION bit(1) // Single motion. Circumvents planner state. Used by home/park.
#define PL_COND_FLAG_NO_FEED_OVERRIDE bit(2) // Motion does not honor feed override.
#define PL_COND_FLAG_INVERSE_TIME bit(3) // Interprets feed rate value as inverse time when set.
#define PL_COND_FLAG_SPINDLE_CW bit(4)
#define PL_COND_FLAG_SPINDLE_CCW bit(5)
#define PL_COND_FLAG_COOLANT_FLOOD bit(6)
#define PL_COND_FLAG_COOLANT_MIST bit(7)
#define PL_COND_MOTION_MASK (PL_COND_FLAG_RAPID_MOTION | PL_COND_FLAG_SYSTEM_MOTION | PL_COND_FLAG_NO_FEED_OVERRIDE)
#define PL_COND_ACCESSORY_MASK (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW | PL_COND_FLAG_COOLANT_FLOOD | PL_COND_FLAG_COOLANT_MIST)
// This struct stores a linear movement of a g-code block motion with its critical "nominal" values
// are as specified in the source g-code.
typedef struct {
// Fields used by the bresenham algorithm for tracing the line
// NOTE: Used by stepper algorithm to execute the block correctly. Do not alter these values.
uint32_t steps[N_AXIS]; // Step count along each axis
uint32_t step_event_count; // The maximum step axis count and number of steps required to complete this block.
uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
uint32_t steps[N_AXIS]; // Step count along each axis
uint32_t step_event_count; // The maximum step axis count and number of steps required to complete this block.
uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
// Block condition data to ensure correct execution depending on states and overrides.
uint8_t condition; // Block bitflag variable defining block run conditions. Copied from pl_line_data.
uint8_t condition; // Block bitflag variable defining block run conditions. Copied from pl_line_data.
#ifdef USE_LINE_NUMBERS
int32_t line_number; // Block line number for real-time reporting. Copied from pl_line_data.
#endif
// Fields used by the motion planner to manage acceleration. Some of these values may be updated
// by the stepper module during execution of special motion cases for replanning purposes.
float entry_speed_sqr; // The current planned entry speed at block junction in (mm/min)^2
float max_entry_speed_sqr; // Maximum allowable entry speed based on the minimum of junction limit and
float entry_speed_sqr; // The current planned entry speed at block junction in (mm/min)^2
float max_entry_speed_sqr; // Maximum allowable entry speed based on the minimum of junction limit and
// neighboring nominal speeds with overrides in (mm/min)^2
float acceleration; // Axis-limit adjusted line acceleration in (mm/min^2). Does not change.
float millimeters; // The remaining distance for this block to be executed in (mm).
float acceleration; // Axis-limit adjusted line acceleration in (mm/min^2). Does not change.
float millimeters; // The remaining distance for this block to be executed in (mm).
// NOTE: This value may be altered by stepper algorithm during execution.
// Stored rate limiting data used by planner when changes occur.
float max_junction_speed_sqr; // Junction entry speed limit based on direction vectors in (mm/min)^2
float rapid_rate; // Axis-limit adjusted maximum rate for this block direction in (mm/min)
float programmed_rate; // Programmed rate of this block (mm/min).
float max_junction_speed_sqr; // Junction entry speed limit based on direction vectors in (mm/min)^2
float rapid_rate; // Axis-limit adjusted maximum rate for this block direction in (mm/min)
float programmed_rate; // Programmed rate of this block (mm/min).
// Stored spindle speed data used by spindle overrides and resuming methods.
float spindle_speed; // Block spindle speed. Copied from pl_line_data.
float spindle_speed; // Block spindle speed. Copied from pl_line_data.
//#endif
} plan_block_t;
// Planner data prototype. Must be used when passing new motions to the planner.
typedef struct {
float feed_rate; // Desired feed rate for line motion. Value is ignored, if rapid motion.
uint32_t spindle_speed; // Desired spindle speed through line motion.
uint8_t condition; // Bitflag variable to indicate planner conditions. See defines above.
float feed_rate; // Desired feed rate for line motion. Value is ignored, if rapid motion.
uint32_t spindle_speed; // Desired spindle speed through line motion.
uint8_t condition; // Bitflag variable to indicate planner conditions. See defines above.
#ifdef USE_LINE_NUMBERS
int32_t line_number; // Desired line number to report when executing.
int32_t line_number; // Desired line number to report when executing.
#endif
} plan_line_data_t;
// Initialize and reset the motion plan subsystem
void plan_reset(); // Reset all
void plan_reset_buffer(); // Reset buffer only.
void plan_reset(); // Reset all
void plan_reset_buffer(); // Reset buffer only.
// Add a new linear movement to the buffer. target[N_AXIS] is the signed, absolute target position
// in millimeters. Feed rate specifies the speed of the motion. If feed rate is inverted, the feed

View File

@ -1,138 +0,0 @@
/*
print.c - Functions for formatting output strings
Part of Grbl
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
Copyright (c) 2009-2011 Simen Svale Skogsrud
2018 - Bart Dring This file was modifed 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/>.
*/
#include "grbl.h"
// void printIntegerInBase(unsigned long n, unsigned long base)
// {
// unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars.
// unsigned long i = 0;
//
// if (n == 0) {
// serial_write('0');
// return;
// }
//
// while (n > 0) {
// buf[i++] = n % base;
// n /= base;
// }
//
// for (; i > 0; i--)
// serial_write(buf[i - 1] < 10 ?
// '0' + buf[i - 1] :
// 'A' + buf[i - 1] - 10);
// }
// Prints an uint8 variable in base 10.
void print_uint8_base10(uint8_t n) {
uint8_t digit_a = 0;
uint8_t digit_b = 0;
if (n >= 100) { // 100-255
digit_a = '0' + n % 10;
n /= 10;
}
if (n >= 10) { // 10-99
digit_b = '0' + n % 10;
n /= 10;
}
serial_write('0' + n);
if (digit_b) serial_write(digit_b);
if (digit_a) serial_write(digit_a);
}
// Prints an uint8 variable in base 2 with desired number of desired digits.
void print_uint8_base2_ndigit(uint8_t n, uint8_t digits) {
unsigned char buf[digits];
uint8_t i = 0;
for (; i < digits; i++) {
buf[i] = n % 2 ;
n /= 2;
}
for (; i > 0; i--)
Serial.print('0' + buf[i - 1]);
}
void print_uint32_base10(uint32_t n) {
if (n == 0) {
Serial.print('0');
return;
}
unsigned char buf[10];
uint8_t i = 0;
while (n > 0) {
buf[i++] = n % 10;
n /= 10;
}
for (; i > 0; i--)
Serial.print('0' + buf[i - 1]);
}
void printInteger(long n) {
if (n < 0) {
Serial.print('-');
print_uint32_base10(-n);
} else
print_uint32_base10(n);
}
// Convert float to string by immediately converting to a long integer, which contains
// more digits than a float. Number of decimal places, which are tracked by a counter,
// may be set by the user. The integer is then efficiently converted to a string.
// NOTE: AVR '%' and '/' integer operations are very efficient. Bitshifting speed-up
// techniques are actually just slightly slower. Found this out the hard way.
void printFloat(float n, uint8_t decimal_places) {
Serial.print(n, decimal_places);
}
// Floating value printing handlers for special variables types used in Grbl and are defined
// in the config.h.
// - CoordValue: Handles all position or coordinate values in inches or mm reporting.
// - RateValue: Handles feed rate and current velocity in inches or mm reporting.
void printFloat_CoordValue(float n) {
if (report_inches->get())
printFloat(n * INCH_PER_MM, N_DECIMAL_COORDVALUE_INCH);
else
printFloat(n, N_DECIMAL_COORDVALUE_MM);
}
// Debug tool to print free memory in bytes at the called point.
// NOTE: Keep commented unless using. Part of this function always gets compiled in.
// void printFreeMemory()
// {
// extern int __heap_start, *__brkval;
// uint16_t free; // Up to 64k values.
// free = (int) &free - (__brkval == 0 ? (int) &__heap_start : (int) __brkval);
// printInteger((int32_t)free);
// printString(" ");
// }

View File

@ -1,50 +0,0 @@
#pragma once
/*
print.h - Functions for formatting output strings
Part of Grbl
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
Copyright (c) 2009-2011 Simen Svale Skogsrud
2018 - Bart Dring This file was modifed 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/>.
*/
void printString(const char* s);
void printPgmString(const char* s);
void printInteger(long n);
void print_uint32_base10(uint32_t n);
// Prints an uint8 variable in base 10.
void print_uint8_base10(uint8_t n);
// Prints an uint8 variable in base 2 with desired number of desired digits.
void print_uint8_base2_ndigit(uint8_t n, uint8_t digits);
void printFloat(float n, uint8_t decimal_places);
// Floating value printing handlers for special variables types used in Grbl.
// - CoordValue: Handles all position or coordinate values in inches or mm reporting.
// - RateValue: Handles feed rate and current velocity in inches or mm reporting.
void printFloat_CoordValue(float n);
void printFloat_RateValue(float n);
// Debug tool to print free memory in bytes at the called point. Not used otherwise.
void printFreeMemory();

View File

@ -23,31 +23,30 @@
#include "grbl.h"
// Inverts the probe pin state depending on user settings and probing cycle mode.
uint8_t probe_invert_mask;
// Probe pin initialization routine.
void probe_init() {
#ifdef PROBE_PIN
#ifdef DISABLE_PROBE_PIN_PULL_UP
# ifdef DISABLE_PROBE_PIN_PULL_UP
pinMode(PROBE_PIN, INPUT);
#else
pinMode(PROBE_PIN, INPUT_PULLUP); // Enable internal pull-up resistors. Normal high operation.
#endif
probe_configure_invert_mask(false); // Initialize invert mask.
# else
pinMode(PROBE_PIN, INPUT_PULLUP); // Enable internal pull-up resistors. Normal high operation.
# endif
probe_configure_invert_mask(false); // Initialize invert mask.
#endif
}
// Called by probe_init() and the mc_probe() routines. Sets up the probe pin invert mask to
// appropriately set the pin logic according to setting for normal-high/normal-low operation
// and the probing cycle modes for toward-workpiece/away-from-workpiece.
void probe_configure_invert_mask(uint8_t is_probe_away) {
probe_invert_mask = 0; // Initialize as zero.
if (probe_invert->get()) probe_invert_mask ^= PROBE_MASK;
if (is_probe_away) probe_invert_mask ^= PROBE_MASK;
probe_invert_mask = 0; // Initialize as zero.
if (probe_invert->get())
probe_invert_mask ^= PROBE_MASK;
if (is_probe_away)
probe_invert_mask ^= PROBE_MASK;
}
// Returns the probe pin state. Triggered = true. Called by gcode parser and probe state monitor.
@ -59,7 +58,6 @@ uint8_t probe_get_state() {
#endif
}
// Monitors probe pin state and records the system position when detected. Called by the
// stepper ISR per ISR tick.
// NOTE: This function must be extremely efficient as to not bog down the stepper ISR.

View File

@ -24,8 +24,8 @@
*/
// Values that define the probing state machine.
#define PROBE_OFF 0 // Probing disabled or not in use. (Must be zero.)
#define PROBE_ACTIVE 1 // Actively watching the input pin.
#define PROBE_OFF 0 // Probing disabled or not in use. (Must be zero.)
#define PROBE_ACTIVE 1 // Actively watching the input pin.
// Probe pin initialization routine.
void probe_init();

View File

@ -26,10 +26,10 @@
static void protocol_exec_rt_suspend();
static char line[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
static char comment[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
static uint8_t line_flags = 0;
static uint8_t char_counter = 0;
static char line[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
static char comment[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
static uint8_t line_flags = 0;
static uint8_t char_counter = 0;
static uint8_t comment_char_counter = 0;
typedef struct {
@ -41,8 +41,8 @@ client_line_t client_lines[CLIENT_COUNT];
static void empty_line(uint8_t client) {
client_line_t* cl = &client_lines[client];
cl->len = 0;
cl->buffer[0] = '\0';
cl->len = 0;
cl->buffer[0] = '\0';
}
static void empty_lines() {
for (uint8_t client = 0; client < CLIENT_COUNT; client++)
@ -68,7 +68,7 @@ err_t add_char_to_line(char c, uint8_t client) {
return STATUS_EOL;
}
cl->buffer[cl->len++] = c;
cl->buffer[cl->len] = '\0';
cl->buffer[cl->len] = '\0';
return STATUS_OK;
}
@ -97,7 +97,7 @@ void protocol_main_loop() {
#ifdef CHECK_LIMITS_AT_INIT
if (hard_limits->get()) {
if (limits_get_state()) {
sys.state = STATE_ALARM; // Ensure alarm state is active.
sys.state = STATE_ALARM; // Ensure alarm state is active.
report_feedback_message(MESSAGE_CHECK_LIMITS);
}
}
@ -107,16 +107,16 @@ void protocol_main_loop() {
// Re-initialize the sleep state as an ALARM mode to ensure user homes or acknowledges.
if (sys.state & (STATE_ALARM | STATE_SLEEP)) {
report_feedback_message(MESSAGE_ALARM_LOCK);
sys.state = STATE_ALARM; // Ensure alarm state is set.
sys.state = STATE_ALARM; // Ensure alarm state is set.
} else {
// Check if the safety door is open.
sys.state = STATE_IDLE;
if (system_check_safety_door_ajar()) {
bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR);
protocol_execute_realtime(); // Enter safety door mode. Should return as IDLE state.
protocol_execute_realtime(); // Enter safety door mode. Should return as IDLE state.
}
// All systems go!
system_execute_startup(line); // Execute startup script.
system_execute_startup(line); // Execute startup script.
}
// ---------------------------------------------------------------------------------
// Primary loop! Upon a system abort, this exits back to main() to reset the system.
@ -134,7 +134,7 @@ void protocol_main_loop() {
char temp[50];
sd_get_current_filename(temp);
grbl_notifyf("SD print done", "%s print is successful", temp);
closeFile(); // close file and clear SD ready/running flags
closeFile(); // close file and clear SD ready/running flags
}
}
#endif
@ -142,40 +142,39 @@ void protocol_main_loop() {
// Filtering, if necessary, is done later in gc_execute_line(), so the
// filtering is the same with serial and file input.
uint8_t client = CLIENT_SERIAL;
char* line;
char* line;
for (client = 0; client < CLIENT_COUNT; client++) {
while ((c = serial_read(client)) != SERIAL_NO_DATA) {
err_t res = add_char_to_line(c, client);
switch (res) {
case STATUS_OK:
break;
case STATUS_EOL:
protocol_execute_realtime(); // Runtime command check point.
if (sys.abort) {
return; // Bail to calling function upon system abort
}
line = client_lines[client].buffer;
case STATUS_OK: break;
case STATUS_EOL:
protocol_execute_realtime(); // Runtime command check point.
if (sys.abort) {
return; // Bail to calling function upon system abort
}
line = client_lines[client].buffer;
#ifdef REPORT_ECHO_RAW_LINE_RECEIVED
report_echo_line_received(line, client);
report_echo_line_received(line, client);
#endif
// auth_level can be upgraded by supplying a password on the command line
report_status_message(execute_line(line, client, LEVEL_GUEST), client);
empty_line(client);
break;
case STATUS_OVERFLOW:
report_status_message(STATUS_OVERFLOW, client);
empty_line(client);
break;
// auth_level can be upgraded by supplying a password on the command line
report_status_message(execute_line(line, client, LEVEL_GUEST), client);
empty_line(client);
break;
case STATUS_OVERFLOW:
report_status_message(STATUS_OVERFLOW, client);
empty_line(client);
break;
}
} // while serial read
} // for clients
} // while serial read
} // for clients
// If there are no more characters in the serial read buffer to be processed and executed,
// this indicates that g-code streaming has either filled the planner buffer or has
// completed. In either case, auto-cycle start, if enabled, any queued moves.
protocol_auto_cycle_start();
protocol_execute_realtime(); // Runtime command check point.
if (sys.abort) {
return; // Bail to main() program loop to reset system.
return; // Bail to main() program loop to reset system.
}
// check to see if we should disable the stepper drivers ... esp32 work around for disable in main loop.
if (stepper_idle) {
@ -186,19 +185,18 @@ void protocol_main_loop() {
return; /* Never reached */
}
// Block until all buffered steps are executed or in a cycle state. Works with feed hold
// during a synchronize call, if it should happen. Also, waits for clean cycle end.
void protocol_buffer_synchronize() {
// If system is queued, ensure cycle resumes if the auto start flag is present.
protocol_auto_cycle_start();
do {
protocol_execute_realtime(); // Check and execute run-time commands
if (sys.abort) return; // Check for system abort
protocol_execute_realtime(); // Check and execute run-time commands
if (sys.abort)
return; // Check for system abort
} while (plan_get_current_block() || (sys.state == STATE_CYCLE));
}
// Auto-cycle start triggers when there is a motion ready to execute and if the main program is not
// actively parsing commands.
// NOTE: This function is called from the main loop, buffer sync, and mc_line() only and executes
@ -206,12 +204,11 @@ void protocol_buffer_synchronize() {
// is finished, single commands), a command that needs to wait for the motions in the buffer to
// execute calls a buffer sync, or the planner buffer is full and ready to go.
void protocol_auto_cycle_start() {
if (plan_get_current_block() != NULL) { // Check if there are any blocks in the buffer.
system_set_exec_state_flag(EXEC_CYCLE_START); // If so, execute them!
if (plan_get_current_block() != NULL) { // Check if there are any blocks in the buffer.
system_set_exec_state_flag(EXEC_CYCLE_START); // If so, execute them!
}
}
// This function is the general interface to Grbl's real-time command execution system. It is called
// from various check points in the main program, primarily where there may be a while loop waiting
// for a buffer to clear space or any point where the execution time from the last check point may
@ -225,26 +222,26 @@ void protocol_auto_cycle_start() {
// limit switches, or the main program.
void protocol_execute_realtime() {
protocol_exec_rt_system();
if (sys.suspend) protocol_exec_rt_suspend();
if (sys.suspend)
protocol_exec_rt_suspend();
}
// Executes run-time commands, when required. This function primarily operates as Grbl's state
// machine and controls the various real-time features Grbl has to offer.
// NOTE: Do not alter this unless you know exactly what you are doing!
void protocol_exec_rt_system() {
uint8_t rt_exec; // Temp variable to avoid calling volatile multiple times.
rt_exec = sys_rt_exec_alarm; // Copy volatile sys_rt_exec_alarm.
if (rt_exec) { // Enter only if any bit flag is true
uint8_t rt_exec; // Temp variable to avoid calling volatile multiple times.
rt_exec = sys_rt_exec_alarm; // Copy volatile sys_rt_exec_alarm.
if (rt_exec) { // Enter only if any bit flag is true
// System alarm. Everything has shutdown by something that has gone severely wrong. Report
// the source of the error to the user. If critical, Grbl disables by entering an infinite
// loop until system reset/abort.
sys.state = STATE_ALARM; // Set system alarm state
sys.state = STATE_ALARM; // Set system alarm state
report_alarm_message(rt_exec);
// Halt everything upon a critical event flag. Currently hard and soft limits flag this.
if ((rt_exec == EXEC_ALARM_HARD_LIMIT) || (rt_exec == EXEC_ALARM_SOFT_LIMIT)) {
report_feedback_message(MESSAGE_CRITICAL_EVENT);
system_clear_exec_state_flag(EXEC_RESET); // Disable any existing reset
system_clear_exec_state_flag(EXEC_RESET); // Disable any existing reset
do {
// Block everything, except reset and status reports, until user issues reset or power
// cycles. Hard limits typically occur while unattended or not paying attention. Gives
@ -253,14 +250,14 @@ void protocol_exec_rt_system() {
// lost, continued streaming could cause a serious crash if by chance it gets executed.
} while (bit_isfalse(sys_rt_exec_state, EXEC_RESET));
}
system_clear_exec_alarm(); // Clear alarm
system_clear_exec_alarm(); // Clear alarm
}
rt_exec = sys_rt_exec_state; // Copy volatile sys_rt_exec_state.
rt_exec = sys_rt_exec_state; // Copy volatile sys_rt_exec_state.
if (rt_exec) {
// Execute system abort.
if (rt_exec & EXEC_RESET) {
sys.abort = true; // Only place this is set true.
return; // Nothing else to do but exit.
return; // Nothing else to do but exit.
}
// Execute and serial print status
if (rt_exec & EXEC_STATUS_REPORT) {
@ -274,28 +271,32 @@ void protocol_exec_rt_system() {
if (!(sys.state & (STATE_ALARM | STATE_CHECK_MODE))) {
// If in CYCLE or JOG states, immediately initiate a motion HOLD.
if (sys.state & (STATE_CYCLE | STATE_JOG)) {
if (!(sys.suspend & (SUSPEND_MOTION_CANCEL | SUSPEND_JOG_CANCEL))) { // Block, if already holding.
st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
sys.step_control = STEP_CONTROL_EXECUTE_HOLD; // Initiate suspend state with active flag.
if (sys.state == STATE_JOG) { // Jog cancelled upon any hold event, except for sleeping.
if (!(rt_exec & EXEC_SLEEP)) sys.suspend |= SUSPEND_JOG_CANCEL;
if (!(sys.suspend & (SUSPEND_MOTION_CANCEL | SUSPEND_JOG_CANCEL))) { // Block, if already holding.
st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
sys.step_control = STEP_CONTROL_EXECUTE_HOLD; // Initiate suspend state with active flag.
if (sys.state == STATE_JOG) { // Jog cancelled upon any hold event, except for sleeping.
if (!(rt_exec & EXEC_SLEEP))
sys.suspend |= SUSPEND_JOG_CANCEL;
}
}
}
// If IDLE, Grbl is not in motion. Simply indicate suspend state and hold is complete.
if (sys.state == STATE_IDLE) sys.suspend = SUSPEND_HOLD_COMPLETE;
if (sys.state == STATE_IDLE)
sys.suspend = SUSPEND_HOLD_COMPLETE;
// Execute and flag a motion cancel with deceleration and return to idle. Used primarily by probing cycle
// to halt and cancel the remainder of the motion.
if (rt_exec & EXEC_MOTION_CANCEL) {
// MOTION_CANCEL only occurs during a CYCLE, but a HOLD and SAFETY_DOOR may been initiated beforehand
// to hold the CYCLE. Motion cancel is valid for a single planner block motion only, while jog cancel
// will handle and clear multiple planner block motions.
if (!(sys.state & STATE_JOG)) sys.suspend |= SUSPEND_MOTION_CANCEL; // NOTE: State is STATE_CYCLE.
if (!(sys.state & STATE_JOG))
sys.suspend |= SUSPEND_MOTION_CANCEL; // NOTE: State is STATE_CYCLE.
}
// Execute a feed hold with deceleration, if required. Then, suspend system.
if (rt_exec & EXEC_FEED_HOLD) {
// Block SAFETY_DOOR, JOG, and SLEEP states from changing to HOLD state.
if (!(sys.state & (STATE_SAFETY_DOOR | STATE_JOG | STATE_SLEEP))) sys.state = STATE_HOLD;
if (!(sys.state & (STATE_SAFETY_DOOR | STATE_JOG | STATE_SLEEP)))
sys.state = STATE_HOLD;
}
// Execute a safety door stop with a feed hold and disable spindle/coolant.
// NOTE: Safety door differs from feed holds by stopping everything no matter state, disables powered
@ -307,20 +308,21 @@ void protocol_exec_rt_system() {
// Check if the safety re-opened during a restore parking motion only. Ignore if
// already retracting, parked or in sleep state.
if (sys.state == STATE_SAFETY_DOOR) {
if (sys.suspend & SUSPEND_INITIATE_RESTORE) { // Actively restoring
if (sys.suspend & SUSPEND_INITIATE_RESTORE) { // Actively restoring
#ifdef PARKING_ENABLE
// Set hold and reset appropriate control flags to restart parking sequence.
if (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION) {
st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
sys.step_control = (STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_SYS_MOTION);
sys.suspend &= ~(SUSPEND_HOLD_COMPLETE);
} // else NO_MOTION is active.
} // else NO_MOTION is active.
#endif
sys.suspend &= ~(SUSPEND_RETRACT_COMPLETE | SUSPEND_INITIATE_RESTORE | SUSPEND_RESTORE_COMPLETE);
sys.suspend |= SUSPEND_RESTART_RETRACT;
}
}
if (sys.state != STATE_SLEEP) sys.state = STATE_SAFETY_DOOR;
if (sys.state != STATE_SLEEP)
sys.state = STATE_SAFETY_DOOR;
}
// NOTE: This flag doesn't change when the door closes, unlike sys.state. Ensures any parking motions
// are executed if the door switch closes and the state returns to HOLD.
@ -328,7 +330,8 @@ void protocol_exec_rt_system() {
}
}
if (rt_exec & EXEC_SLEEP) {
if (sys.state == STATE_ALARM) sys.suspend |= (SUSPEND_RETRACT_COMPLETE | SUSPEND_HOLD_COMPLETE);
if (sys.state == STATE_ALARM)
sys.suspend |= (SUSPEND_RETRACT_COMPLETE | SUSPEND_HOLD_COMPLETE);
sys.state = STATE_SLEEP;
}
system_clear_exec_state_flag((EXEC_MOTION_CANCEL | EXEC_FEED_HOLD | EXEC_SAFETY_DOOR | EXEC_SLEEP));
@ -341,7 +344,7 @@ void protocol_exec_rt_system() {
// Resume door state when parking motion has retracted and door has been closed.
if ((sys.state == STATE_SAFETY_DOOR) && !(sys.suspend & SUSPEND_SAFETY_DOOR_AJAR)) {
if (sys.suspend & SUSPEND_RESTORE_COMPLETE) {
sys.state = STATE_IDLE; // Set to IDLE to immediately resume the cycle.
sys.state = STATE_IDLE; // Set to IDLE to immediately resume the cycle.
} else if (sys.suspend & SUSPEND_RETRACT_COMPLETE) {
// Flag to re-energize powered components and restore original position, if disabled by SAFETY_DOOR.
// NOTE: For a safety door to resume, the switch must be closed, as indicated by HOLD state, and
@ -354,18 +357,18 @@ void protocol_exec_rt_system() {
// Cycle start only when IDLE or when a hold is complete and ready to resume.
if ((sys.state == STATE_IDLE) || ((sys.state & STATE_HOLD) && (sys.suspend & SUSPEND_HOLD_COMPLETE))) {
if (sys.state == STATE_HOLD && sys.spindle_stop_ovr) {
sys.spindle_stop_ovr |= SPINDLE_STOP_OVR_RESTORE_CYCLE; // Set to restore in suspend routine and cycle start after.
sys.spindle_stop_ovr |= SPINDLE_STOP_OVR_RESTORE_CYCLE; // Set to restore in suspend routine and cycle start after.
} else {
// Start cycle only if queued motions exist in planner buffer and the motion is not canceled.
sys.step_control = STEP_CONTROL_NORMAL_OP; // Restore step control to normal operation
sys.step_control = STEP_CONTROL_NORMAL_OP; // Restore step control to normal operation
if (plan_get_current_block() && bit_isfalse(sys.suspend, SUSPEND_MOTION_CANCEL)) {
sys.suspend = SUSPEND_DISABLE; // Break suspend state.
sys.state = STATE_CYCLE;
st_prep_buffer(); // Initialize step segment buffer before beginning cycle.
sys.suspend = SUSPEND_DISABLE; // Break suspend state.
sys.state = STATE_CYCLE;
st_prep_buffer(); // Initialize step segment buffer before beginning cycle.
st_wake_up();
} else { // Otherwise, do nothing. Set and resume IDLE state.
sys.suspend = SUSPEND_DISABLE; // Break suspend state.
sys.state = STATE_IDLE;
} else { // Otherwise, do nothing. Set and resume IDLE state.
sys.suspend = SUSPEND_DISABLE; // Break suspend state.
sys.state = STATE_IDLE;
}
}
}
@ -382,70 +385,84 @@ void protocol_exec_rt_system() {
// Hold complete. Set to indicate ready to resume. Remain in HOLD or DOOR states until user
// has issued a resume command or reset.
plan_cycle_reinitialize();
if (sys.step_control & STEP_CONTROL_EXECUTE_HOLD) sys.suspend |= SUSPEND_HOLD_COMPLETE;
if (sys.step_control & STEP_CONTROL_EXECUTE_HOLD)
sys.suspend |= SUSPEND_HOLD_COMPLETE;
bit_false(sys.step_control, (STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_SYS_MOTION));
} else {
// Motion complete. Includes CYCLE/JOG/HOMING states and jog cancel/motion cancel/soft limit events.
// NOTE: Motion and jog cancel both immediately return to idle after the hold completes.
if (sys.suspend & SUSPEND_JOG_CANCEL) { // For jog cancel, flush buffers and sync positions.
if (sys.suspend & SUSPEND_JOG_CANCEL) { // For jog cancel, flush buffers and sync positions.
sys.step_control = STEP_CONTROL_NORMAL_OP;
plan_reset();
st_reset();
gc_sync_position();
plan_sync_position();
}
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) { // Only occurs when safety door opens during jog.
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) { // Only occurs when safety door opens during jog.
sys.suspend &= ~(SUSPEND_JOG_CANCEL);
sys.suspend |= SUSPEND_HOLD_COMPLETE;
sys.state = STATE_SAFETY_DOOR;
} else {
sys.suspend = SUSPEND_DISABLE;
sys.state = STATE_IDLE;
sys.state = STATE_IDLE;
}
}
system_clear_exec_state_flag(EXEC_CYCLE_STOP);
}
}
// Execute overrides.
rt_exec = sys_rt_exec_motion_override; // Copy volatile sys_rt_exec_motion_override
rt_exec = sys_rt_exec_motion_override; // Copy volatile sys_rt_exec_motion_override
if (rt_exec) {
system_clear_exec_motion_overrides(); // Clear all motion override flags.
uint8_t new_f_override = sys.f_override;
if (rt_exec & EXEC_FEED_OVR_RESET) new_f_override = DEFAULT_FEED_OVERRIDE;
if (rt_exec & EXEC_FEED_OVR_COARSE_PLUS) new_f_override += FEED_OVERRIDE_COARSE_INCREMENT;
if (rt_exec & EXEC_FEED_OVR_COARSE_MINUS) new_f_override -= FEED_OVERRIDE_COARSE_INCREMENT;
if (rt_exec & EXEC_FEED_OVR_FINE_PLUS) new_f_override += FEED_OVERRIDE_FINE_INCREMENT;
if (rt_exec & EXEC_FEED_OVR_FINE_MINUS) new_f_override -= FEED_OVERRIDE_FINE_INCREMENT;
new_f_override = MIN(new_f_override, MAX_FEED_RATE_OVERRIDE);
new_f_override = MAX(new_f_override, MIN_FEED_RATE_OVERRIDE);
system_clear_exec_motion_overrides(); // Clear all motion override flags.
uint8_t new_f_override = sys.f_override;
if (rt_exec & EXEC_FEED_OVR_RESET)
new_f_override = DEFAULT_FEED_OVERRIDE;
if (rt_exec & EXEC_FEED_OVR_COARSE_PLUS)
new_f_override += FEED_OVERRIDE_COARSE_INCREMENT;
if (rt_exec & EXEC_FEED_OVR_COARSE_MINUS)
new_f_override -= FEED_OVERRIDE_COARSE_INCREMENT;
if (rt_exec & EXEC_FEED_OVR_FINE_PLUS)
new_f_override += FEED_OVERRIDE_FINE_INCREMENT;
if (rt_exec & EXEC_FEED_OVR_FINE_MINUS)
new_f_override -= FEED_OVERRIDE_FINE_INCREMENT;
new_f_override = MIN(new_f_override, MAX_FEED_RATE_OVERRIDE);
new_f_override = MAX(new_f_override, MIN_FEED_RATE_OVERRIDE);
uint8_t new_r_override = sys.r_override;
if (rt_exec & EXEC_RAPID_OVR_RESET) new_r_override = DEFAULT_RAPID_OVERRIDE;
if (rt_exec & EXEC_RAPID_OVR_MEDIUM) new_r_override = RAPID_OVERRIDE_MEDIUM;
if (rt_exec & EXEC_RAPID_OVR_LOW) new_r_override = RAPID_OVERRIDE_LOW;
if (rt_exec & EXEC_RAPID_OVR_RESET)
new_r_override = DEFAULT_RAPID_OVERRIDE;
if (rt_exec & EXEC_RAPID_OVR_MEDIUM)
new_r_override = RAPID_OVERRIDE_MEDIUM;
if (rt_exec & EXEC_RAPID_OVR_LOW)
new_r_override = RAPID_OVERRIDE_LOW;
if ((new_f_override != sys.f_override) || (new_r_override != sys.r_override)) {
sys.f_override = new_f_override;
sys.r_override = new_r_override;
sys.report_ovr_counter = 0; // Set to report change immediately
sys.f_override = new_f_override;
sys.r_override = new_r_override;
sys.report_ovr_counter = 0; // Set to report change immediately
plan_update_velocity_profile_parameters();
plan_cycle_reinitialize();
}
}
rt_exec = sys_rt_exec_accessory_override;
if (rt_exec) {
system_clear_exec_accessory_overrides(); // Clear all accessory override flags.
system_clear_exec_accessory_overrides(); // Clear all accessory override flags.
// NOTE: Unlike motion overrides, spindle overrides do not require a planner reinitialization.
uint8_t last_s_override = sys.spindle_speed_ovr;
if (rt_exec & EXEC_SPINDLE_OVR_RESET) last_s_override = DEFAULT_SPINDLE_SPEED_OVERRIDE;
if (rt_exec & EXEC_SPINDLE_OVR_COARSE_PLUS) last_s_override += SPINDLE_OVERRIDE_COARSE_INCREMENT;
if (rt_exec & EXEC_SPINDLE_OVR_COARSE_MINUS) last_s_override -= SPINDLE_OVERRIDE_COARSE_INCREMENT;
if (rt_exec & EXEC_SPINDLE_OVR_FINE_PLUS) last_s_override += SPINDLE_OVERRIDE_FINE_INCREMENT;
if (rt_exec & EXEC_SPINDLE_OVR_FINE_MINUS) last_s_override -= SPINDLE_OVERRIDE_FINE_INCREMENT;
uint8_t last_s_override = sys.spindle_speed_ovr;
if (rt_exec & EXEC_SPINDLE_OVR_RESET)
last_s_override = DEFAULT_SPINDLE_SPEED_OVERRIDE;
if (rt_exec & EXEC_SPINDLE_OVR_COARSE_PLUS)
last_s_override += SPINDLE_OVERRIDE_COARSE_INCREMENT;
if (rt_exec & EXEC_SPINDLE_OVR_COARSE_MINUS)
last_s_override -= SPINDLE_OVERRIDE_COARSE_INCREMENT;
if (rt_exec & EXEC_SPINDLE_OVR_FINE_PLUS)
last_s_override += SPINDLE_OVERRIDE_FINE_INCREMENT;
if (rt_exec & EXEC_SPINDLE_OVR_FINE_MINUS)
last_s_override -= SPINDLE_OVERRIDE_FINE_INCREMENT;
last_s_override = MIN(last_s_override, MAX_SPINDLE_SPEED_OVERRIDE);
last_s_override = MAX(last_s_override, MIN_SPINDLE_SPEED_OVERRIDE);
if (last_s_override != sys.spindle_speed_ovr) {
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
sys.spindle_speed_ovr = last_s_override;
sys.report_ovr_counter = 0; // Set to report change immediately
sys.spindle_speed_ovr = last_s_override;
sys.report_ovr_counter = 0; // Set to report change immediately
// If spinlde is on, tell it the rpm has been overridden
if (gc_state.modal.spindle != SPINDLE_DISABLE)
spindle->set_rpm(gc_state.spindle_speed);
@ -454,8 +471,10 @@ void protocol_exec_rt_system() {
// Spindle stop override allowed only while in HOLD state.
// NOTE: Report counters are set in spindle_set_state() when spindle stop is executed.
if (sys.state == STATE_HOLD) {
if (!(sys.spindle_stop_ovr)) sys.spindle_stop_ovr = SPINDLE_STOP_OVR_INITIATE;
else if (sys.spindle_stop_ovr & SPINDLE_STOP_OVR_ENABLED) sys.spindle_stop_ovr |= SPINDLE_STOP_OVR_RESTORE;
if (!(sys.spindle_stop_ovr))
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_INITIATE;
else if (sys.spindle_stop_ovr & SPINDLE_STOP_OVR_ENABLED)
sys.spindle_stop_ovr |= SPINDLE_STOP_OVR_RESTORE;
}
}
// NOTE: Since coolant state always performs a planner sync whenever it changes, the current
@ -479,7 +498,7 @@ void protocol_exec_rt_system() {
coolant_state |= COOLANT_MIST_ENABLE;
}
#endif
coolant_set_state(coolant_state); // Report counter set in coolant_set_state().
coolant_set_state(coolant_state); // Report counter set in coolant_set_state().
gc_state.modal.coolant = coolant_state;
}
}
@ -495,7 +514,6 @@ void protocol_exec_rt_system() {
st_prep_buffer();
}
// Handles Grbl system suspend procedures, such as feed hold, safety door, and parking motion.
// The system will enter this loop, create local variables for suspend tasks, and return to
// whatever function that invoked the suspend, such that Grbl resumes normal operation.
@ -504,25 +522,25 @@ void protocol_exec_rt_system() {
static void protocol_exec_rt_suspend() {
#ifdef PARKING_ENABLE
// Declare and initialize parking local variables
float restore_target[N_AXIS];
float parking_target[N_AXIS];
float retract_waypoint = PARKING_PULLOUT_INCREMENT;
plan_line_data_t plan_data;
float restore_target[N_AXIS];
float parking_target[N_AXIS];
float retract_waypoint = PARKING_PULLOUT_INCREMENT;
plan_line_data_t plan_data;
plan_line_data_t* pl_data = &plan_data;
memset(pl_data, 0, sizeof(plan_line_data_t));
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION | PL_COND_FLAG_NO_FEED_OVERRIDE);
#ifdef USE_LINE_NUMBERS
# ifdef USE_LINE_NUMBERS
pl_data->line_number = PARKING_MOTION_LINE_NUMBER;
#endif
# endif
#endif
plan_block_t* block = plan_get_current_block();
uint8_t restore_condition;
float restore_spindle_speed;
uint8_t restore_condition;
float restore_spindle_speed;
if (block == NULL) {
restore_condition = (gc_state.modal.spindle | gc_state.modal.coolant);
restore_condition = (gc_state.modal.spindle | gc_state.modal.coolant);
restore_spindle_speed = gc_state.spindle_speed;
} else {
restore_condition = block->condition;
restore_condition = block->condition;
restore_spindle_speed = block->spindle_speed;
}
#ifdef DISABLE_LASER_DURING_HOLD
@ -531,7 +549,8 @@ static void protocol_exec_rt_suspend() {
#endif
while (sys.suspend) {
if (sys.abort) return;
if (sys.abort)
return;
// Block until initial hold is complete and the machine has stopped motion.
if (sys.suspend & SUSPEND_HOLD_COMPLETE) {
// Parking manager. Handles de/re-energizing, switch state checks, and parking motions for
@ -542,8 +561,8 @@ static void protocol_exec_rt_suspend() {
// Ensure any prior spindle stop override is disabled at start of safety door routine.
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED;
#ifndef PARKING_ENABLE
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
#else
// Get current position and store restore location and spindle retract waypoint.
system_convert_array_steps_to_mpos(parking_target, sys_position);
@ -555,41 +574,37 @@ static void protocol_exec_rt_suspend() {
// Execute slow pull-out parking retract motion. Parking requires homing enabled, the
// current location not exceeding the parking target location, and laser mode disabled.
// NOTE: State is will remain DOOR, until the de-energizing and retract is complete.
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
if (homing_enable->get() &&
(parking_target[PARKING_AXIS] < PARKING_TARGET) &&
!laser_mode->get() &&
(sys.override_ctrl == OVERRIDE_PARKING_MOTION)) {
#else
if (homing_enable->get() &&
(parking_target[PARKING_AXIS] < PARKING_TARGET) &&
!laser_mode->get()) {
#endif
# ifdef ENABLE_PARKING_OVERRIDE_CONTROL
if (homing_enable->get() && (parking_target[PARKING_AXIS] < PARKING_TARGET) && !laser_mode->get() &&
(sys.override_ctrl == OVERRIDE_PARKING_MOTION)) {
# else
if (homing_enable->get() && (parking_target[PARKING_AXIS] < PARKING_TARGET) && !laser_mode->get()) {
# endif
// Retract spindle by pullout distance. Ensure retraction motion moves away from
// the workpiece and waypoint motion doesn't exceed the parking target location.
if (parking_target[PARKING_AXIS] < retract_waypoint) {
parking_target[PARKING_AXIS] = retract_waypoint;
pl_data->feed_rate = PARKING_PULLOUT_RATE;
pl_data->condition |= (restore_condition & PL_COND_ACCESSORY_MASK); // Retain accessory state
pl_data->feed_rate = PARKING_PULLOUT_RATE;
pl_data->condition |= (restore_condition & PL_COND_ACCESSORY_MASK); // Retain accessory state
pl_data->spindle_speed = restore_spindle_speed;
mc_parking_motion(parking_target, pl_data);
}
// NOTE: Clear accessory state after retract and after an aborted restore motion.
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION | PL_COND_FLAG_NO_FEED_OVERRIDE);
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION | PL_COND_FLAG_NO_FEED_OVERRIDE);
pl_data->spindle_speed = 0.0;
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
// Execute fast parking retract motion to parking target location.
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
// Execute fast parking retract motion to parking target location.
if (parking_target[PARKING_AXIS] < PARKING_TARGET) {
parking_target[PARKING_AXIS] = PARKING_TARGET;
pl_data->feed_rate = PARKING_RATE;
parking_target[PARKING_AXIS] = PARKING_TARGET;
pl_data->feed_rate = PARKING_RATE;
mc_parking_motion(parking_target, pl_data);
}
} else {
// Parking motion not possible. Just disable the spindle and coolant.
// NOTE: Laser mode does not start a parking motion to ensure the laser stops immediately.
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
}
#endif
sys.suspend &= ~(SUSPEND_RESTART_RETRACT);
@ -598,16 +613,17 @@ static void protocol_exec_rt_suspend() {
if (sys.state == STATE_SLEEP) {
report_feedback_message(MESSAGE_SLEEP_MODE);
// Spindle and coolant should already be stopped, but do it again just to be sure.
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
st_go_idle(); // Disable steppers
while (!(sys.abort)) protocol_exec_rt_system(); // Do nothing until reset.
return; // Abort received. Return to re-initialize.
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
coolant_set_state(COOLANT_DISABLE); // De-energize
st_go_idle(); // Disable steppers
while (!(sys.abort))
protocol_exec_rt_system(); // Do nothing until reset.
return; // Abort received. Return to re-initialize.
}
// Allows resuming from parking/safety door. Actively checks if safety door is closed and ready to resume.
if (sys.state == STATE_SAFETY_DOOR) {
if (!(system_check_safety_door_ajar())) {
sys.suspend &= ~(SUSPEND_SAFETY_DOOR_AJAR); // Reset door ajar flag to denote ready to resume.
sys.suspend &= ~(SUSPEND_SAFETY_DOOR_AJAR); // Reset door ajar flag to denote ready to resume.
}
}
// Handles parking restore and safety door resume.
@ -615,36 +631,37 @@ static void protocol_exec_rt_suspend() {
#ifdef PARKING_ENABLE
// Execute fast restore motion to the pull-out position. Parking requires homing enabled.
// NOTE: State is will remain DOOR, until the de-energizing and retract is complete.
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
# ifdef ENABLE_PARKING_OVERRIDE_CONTROL
if (homing_enable->get() && !laser_mode->get()) &&
(sys.override_ctrl == OVERRIDE_PARKING_MOTION)) {
#else
# else
if (homing_enable->get() && !laser_mode->get()) {
#endif
// Check to ensure the motion doesn't move below pull-out position.
if (parking_target[PARKING_AXIS] <= PARKING_TARGET) {
parking_target[PARKING_AXIS] = retract_waypoint;
pl_data->feed_rate = PARKING_RATE;
mc_parking_motion(parking_target, pl_data);
# endif
// Check to ensure the motion doesn't move below pull-out position.
if (parking_target[PARKING_AXIS] <= PARKING_TARGET) {
parking_target[PARKING_AXIS] = retract_waypoint;
pl_data->feed_rate = PARKING_RATE;
mc_parking_motion(parking_target, pl_data);
}
}
}
#endif
// Delayed Tasks: Restart spindle and coolant, delay to power-up, then resume cycle.
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
// Block if safety door re-opened during prior restore actions.
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
// Block if safety door re-opened during prior restore actions.
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
if (laser_mode->get()) {
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
} else {
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), (uint32_t)restore_spindle_speed);
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)),
(uint32_t)restore_spindle_speed);
delay_sec(SAFETY_DOOR_SPINDLE_DELAY, DELAY_MODE_SYS_SUSPEND);
}
}
}
if (gc_state.modal.coolant != COOLANT_DISABLE) {
// Block if safety door re-opened during prior restore actions.
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
// Block if safety door re-opened during prior restore actions.
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
// NOTE: Laser mode will honor this delay. An exhaust system is often controlled by this pin.
coolant_set_state((restore_condition & (PL_COND_FLAG_COOLANT_FLOOD | PL_COND_FLAG_COOLANT_FLOOD)));
delay_sec(SAFETY_DOOR_COOLANT_DELAY, DELAY_MODE_SYS_SUSPEND);
@ -652,27 +669,27 @@ static void protocol_exec_rt_suspend() {
}
#ifdef PARKING_ENABLE
// Execute slow plunge motion from pull-out position to resume position.
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
# ifdef ENABLE_PARKING_OVERRIDE_CONTROL
if (homing_enable->get() && !laser_mode->get()) &&
(sys.override_ctrl == OVERRIDE_PARKING_MOTION)) {
#else
# else
if (homing_enable->get() && !laser_mode->get()) {
#endif
// Block if safety door re-opened during prior restore actions.
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
// Regardless if the retract parking motion was a valid/safe motion or not, the
// restore parking motion should logically be valid, either by returning to the
// original position through valid machine space or by not moving at all.
pl_data->feed_rate = PARKING_PULLOUT_RATE;
pl_data->condition |= (restore_condition & PL_COND_ACCESSORY_MASK); // Restore accessory state
pl_data->spindle_speed = restore_spindle_speed;
mc_parking_motion(restore_target, pl_data);
# endif
// Block if safety door re-opened during prior restore actions.
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
// Regardless if the retract parking motion was a valid/safe motion or not, the
// restore parking motion should logically be valid, either by returning to the
// original position through valid machine space or by not moving at all.
pl_data->feed_rate = PARKING_PULLOUT_RATE;
pl_data->condition |= (restore_condition & PL_COND_ACCESSORY_MASK); // Restore accessory state
pl_data->spindle_speed = restore_spindle_speed;
mc_parking_motion(restore_target, pl_data);
}
}
}
#endif
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
sys.suspend |= SUSPEND_RESTORE_COMPLETE;
system_set_exec_state_flag(EXEC_CYCLE_START); // Set to resume program.
sys.suspend |= SUSPEND_RESTORE_COMPLETE;
system_set_exec_state_flag(EXEC_CYCLE_START); // Set to resume program.
}
}
}
@ -683,10 +700,10 @@ static void protocol_exec_rt_suspend() {
// Handles beginning of spindle stop
if (sys.spindle_stop_ovr & SPINDLE_STOP_OVR_INITIATE) {
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_ENABLED; // Set stop override state to enabled, if de-energized.
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_ENABLED; // Set stop override state to enabled, if de-energized.
} else {
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED; // Clear stop override state
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED; // Clear stop override state
}
// Handles restoring of spindle state
} else if (sys.spindle_stop_ovr & (SPINDLE_STOP_OVR_RESTORE | SPINDLE_STOP_OVR_RESTORE_CYCLE)) {
@ -696,18 +713,20 @@ static void protocol_exec_rt_suspend() {
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
} else
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), (uint32_t)restore_spindle_speed);
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)),
(uint32_t)restore_spindle_speed);
}
if (sys.spindle_stop_ovr & SPINDLE_STOP_OVR_RESTORE_CYCLE) {
system_set_exec_state_flag(EXEC_CYCLE_START); // Set to resume program.
}
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED; // Clear stop override state
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED; // Clear stop override state
}
} else {
// Handles spindle state during hold. NOTE: Spindle speed overrides may be altered during hold state.
// NOTE: STEP_CONTROL_UPDATE_SPINDLE_RPM is automatically reset upon resume in step generator.
if (bit_istrue(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM)) {
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), (uint32_t)restore_spindle_speed);
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)),
(uint32_t)restore_spindle_speed);
bit_false(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
}
}
@ -716,4 +735,3 @@ static void protocol_exec_rt_suspend() {
protocol_exec_rt_system();
}
}

View File

@ -31,7 +31,7 @@
// memory space we can invest into here or we re-write the g-code parser not to have this
// buffer.
#ifndef LINE_BUFFER_SIZE
#define LINE_BUFFER_SIZE 80
# define LINE_BUFFER_SIZE 80
#endif
// Starts Grbl main loop. It handles all incoming characters from the serial port and executes

View File

@ -54,18 +54,19 @@ EspClass esp;
// 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;
if (client == CLIENT_INPUT)
return;
#ifdef ENABLE_BLUETOOTH
if (SerialBT.hasClient() && (client == CLIENT_BT || client == CLIENT_ALL)) {
SerialBT.print(text);
//delay(10); // possible fix for dropped characters
}
#endif
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_OUT)
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_OUT)
if (client == CLIENT_WEBUI || client == CLIENT_ALL)
Serial2Socket.write((const uint8_t*)text, strlen(text));
#endif
#if defined (ENABLE_WIFI) && defined(ENABLE_TELNET)
#if defined(ENABLE_WIFI) && defined(ENABLE_TELNET)
if (client == CLIENT_TELNET || client == CLIENT_ALL)
telnet_server.write((const uint8_t*)text, strlen(text));
#endif
@ -75,9 +76,10 @@ void grbl_send(uint8_t client, const char* text) {
// This is a formating version of the grbl_send(CLIENT_ALL,...) function that work like printf
void grbl_sendf(uint8_t client, const char* format, ...) {
if (client == CLIENT_INPUT) return;
char loc_buf[64];
char* temp = loc_buf;
if (client == CLIENT_INPUT)
return;
char loc_buf[64];
char* temp = loc_buf;
va_list arg;
va_list copy;
va_start(arg, format);
@ -97,10 +99,12 @@ void grbl_sendf(uint8_t client, const char* format, ...) {
}
// Use to send [MSG:xxxx] Type messages. The level allows messages to be easily suppressed
void grbl_msg_sendf(uint8_t client, uint8_t level, const char* format, ...) {
if (client == CLIENT_INPUT) return;
if (level > GRBL_MSG_LEVEL) return;
char loc_buf[100];
char* temp = loc_buf;
if (client == CLIENT_INPUT)
return;
if (level > GRBL_MSG_LEVEL)
return;
char loc_buf[100];
char* temp = loc_buf;
va_list arg;
va_list copy;
va_start(arg, format);
@ -127,8 +131,8 @@ void grbl_notify(const char* title, const char* msg) {
}
void grbl_notifyf(const char* title, const char* format, ...) {
char loc_buf[64];
char* temp = loc_buf;
char loc_buf[64];
char* temp = loc_buf;
va_list arg;
va_list copy;
va_start(arg, format);
@ -150,9 +154,9 @@ void grbl_notifyf(const char* title, const char* format, ...) {
// formats axis values into a string and returns that string in rpt
static void report_util_axis_values(float* axis_value, char* rpt) {
uint8_t idx;
char axisVal[20];
float unit_conv = 1.0; // unit conversion multiplier..default is mm
rpt[0] = '\0';
char axisVal[20];
float unit_conv = 1.0; // unit conversion multiplier..default is mm
rpt[0] = '\0';
if (report_inches->get())
unit_conv = 1.0 / MM_PER_INCH;
for (idx = 0; idx < N_AXIS; idx++) {
@ -169,19 +173,20 @@ static void report_util_axis_values(float* axis_value, char* rpt) {
void get_state(char* foo) {
// pad them to same length
switch (sys.state) {
case STATE_IDLE: strcpy(foo, " Idle ");; break;
case STATE_CYCLE: strcpy(foo, " Run "); break;
case STATE_HOLD: strcpy(foo, " Hold "); break;
case STATE_HOMING: strcpy(foo, " Home "); break;
case STATE_ALARM: strcpy(foo, " Alarm"); break;
case STATE_CHECK_MODE: strcpy(foo, " Check"); break;
case STATE_SAFETY_DOOR: strcpy(foo, " Door "); break;
default: strcpy(foo, " ? "); break;
case STATE_IDLE:
strcpy(foo, " Idle ");
;
break;
case STATE_CYCLE: strcpy(foo, " Run "); break;
case STATE_HOLD: strcpy(foo, " Hold "); break;
case STATE_HOMING: strcpy(foo, " Home "); break;
case STATE_ALARM: strcpy(foo, " Alarm"); break;
case STATE_CHECK_MODE: strcpy(foo, " Check"); break;
case STATE_SAFETY_DOOR: strcpy(foo, " Door "); break;
default: strcpy(foo, " ? "); break;
}
}
// Handles the primary confirmation protocol response for streaming interfaces and human-feedback.
// For every incoming line, this method responds with an 'ok' for a successful command or an
// 'error:' to indicate some error event with the line or some critical system error during
@ -190,42 +195,40 @@ void get_state(char* foo) {
// responses.
void report_status_message(uint8_t status_code, uint8_t client) {
switch (status_code) {
case STATUS_OK: // STATUS_OK
case STATUS_OK: // STATUS_OK
#ifdef ENABLE_SD_CARD
if (get_sd_state(false) == SDCARD_BUSY_PRINTING)
SD_ready_next = true; // flag so system_execute_line() will send the next line
else
grbl_send(client, "ok\r\n");
if (get_sd_state(false) == SDCARD_BUSY_PRINTING)
SD_ready_next = true; // flag so system_execute_line() will send the next line
else
grbl_send(client, "ok\r\n");
#else
grbl_send(client, "ok\r\n");
grbl_send(client, "ok\r\n");
#endif
break;
default:
break;
default:
#ifdef ENABLE_SD_CARD
// do we need to stop a running SD job?
if (get_sd_state(false) == SDCARD_BUSY_PRINTING) {
if (status_code == STATUS_GCODE_UNSUPPORTED_COMMAND) {
grbl_sendf(client, "error:%d\r\n", status_code); // most senders seem to tolerate this error and keep on going
grbl_sendf(CLIENT_ALL, "error:%d in SD file at line %d\r\n", status_code, sd_get_current_line_number());
// don't close file
} else {
grbl_notifyf("SD print error", "Error:%d during SD file at line: %d", status_code, sd_get_current_line_number());
grbl_sendf(CLIENT_ALL, "error:%d in SD file at line %d\r\n", status_code, sd_get_current_line_number());
closeFile();
// do we need to stop a running SD job?
if (get_sd_state(false) == SDCARD_BUSY_PRINTING) {
if (status_code == STATUS_GCODE_UNSUPPORTED_COMMAND) {
grbl_sendf(client, "error:%d\r\n", status_code); // most senders seem to tolerate this error and keep on going
grbl_sendf(CLIENT_ALL, "error:%d in SD file at line %d\r\n", status_code, sd_get_current_line_number());
// don't close file
} else {
grbl_notifyf("SD print error", "Error:%d during SD file at line: %d", status_code, sd_get_current_line_number());
grbl_sendf(CLIENT_ALL, "error:%d in SD file at line %d\r\n", status_code, sd_get_current_line_number());
closeFile();
}
return;
}
return;
}
#endif
grbl_sendf(client, "error:%d\r\n", status_code);
grbl_sendf(client, "error:%d\r\n", status_code);
}
}
// Prints alarm messages.
void report_alarm_message(uint8_t alarm_code) {
grbl_sendf(CLIENT_ALL, "ALARM:%d\r\n", alarm_code); // OK to send to all clients
delay_ms(500); // Force delay to ensure message clears serial write buffer.
grbl_sendf(CLIENT_ALL, "ALARM:%d\r\n", alarm_code); // OK to send to all clients
delay_ms(500); // Force delay to ensure message clears serial write buffer.
}
// Prints feedback messages. This serves as a centralized method to provide additional
@ -233,40 +236,31 @@ void report_alarm_message(uint8_t alarm_code) {
// messages such as setup warnings, switch toggling, and how to exit alarms.
// 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(uint8_t message_code) { // OK to send to all clients
void report_feedback_message(uint8_t message_code) { // OK to send to all clients
switch (message_code) {
case MESSAGE_CRITICAL_EVENT:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Reset to continue"); break;
case MESSAGE_ALARM_LOCK:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "'$H'|'$X' to unlock"); break;
case MESSAGE_ALARM_UNLOCK:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Caution: Unlocked"); break;
case MESSAGE_ENABLED:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Enabled"); break;
case MESSAGE_DISABLED:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Disabled"); break;
case MESSAGE_SAFETY_DOOR_AJAR:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Check door"); break;
case MESSAGE_CHECK_LIMITS:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Check limits"); break;
case MESSAGE_PROGRAM_END:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Program End"); break;
case MESSAGE_RESTORE_DEFAULTS:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Restoring defaults"); break;
case MESSAGE_SPINDLE_RESTORE:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Restoring spindle");; break;
case MESSAGE_SLEEP_MODE:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Sleeping"); break;
case MESSAGE_CRITICAL_EVENT: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Reset to continue"); break;
case MESSAGE_ALARM_LOCK: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "'$H'|'$X' to unlock"); break;
case MESSAGE_ALARM_UNLOCK: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Caution: Unlocked"); break;
case MESSAGE_ENABLED: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Enabled"); break;
case MESSAGE_DISABLED: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Disabled"); break;
case MESSAGE_SAFETY_DOOR_AJAR: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Check door"); break;
case MESSAGE_CHECK_LIMITS: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Check limits"); break;
case MESSAGE_PROGRAM_END: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Program End"); break;
case MESSAGE_RESTORE_DEFAULTS: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Restoring defaults"); break;
case MESSAGE_SPINDLE_RESTORE:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Restoring spindle");
;
break;
case MESSAGE_SLEEP_MODE: grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Sleeping"); break;
#ifdef ENABLE_SD_CARD
case MESSAGE_SD_FILE_QUIT:
grbl_notifyf("SD print canceled", "Reset during SD file at line: %d", sd_get_current_line_number());
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Reset during SD file at line: %d", sd_get_current_line_number());
break;
case MESSAGE_SD_FILE_QUIT:
grbl_notifyf("SD print canceled", "Reset during SD file at line: %d", sd_get_current_line_number());
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Reset during SD file at line: %d", sd_get_current_line_number());
break;
#endif
}
}
// Welcome message
void report_init_message(uint8_t client) {
grbl_send(client, "\r\nGrbl " GRBL_VERSION " ['$' for help]\r\n");
@ -277,17 +271,15 @@ void report_grbl_help(uint8_t client) {
grbl_send(client, "[HLP:$$ $+ $# $S $L $G $I $N $x=val $Nx=line $J=line $SLP $C $X $H $F $E=err ~ ! ? ctrl-x]\r\n");
}
// Prints current probe parameters. Upon a probe command, these parameters are updated upon a
// successful probe or upon a failed probe with the G38.3 without errors command (if supported).
// These values are retained until Grbl is power-cycled, whereby they will be re-zeroed.
void report_probe_parameters(uint8_t client) {
// Report in terms of machine position.
float print_position[N_AXIS];
char probe_rpt[100]; // the probe report we are building here
char temp[60];
strcpy(probe_rpt, "[PRB:"); // initialize the string with the first characters
char probe_rpt[100]; // the probe report we are building here
char temp[60];
strcpy(probe_rpt, "[PRB:"); // initialize the string with the first characters
// get the machine position and put them into a string and append to the probe report
system_convert_array_steps_to_mpos(print_position, sys_probe_position);
report_util_axis_values(print_position, temp);
@ -295,18 +287,15 @@ void report_probe_parameters(uint8_t client) {
// add the success indicator and add closing characters
sprintf(temp, ":%d]\r\n", sys.probe_succeeded);
strcat(probe_rpt, temp);
grbl_send(client, probe_rpt); // send the report
grbl_send(client, probe_rpt); // send the report
}
// Prints Grbl NGC parameters (coordinate offsets, probing)
void report_ngc_parameters(uint8_t client) {
float coord_data[N_AXIS];
float coord_data[N_AXIS];
uint8_t coord_select;
char temp[60];
char ngc_rpt[500];
char temp[60];
char ngc_rpt[500];
ngc_rpt[0] = '\0';
for (coord_select = 0; coord_select <= SETTING_INDEX_NCOORD; coord_select++) {
if (!(settings_read_coord_data(coord_select, coord_data))) {
@ -315,23 +304,23 @@ void report_ngc_parameters(uint8_t client) {
}
strcat(ngc_rpt, "[G");
switch (coord_select) {
case 6: strcat(ngc_rpt, "28"); break;
case 7: strcat(ngc_rpt, "30"); break;
default:
sprintf(temp, "%d", coord_select + 54);
strcat(ngc_rpt, temp);
break; // G54-G59
case 6: strcat(ngc_rpt, "28"); break;
case 7: strcat(ngc_rpt, "30"); break;
default:
sprintf(temp, "%d", coord_select + 54);
strcat(ngc_rpt, temp);
break; // G54-G59
}
strcat(ngc_rpt, ":");
report_util_axis_values(coord_data, temp);
strcat(ngc_rpt, temp);
strcat(ngc_rpt, "]\r\n");
}
strcat(ngc_rpt, "[G92:"); // Print G92,G92.1 which are not persistent in memory
strcat(ngc_rpt, "[G92:"); // Print G92,G92.1 which are not persistent in memory
report_util_axis_values(gc_state.coord_offset, temp);
strcat(ngc_rpt, temp);
strcat(ngc_rpt, "]\r\n");
strcat(ngc_rpt, "[TLO:"); // Print tool length offset value
strcat(ngc_rpt, "[TLO:"); // Print tool length offset value
if (report_inches->get())
sprintf(temp, "%4.3f]\r\n", gc_state.tool_length_offset * INCH_PER_MM);
else
@ -341,8 +330,6 @@ void report_ngc_parameters(uint8_t client) {
report_probe_parameters(client);
}
// Print current gcode parser mode state
void report_gcode_modes(uint8_t client) {
char temp[20];
@ -366,24 +353,27 @@ void report_gcode_modes(uint8_t client) {
if (gc_state.modal.program_flow) {
//report_util_gcode_modes_M();
switch (gc_state.modal.program_flow) {
case PROGRAM_FLOW_PAUSED : strcat(modes_rpt, " M0"); //serial_write('0'); break;
// case PROGRAM_FLOW_OPTIONAL_STOP : serial_write('1'); break; // M1 is ignored and not supported.
case PROGRAM_FLOW_COMPLETED_M2 :
case PROGRAM_FLOW_COMPLETED_M30 :
sprintf(temp, " M%d", gc_state.modal.program_flow);
strcat(modes_rpt, temp);
break;
case PROGRAM_FLOW_PAUSED:
strcat(modes_rpt, " M0"); //serial_write('0'); break;
// case PROGRAM_FLOW_OPTIONAL_STOP : serial_write('1'); break; // M1 is ignored and not supported.
case PROGRAM_FLOW_COMPLETED_M2:
case PROGRAM_FLOW_COMPLETED_M30:
sprintf(temp, " M%d", gc_state.modal.program_flow);
strcat(modes_rpt, temp);
break;
}
}
switch (gc_state.modal.spindle) {
case SPINDLE_ENABLE_CW : strcat(modes_rpt, " M3"); break;
case SPINDLE_ENABLE_CCW : strcat(modes_rpt, " M4"); break;
case SPINDLE_DISABLE : strcat(modes_rpt, " M5"); break;
case SPINDLE_ENABLE_CW: strcat(modes_rpt, " M3"); break;
case SPINDLE_ENABLE_CCW: strcat(modes_rpt, " M4"); break;
case SPINDLE_DISABLE: strcat(modes_rpt, " M5"); break;
}
//report_util_gcode_modes_M(); // optional M7 and M8 should have been dealt with by here
if (gc_state.modal.coolant) { // Note: Multiple coolant states may be active at the same time.
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_MIST) strcat(modes_rpt, " M7");
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_FLOOD) strcat(modes_rpt, " M8");
if (gc_state.modal.coolant) { // Note: Multiple coolant states may be active at the same time.
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_MIST)
strcat(modes_rpt, " M7");
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_FLOOD)
strcat(modes_rpt, " M8");
} else
strcat(modes_rpt, " M9");
@ -402,15 +392,13 @@ void report_gcode_modes(uint8_t client) {
grbl_send(client, modes_rpt);
}
// Prints specified startup line
void report_startup_line(uint8_t n, const char* line, uint8_t client) {
grbl_sendf(client, "$N%d=%s\r\n", n, line); // OK to send to all
grbl_sendf(client, "$N%d=%s\r\n", n, line); // OK to send to all
}
void report_execute_startup_message(const char* line, uint8_t status_code, uint8_t client) {
grbl_sendf(client, ">%s:", line); // OK to send to all
grbl_sendf(client, ">%s:", line); // OK to send to all
report_status_message(status_code, client);
}
@ -420,10 +408,10 @@ void report_build_info(char* line, uint8_t client) {
strcpy(build_info, "[VER:" GRBL_VERSION "." GRBL_VERSION_BUILD ":");
strcat(build_info, line);
strcat(build_info, "]\r\n[OPT:");
strcat(build_info, "V"); // variable spindle..always on now
strcat(build_info, "V"); // variable spindle..always on now
strcat(build_info, "N");
#ifdef COOLANT_MIST_PIN
strcat(build_info, "M"); // TODO Need to deal with M8...it could be disabled
strcat(build_info, "M"); // TODO Need to deal with M8...it could be disabled
#endif
#ifdef COREXY
strcat(build_info, "C");
@ -432,7 +420,7 @@ void report_build_info(char* line, uint8_t client) {
strcat(build_info, "P");
#endif
#if (defined(HOMING_FORCE_SET_ORIGIN) || defined(HOMING_FORCE_POSITIVE_SPACE))
strcat(build_info, "Z"); // homing MPOS bahavior is not the default behavior
strcat(build_info, "Z"); // homing MPOS bahavior is not the default behavior
#endif
#ifdef HOMING_SINGLE_AXIS_COMMANDS
strcat(build_info, "H");
@ -452,36 +440,36 @@ void report_build_info(char* line, uint8_t client) {
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
serial_write('R');
#endif
#if defined (ENABLE_WIFI)
#if defined(ENABLE_WIFI)
strcat(build_info, "W");
#endif
#ifndef ENABLE_RESTORE_EEPROM_WIPE_ALL // NOTE: Shown when disabled.
#ifndef ENABLE_RESTORE_EEPROM_WIPE_ALL // NOTE: Shown when disabled.
strcat(build_info, "*");
#endif
#ifndef ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS // NOTE: Shown when disabled.
#ifndef ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS // NOTE: Shown when disabled.
strcat(build_info, "$");
#endif
#ifndef ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS // NOTE: Shown when disabled.
#ifndef ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS // NOTE: Shown when disabled.
strcat(build_info, "#");
#endif
#ifndef ENABLE_BUILD_INFO_WRITE_COMMAND // NOTE: Shown when disabled.
#ifndef ENABLE_BUILD_INFO_WRITE_COMMAND // NOTE: Shown when disabled.
strcat(build_info, "I");
#endif
#ifndef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE // NOTE: Shown when disabled.
#ifndef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE // NOTE: Shown when disabled.
strcat(build_info, "E");
#endif
#ifndef FORCE_BUFFER_SYNC_DURING_WCO_CHANGE // NOTE: Shown when disabled.
#ifndef FORCE_BUFFER_SYNC_DURING_WCO_CHANGE // NOTE: Shown when disabled.
strcat(build_info, "W");
#endif
// NOTE: Compiled values, like override increments/max/min values, may be added at some point later.
// These will likely have a comma delimiter to separate them.
strcat(build_info, "]\r\n");
grbl_send(client, build_info); // ok to send to all
grbl_send(client, build_info); // ok to send to all
report_machine_type(client);
#if defined (ENABLE_WIFI)
#if defined(ENABLE_WIFI)
grbl_send(client, (char*)wifi_config.info());
#endif
#if defined (ENABLE_BLUETOOTH)
#if defined(ENABLE_BLUETOOTH)
grbl_send(client, (char*)bt_config.info());
#endif
}
@ -499,53 +487,55 @@ void report_echo_line_received(char* line, uint8_t client) {
// 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[N_AXIS]; // Copy current state of the system position variable
int32_t current_position[N_AXIS]; // Copy current state of the system position variable
memcpy(current_position, sys_position, sizeof(sys_position));
float print_position[N_AXIS];
char status[200];
char temp[80];
char status[200];
char temp[80];
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 & SUSPEND_JOG_CANCEL)) {
strcat(status, "Hold:");
if (sys.suspend & SUSPEND_HOLD_COMPLETE) strcat(status, "0"); // Ready to resume
else strcat(status, "1"); // Actively holding
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_CHECK_MODE: strcat(status, "Check"); break;
case STATE_SAFETY_DOOR:
strcat(status, "Door:");
if (sys.suspend & SUSPEND_INITIATE_RESTORE) {
strcat(status, "3"); // Restoring
} else {
if (sys.suspend & SUSPEND_RETRACT_COMPLETE) {
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) {
strcat(status, "1"); // Door ajar
} else
strcat(status, "0");
// Door closed and ready to resume
case STATE_IDLE: strcat(status, "Idle"); break;
case STATE_CYCLE: strcat(status, "Run"); break;
case STATE_HOLD:
if (!(sys.suspend & SUSPEND_JOG_CANCEL)) {
strcat(status, "Hold:");
if (sys.suspend & SUSPEND_HOLD_COMPLETE)
strcat(status, "0"); // Ready to resume
else
strcat(status, "1"); // Actively holding
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_CHECK_MODE: strcat(status, "Check"); break;
case STATE_SAFETY_DOOR:
strcat(status, "Door:");
if (sys.suspend & SUSPEND_INITIATE_RESTORE) {
strcat(status, "3"); // Restoring
} else {
strcat(status, "2"); // Retracting
if (sys.suspend & SUSPEND_RETRACT_COMPLETE) {
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) {
strcat(status, "1"); // Door ajar
} else
strcat(status, "0");
// Door closed and ready to resume
} else {
strcat(status, "2"); // Retracting
}
}
}
break;
case STATE_SLEEP: strcat(status, "Sleep"); break;
break;
case STATE_SLEEP: strcat(status, "Sleep"); break;
}
float wco[N_AXIS];
if (bit_isfalse(status_mask->get(), BITFLAG_RT_STATUS_POSITION_TYPE) ||
(sys.report_wco_counter == 0)) {
if (bit_isfalse(status_mask->get(), BITFLAG_RT_STATUS_POSITION_TYPE) || (sys.report_wco_counter == 0)) {
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 (idx == TOOL_LENGTH_OFFSET_AXIS)
wco[idx] += gc_state.tool_length_offset;
if (bit_isfalse(status_mask->get(), BITFLAG_RT_STATUS_POSITION_TYPE))
print_position[idx] -= wco[idx];
}
@ -565,16 +555,16 @@ void report_realtime_status(uint8_t client) {
#ifdef REPORT_FIELD_BUFFER_STATE
if (bit_istrue(status_mask->get(), BITFLAG_RT_STATUS_BUFFER_STATE)) {
int bufsize = DEFAULTBUFFERSIZE;
#if defined (ENABLE_WIFI) && defined(ENABLE_TELNET)
# if defined(ENABLE_WIFI) && defined(ENABLE_TELNET)
if (client == CLIENT_TELNET)
bufsize = telnet_server.get_rx_buffer_available();
#endif //ENABLE_WIFI && ENABLE_TELNET
#if defined(ENABLE_BLUETOOTH)
# endif //ENABLE_WIFI && ENABLE_TELNET
# if defined(ENABLE_BLUETOOTH)
if (client == CLIENT_BT) {
//TODO FIXME
bufsize = 512 - SerialBT.available();
}
#endif //ENABLE_BLUETOOTH
# endif //ENABLE_BLUETOOTH
if (client == CLIENT_SERIAL)
bufsize = serial_get_rx_buffer_available(CLIENT_SERIAL);
sprintf(temp, "|Bf:%d,%d", plan_get_block_buffer_available(), bufsize);
@ -582,7 +572,7 @@ void report_realtime_status(uint8_t client) {
}
#endif
#ifdef USE_LINE_NUMBERS
#ifdef REPORT_FIELD_LINE_NUMBERS
# ifdef REPORT_FIELD_LINE_NUMBERS
// Report current line number
plan_block_t* cur_block = plan_get_current_block();
if (cur_block != NULL) {
@ -592,79 +582,99 @@ void report_realtime_status(uint8_t client) {
strcat(status, temp);
}
}
#endif
# endif
#endif
// Report realtime feed speed
#ifdef REPORT_FIELD_CURRENT_FEED_SPEED
if (report_inches->get())
sprintf(temp, "|FS:%.1f,%d", st_get_realtime_rate()/ MM_PER_INCH, sys.spindle_speed);
sprintf(temp, "|FS:%.1f,%d", st_get_realtime_rate() / MM_PER_INCH, sys.spindle_speed);
else
sprintf(temp, "|FS:%.0f,%d", st_get_realtime_rate(), sys.spindle_speed);
strcat(status, temp);
#endif
#ifdef REPORT_FIELD_PIN_STATE
uint8_t lim_pin_state = limits_get_state();
uint8_t lim_pin_state = limits_get_state();
uint8_t ctrl_pin_state = system_control_get_state();
uint8_t prb_pin_state = probe_get_state();
uint8_t prb_pin_state = probe_get_state();
if (lim_pin_state | ctrl_pin_state | prb_pin_state) {
strcat(status, "|Pn:");
if (prb_pin_state) strcat(status, "P");
if (prb_pin_state)
strcat(status, "P");
if (lim_pin_state) {
if (bit_istrue(lim_pin_state, bit(X_AXIS))) strcat(status, "X");
if (bit_istrue(lim_pin_state, bit(Y_AXIS))) strcat(status, "Y");
if (bit_istrue(lim_pin_state, bit(Z_AXIS))) strcat(status, "Z");
#if (N_AXIS > A_AXIS)
if (bit_istrue(lim_pin_state, bit(A_AXIS))) strcat(status, "A");
#endif
#if (N_AXIS > B_AXIS)
if (bit_istrue(lim_pin_state, bit(B_AXIS))) strcat(status, "B");
#endif
#if (N_AXIS > C_AXIS)
if (bit_istrue(lim_pin_state, bit(C_AXIS))) strcat(status, "C");
#endif
if (bit_istrue(lim_pin_state, bit(X_AXIS)))
strcat(status, "X");
if (bit_istrue(lim_pin_state, bit(Y_AXIS)))
strcat(status, "Y");
if (bit_istrue(lim_pin_state, bit(Z_AXIS)))
strcat(status, "Z");
# if (N_AXIS > A_AXIS)
if (bit_istrue(lim_pin_state, bit(A_AXIS)))
strcat(status, "A");
# endif
# if (N_AXIS > B_AXIS)
if (bit_istrue(lim_pin_state, bit(B_AXIS)))
strcat(status, "B");
# endif
# if (N_AXIS > C_AXIS)
if (bit_istrue(lim_pin_state, bit(C_AXIS)))
strcat(status, "C");
# endif
}
if (ctrl_pin_state) {
#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
if (bit_istrue(ctrl_pin_state, CONTROL_PIN_INDEX_SAFETY_DOOR)) strcat(status, "D");
#endif
if (bit_istrue(ctrl_pin_state, CONTROL_PIN_INDEX_RESET)) strcat(status, "R");
if (bit_istrue(ctrl_pin_state, CONTROL_PIN_INDEX_FEED_HOLD)) strcat(status, "H");
if (bit_istrue(ctrl_pin_state, CONTROL_PIN_INDEX_CYCLE_START)) strcat(status, "S");
# ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
if (bit_istrue(ctrl_pin_state, CONTROL_PIN_INDEX_SAFETY_DOOR))
strcat(status, "D");
# endif
if (bit_istrue(ctrl_pin_state, CONTROL_PIN_INDEX_RESET))
strcat(status, "R");
if (bit_istrue(ctrl_pin_state, CONTROL_PIN_INDEX_FEED_HOLD))
strcat(status, "H");
if (bit_istrue(ctrl_pin_state, CONTROL_PIN_INDEX_CYCLE_START))
strcat(status, "S");
}
}
#endif
#ifdef REPORT_FIELD_WORK_COORD_OFFSET
if (sys.report_wco_counter > 0) sys.report_wco_counter--;
if (sys.report_wco_counter > 0)
sys.report_wco_counter--;
else {
if (sys.state & (STATE_HOMING | STATE_CYCLE | STATE_HOLD | STATE_JOG | STATE_SAFETY_DOOR)) {
sys.report_wco_counter = (REPORT_WCO_REFRESH_BUSY_COUNT - 1); // Reset counter for slow refresh
} else sys.report_wco_counter = (REPORT_WCO_REFRESH_IDLE_COUNT - 1);
if (sys.report_ovr_counter == 0) sys.report_ovr_counter = 1; // Set override on next report.
sys.report_wco_counter = (REPORT_WCO_REFRESH_BUSY_COUNT - 1); // Reset counter for slow refresh
} else
sys.report_wco_counter = (REPORT_WCO_REFRESH_IDLE_COUNT - 1);
if (sys.report_ovr_counter == 0)
sys.report_ovr_counter = 1; // Set override on next report.
strcat(status, "|WCO:");
report_util_axis_values(wco, temp);
strcat(status, temp);
}
#endif
#ifdef REPORT_FIELD_OVERRIDES
if (sys.report_ovr_counter > 0) sys.report_ovr_counter--;
if (sys.report_ovr_counter > 0)
sys.report_ovr_counter--;
else {
if (sys.state & (STATE_HOMING | STATE_CYCLE | STATE_HOLD | STATE_JOG | STATE_SAFETY_DOOR)) {
sys.report_ovr_counter = (REPORT_OVR_REFRESH_BUSY_COUNT - 1); // Reset counter for slow refresh
} else sys.report_ovr_counter = (REPORT_OVR_REFRESH_IDLE_COUNT - 1);
sys.report_ovr_counter = (REPORT_OVR_REFRESH_BUSY_COUNT - 1); // Reset counter for slow refresh
} else
sys.report_ovr_counter = (REPORT_OVR_REFRESH_IDLE_COUNT - 1);
sprintf(temp, "|Ov:%d,%d,%d", sys.f_override, sys.r_override, sys.spindle_speed_ovr);
strcat(status, temp);
uint8_t sp_state = spindle->get_state();
uint8_t sp_state = spindle->get_state();
uint8_t cl_state = coolant_get_state();
if (sp_state || cl_state) {
strcat(status, "|A:");
if (sp_state) { // != SPINDLE_STATE_DISABLE
if (sp_state == SPINDLE_STATE_CW) strcat(status, "S"); // CW
else strcat(status, "C"); // CCW
if (sp_state) { // != SPINDLE_STATE_DISABLE
if (sp_state == SPINDLE_STATE_CW)
strcat(status, "S"); // CW
else
strcat(status, "C"); // CCW
}
if (cl_state & COOLANT_STATE_FLOOD) strcat(status, "F");
#ifdef COOLANT_MIST_PIN // TODO Deal with M8 - Flood
if (cl_state & COOLANT_STATE_MIST) strcat(status, "M");
#endif
if (cl_state & COOLANT_STATE_FLOOD)
strcat(status, "F");
# ifdef COOLANT_MIST_PIN // TODO Deal with M8 - Flood
if (cl_state & COOLANT_STATE_MIST)
strcat(status, "M");
# endif
}
}
#endif
@ -692,15 +702,15 @@ void report_realtime_steps() {
}
void report_gcode_comment(char* comment) {
char msg[80];
char msg[80];
const uint8_t offset = 4; // ignore "MSG_" part of comment
uint8_t index = offset;
uint8_t index = offset;
if (strstr(comment, "MSG")) {
while (index < strlen(comment)) {
msg[index - offset] = comment[index];
index++;
}
msg[index - offset] = 0; // null terminate
msg[index - offset] = 0; // null terminate
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "GCode Comment...%s", msg);
}
}
@ -709,7 +719,6 @@ void report_machine_type(uint8_t client) {
grbl_msg_sendf(client, MSG_LEVEL_INFO, "Using machine:%s", MACHINE_NAME);
}
/*
Print a message in hex format
Ex: report_hex_msg(msg, "Rx:", 6);
@ -725,7 +734,6 @@ void report_hex_msg(char* buf, const char* prefix, int len) {
}
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s", report);
}
void report_hex_msg(uint8_t* buf, const char* prefix, int len) {
@ -738,24 +746,16 @@ void report_hex_msg(uint8_t* buf, const char* prefix, int len) {
}
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s", report);
}
char report_get_axis_letter(uint8_t axis) {
switch (axis) {
case X_AXIS:
return 'X';
case Y_AXIS:
return 'Y';
case Z_AXIS:
return 'Z';
case A_AXIS:
return 'A';
case B_AXIS:
return 'B';
case C_AXIS:
return 'C';
default:
return '?';
case X_AXIS: return 'X';
case Y_AXIS: return 'Y';
case Z_AXIS: return 'Z';
case A_AXIS: return 'A';
case B_AXIS: return 'B';
case C_AXIS: return 'C';
default: return '?';
}
}

View File

@ -61,22 +61,22 @@
#define STATUS_GCODE_MAX_VALUE_EXCEEDED 38
#define STATUS_P_PARAM_MAX_EXCEEDED 39
#define STATUS_SD_FAILED_MOUNT 60 // SD Failed to mount
#define STATUS_SD_FAILED_READ 61 // SD Failed to read file
#define STATUS_SD_FAILED_OPEN_DIR 62 // SD card failed to open directory
#define STATUS_SD_DIR_NOT_FOUND 63 // SD Card directory not found
#define STATUS_SD_FILE_EMPTY 64 // SD Card directory not found
#define STATUS_SD_FILE_NOT_FOUND 65 // SD Card file not found
#define STATUS_SD_FAILED_OPEN_FILE 66 // SD card failed to open file
#define STATUS_SD_FAILED_BUSY 67 // SD card is busy
#define STATUS_SD_FAILED_MOUNT 60 // SD Failed to mount
#define STATUS_SD_FAILED_READ 61 // SD Failed to read file
#define STATUS_SD_FAILED_OPEN_DIR 62 // SD card failed to open directory
#define STATUS_SD_DIR_NOT_FOUND 63 // SD Card directory not found
#define STATUS_SD_FILE_EMPTY 64 // SD Card directory not found
#define STATUS_SD_FILE_NOT_FOUND 65 // SD Card file not found
#define STATUS_SD_FAILED_OPEN_FILE 66 // SD card failed to open file
#define STATUS_SD_FAILED_BUSY 67 // SD card is busy
#define STATUS_SD_FAILED_DEL_DIR 68
#define STATUS_SD_FAILED_DEL_FILE 69
#define STATUS_BT_FAIL_BEGIN 70 // Bluetooth failed to start
#define STATUS_BT_FAIL_BEGIN 70 // Bluetooth failed to start
#define STATUS_WIFI_FAIL_BEGIN 71 // WiFi failed to start
#define STATUS_NUMBER_RANGE 80 // Setting number range problem
#define STATUS_INVALID_VALUE 81 // Setting string problem
#define STATUS_NUMBER_RANGE 80 // Setting number range problem
#define STATUS_INVALID_VALUE 81 // Setting string problem
#define STATUS_MESSAGE_FAILED 90
@ -85,19 +85,19 @@
#define STATUS_AUTHENTICATION_FAILED 110
#define STATUS_EOL 111
typedef uint8_t err_t; // For status codes
const char* errorString(err_t errorNumber);
typedef uint8_t err_t; // For status codes
const char* errorString(err_t errorNumber);
// Define Grbl alarm codes. Valid values (1-255). 0 is reserved.
#define ALARM_HARD_LIMIT_ERROR EXEC_ALARM_HARD_LIMIT
#define ALARM_SOFT_LIMIT_ERROR EXEC_ALARM_SOFT_LIMIT
#define ALARM_ABORT_CYCLE EXEC_ALARM_ABORT_CYCLE
#define ALARM_PROBE_FAIL_INITIAL EXEC_ALARM_PROBE_FAIL_INITIAL
#define ALARM_PROBE_FAIL_CONTACT EXEC_ALARM_PROBE_FAIL_CONTACT
#define ALARM_HOMING_FAIL_RESET EXEC_ALARM_HOMING_FAIL_RESET
#define ALARM_HOMING_FAIL_DOOR EXEC_ALARM_HOMING_FAIL_DOOR
#define ALARM_HOMING_FAIL_PULLOFF EXEC_ALARM_HOMING_FAIL_PULLOFF
#define ALARM_HOMING_FAIL_APPROACH EXEC_ALARM_HOMING_FAIL_APPROACH
#define ALARM_HARD_LIMIT_ERROR EXEC_ALARM_HARD_LIMIT
#define ALARM_SOFT_LIMIT_ERROR EXEC_ALARM_SOFT_LIMIT
#define ALARM_ABORT_CYCLE EXEC_ALARM_ABORT_CYCLE
#define ALARM_PROBE_FAIL_INITIAL EXEC_ALARM_PROBE_FAIL_INITIAL
#define ALARM_PROBE_FAIL_CONTACT EXEC_ALARM_PROBE_FAIL_CONTACT
#define ALARM_HOMING_FAIL_RESET EXEC_ALARM_HOMING_FAIL_RESET
#define ALARM_HOMING_FAIL_DOOR EXEC_ALARM_HOMING_FAIL_DOOR
#define ALARM_HOMING_FAIL_PULLOFF EXEC_ALARM_HOMING_FAIL_PULLOFF
#define ALARM_HOMING_FAIL_APPROACH EXEC_ALARM_HOMING_FAIL_APPROACH
// Define Grbl feedback message codes. Valid values (0-255).
#define MESSAGE_CRITICAL_EVENT 1
@ -111,22 +111,22 @@ const char* errorString(err_t errorNumber);
#define MESSAGE_RESTORE_DEFAULTS 9
#define MESSAGE_SPINDLE_RESTORE 10
#define MESSAGE_SLEEP_MODE 11
#define MESSAGE_SD_FILE_QUIT 60 // mc_reset was called during an SD job
#define MESSAGE_SD_FILE_QUIT 60 // mc_reset was called during an SD job
#define CLIENT_SERIAL 0
#define CLIENT_BT 1
#define CLIENT_WEBUI 2
#define CLIENT_TELNET 3
#define CLIENT_INPUT 4
#define CLIENT_ALL 0xFF
#define CLIENT_COUNT 5 // total number of client types regardless if they are used
#define CLIENT_SERIAL 0
#define CLIENT_BT 1
#define CLIENT_WEBUI 2
#define CLIENT_TELNET 3
#define CLIENT_INPUT 4
#define CLIENT_ALL 0xFF
#define CLIENT_COUNT 5 // total number of client types regardless if they are used
#define MSG_LEVEL_NONE 0 // set GRBL_MSG_LEVEL in config.h to the level you want to see
#define MSG_LEVEL_ERROR 1
#define MSG_LEVEL_WARNING 2
#define MSG_LEVEL_INFO 3
#define MSG_LEVEL_DEBUG 4
#define MSG_LEVEL_VERBOSE 5
#define MSG_LEVEL_NONE 0 // set GRBL_MSG_LEVEL in config.h to the level you want to see
#define MSG_LEVEL_ERROR 1
#define MSG_LEVEL_WARNING 2
#define MSG_LEVEL_INFO 3
#define MSG_LEVEL_DEBUG 4
#define MSG_LEVEL_VERBOSE 5
// functions to send data to the user.
void grbl_send(uint8_t client, const char* text);
@ -181,12 +181,12 @@ void report_build_info(char* line, uint8_t client);
void report_gcode_comment(char* comment);
#ifdef DEBUG
void report_realtime_debug();
void report_realtime_debug();
#endif
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);
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);

View File

@ -72,55 +72,54 @@ void serial_init() {
Serial.begin(BAUD_RATE);
// reset all buffers
serial_reset_read_buffer(CLIENT_ALL);
grbl_send(CLIENT_SERIAL, "\r\n"); // create some white space after ESP32 boot info
grbl_send(CLIENT_SERIAL, "\r\n"); // create some white space after ESP32 boot info
serialCheckTaskHandle = 0;
// create a task to check for incoming data
xTaskCreatePinnedToCore(serialCheckTask, // task
"serialCheckTask", // name for task
8192, // size of task stack
NULL, // parameters
1, // priority
xTaskCreatePinnedToCore(serialCheckTask, // task
"serialCheckTask", // name for task
8192, // size of task stack
NULL, // parameters
1, // priority
&serialCheckTaskHandle,
1 // core
);
1 // 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
while (true) { // run continuously
uint8_t data = 0;
uint8_t client = CLIENT_ALL; // who sent the data
while (true) { // run continuously
while (any_client_has_data()) {
if (Serial.available()) {
client = CLIENT_SERIAL;
data = Serial.read();
data = Serial.read();
} else if (inputBuffer.available()) {
client = CLIENT_INPUT;
data = inputBuffer.read();
data = inputBuffer.read();
} else {
//currently is wifi or BT but better to prepare both can be live
#ifdef ENABLE_BLUETOOTH
if (SerialBT.hasClient() && SerialBT.available()) {
client = CLIENT_BT;
data = SerialBT.read();
data = SerialBT.read();
//Serial.write(data); // echo all data to serial
} else {
#endif
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
if (Serial2Socket.available()) {
client = CLIENT_WEBUI;
data = Serial2Socket.read();
data = Serial2Socket.read();
} else {
#endif
#if defined (ENABLE_WIFI) && defined(ENABLE_TELNET)
#if defined(ENABLE_WIFI) && defined(ENABLE_TELNET)
if (telnet_server.available()) {
client = CLIENT_TELNET;
data = telnet_server.read();
data = telnet_server.read();
}
#endif
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
}
#endif
#ifdef ENABLE_BLUETOOTH
@ -144,11 +143,11 @@ void serialCheckTask(void* pvParameters) {
#ifdef ENABLE_BLUETOOTH
bt_config.handle();
#endif
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
Serial2Socket.handle_flush();
#endif
vTaskDelay(1 / portTICK_RATE_MS); // Yield to other tasks
} // while(true)
} // while(true)
}
void serial_reset_read_buffer(uint8_t client) {
@ -183,13 +182,13 @@ bool any_client_has_data() {
#ifdef ENABLE_BLUETOOTH
|| (SerialBT.hasClient() && SerialBT.available())
#endif
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|| Serial2Socket.available()
#endif
#if defined (ENABLE_WIFI) && defined(ENABLE_TELNET)
#if defined(ENABLE_WIFI) && defined(ENABLE_TELNET)
|| telnet_server.available()
#endif
);
);
}
// checks to see if a character is a realtime character
@ -200,48 +199,50 @@ bool is_realtime_command(uint8_t data) {
// Act upon a realtime character
void execute_realtime_command(uint8_t command, uint8_t client) {
switch (command) {
case CMD_RESET:
mc_reset(); // Call motion control reset routine.
break;
case CMD_STATUS_REPORT:
report_realtime_status(client); // direct call instead of setting flag
break;
case CMD_CYCLE_START:
system_set_exec_state_flag(EXEC_CYCLE_START); // Set as true
break;
case CMD_FEED_HOLD:
system_set_exec_state_flag(EXEC_FEED_HOLD); // Set as true
break;
case CMD_SAFETY_DOOR:
system_set_exec_state_flag(EXEC_SAFETY_DOOR);
break; // Set as true
case CMD_JOG_CANCEL:
if (sys.state & STATE_JOG) // Block all other states from invoking motion cancel.
system_set_exec_state_flag(EXEC_MOTION_CANCEL);
break;
case CMD_RESET:
mc_reset(); // Call motion control reset routine.
break;
case CMD_STATUS_REPORT:
report_realtime_status(client); // direct call instead of setting flag
break;
case CMD_CYCLE_START:
system_set_exec_state_flag(EXEC_CYCLE_START); // Set as true
break;
case CMD_FEED_HOLD:
system_set_exec_state_flag(EXEC_FEED_HOLD); // Set as true
break;
case CMD_SAFETY_DOOR: system_set_exec_state_flag(EXEC_SAFETY_DOOR); break; // Set as true
case CMD_JOG_CANCEL:
if (sys.state & STATE_JOG) // Block all other states from invoking motion cancel.
system_set_exec_state_flag(EXEC_MOTION_CANCEL);
break;
#ifdef DEBUG
case CMD_DEBUG_REPORT: {uint8_t sreg = SREG; cli(); bit_true(sys_rt_exec_debug, EXEC_DEBUG_REPORT); SREG = sreg;} break;
case CMD_DEBUG_REPORT: {
uint8_t sreg = SREG;
cli();
bit_true(sys_rt_exec_debug, EXEC_DEBUG_REPORT);
SREG = sreg;
} break;
#endif
case CMD_FEED_OVR_RESET: system_set_exec_motion_override_flag(EXEC_FEED_OVR_RESET); break;
case CMD_FEED_OVR_COARSE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_PLUS); break;
case CMD_FEED_OVR_COARSE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_MINUS); break;
case CMD_FEED_OVR_FINE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_PLUS); break;
case CMD_FEED_OVR_FINE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_MINUS); break;
case CMD_RAPID_OVR_RESET: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_RESET); break;
case CMD_RAPID_OVR_MEDIUM: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_MEDIUM); break;
case CMD_RAPID_OVR_LOW: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_LOW); break;
case CMD_SPINDLE_OVR_RESET: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_RESET); break;
case CMD_SPINDLE_OVR_COARSE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_PLUS); break;
case CMD_SPINDLE_OVR_COARSE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_MINUS); break;
case CMD_SPINDLE_OVR_FINE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_PLUS); break;
case CMD_SPINDLE_OVR_FINE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_MINUS); break;
case CMD_SPINDLE_OVR_STOP: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_STOP); break;
case CMD_FEED_OVR_RESET: system_set_exec_motion_override_flag(EXEC_FEED_OVR_RESET); break;
case CMD_FEED_OVR_COARSE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_PLUS); break;
case CMD_FEED_OVR_COARSE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_MINUS); break;
case CMD_FEED_OVR_FINE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_PLUS); break;
case CMD_FEED_OVR_FINE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_MINUS); break;
case CMD_RAPID_OVR_RESET: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_RESET); break;
case CMD_RAPID_OVR_MEDIUM: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_MEDIUM); break;
case CMD_RAPID_OVR_LOW: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_LOW); break;
case CMD_SPINDLE_OVR_RESET: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_RESET); break;
case CMD_SPINDLE_OVR_COARSE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_PLUS); break;
case CMD_SPINDLE_OVR_COARSE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_MINUS); break;
case CMD_SPINDLE_OVR_FINE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_PLUS); break;
case CMD_SPINDLE_OVR_FINE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_MINUS); break;
case CMD_SPINDLE_OVR_STOP: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_STOP); break;
#ifdef COOLANT_FLOOD_PIN
case CMD_COOLANT_FLOOD_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_FLOOD_OVR_TOGGLE); break;
case CMD_COOLANT_FLOOD_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_FLOOD_OVR_TOGGLE); break;
#endif
#ifdef COOLANT_MIST_PIN
case CMD_COOLANT_MIST_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_MIST_OVR_TOGGLE); break;
case CMD_COOLANT_MIST_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_MIST_OVR_TOGGLE); break;
#endif
}
}

View File

@ -23,14 +23,14 @@
#include "grbl.h"
#ifndef RX_BUFFER_SIZE
#define RX_BUFFER_SIZE 128
# define RX_BUFFER_SIZE 128
#endif
#ifndef TX_BUFFER_SIZE
#ifdef USE_LINE_NUMBERS
#define TX_BUFFER_SIZE 112
#else
#define TX_BUFFER_SIZE 104
#endif
# ifdef USE_LINE_NUMBERS
# define TX_BUFFER_SIZE 112
# else
# define TX_BUFFER_SIZE 104
# endif
#endif
#define SERIAL_NO_DATA 0xff

View File

@ -18,43 +18,39 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifdef ARDUINO_ARCH_ESP32
#include "grbl.h"
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP)
#if defined(ENABLE_WIFI) && defined(ENABLE_HTTP)
#include "serial2socket.h"
#include "web_server.h"
#include <WebSocketsServer.h>
#include <WiFi.h>
# include "serial2socket.h"
# include "web_server.h"
# include <WebSocketsServer.h>
# include <WiFi.h>
Serial_2_Socket Serial2Socket;
Serial_2_Socket::Serial_2_Socket() {
_web_socket = NULL;
_web_socket = NULL;
_TXbufferSize = 0;
_RXbufferSize = 0;
_RXbufferpos = 0;
_RXbufferpos = 0;
}
Serial_2_Socket::~Serial_2_Socket() {
if (_web_socket) detachWS();
if (_web_socket)
detachWS();
_TXbufferSize = 0;
_RXbufferSize = 0;
_RXbufferpos = 0;
_RXbufferpos = 0;
}
void Serial_2_Socket::begin(long speed) {
_TXbufferSize = 0;
_RXbufferSize = 0;
_RXbufferpos = 0;
_RXbufferpos = 0;
}
void Serial_2_Socket::end() {
_TXbufferSize = 0;
_RXbufferSize = 0;
_RXbufferpos = 0;
_RXbufferpos = 0;
}
long Serial_2_Socket::baudRate() {
@ -63,7 +59,7 @@ long Serial_2_Socket::baudRate() {
bool Serial_2_Socket::attachWS(void* web_socket) {
if (web_socket) {
_web_socket = web_socket;
_web_socket = web_socket;
_TXbufferSize = 0;
return true;
}
@ -82,9 +78,9 @@ int Serial_2_Socket::available() {
return _RXbufferSize;
}
size_t Serial_2_Socket::write(uint8_t c) {
if (!_web_socket) return 0;
if (!_web_socket)
return 0;
write(&c, 1);
return 1;
}
@ -97,10 +93,12 @@ size_t Serial_2_Socket::write(const uint8_t* buffer, size_t size) {
log_i("[SOCKET]No socket");
return 0;
}
#if defined(ENABLE_SERIAL2SOCKET_OUT)
if (_TXbufferSize == 0)_lastflush = millis();
# if defined(ENABLE_SERIAL2SOCKET_OUT)
if (_TXbufferSize == 0)
_lastflush = millis();
//send full line
if (_TXbufferSize + size > TXBUFFERSIZE) flush();
if (_TXbufferSize + size > TXBUFFERSIZE)
flush();
//need periodic check to force to flush in case of no end
for (int i = 0; i < size; i++) {
_TXbuffer[_TXbufferSize] = buffer[i];
@ -108,43 +106,49 @@ size_t Serial_2_Socket::write(const uint8_t* buffer, size_t size) {
}
log_i("[SOCKET]buffer size %d", _TXbufferSize);
handle_flush();
#endif
# endif
return size;
}
int Serial_2_Socket::peek(void) {
if (_RXbufferSize > 0)return _RXbuffer[_RXbufferpos];
else return -1;
if (_RXbufferSize > 0)
return _RXbuffer[_RXbufferpos];
else
return -1;
}
bool Serial_2_Socket::push(const char* data) {
#if defined(ENABLE_SERIAL2SOCKET_IN)
# if defined(ENABLE_SERIAL2SOCKET_IN)
int data_size = strlen(data);
if ((data_size + _RXbufferSize) <= RXBUFFERSIZE) {
int current = _RXbufferpos + _RXbufferSize;
if (current > RXBUFFERSIZE) current = current - RXBUFFERSIZE;
if (current > RXBUFFERSIZE)
current = current - RXBUFFERSIZE;
for (int i = 0; i < data_size; i++) {
if (current > (RXBUFFERSIZE - 1)) current = 0;
if (current > (RXBUFFERSIZE - 1))
current = 0;
_RXbuffer[current] = data[i];
current ++;
current++;
}
_RXbufferSize += strlen(data);
return true;
}
return false;
#else
# else
return true;
#endif
# endif
}
int Serial_2_Socket::read(void) {
if (_RXbufferSize > 0) {
int v = _RXbuffer[_RXbufferpos];
_RXbufferpos++;
if (_RXbufferpos > (RXBUFFERSIZE - 1))_RXbufferpos = 0;
if (_RXbufferpos > (RXBUFFERSIZE - 1))
_RXbufferpos = 0;
_RXbufferSize--;
return v;
} else return -1;
} else
return -1;
}
void Serial_2_Socket::handle_flush() {
@ -170,6 +174,4 @@ void Serial_2_Socket::flush(void) {
}
}
#endif // ENABLE_WIFI
#endif // ARDUINO_ARCH_ESP32
#endif // ENABLE_WIFI

View File

@ -20,54 +20,43 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "Print.h"
#define TXBUFFERSIZE 1200
#define RXBUFFERSIZE 128
#define FLUSHTIMEOUT 500
class Serial_2_Socket: public Print {
public:
class Serial_2_Socket : public Print {
public:
Serial_2_Socket();
~Serial_2_Socket();
size_t write(uint8_t c);
size_t write(const uint8_t* buffer, size_t size);
inline size_t write(const char* s) {
return write((uint8_t*) s, strlen(s));
}
inline size_t write(unsigned long n) {
return write((uint8_t) n);
}
inline size_t write(long n) {
return write((uint8_t) n);
}
inline size_t write(unsigned int n) {
return write((uint8_t) n);
}
inline size_t write(int n) {
return write((uint8_t) n);
}
long baudRate();
void begin(long speed);
void end();
int available();
int peek(void);
int read(void);
bool push(const char* data);
void flush(void);
void handle_flush();
operator bool() const;
bool attachWS(void* web_socket);
bool detachWS();
private:
inline size_t write(const char* s) { return write((uint8_t*)s, strlen(s)); }
inline size_t write(unsigned long n) { return write((uint8_t)n); }
inline size_t write(long n) { return write((uint8_t)n); }
inline size_t write(unsigned int n) { return write((uint8_t)n); }
inline size_t write(int n) { return write((uint8_t)n); }
long baudRate();
void begin(long speed);
void end();
int available();
int peek(void);
int read(void);
bool push(const char* data);
void flush(void);
void handle_flush();
operator bool() const;
bool attachWS(void* web_socket);
bool detachWS();
private:
uint32_t _lastflush;
void* _web_socket;
uint8_t _TXbuffer[TXBUFFERSIZE];
void* _web_socket;
uint8_t _TXbuffer[TXBUFFERSIZE];
uint16_t _TXbufferSize;
uint8_t _RXbuffer[RXBUFFERSIZE];
uint8_t _RXbuffer[RXBUFFERSIZE];
uint16_t _RXbufferSize;
uint16_t _RXbufferpos;
};
extern Serial_2_Socket Serial2Socket;

View File

@ -28,201 +28,200 @@
static TaskHandle_t servosSyncTaskHandle = 0;
#ifdef SERVO_X_PIN
ServoAxis X_Servo_Axis(X_AXIS, SERVO_X_PIN);
#endif
#ifdef SERVO_Y_PIN
ServoAxis Y_Servo_Axis(Y_AXIS, SERVO_Y_PIN);
#endif
#ifdef SERVO_Z_PIN
ServoAxis Z_Servo_Axis(Z_AXIS, SERVO_Z_PIN);
#endif
# ifdef SERVO_X_PIN
ServoAxis X_Servo_Axis(X_AXIS, SERVO_X_PIN);
# endif
# ifdef SERVO_Y_PIN
ServoAxis Y_Servo_Axis(Y_AXIS, SERVO_Y_PIN);
# endif
# ifdef SERVO_Z_PIN
ServoAxis Z_Servo_Axis(Z_AXIS, SERVO_Z_PIN);
# endif
#ifdef SERVO_A_PIN
ServoAxis A_Servo_Axis(A_AXIS, SERVO_A_PIN);
#endif
#ifdef SERVO_B_PIN
ServoAxis B_Servo_Axis(B_AXIS, SERVO_B_PIN);
#endif
#ifdef SERVO_C_PIN
ServoAxis C_Servo_Axis(C_AXIS, SERVO_C_PIN);
#endif
# ifdef SERVO_A_PIN
ServoAxis A_Servo_Axis(A_AXIS, SERVO_A_PIN);
# endif
# ifdef SERVO_B_PIN
ServoAxis B_Servo_Axis(B_AXIS, SERVO_B_PIN);
# endif
# ifdef SERVO_C_PIN
ServoAxis C_Servo_Axis(C_AXIS, SERVO_C_PIN);
# endif
void init_servos() {
// ======================== X Axis ===========================
#ifdef SERVO_X_PIN
# ifdef SERVO_X_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "X Servo range %4.3f to %4.3f", SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
X_Servo_Axis.init();
X_Servo_Axis.set_range(SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
#ifdef SERVO_X_HOMING_TYPE
# ifdef SERVO_X_HOMING_TYPE
X_Servo_Axis.set_homing_type(SERVO_X_HOMING_TYPE);
#endif
#ifdef SERVO_X_HOME_POS
# endif
# ifdef SERVO_X_HOME_POS
X_Servo_Axis.set_homing_position(SERVO_X_HOME_POS);
#endif
#ifdef SERVO_X_MPOS // value should be true or false
# endif
# ifdef SERVO_X_MPOS // value should be true or false
X_Servo_Axis.set_use_mpos(SERVO_X_MPOS);
#endif
#ifdef SERVO_X_DISABLE_ON_ALARM
# endif
# ifdef SERVO_X_DISABLE_ON_ALARM
set_disable_on_alarm(SERVO_X_DISABLE_ON_ALARM);
#endif
#ifdef SERVO_X_DISABLE_WITH_STEPPERS
# endif
# ifdef SERVO_X_DISABLE_WITH_STEPPERS
set_disable_with_steppers(SERVO_X_DISABLE_WITH_STEPPERS);
#endif
#endif
# endif
# endif
// ======================== Y Axis ===========================
#ifdef SERVO_Y_PIN
# ifdef SERVO_Y_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Y Servo range %4.3f to %4.3f", SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
Y_Servo_Axis.init();
Y_Servo_Axis.set_range(SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
#ifdef SERVO_Y_HOMING_TYPE
# ifdef SERVO_Y_HOMING_TYPE
Y_Servo_Axis.set_homing_type(SERVO_Y_HOMING_TYPE);
#endif
#ifdef SERVO_Y_HOME_POS
# endif
# ifdef SERVO_Y_HOME_POS
Y_Servo_Axis.set_homing_position(SERVO_Y_HOME_POS);
#endif
#ifdef SERVO_Y_MPOS // value should be true or false
# endif
# ifdef SERVO_Y_MPOS // value should be true or false
Y_Servo_Axis.set_use_mpos(SERVO_Y_MPOS);
#endif
#ifdef SERVO_Y_DISABLE_ON_ALARM
# endif
# ifdef SERVO_Y_DISABLE_ON_ALARM
set_disable_on_alarm(SERVO_Y_DISABLE_ON_ALARM);
#endif
#ifdef SERVO_Y_DISABLE_WITH_STEPPERS
# endif
# ifdef SERVO_Y_DISABLE_WITH_STEPPERS
set_disable_with_steppers(SERVO_Y_DISABLE_WITH_STEPPERS);
#endif
#endif
# endif
# endif
// ======================== Z Axis ===========================
#ifdef SERVO_Z_PIN
# ifdef SERVO_Z_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Z Servo range %4.3f to %4.3f", SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
Z_Servo_Axis.init();
Z_Servo_Axis.set_range(SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
#ifdef SERVO_Z_HOMING_TYPE
# ifdef SERVO_Z_HOMING_TYPE
Z_Servo_Axis.set_homing_type(SERVO_Z_HOMING_TYPE);
#endif
#ifdef SERVO_Z_HOME_POS
# endif
# ifdef SERVO_Z_HOME_POS
Z_Servo_Axis.set_homing_position(SERVO_Z_HOME_POS);
#endif
#ifdef SERVO_Z_MPOS // value should be true or false
# endif
# ifdef SERVO_Z_MPOS // value should be true or false
Z_Servo_Axis.set_use_mpos(SERVO_Z_MPOS);
#endif
#ifdef SERVO_Z_DISABLE_ON_ALARM
# endif
# ifdef SERVO_Z_DISABLE_ON_ALARM
set_disable_on_alarm(SERVO_Z_DISABLE_ON_ALARM);
#endif
#ifdef SERVO_Z_DISABLE_WITH_STEPPERS
# endif
# ifdef SERVO_Z_DISABLE_WITH_STEPPERS
set_disable_with_steppers(SERVO_Z_DISABLE_WITH_STEPPERS);
#endif
#endif
# endif
# endif
// ======================== A Axis ===========================
#ifdef SERVO_A_PIN
# ifdef SERVO_A_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "A Servo range %4.3f to %4.3f", SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX);
A_Servo_Axis.init();
A_Servo_Axis.set_range(SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX);
#ifdef SERVO_A_HOMING_TYPE
# ifdef SERVO_A_HOMING_TYPE
A_Servo_Axis.set_homing_type(SERVO_A_HOMING_TYPE);
#endif
#ifdef SERVO_A_HOME_POS
# endif
# ifdef SERVO_A_HOME_POS
A_Servo_Axis.set_homing_position(SERVO_A_HOME_POS);
#endif
#ifdef SERVO_A_MPOS // value should be true or false
# endif
# ifdef SERVO_A_MPOS // value should be true or false
A_Servo_Axis.set_use_mpos(SERVO_A_MPOS);
#endif
#ifdef SERVO_A_DISABLE_ON_ALARM
# endif
# ifdef SERVO_A_DISABLE_ON_ALARM
set_disable_on_alarm(SERVO_A_DISABLE_ON_ALARM);
#endif
#ifdef SERVO_A_DISABLE_WITH_STEPPERS
# endif
# ifdef SERVO_A_DISABLE_WITH_STEPPERS
set_disable_with_steppers(SERVO_A_DISABLE_WITH_STEPPERS);
#endif
#endif
# endif
# endif
// ======================== B Axis ===========================
#ifdef SERVO_B_PIN
# ifdef SERVO_B_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "B Servo range %4.3f to %4.3f", SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX);
B_Servo_Axis.init();
B_Servo_Axis.set_range(SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX);
#ifdef SERVO_B_HOMING_TYPE
# ifdef SERVO_B_HOMING_TYPE
B_Servo_Axis.set_homing_type(SERVO_B_HOMING_TYPE);
#endif
#ifdef SERVO_B_HOME_POS
# endif
# ifdef SERVO_B_HOME_POS
B_Servo_Axis.set_homing_position(SERVO_B_HOME_POS);
#endif
#ifdef SERVO_B_MPOS // value should be true or false
# endif
# ifdef SERVO_B_MPOS // value should be true or false
B_Servo_Axis.set_use_mpos(SERVO_B_MPOS);
#endif
#ifdef SERVO_B_DISABLE_ON_ALARM
# endif
# ifdef SERVO_B_DISABLE_ON_ALARM
set_disable_on_alarm(SERVO_B_DISABLE_ON_ALARM);
#endif
#ifdef SERVO_B_DISABLE_WITH_STEPPERS
# endif
# ifdef SERVO_B_DISABLE_WITH_STEPPERS
set_disable_with_steppers(SERVO_B_DISABLE_WITH_STEPPERS);
#endif
#endif
# endif
# endif
// ======================== C Axis ===========================
#ifdef SERVO_C_PIN
# ifdef SERVO_C_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "C Servo range %4.3f to %4.3f", SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX);
C_Servo_Axis.init();
C_Servo_Axis.set_range(SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX);
#ifdef SERVO_C_HOMING_TYPE
# ifdef SERVO_C_HOMING_TYPE
C_Servo_Axis.set_homing_type(SERVO_C_HOMING_TYPE);
#endif
#ifdef SERVO_C_HOME_POS
# endif
# ifdef SERVO_C_HOME_POS
C_Servo_Axis.set_homing_position(SERVO_C_HOME_POS);
#endif
#ifdef SERVO_C_MPOS // value should be true or false
# endif
# ifdef SERVO_C_MPOS // value should be true or false
C_Servo_Axis.set_use_mpos(SERVO_C_MPOS);
#endif
#ifdef SERVO_C_DISABLE_ON_ALARM
# endif
# ifdef SERVO_C_DISABLE_ON_ALARM
set_disable_on_alarm(SERVO_C_DISABLE_ON_ALARM);
#endif
#ifdef SERVO_C_DISABLE_WITH_STEPPERS
# endif
# ifdef SERVO_C_DISABLE_WITH_STEPPERS
set_disable_with_steppers(SERVO_C_DISABLE_WITH_STEPPERS);
#endif
#endif
# endif
# endif
// setup a task that will calculate the determine and set the servo positions
xTaskCreatePinnedToCore(servosSyncTask, // task
"servosSyncTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
xTaskCreatePinnedToCore(servosSyncTask, // task
"servosSyncTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
&servosSyncTaskHandle,
0 // core
);
0 // core
);
}
// this is the task
void servosSyncTask(void* pvParameters) {
TickType_t xLastWakeTime;
TickType_t xLastWakeTime;
const TickType_t xServoFrequency = SERVO_TIMER_INT_FREQ; // in ticks (typically ms)
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) { // don't ever return from this or the task dies
#ifdef SERVO_X_PIN
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) { // don't ever return from this or the task dies
# ifdef SERVO_X_PIN
X_Servo_Axis.set_location();
#endif
#ifdef SERVO_Y_PIN
# endif
# ifdef SERVO_Y_PIN
Y_Servo_Axis.set_location();
#endif
#ifdef SERVO_Z_PIN
# endif
# ifdef SERVO_Z_PIN
Z_Servo_Axis.set_location();
#endif
#ifdef SERVO_A_PIN
# endif
# ifdef SERVO_A_PIN
A_Servo_Axis.set_location();
#endif
#ifdef SERVO_B_PIN
# endif
# ifdef SERVO_B_PIN
B_Servo_Axis.set_location();
#endif
#ifdef SERVO_C_PIN
# endif
# ifdef SERVO_C_PIN
C_Servo_Axis.set_location();
#endif
# endif
vTaskDelayUntil(&xLastWakeTime, xServoFrequency);
}
}
// =============================== Class Stuff ================================= //
ServoAxis::ServoAxis(uint8_t axis, uint8_t pin_num) { // constructor
_axis = axis;
_pin_num = pin_num;
ServoAxis::ServoAxis(uint8_t axis, uint8_t pin_num) { // constructor
_axis = axis;
_pin_num = pin_num;
_channel_num = sys_get_next_PWM_chan_num();
_showError = true; // this will be used to show calibration error only once
_use_mpos = true; // default is to use the machine position rather than work position
_showError = true; // this will be used to show calibration error only once
_use_mpos = true; // default is to use the machine position rather than work position
}
void ServoAxis::init() {
@ -235,10 +234,10 @@ void ServoAxis::init() {
void ServoAxis::set_location() {
// These are the pulse lengths for the minimum and maximum positions
// Note: Some machines will have the physical max/min inverted with pulse length max/min due to invert setting $3=...
float servo_pulse_min, servo_pulse_max;
float min_pulse_cal, max_pulse_cal; // calibration values in percent 110% = 1.1
float servo_pulse_min, servo_pulse_max;
float min_pulse_cal, max_pulse_cal; // calibration values in percent 110% = 1.1
uint32_t servo_pulse_len;
float servo_pos, mpos, offset;
float servo_pos, mpos, offset;
// skip location if we are in alarm mode
if (_disable_on_alarm && (sys.state == STATE_ALARM)) {
disable();
@ -250,14 +249,14 @@ void ServoAxis::set_location() {
return;
}
if ((_homing_type == SERVO_HOMING_TARGET) && (sys.state == STATE_HOMING)) {
servo_pos = _homing_position; // go to servos home position
servo_pos = _homing_position; // go to servos home position
} else {
mpos = system_convert_axis_steps_to_mpos(sys_position, _axis); // get the axis machine position in mm
if (_use_mpos)
servo_pos = mpos;
else {
offset = gc_state.coord_system[_axis] + gc_state.coord_offset[_axis]; // get the current axis work offset
servo_pos = mpos - offset; // determine the current work position
offset = gc_state.coord_system[_axis] + gc_state.coord_offset[_axis]; // get the current axis work offset
servo_pos = mpos - offset; // determine the current work position
}
}
// 1. Get the pulse ranges of the servos
@ -270,17 +269,17 @@ void ServoAxis::set_location() {
if (bit_istrue(dir_invert_mask->get(), bit(_axis))) // this allows the user to change the direction via settings
swap(servo_pulse_min, servo_pulse_max);
// get the calibration values
if (_cal_is_valid()) { // if calibration settings are OK then apply them
if (_cal_is_valid()) { // if calibration settings are OK then apply them
// apply a calibration
// the cals apply differently if the direction is reverse (i.e. longer pulse is lower position)
if (bit_isfalse(dir_invert_mask->get(), bit(_axis))) { // normal direction
if (bit_isfalse(dir_invert_mask->get(), bit(_axis))) { // normal direction
min_pulse_cal = 2.0 - (axis_settings[_axis]->steps_per_mm->get() / 100.0);
max_pulse_cal = (axis_settings[_axis]->max_travel->get() / 100.0);
} else { // inverted direction
} else { // inverted direction
min_pulse_cal = (axis_settings[_axis]->steps_per_mm->get() / 100.0);
max_pulse_cal = 2.0 - (axis_settings[_axis]->max_travel->get() / -100.0);
}
} else { // settings are not valid so don't apply any calibration
} else { // settings are not valid so don't apply any calibration
min_pulse_cal = 1.0;
max_pulse_cal = 1.0;
}
@ -293,7 +292,7 @@ void ServoAxis::set_location() {
}
void ServoAxis::_write_pwm(uint32_t duty) {
if (ledcRead(_channel_num) != duty) // only write if it is changing
if (ledcRead(_channel_num) != duty) // only write if it is changing
ledcWrite(_channel_num, duty);
}
@ -319,7 +318,7 @@ bool ServoAxis::_cal_is_valid() {
if ((travel < -SERVO_CAL_MAX) || travel > -SERVO_CAL_MIN) {
if (_showError) {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo calibration ($13%d) value error. Reset to 100", _axis);
char reset_val[] = "-100"; // stored as a negative
char reset_val[] = "-100"; // stored as a negative
axis_settings[_axis]->max_travel->setStringValue(reset_val);
}
settingsOK = false;
@ -378,6 +377,4 @@ void ServoAxis::set_use_mpos(bool use_mpos) {
_use_mpos = use_mpos;
}
#endif

View File

@ -55,21 +55,20 @@
#include "Motors/RcServoClass.h"
#define SERVO_HOMING_OFF 0 // servo is off during homing
#define SERVO_HOMING_TARGET 1 // servo is send to a location during homing
#define SERVO_HOMING_OFF 0 // servo is off during homing
#define SERVO_HOMING_TARGET 1 // servo is send to a location during homing
extern float my_location;
void init_servos();
void servosSyncTask(void* pvParameters);
class ServoAxis {
public:
ServoAxis(uint8_t axis, uint8_t pin_num); // constructor
public:
ServoAxis(uint8_t axis, uint8_t pin_num); // constructor
void init();
void set_location();
void disable(); // sets PWM to 0% duty cycle. Most servos can be manually moved in this state
void disable(); // sets PWM to 0% duty cycle. Most servos can be manually moved in this state
void set_range(float min, float max);
void set_homing_type(uint8_t homing_type);
void set_homing_position(float homing_position);
@ -77,28 +76,26 @@ class ServoAxis {
void set_disable_with_steppers(bool disable_with_steppers);
void set_use_mpos(bool use_mpos);
private:
int _axis; // these should be assign in constructor using Grbl X_AXIS type values
int _pin_num; // The GPIO pin being used
int _channel_num; // The PWM channel
private:
int _axis; // these should be assign in constructor using Grbl X_AXIS type values
int _pin_num; // The GPIO pin being used
int _channel_num; // The PWM channel
bool _showError;
uint32_t _pwm_freq = SERVO_PULSE_FREQ;
uint32_t _pwm_freq = SERVO_PULSE_FREQ;
uint32_t _pwm_resolution_bits = SERVO_PULSE_RES_BITS;
float _pulse_min = SERVO_MIN_PULSE; // in pwm counts
float _pulse_max = SERVO_MAX_PULSE; // in pwm counts
float _position_min = SERVO_POSITION_MIN_DEFAULT; // position in millimeters
float _position_max = SERVO_POSITION_MAX_DEFAULT; // position in millimeters
float _pulse_min = SERVO_MIN_PULSE; // in pwm counts
float _pulse_max = SERVO_MAX_PULSE; // in pwm counts
float _position_min = SERVO_POSITION_MIN_DEFAULT; // position in millimeters
float _position_max = SERVO_POSITION_MAX_DEFAULT; // position in millimeters
uint8_t _homing_type = SERVO_HOMING_OFF;
float _homing_position = SERVO_POSITION_MAX_DEFAULT;
bool _disable_on_alarm = true;
bool _disable_with_steppers = false;
bool _use_mpos = true;
uint8_t _homing_type = SERVO_HOMING_OFF;
float _homing_position = SERVO_POSITION_MAX_DEFAULT;
bool _disable_on_alarm = true;
bool _disable_with_steppers = false;
bool _use_mpos = true;
bool _validate_cal_settings();
void _write_pwm(uint32_t duty);
bool _cal_is_valid(); // checks to see if calibration values are in acceptable range
bool _cal_is_valid(); // checks to see if calibration values are in acceptable range
};

View File

@ -24,11 +24,10 @@
#include "grbl.h"
// Read selected coordinate data from EEPROM. Updates pointed coord_data value.
uint8_t settings_read_coord_data(uint8_t coord_select, float* coord_data) {
uint32_t addr = coord_select * (sizeof(float) * N_AXIS + 1) + EEPROM_ADDR_PARAMETERS;
if (!(memcpy_from_eeprom_with_checksum((char*)coord_data, addr, sizeof(float)*N_AXIS))) {
if (!(memcpy_from_eeprom_with_checksum((char*)coord_data, addr, sizeof(float) * N_AXIS))) {
// Reset with default zero vector
clear_vector_float(coord_data);
settings_write_coord_data(coord_select, coord_data);
@ -43,7 +42,7 @@ void settings_write_coord_data(uint8_t coord_select, float* coord_data) {
protocol_buffer_synchronize();
#endif
uint32_t addr = coord_select * (sizeof(float) * N_AXIS + 1) + EEPROM_ADDR_PARAMETERS;
memcpy_to_eeprom_with_checksum(addr, (char*)coord_data, sizeof(float)*N_AXIS);
memcpy_to_eeprom_with_checksum(addr, (char*)coord_data, sizeof(float) * N_AXIS);
}
// Method to store build info into EEPROM
@ -57,7 +56,7 @@ void settings_store_build_info(const char* line) {
uint8_t settings_read_build_info(char* line) {
if (!(memcpy_from_eeprom_with_checksum((char*)line, EEPROM_ADDR_BUILD_INFO, LINE_BUFFER_SIZE))) {
// Reset line with default value
line[0] = 0; // Empty line
line[0] = 0; // Empty line
settings_store_build_info(line);
return (false);
}
@ -74,4 +73,3 @@ uint8_t get_step_pin_mask(uint8_t axis_idx) {
uint8_t get_direction_pin_mask(uint8_t axis_idx) {
return bit(axis_idx);
}

View File

@ -26,38 +26,37 @@
#include "grbl.h"
// Define status reporting boolean enable bit flags in status_report_mask
#define BITFLAG_RT_STATUS_POSITION_TYPE bit(0)
#define BITFLAG_RT_STATUS_BUFFER_STATE bit(1)
#define BITFLAG_RT_STATUS_POSITION_TYPE bit(0)
#define BITFLAG_RT_STATUS_BUFFER_STATE bit(1)
// Define settings restore bitflags.
#define SETTINGS_RESTORE_DEFAULTS bit(0)
#define SETTINGS_RESTORE_PARAMETERS bit(1)
#define SETTINGS_RESTORE_STARTUP_LINES bit(2)
#define SETTINGS_RESTORE_BUILD_INFO bit(3)
#define SETTINGS_RESTORE_WIFI_SETTINGS bit(4)
#define SETTINGS_RESTORE_WIFI_SETTINGS bit(4)
#ifndef SETTINGS_RESTORE_ALL
#define SETTINGS_RESTORE_ALL 0xFF // All bitflags
# define SETTINGS_RESTORE_ALL 0xFF // All bitflags
#endif
// Define EEPROM memory address location values for Grbl settings and parameters
// NOTE: The Atmega328p has 1KB EEPROM. The upper half is reserved for parameters and
// the startup script. The lower half contains the global settings and space for future
// developments.
#define EEPROM_SIZE 1024U
#define EEPROM_ADDR_PARAMETERS 512U
#define EEPROM_ADDR_BUILD_INFO 942U
#define EEPROM_SIZE 1024U
#define EEPROM_ADDR_PARAMETERS 512U
#define EEPROM_ADDR_BUILD_INFO 942U
// Define EEPROM address indexing for coordinate parameters
#define N_COORDINATE_SYSTEM 6 // Number of supported work coordinate systems (from index 1)
#define SETTING_INDEX_NCOORD N_COORDINATE_SYSTEM+1 // Total number of system stored (from index 0)
#define N_COORDINATE_SYSTEM 6 // Number of supported work coordinate systems (from index 1)
#define SETTING_INDEX_NCOORD N_COORDINATE_SYSTEM + 1 // Total number of system stored (from index 0)
// NOTE: Work coordinate indices are (0=G54, 1=G55, ... , 6=G59)
#define SETTING_INDEX_G28 N_COORDINATE_SYSTEM // Home position 1
#define SETTING_INDEX_G30 N_COORDINATE_SYSTEM+1 // Home position 2
#define SETTING_INDEX_G28 N_COORDINATE_SYSTEM // Home position 1
#define SETTING_INDEX_G30 N_COORDINATE_SYSTEM + 1 // Home position 2
// #define SETTING_INDEX_G92 N_COORDINATE_SYSTEM+2 // Coordinate offset (G92.2,G92.3 not supported)
#define USER_SETTING_COUNT 5 // for user to define for their machine
#define USER_SETTING_COUNT 5 // for user to define for their machine
// Initialize the configuration subsystem (load settings from EEPROM)
void settings_init();
@ -65,7 +64,7 @@ void settings_restore(uint8_t restore_flag);
void write_global_settings();
uint8_t settings_read_build_info(char* line);
void settings_store_build_info(const char* line);
void settings_store_build_info(const char* line);
// Writes selected coordinate data to EEPROM
void settings_write_coord_data(uint8_t coord_select, float* coord_data);

View File

@ -28,28 +28,28 @@ int8_t solenoid_pwm_chan_num;
static TaskHandle_t solenoidSyncTaskHandle = 0;
// used to delay turn on
bool solenoid_pen_enable;
bool solenoid_pen_enable;
uint16_t solenoide_hold_count;
void solenoid_init() {
grbl_send(CLIENT_SERIAL, "[MSG:Solenoid Mode]\r\n"); // startup message
//validate_servo_settings(true); // display any calibration errors
solenoid_pen_enable = false; // start delay has not completed yet.
solenoide_hold_count = 0; // initialize
solenoid_pen_enable = false; // start delay has not completed yet.
solenoide_hold_count = 0; // initialize
// setup PWM channel
solenoid_pwm_chan_num = sys_get_next_PWM_chan_num();
ledcSetup(solenoid_pwm_chan_num, SOLENOID_PWM_FREQ, SOLENOID_PWM_RES_BITS);
ledcAttachPin(SOLENOID_PEN_PIN, solenoid_pwm_chan_num);
solenoid_disable(); // start it it off
solenoid_disable(); // start it it off
// setup a task that will calculate the determine and set the servo position
xTaskCreatePinnedToCore(solenoidSyncTask, // task
"solenoidSyncTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
xTaskCreatePinnedToCore(solenoidSyncTask, // task
"solenoidSyncTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
&solenoidSyncTaskHandle,
0 // core
);
0 // core
);
}
// turn off the PWM (0 duty)
@ -59,20 +59,20 @@ void solenoid_disable() {
// this is the task
void solenoidSyncTask(void* pvParameters) {
int32_t current_position[N_AXIS]; // copy of current location
float m_pos[N_AXIS]; // machine position in mm
TickType_t xLastWakeTime;
const TickType_t xSolenoidFrequency = SOLENOID_TIMER_INT_FREQ; // in ticks (typically ms)
uint16_t solenoid_delay_counter = 0;
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) { // don't ever return from this or the task dies
int32_t current_position[N_AXIS]; // copy of current location
float m_pos[N_AXIS]; // machine position in mm
TickType_t xLastWakeTime;
const TickType_t xSolenoidFrequency = SOLENOID_TIMER_INT_FREQ; // in ticks (typically ms)
uint16_t solenoid_delay_counter = 0;
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) { // don't ever return from this or the task dies
if (!solenoid_pen_enable) {
solenoid_delay_counter++;
solenoid_pen_enable = (solenoid_delay_counter > SOLENOID_TURNON_DELAY);
} else {
memcpy(current_position, sys_position, sizeof(sys_position)); // get current position in step
system_convert_array_steps_to_mpos(m_pos, current_position); // convert to millimeters
calc_solenoid(m_pos[Z_AXIS]); // calculate kinematics and move the servos
memcpy(current_position, sys_position, sizeof(sys_position)); // get current position in step
system_convert_array_steps_to_mpos(m_pos, current_position); // convert to millimeters
calc_solenoid(m_pos[Z_AXIS]); // calculate kinematics and move the servos
}
vTaskDelayUntil(&xLastWakeTime, xSolenoidFrequency);
}
@ -81,11 +81,11 @@ void solenoidSyncTask(void* pvParameters) {
// calculate and set the PWM value for the servo
void calc_solenoid(float penZ) {
uint32_t solenoid_pen_pulse_len;
if (!solenoid_pen_enable) // only proceed if startup delay as expired
if (!solenoid_pen_enable) // only proceed if startup delay as expired
return;
if (penZ < 0 && (sys.state != STATE_ALARM)) { // alarm also makes it go up
solenoide_hold_count = 0; // reset this count
solenoid_pen_pulse_len = 0; //
solenoide_hold_count = 0; // reset this count
solenoid_pen_pulse_len = 0; //
} else {
if (solenoide_hold_count < SOLENOID_PULSE_LEN_HOLD) {
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_UP;
@ -105,4 +105,3 @@ void calc_solenoid(float penZ) {
}
#endif

View File

@ -35,34 +35,34 @@
*/
#ifndef SOLENOID_PWM_FREQ
#define SOLENOID_PWM_FREQ 5000
# define SOLENOID_PWM_FREQ 5000
#endif
#ifndef SOLENOID_PWM_RES_BITS
#define SOLENOID_PWM_RES_BITS 8
# define SOLENOID_PWM_RES_BITS 8
#endif
#ifndef SOLENOID_TURNON_DELAY
#define SOLENOID_TURNON_DELAY (SOLENOID_TIMER_INT_FREQ/2)
# define SOLENOID_TURNON_DELAY (SOLENOID_TIMER_INT_FREQ / 2)
#endif
#ifndef SOLENOID_PULSE_LEN_UP
#define SOLENOID_PULSE_LEN_UP 255
# define SOLENOID_PULSE_LEN_UP 255
#endif
#ifndef SOLENOID_HOLD_DELAY
#define SOLENOID_HOLD_DELAY (SOLENOID_TIMER_INT_FREQ/2) // in task counts...after this delay power will change to hold level
# define SOLENOID_HOLD_DELAY (SOLENOID_TIMER_INT_FREQ / 2) // in task counts...after this delay power will change to hold level
#endif
#ifndef SOLENOID_PULSE_LEN_HOLD
#define SOLENOID_PULSE_LEN_HOLD 80 // solenoid hold level ... typically a lower value to prevent overheating
# define SOLENOID_PULSE_LEN_HOLD 80 // solenoid hold level ... typically a lower value to prevent overheating
#endif
#ifndef SOLENOID_TIMER_INT_FREQ
#define SOLENOID_TIMER_INT_FREQ 50
# define SOLENOID_TIMER_INT_FREQ 50
#endif
void solenoid_init();
void solenoid_disable();
void solenoidSyncTask(void* pvParameters);
void calc_solenoid(float penZ);
void solenoid_init();
void solenoid_disable();
void solenoidSyncTask(void* pvParameters);
void calc_solenoid(float penZ);

File diff suppressed because it is too large Load Diff

View File

@ -25,16 +25,14 @@
*/
#ifndef SEGMENT_BUFFER_SIZE
#define SEGMENT_BUFFER_SIZE 6
# define SEGMENT_BUFFER_SIZE 6
#endif
#include "grbl.h"
#include "config.h"
// Some useful constants.
#define DT_SEGMENT (1.0/(ACCELERATION_TICKS_PER_SECOND*60.0)) // min/segment
#define DT_SEGMENT (1.0 / (ACCELERATION_TICKS_PER_SECOND * 60.0)) // min/segment
#define REQ_MM_INCREMENT_SCALAR 1.25
#define RAMP_ACCEL 0
#define RAMP_CRUISE 1
@ -59,21 +57,21 @@
#define MAX_AMASS_LEVEL 3
// AMASS_LEVEL0: Normal operation. No AMASS. No upper cutoff frequency. Starts at LEVEL1 cutoff frequency.
// Note ESP32 use F_STEPPER_TIMER rather than the AVR F_CPU
#define AMASS_LEVEL1 (F_STEPPER_TIMER/8000) // Over-drives ISR (x2). Defined as F_CPU/(Cutoff frequency in Hz)
#define AMASS_LEVEL2 (F_STEPPER_TIMER/4000) // Over-drives ISR (x4)
#define AMASS_LEVEL3 (F_STEPPER_TIMER/2000) // Over-drives ISR (x8)
#define AMASS_LEVEL1 (F_STEPPER_TIMER / 8000) // Over-drives ISR (x2). Defined as F_CPU/(Cutoff frequency in Hz)
#define AMASS_LEVEL2 (F_STEPPER_TIMER / 4000) // Over-drives ISR (x4)
#define AMASS_LEVEL3 (F_STEPPER_TIMER / 2000) // Over-drives ISR (x8)
#if MAX_AMASS_LEVEL <= 0
error "AMASS must have 1 or more levels to operate correctly."
error "AMASS must have 1 or more levels to operate correctly."
#endif
//#endif
#define STEP_TIMER_GROUP TIMER_GROUP_0
#define STEP_TIMER_INDEX TIMER_0
// esp32 work around for diable in main loop
extern uint64_t stepper_idle_counter;
extern bool stepper_idle;
// esp32 work around for diable in main loop
extern uint64_t stepper_idle_counter;
extern bool stepper_idle;
extern uint8_t ganged_mode;
@ -111,7 +109,7 @@ void st_update_plan_block_parameters();
float st_get_realtime_rate();
// disable (or enable) steppers via STEPPERS_DISABLE_PIN
bool get_stepper_disable(); // returns the state of the pin
bool get_stepper_disable(); // returns the state of the pin
void set_stepper_pins_on(uint8_t onMask);
void set_direction_pins_on(uint8_t onMask);

View File

@ -21,10 +21,10 @@
#include "grbl.h"
#include "config.h"
xQueueHandle control_sw_queue; // used by control switch debouncing
bool debouncing = false; // debouncing in process
xQueueHandle control_sw_queue; // used by control switch debouncing
bool debouncing = false; // debouncing in process
void system_ini() { // Renamed from system_init() due to conflict with esp32 files
void system_ini() { // Renamed from system_init() due to conflict with esp32 files
// setup control inputs
#ifdef CONTROL_SAFETY_DOOR_PIN
@ -70,7 +70,7 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fil
"controlCheckTask",
2048,
NULL,
5, // priority
5, // priority
NULL);
#endif
@ -81,19 +81,19 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fil
// Setup USER_DIGITAL_PINs controlled by M62 and M63
#ifdef USER_DIGITAL_PIN_1
pinMode(USER_DIGITAL_PIN_1, OUTPUT);
sys_io_control(bit(1), false); // turn off
sys_io_control(bit(1), false); // turn off
#endif
#ifdef USER_DIGITAL_PIN_2
pinMode(USER_DIGITAL_PIN_2, OUTPUT);
sys_io_control(bit(2), false); // turn off
sys_io_control(bit(2), false); // turn off
#endif
#ifdef USER_DIGITAL_PIN_3
pinMode(USER_DIGITAL_PIN_3, OUTPUT);
sys_io_control(bit(3), false); // turn off
sys_io_control(bit(3), false); // turn off
#endif
#ifdef USER_DIGITAL_PIN_4
pinMode(USER_DIGITAL_PIN_4, OUTPUT);
sys_io_control(bit(4), false); // turn off
sys_io_control(bit(4), false); // turn off
#endif
}
@ -102,8 +102,8 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fil
void controlCheckTask(void* pvParameters) {
while (true) {
int evt;
xQueueReceive(control_sw_queue, &evt, portMAX_DELAY); // block until receive queue
vTaskDelay(CONTROL_SW_DEBOUNCE_PERIOD); // delay a while
xQueueReceive(control_sw_queue, &evt, portMAX_DELAY); // block until receive queue
vTaskDelay(CONTROL_SW_DEBOUNCE_PERIOD); // delay a while
uint8_t pin = system_control_get_state();
if (pin)
system_exec_control_pin(pin);
@ -116,7 +116,7 @@ void IRAM_ATTR isr_control_inputs() {
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
// we will start a task that will recheck the switches after a small delay
int evt;
if (!debouncing) { // prevent resending until debounce is done
if (!debouncing) { // prevent resending until debounce is done
debouncing = true;
xQueueSendFromISR(control_sw_queue, &evt, NULL);
}
@ -131,7 +131,7 @@ uint8_t system_check_safety_door_ajar() {
#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
return (system_control_get_state() & CONTROL_PIN_INDEX_SAFETY_DOOR);
#else
return (false); // Input pin not enabled, so just return that it's closed.
return (false); // Input pin not enabled, so just return that it's closed.
#endif
}
@ -192,7 +192,6 @@ void system_clear_exec_accessory_overrides() {
//SREG = sreg;
}
void system_flag_wco_change() {
#ifdef FORCE_BUFFER_SYNC_DURING_WCO_CHANGE
protocol_buffer_synchronize();
@ -200,7 +199,6 @@ void system_flag_wco_change() {
sys.report_wco_counter = 0;
}
// Returns machine position of axis 'idx'. Must be sent a 'step' array.
// NOTE: If motor steps and machine position are not in the same coordinate frame, this function
// serves as a central place to compute the transformation.
@ -236,16 +234,20 @@ uint8_t system_check_travel_limits(float* target) {
uint8_t mask = homing_dir_mask->get();
// When homing forced set origin is enabled, soft limits checks need to account for directionality.
if (bit_istrue(mask, bit(idx))) {
if (target[idx] < 0 || target[idx] > travel) return (true);
if (target[idx] < 0 || target[idx] > travel)
return (true);
} else {
if (target[idx] > 0 || target[idx] < -travel) return (true);
if (target[idx] > 0 || target[idx] < -travel)
return (true);
}
#else
#ifdef HOMING_FORCE_POSITIVE_SPACE
if (target[idx] < 0 || target[idx] > travel) return (true);
#else
if (target[idx] > 0 || target[idx] < -travel) return (true);
#endif
# ifdef HOMING_FORCE_POSITIVE_SPACE
if (target[idx] < 0 || target[idx] > travel)
return (true);
# else
if (target[idx] > 0 || target[idx] < -travel)
return (true);
# endif
#endif
}
return (false);
@ -255,40 +257,48 @@ uint8_t system_check_travel_limits(float* target) {
// triggered is 1 and not triggered is 0. Invert mask is applied. Bitfield organization is
// defined by the CONTROL_PIN_INDEX in the header file.
uint8_t system_control_get_state() {
uint8_t defined_pin_mask = 0; // a mask of defined pins
uint8_t control_state = 0;
uint8_t defined_pin_mask = 0; // a mask of defined pins
uint8_t control_state = 0;
#ifdef CONTROL_SAFETY_DOOR_PIN
defined_pin_mask |= CONTROL_PIN_INDEX_SAFETY_DOOR;
if (digitalRead(CONTROL_SAFETY_DOOR_PIN)) control_state |= CONTROL_PIN_INDEX_SAFETY_DOOR;
if (digitalRead(CONTROL_SAFETY_DOOR_PIN))
control_state |= CONTROL_PIN_INDEX_SAFETY_DOOR;
#endif
#ifdef CONTROL_RESET_PIN
defined_pin_mask |= CONTROL_PIN_INDEX_RESET;
if (digitalRead(CONTROL_RESET_PIN)) control_state |= CONTROL_PIN_INDEX_RESET;
if (digitalRead(CONTROL_RESET_PIN))
control_state |= CONTROL_PIN_INDEX_RESET;
#endif
#ifdef CONTROL_FEED_HOLD_PIN
defined_pin_mask |= CONTROL_PIN_INDEX_FEED_HOLD;
if (digitalRead(CONTROL_FEED_HOLD_PIN)) control_state |= CONTROL_PIN_INDEX_FEED_HOLD;
if (digitalRead(CONTROL_FEED_HOLD_PIN))
control_state |= CONTROL_PIN_INDEX_FEED_HOLD;
#endif
#ifdef CONTROL_CYCLE_START_PIN
defined_pin_mask |= CONTROL_PIN_INDEX_CYCLE_START;
if (digitalRead(CONTROL_CYCLE_START_PIN)) control_state |= CONTROL_PIN_INDEX_CYCLE_START;
if (digitalRead(CONTROL_CYCLE_START_PIN))
control_state |= CONTROL_PIN_INDEX_CYCLE_START;
#endif
#ifdef MACRO_BUTTON_0_PIN
defined_pin_mask |= CONTROL_PIN_INDEX_MACRO_0;
if (digitalRead(MACRO_BUTTON_0_PIN)) control_state |= CONTROL_PIN_INDEX_MACRO_0;
if (digitalRead(MACRO_BUTTON_0_PIN))
control_state |= CONTROL_PIN_INDEX_MACRO_0;
#endif
#ifdef MACRO_BUTTON_1_PIN
defined_pin_mask |= CONTROL_PIN_INDEX_MACRO_1;
if (digitalRead(MACRO_BUTTON_1_PIN)) control_state |= CONTROL_PIN_INDEX_MACRO_1;
if (digitalRead(MACRO_BUTTON_1_PIN))
control_state |= CONTROL_PIN_INDEX_MACRO_1;
#endif
#ifdef MACRO_BUTTON_2_PIN
defined_pin_mask |= CONTROL_PIN_INDEX_MACRO_2;
if (digitalRead(MACRO_BUTTON_2_PIN)) control_state |= CONTROL_PIN_INDEX_MACRO_2;
if (digitalRead(MACRO_BUTTON_2_PIN))
control_state |= CONTROL_PIN_INDEX_MACRO_2;
#endif
#ifdef MACRO_BUTTON_3_PIN
defined_pin_mask |= CONTROL_PIN_INDEX_MACRO_3;
if (digitalRead(MACRO_BUTTON_3_PIN)) control_state |= CONTROL_PIN_INDEX_MACRO_3;
if (digitalRead(MACRO_BUTTON_3_PIN))
control_state |= CONTROL_PIN_INDEX_MACRO_3;
#endif
#ifdef INVERT_CONTROL_PIN_MASK
control_state ^= (INVERT_CONTROL_PIN_MASK & defined_pin_mask);
@ -309,22 +319,22 @@ void system_exec_control_pin(uint8_t pin) {
bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR);
#ifdef MACRO_BUTTON_0_PIN
else if (bit_istrue(pin, CONTROL_PIN_INDEX_MACRO_0)) {
user_defined_macro(CONTROL_PIN_INDEX_MACRO_0); // function must be implemented by user
user_defined_macro(CONTROL_PIN_INDEX_MACRO_0); // function must be implemented by user
}
#endif
#ifdef MACRO_BUTTON_1_PIN
else if (bit_istrue(pin, CONTROL_PIN_INDEX_MACRO_1)) {
user_defined_macro(CONTROL_PIN_INDEX_MACRO_1); // function must be implemented by user
user_defined_macro(CONTROL_PIN_INDEX_MACRO_1); // function must be implemented by user
}
#endif
#ifdef MACRO_BUTTON_2_PIN
else if (bit_istrue(pin, CONTROL_PIN_INDEX_MACRO_2)) {
user_defined_macro(CONTROL_PIN_INDEX_MACRO_2); // function must be implemented by user
user_defined_macro(CONTROL_PIN_INDEX_MACRO_2); // function must be implemented by user
}
#endif
#ifdef MACRO_BUTTON_3_PIN
else if (bit_istrue(pin, CONTROL_PIN_INDEX_MACRO_3)) {
user_defined_macro(CONTROL_PIN_INDEX_MACRO_3); // function must be implemented by user
user_defined_macro(CONTROL_PIN_INDEX_MACRO_3); // function must be implemented by user
}
#endif
}
@ -374,12 +384,11 @@ void fast_sys_io_control(uint8_t io_num_mask, bool turnOn) {
#endif
}
// Call this function to get an RMT channel number
// returns -1 for error
int8_t sys_get_next_RMT_chan_num() {
static uint8_t next_RMT_chan_num = 0; // channels 0-7 are valid
if (next_RMT_chan_num < 8) // 7 is the max PWM channel number
static uint8_t next_RMT_chan_num = 0; // channels 0-7 are valid
if (next_RMT_chan_num < 8) // 7 is the max PWM channel number
return next_RMT_chan_num++;
else {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_ERROR, "Error: out of RMT channels");
@ -387,7 +396,6 @@ int8_t sys_get_next_RMT_chan_num() {
}
}
/*
This returns an unused pwm channel.
The 8 channels share 4 timers, so pairs 0,1 & 2,3 , etc
@ -398,8 +406,8 @@ int8_t sys_get_next_RMT_chan_num() {
TODO: Make this more robust.
*/
int8_t sys_get_next_PWM_chan_num() {
static uint8_t next_PWM_chan_num = 2; // start at 2 to avoid spindle
if (next_PWM_chan_num < 8) // 7 is the max PWM channel number
static uint8_t next_PWM_chan_num = 2; // start at 2 to avoid spindle
if (next_PWM_chan_num < 8) // 7 is the max PWM channel number
return next_PWM_chan_num++;
else {
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_ERROR, "Error: out of PWM channels");

View File

@ -40,7 +40,7 @@ typedef struct {
uint8_t report_ovr_counter; // Tracks when to add override data to status reports.
uint8_t report_wco_counter; // Tracks when to add work coordinate offset data to status reports.
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
uint8_t override_ctrl; // Tracks override control states.
uint8_t override_ctrl; // Tracks override control states.
#endif
uint32_t spindle_speed;
@ -48,98 +48,95 @@ typedef struct {
} system_t;
extern system_t sys;
// Define system executor bit map. Used internally by realtime protocol as realtime command flags,
// which notifies the main program to execute the specified realtime command asynchronously.
// NOTE: The system executor uses an unsigned 8-bit volatile variable (8 flag limit.) The default
// flags are always false, so the realtime protocol only needs to check for a non-zero value to
// know when there is a realtime command to execute.
#define EXEC_STATUS_REPORT bit(0) // bitmask 00000001
#define EXEC_CYCLE_START bit(1) // bitmask 00000010
#define EXEC_CYCLE_STOP bit(2) // bitmask 00000100
#define EXEC_FEED_HOLD bit(3) // bitmask 00001000
#define EXEC_RESET bit(4) // bitmask 00010000
#define EXEC_SAFETY_DOOR bit(5) // bitmask 00100000
#define EXEC_MOTION_CANCEL bit(6) // bitmask 01000000
#define EXEC_SLEEP bit(7) // bitmask 10000000
#define EXEC_STATUS_REPORT bit(0) // bitmask 00000001
#define EXEC_CYCLE_START bit(1) // bitmask 00000010
#define EXEC_CYCLE_STOP bit(2) // bitmask 00000100
#define EXEC_FEED_HOLD bit(3) // bitmask 00001000
#define EXEC_RESET bit(4) // bitmask 00010000
#define EXEC_SAFETY_DOOR bit(5) // bitmask 00100000
#define EXEC_MOTION_CANCEL bit(6) // bitmask 01000000
#define EXEC_SLEEP bit(7) // bitmask 10000000
// Alarm executor codes. Valid values (1-255). Zero is reserved.
#define EXEC_ALARM_HARD_LIMIT 1
#define EXEC_ALARM_SOFT_LIMIT 2
#define EXEC_ALARM_ABORT_CYCLE 3
#define EXEC_ALARM_PROBE_FAIL_INITIAL 4
#define EXEC_ALARM_PROBE_FAIL_CONTACT 5
#define EXEC_ALARM_HOMING_FAIL_RESET 6
#define EXEC_ALARM_HOMING_FAIL_DOOR 7
#define EXEC_ALARM_HOMING_FAIL_PULLOFF 8
#define EXEC_ALARM_HARD_LIMIT 1
#define EXEC_ALARM_SOFT_LIMIT 2
#define EXEC_ALARM_ABORT_CYCLE 3
#define EXEC_ALARM_PROBE_FAIL_INITIAL 4
#define EXEC_ALARM_PROBE_FAIL_CONTACT 5
#define EXEC_ALARM_HOMING_FAIL_RESET 6
#define EXEC_ALARM_HOMING_FAIL_DOOR 7
#define EXEC_ALARM_HOMING_FAIL_PULLOFF 8
#define EXEC_ALARM_HOMING_FAIL_APPROACH 9
#define EXEC_ALARM_SPINDLE_CONTROL 10
#define EXEC_ALARM_SPINDLE_CONTROL 10
// Override bit maps. Realtime bitflags to control feed, rapid, spindle, and coolant overrides.
// Spindle/coolant and feed/rapids are separated into two controlling flag variables.
#define EXEC_FEED_OVR_RESET bit(0)
#define EXEC_FEED_OVR_COARSE_PLUS bit(1)
#define EXEC_FEED_OVR_COARSE_MINUS bit(2)
#define EXEC_FEED_OVR_FINE_PLUS bit(3)
#define EXEC_FEED_OVR_FINE_MINUS bit(4)
#define EXEC_RAPID_OVR_RESET bit(5)
#define EXEC_RAPID_OVR_MEDIUM bit(6)
#define EXEC_RAPID_OVR_LOW bit(7)
#define EXEC_FEED_OVR_RESET bit(0)
#define EXEC_FEED_OVR_COARSE_PLUS bit(1)
#define EXEC_FEED_OVR_COARSE_MINUS bit(2)
#define EXEC_FEED_OVR_FINE_PLUS bit(3)
#define EXEC_FEED_OVR_FINE_MINUS bit(4)
#define EXEC_RAPID_OVR_RESET bit(5)
#define EXEC_RAPID_OVR_MEDIUM bit(6)
#define EXEC_RAPID_OVR_LOW bit(7)
// #define EXEC_RAPID_OVR_EXTRA_LOW bit(*) // *NOT SUPPORTED*
#define EXEC_SPINDLE_OVR_RESET bit(0)
#define EXEC_SPINDLE_OVR_COARSE_PLUS bit(1)
#define EXEC_SPINDLE_OVR_COARSE_MINUS bit(2)
#define EXEC_SPINDLE_OVR_FINE_PLUS bit(3)
#define EXEC_SPINDLE_OVR_FINE_MINUS bit(4)
#define EXEC_SPINDLE_OVR_STOP bit(5)
#define EXEC_COOLANT_FLOOD_OVR_TOGGLE bit(6)
#define EXEC_COOLANT_MIST_OVR_TOGGLE bit(7)
#define EXEC_SPINDLE_OVR_RESET bit(0)
#define EXEC_SPINDLE_OVR_COARSE_PLUS bit(1)
#define EXEC_SPINDLE_OVR_COARSE_MINUS bit(2)
#define EXEC_SPINDLE_OVR_FINE_PLUS bit(3)
#define EXEC_SPINDLE_OVR_FINE_MINUS bit(4)
#define EXEC_SPINDLE_OVR_STOP bit(5)
#define EXEC_COOLANT_FLOOD_OVR_TOGGLE bit(6)
#define EXEC_COOLANT_MIST_OVR_TOGGLE bit(7)
// Define system state bit map. The state variable primarily tracks the individual functions
// of Grbl to manage each without overlapping. It is also used as a messaging flag for
// critical events.
#define STATE_IDLE 0 // Must be zero. No flags.
#define STATE_ALARM bit(0) // In alarm state. Locks out all g-code processes. Allows settings access.
#define STATE_CHECK_MODE bit(1) // G-code check mode. Locks out planner and motion only.
#define STATE_HOMING bit(2) // Performing homing cycle
#define STATE_CYCLE bit(3) // Cycle is running or motions are being executed.
#define STATE_HOLD bit(4) // Active feed hold
#define STATE_JOG bit(5) // Jogging mode.
#define STATE_SAFETY_DOOR bit(6) // Safety door is ajar. Feed holds and de-energizes system.
#define STATE_SLEEP bit(7) // Sleep state.
#define STATE_IDLE 0 // Must be zero. No flags.
#define STATE_ALARM bit(0) // In alarm state. Locks out all g-code processes. Allows settings access.
#define STATE_CHECK_MODE bit(1) // G-code check mode. Locks out planner and motion only.
#define STATE_HOMING bit(2) // Performing homing cycle
#define STATE_CYCLE bit(3) // Cycle is running or motions are being executed.
#define STATE_HOLD bit(4) // Active feed hold
#define STATE_JOG bit(5) // Jogging mode.
#define STATE_SAFETY_DOOR bit(6) // Safety door is ajar. Feed holds and de-energizes system.
#define STATE_SLEEP bit(7) // Sleep state.
// Define system suspend flags. Used in various ways to manage suspend states and procedures.
#define SUSPEND_DISABLE 0 // Must be zero.
#define SUSPEND_HOLD_COMPLETE bit(0) // Indicates initial feed hold is complete.
#define SUSPEND_RESTART_RETRACT bit(1) // Flag to indicate a retract from a restore parking motion.
#define SUSPEND_RETRACT_COMPLETE bit(2) // (Safety door only) Indicates retraction and de-energizing is complete.
#define SUSPEND_INITIATE_RESTORE bit(3) // (Safety door only) Flag to initiate resume procedures from a cycle start.
#define SUSPEND_RESTORE_COMPLETE bit(4) // (Safety door only) Indicates ready to resume normal operation.
#define SUSPEND_SAFETY_DOOR_AJAR bit(5) // Tracks safety door state for resuming.
#define SUSPEND_MOTION_CANCEL bit(6) // Indicates a canceled resume motion. Currently used by probing routine.
#define SUSPEND_JOG_CANCEL bit(7) // Indicates a jog cancel in process and to reset buffers when complete.
#define SUSPEND_DISABLE 0 // Must be zero.
#define SUSPEND_HOLD_COMPLETE bit(0) // Indicates initial feed hold is complete.
#define SUSPEND_RESTART_RETRACT bit(1) // Flag to indicate a retract from a restore parking motion.
#define SUSPEND_RETRACT_COMPLETE bit(2) // (Safety door only) Indicates retraction and de-energizing is complete.
#define SUSPEND_INITIATE_RESTORE bit(3) // (Safety door only) Flag to initiate resume procedures from a cycle start.
#define SUSPEND_RESTORE_COMPLETE bit(4) // (Safety door only) Indicates ready to resume normal operation.
#define SUSPEND_SAFETY_DOOR_AJAR bit(5) // Tracks safety door state for resuming.
#define SUSPEND_MOTION_CANCEL bit(6) // Indicates a canceled resume motion. Currently used by probing routine.
#define SUSPEND_JOG_CANCEL bit(7) // Indicates a jog cancel in process and to reset buffers when complete.
// Define step segment generator state flags.
#define STEP_CONTROL_NORMAL_OP 0 // Must be zero.
#define STEP_CONTROL_END_MOTION bit(0)
#define STEP_CONTROL_EXECUTE_HOLD bit(1)
#define STEP_CONTROL_EXECUTE_SYS_MOTION bit(2)
#define STEP_CONTROL_UPDATE_SPINDLE_RPM bit(3)
#define STEP_CONTROL_NORMAL_OP 0 // Must be zero.
#define STEP_CONTROL_END_MOTION bit(0)
#define STEP_CONTROL_EXECUTE_HOLD bit(1)
#define STEP_CONTROL_EXECUTE_SYS_MOTION bit(2)
#define STEP_CONTROL_UPDATE_SPINDLE_RPM bit(3)
// Define control pin index for Grbl internal use. Pin maps may change, but these values don't.
//#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
#define N_CONTROL_PIN 4
#define CONTROL_PIN_INDEX_SAFETY_DOOR bit(0)
#define CONTROL_PIN_INDEX_RESET bit(1)
#define CONTROL_PIN_INDEX_FEED_HOLD bit(2)
#define CONTROL_PIN_INDEX_CYCLE_START bit(3)
#define CONTROL_PIN_INDEX_MACRO_0 bit(4)
#define CONTROL_PIN_INDEX_MACRO_1 bit(5)
#define CONTROL_PIN_INDEX_MACRO_2 bit(6)
#define CONTROL_PIN_INDEX_MACRO_3 bit(7)
#define CONTROL_PIN_INDEX_SAFETY_DOOR bit(0)
#define CONTROL_PIN_INDEX_RESET bit(1)
#define CONTROL_PIN_INDEX_FEED_HOLD bit(2)
#define CONTROL_PIN_INDEX_CYCLE_START bit(3)
#define CONTROL_PIN_INDEX_MACRO_0 bit(4)
#define CONTROL_PIN_INDEX_MACRO_1 bit(5)
#define CONTROL_PIN_INDEX_MACRO_2 bit(6)
#define CONTROL_PIN_INDEX_MACRO_3 bit(7)
//#else
//#define N_CONTROL_PIN 3
//#define CONTROL_PIN_INDEX_RESET bit(0)
@ -148,29 +145,28 @@ extern system_t sys;
//#endif
// Define spindle stop override control states.
#define SPINDLE_STOP_OVR_DISABLED 0 // Must be zero.
#define SPINDLE_STOP_OVR_ENABLED bit(0)
#define SPINDLE_STOP_OVR_INITIATE bit(1)
#define SPINDLE_STOP_OVR_RESTORE bit(2)
#define SPINDLE_STOP_OVR_RESTORE_CYCLE bit(3)
#define SPINDLE_STOP_OVR_DISABLED 0 // Must be zero.
#define SPINDLE_STOP_OVR_ENABLED bit(0)
#define SPINDLE_STOP_OVR_INITIATE bit(1)
#define SPINDLE_STOP_OVR_RESTORE bit(2)
#define SPINDLE_STOP_OVR_RESTORE_CYCLE bit(3)
// NOTE: These position variables may need to be declared as volatiles, if problems arise.
extern int32_t sys_position[N_AXIS]; // Real-time machine (aka home) position vector in steps.
extern int32_t sys_probe_position[N_AXIS]; // Last probe position in machine coordinates and steps.
extern int32_t sys_position[N_AXIS]; // Real-time machine (aka home) position vector in steps.
extern int32_t sys_probe_position[N_AXIS]; // Last probe position in machine coordinates and steps.
extern volatile uint8_t sys_probe_state; // Probing state value. Used to coordinate the probing cycle with stepper ISR.
extern volatile uint8_t sys_rt_exec_state; // Global realtime executor bitflag variable for state management. See EXEC bitmasks.
extern volatile uint8_t sys_rt_exec_alarm; // Global realtime executor bitflag variable for setting various alarms.
extern volatile uint8_t sys_rt_exec_motion_override; // Global realtime executor bitflag variable for motion-based overrides.
extern volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bitflag variable for spindle/coolant overrides.
extern volatile uint8_t sys_probe_state; // Probing state value. Used to coordinate the probing cycle with stepper ISR.
extern volatile uint8_t sys_rt_exec_state; // Global realtime executor bitflag variable for state management. See EXEC bitmasks.
extern volatile uint8_t sys_rt_exec_alarm; // Global realtime executor bitflag variable for setting various alarms.
extern volatile uint8_t sys_rt_exec_motion_override; // Global realtime executor bitflag variable for motion-based overrides.
extern volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bitflag variable for spindle/coolant overrides.
#ifdef DEBUG
#define EXEC_DEBUG_REPORT bit(0)
extern volatile uint8_t sys_rt_exec_debug;
# define EXEC_DEBUG_REPORT bit(0)
extern volatile uint8_t sys_rt_exec_debug;
#endif
void system_ini(); // Renamed from system_init() due to conflict with esp32 files
void system_ini(); // Renamed from system_init() due to conflict with esp32 files
// Returns bitfield of control pin states, organized by CONTROL_PIN_INDEX. (1=triggered, 0=not triggered).
uint8_t system_control_get_state();
@ -191,12 +187,12 @@ void system_clear_exec_motion_overrides();
void system_clear_exec_accessory_overrides();
// Execute the startup script lines stored in EEPROM upon initialization
void system_execute_startup(char* line);
void system_execute_startup(char* line);
uint8_t execute_line(char* line, uint8_t client, auth_t auth_level);
uint8_t system_execute_line(char* line, ESPResponseStream*, auth_t);
uint8_t system_execute_line(char* line, uint8_t client, auth_t);
uint8_t do_command_or_setting(const char *key, char *value, auth_t auth_level, ESPResponseStream*);
void system_flag_wco_change();
uint8_t do_command_or_setting(const char* key, char* value, auth_t auth_level, ESPResponseStream*);
void system_flag_wco_change();
// Returns machine position of axis 'idx'. Must be sent a 'step' array.
float system_convert_axis_steps_to_mpos(int32_t* steps, uint8_t idx);
@ -217,7 +213,6 @@ void system_set_exec_accessory_override_flag(uint8_t mask);
void system_clear_exec_motion_overrides();
void system_clear_exec_accessory_overrides();
int32_t system_convert_corexy_to_x_axis_steps(int32_t* steps);
int32_t system_convert_corexy_to_y_axis_steps(int32_t* steps);

View File

@ -18,30 +18,28 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifdef ARDUINO_ARCH_ESP32
#include "grbl.h"
#if defined (ENABLE_WIFI) && defined (ENABLE_TELNET)
#if defined(ENABLE_WIFI) && defined(ENABLE_TELNET)
#include "wifiservices.h"
# include "wifiservices.h"
#include "telnet_server.h"
#include "wificonfig.h"
#include <WiFi.h>
# include "telnet_server.h"
# include "wificonfig.h"
# include <WiFi.h>
Telnet_Server telnet_server;
bool Telnet_Server::_setupdone = false;
uint16_t Telnet_Server::_port = 0;
WiFiServer* Telnet_Server::_telnetserver = NULL;
WiFiClient Telnet_Server::_telnetClients[MAX_TLNT_CLIENTS];
#ifdef ENABLE_TELNET_WELCOME_MSG
IPAddress Telnet_Server::_telnetClientsIP[MAX_TLNT_CLIENTS];
#endif
bool Telnet_Server::_setupdone = false;
uint16_t Telnet_Server::_port = 0;
WiFiServer* Telnet_Server::_telnetserver = NULL;
WiFiClient Telnet_Server::_telnetClients[MAX_TLNT_CLIENTS];
# ifdef ENABLE_TELNET_WELCOME_MSG
IPAddress Telnet_Server::_telnetClientsIP[MAX_TLNT_CLIENTS];
# endif
Telnet_Server::Telnet_Server() {
_RXbufferSize = 0;
_RXbufferpos = 0;
_RXbufferpos = 0;
}
Telnet_Server::~Telnet_Server() {
end();
@ -51,7 +49,8 @@ bool Telnet_Server::begin() {
bool no_error = true;
end();
_RXbufferSize = 0;
_RXbufferpos = 0;;
_RXbufferpos = 0;
;
if (telnet_enable->get() == 0) {
return false;
}
@ -69,9 +68,9 @@ bool Telnet_Server::begin() {
}
void Telnet_Server::end() {
_setupdone = false;
_setupdone = false;
_RXbufferSize = 0;
_RXbufferpos = 0;
_RXbufferpos = 0;
if (_telnetserver) {
delete _telnetserver;
_telnetserver = NULL;
@ -85,10 +84,11 @@ void Telnet_Server::clearClients() {
for (i = 0; i < MAX_TLNT_CLIENTS; i++) {
//find free/disconnected spot
if (!_telnetClients[i] || !_telnetClients[i].connected()) {
#ifdef ENABLE_TELNET_WELCOME_MSG
# ifdef ENABLE_TELNET_WELCOME_MSG
_telnetClientsIP[i] = IPAddress(0, 0, 0, 0);
#endif
if (_telnetClients[i]) _telnetClients[i].stop();
# endif
if (_telnetClients[i])
_telnetClients[i].stop();
_telnetClients[i] = _telnetserver->available();
break;
}
@ -129,19 +129,21 @@ void Telnet_Server::handle() {
//uint8_t c;
for (uint8_t i = 0; i < MAX_TLNT_CLIENTS; i++) {
if (_telnetClients[i] && _telnetClients[i].connected()) {
#ifdef ENABLE_TELNET_WELCOME_MSG
# ifdef ENABLE_TELNET_WELCOME_MSG
if (_telnetClientsIP[i] != _telnetClients[i].remoteIP()) {
report_init_message(CLIENT_TELNET);
_telnetClientsIP[i] = _telnetClients[i].remoteIP();
}
#endif
# endif
if (_telnetClients[i].available()) {
uint8_t buf[1024];
COMMANDS::wait(0);
int readlen = _telnetClients[i].available();
int readlen = _telnetClients[i].available();
int writelen = TELNETRXBUFFERSIZE - available();
if (readlen > 1024) readlen = 1024;
if (readlen > writelen) readlen = writelen;
if (readlen > 1024)
readlen = 1024;
if (readlen > writelen)
readlen = writelen;
if (readlen > 0) {
_telnetClients[i].read(buf, readlen);
push(buf, readlen);
@ -150,9 +152,9 @@ void Telnet_Server::handle() {
}
} else {
if (_telnetClients[i]) {
#ifdef ENABLE_TELNET_WELCOME_MSG
# ifdef ENABLE_TELNET_WELCOME_MSG
_telnetClientsIP[i] = IPAddress(0, 0, 0, 0);
#endif
# endif
_telnetClients[i].stop();
}
}
@ -161,8 +163,10 @@ void Telnet_Server::handle() {
}
int Telnet_Server::peek(void) {
if (_RXbufferSize > 0)return _RXbuffer[_RXbufferpos];
else return -1;
if (_RXbufferSize > 0)
return _RXbuffer[_RXbufferpos];
else
return -1;
}
int Telnet_Server::available() {
@ -177,8 +181,10 @@ bool Telnet_Server::push(uint8_t data) {
log_i("[TELNET]push %c", data);
if ((1 + _RXbufferSize) <= TELNETRXBUFFERSIZE) {
int current = _RXbufferpos + _RXbufferSize;
if (current > TELNETRXBUFFERSIZE) current = current - TELNETRXBUFFERSIZE;
if (current > (TELNETRXBUFFERSIZE - 1)) current = 0;
if (current > TELNETRXBUFFERSIZE)
current = current - TELNETRXBUFFERSIZE;
if (current > (TELNETRXBUFFERSIZE - 1))
current = 0;
_RXbuffer[current] = data;
_RXbufferSize++;
log_i("[TELNET]buffer size %d", _RXbufferSize);
@ -190,13 +196,15 @@ bool Telnet_Server::push(uint8_t data) {
bool Telnet_Server::push(const uint8_t* data, int data_size) {
if ((data_size + _RXbufferSize) <= TELNETRXBUFFERSIZE) {
int data_processed = 0;
int current = _RXbufferpos + _RXbufferSize;
if (current > TELNETRXBUFFERSIZE) current = current - TELNETRXBUFFERSIZE;
int current = _RXbufferpos + _RXbufferSize;
if (current > TELNETRXBUFFERSIZE)
current = current - TELNETRXBUFFERSIZE;
for (int i = 0; i < data_size; i++) {
if (current > (TELNETRXBUFFERSIZE - 1)) current = 0;
if (current > (TELNETRXBUFFERSIZE - 1))
current = 0;
if (char(data[i]) != '\r') {
_RXbuffer[current] = data[i];
current ++;
current++;
data_processed++;
}
COMMANDS::wait(0);
@ -213,12 +221,12 @@ int Telnet_Server::read(void) {
int v = _RXbuffer[_RXbufferpos];
//log_d("[TELNET]read %c",char(v));
_RXbufferpos++;
if (_RXbufferpos > (TELNETRXBUFFERSIZE - 1))_RXbufferpos = 0;
if (_RXbufferpos > (TELNETRXBUFFERSIZE - 1))
_RXbufferpos = 0;
_RXbufferSize--;
return v;
} else return -1;
} else
return -1;
}
#endif // Enable TELNET && ENABLE_WIFI
#endif // ARDUINO_ARCH_ESP32
#endif // Enable TELNET && ENABLE_WIFI

View File

@ -31,33 +31,34 @@ class WiFiClient;
#define FLUSHTIMEOUT 500
class Telnet_Server {
public:
public:
Telnet_Server();
~Telnet_Server();
bool begin();
void end();
void handle();
size_t write(const uint8_t* buffer, size_t size);
int read(void);
int peek(void);
int available();
int get_rx_buffer_available();
bool push(uint8_t data);
bool push(const uint8_t* data, int datasize);
static uint16_t port() {return _port;}
private:
static bool _setupdone;
bool begin();
void end();
void handle();
size_t write(const uint8_t* buffer, size_t size);
int read(void);
int peek(void);
int available();
int get_rx_buffer_available();
bool push(uint8_t data);
bool push(const uint8_t* data, int datasize);
static uint16_t port() { return _port; }
private:
static bool _setupdone;
static WiFiServer* _telnetserver;
static WiFiClient _telnetClients[MAX_TLNT_CLIENTS];
static WiFiClient _telnetClients[MAX_TLNT_CLIENTS];
#ifdef ENABLE_TELNET_WELCOME_MSG
static IPAddress _telnetClientsIP[MAX_TLNT_CLIENTS];
#endif
static uint16_t _port;
void clearClients();
uint32_t _lastflush;
uint8_t _RXbuffer[TELNETRXBUFFERSIZE];
uint16_t _RXbufferSize;
uint16_t _RXbufferpos;
void clearClients();
uint32_t _lastflush;
uint8_t _RXbuffer[TELNETRXBUFFERSIZE];
uint16_t _RXbufferSize;
uint16_t _RXbufferpos;
};
extern Telnet_Server telnet_server;

File diff suppressed because it is too large Load Diff

View File

@ -28,41 +28,42 @@ class WebServer;
#ifdef ENABLE_AUTHENTICATION
struct auth_ip {
IPAddress ip;
auth_t level;
char userID[17];
char sessionID[17];
uint32_t last_time;
auth_ip* _next;
auth_t level;
char userID[17];
char sessionID[17];
uint32_t last_time;
auth_ip* _next;
};
#endif
class Web_Server {
public:
public:
Web_Server();
~Web_Server();
bool begin();
void end();
void handle();
static long get_client_ID();
static uint16_t port() {return _port;}
private:
static bool _setupdone;
static WebServer* _webserver;
static long _id_connection;
bool begin();
void end();
void handle();
static long get_client_ID();
static uint16_t port() { return _port; }
private:
static bool _setupdone;
static WebServer* _webserver;
static long _id_connection;
static WebSocketsServer* _socket_server;
static uint16_t _port;
static uint8_t _upload_status;
static String getContentType(String filename);
static String get_Splited_Value(String data, char separator, int index);
static auth_t is_authenticated();
static uint16_t _port;
static uint8_t _upload_status;
static String getContentType(String filename);
static String get_Splited_Value(String data, char separator, int index);
static auth_t is_authenticated();
#ifdef ENABLE_AUTHENTICATION
static auth_ip* _head;
static uint8_t _nb_ip;
static bool AddAuthIP(auth_ip* item);
static char* create_session_ID();
static bool ClearAuthIP(IPAddress ip, const char* sessionID);
static uint8_t _nb_ip;
static bool AddAuthIP(auth_ip* item);
static char* create_session_ID();
static bool ClearAuthIP(IPAddress ip, const char* sessionID);
static auth_ip* GetAuth(IPAddress ip, const char* sessionID);
static auth_t ResetAuthIP(IPAddress ip, const char* sessionID);
static auth_t ResetAuthIP(IPAddress ip, const char* sessionID);
#endif
#ifdef ENABLE_SSDP
static void handle_SSDP();
@ -79,7 +80,7 @@ class Web_Server {
static void handleUpdate();
static void WebUpdateUpload();
static bool is_realtime_cmd(char c);
static void pushError(int code, const char* st, bool web_error = 500, uint16_t timeout = 1000);
static void pushError(int code, const char* st, bool web_error = 500, uint16_t timeout = 1000);
static void cancelUpload();
#ifdef ENABLE_SD_CARD
static void handle_direct_SDFileList();

Some files were not shown because too many files have changed in this diff Show More