diff --git a/.clang-format b/.clang-format
new file mode 100644
index 00000000..97d41b66
--- /dev/null
+++ b/.clang-format
@@ -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
+
+...
diff --git a/.editorconfig b/.editorconfig
new file mode 100644
index 00000000..6553990d
--- /dev/null
+++ b/.editorconfig
@@ -0,0 +1,4 @@
+root = true
+
+[*]
+insert_final_newline = true
\ No newline at end of file
diff --git a/CodingStyle.md b/CodingStyle.md
new file mode 100644
index 00000000..a73dde4a
--- /dev/null
+++ b/CodingStyle.md
@@ -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 `_10V`.
+- 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!
diff --git a/Grbl_Esp32/Custom/atari_1020.cpp b/Grbl_Esp32/Custom/atari_1020.cpp
index b111a20f..427560d8 100644
--- a/Grbl_Esp32/Custom/atari_1020.cpp
+++ b/Grbl_Esp32/Custom/atari_1020.cpp
@@ -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);
}
diff --git a/Grbl_Esp32/Custom/custom_code_template.cpp b/Grbl_Esp32/Custom/custom_code_template.cpp
index 1c68d67b..0e6f0779 100644
--- a/Grbl_Esp32/Custom/custom_code_template.cpp
+++ b/Grbl_Esp32/Custom/custom_code_template.cpp
@@ -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
diff --git a/Grbl_Esp32/Custom/esp32_printer_controller.cpp b/Grbl_Esp32/Custom/esp32_printer_controller.cpp
index c232a068..8fd3ef2f 100644
--- a/Grbl_Esp32/Custom/esp32_printer_controller.cpp
+++ b/Grbl_Esp32/Custom/esp32_printer_controller.cpp
@@ -1,5 +1,5 @@
/*
- custom_code_template.cpp (copy and use your machine name)
+ esp32_printer_controller.cpp (copy and use your machine name)
Part of Grbl_ESP32
copyright (c) 2020 - Bart Dring. This file was intended for use on the ESP32
@@ -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
diff --git a/Grbl_Esp32/Custom/polar_coaster.cpp b/Grbl_Esp32/Custom/polar_coaster.cpp
index 036c283c..af07238f 100644
--- a/Grbl_Esp32/Custom/polar_coaster.cpp
+++ b/Grbl_Esp32/Custom/polar_coaster.cpp
@@ -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;
}
}
diff --git a/Grbl_Esp32/Grbl_Esp32.ino b/Grbl_Esp32/Grbl_Esp32.ino
index 26431157..74918296 100644
--- a/Grbl_Esp32/Grbl_Esp32.ino
+++ b/Grbl_Esp32/Grbl_Esp32.ino
@@ -18,55 +18,45 @@
along with Grbl. If not, see .
*/
-#include "grbl.h"
-#include "WiFi.h"
-
-#include "Spindles/SpindleClass.cpp"
-#include "Motors/MotorClass.cpp"
+#include "src/Grbl.h"
+#include
// 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;
-
-
+Spindles::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 +67,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,9 +84,10 @@ 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();
+ Spindles::Spindle::select();
#ifdef ENABLE_WIFI
wifi_config.begin();
#endif
@@ -109,26 +100,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();
diff --git a/Grbl_Esp32/Motors/MotorClass.h b/Grbl_Esp32/Motors/MotorClass.h
deleted file mode 100644
index 072ebbe6..00000000
--- a/Grbl_Esp32/Motors/MotorClass.h
+++ /dev/null
@@ -1,218 +0,0 @@
-/*
- MotorClass.h
- Header file for Motor Classes
- Here is the hierarchy
- Motor
- Nullmotor
- StandardStepper
- TrinamicDriver
- Unipolar
- RC Servo
-
- These are for motors coordinated by Grbl_ESP32
- See motorClass.cpp for more details
-
- Part of Grbl_ESP32
- 2020 - Bart Dring
-
- 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 .
-*/
-
-#ifndef MOTORCLASS_H
-#define MOTORCLASS_H
-
-#include "../grbl.h"
-#include // https://github.com/teemuatlut/TMCStepper
-#include "TrinamicDriverClass.h"
-#include "RcServoClass.h"
-//#include "SolenoidClass.h"
-
-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;
-
-// These are used for setup and to talk to the motors as a group.
-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);
-
-extern bool motor_class_steps; // true if at least one motor class is handling steps
-
-// ==================== Motor Classes ====================
-
-class Motor {
- public:
- Motor();
-
- 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 bool test();
- virtual void set_axis_name();
- virtual void update();
-
- motor_class_id_t type_id;
- uint8_t is_active = false;
-
- protected:
- uint8_t axis_index; // X_AXIS, etc
- uint8_t dual_axis_index; // 0 = primary 1=ganged
-
- 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"
-};
-
-class Nullmotor : public Motor {
-
-};
-
-class StandardStepper : public Motor {
- 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();
- virtual void set_disable(bool disable);
- uint8_t 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);
-
- void config_message();
- void init();
- void set_mode(bool isHoming);
- void read_settings();
- void trinamic_test_response();
- void trinamic_stepper_enable(bool enable);
- void debug_message();
- void set_homing_mode(uint8_t homing_mask, bool ishoming);
- void set_disable(bool disable);
- bool test();
-
- 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 _mode;
- uint8_t _lastMode = 255;
-};
-
-
-class UnipolarMotor : public Motor {
- 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
-
- 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;
-};
-
-class RcServo : public Motor {
- 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);
- virtual void set_disable(bool disable);
- virtual void update();
- void read_settings();
- void set_homing_mode(bool is_homing, bool isHoming);
-
- protected:
- void set_location();
- void _get_calibration();
-
- uint8_t _pwm_pin;
- uint8_t _channel_num;
- uint32_t _current_pwm_duty;
- bool _disabled;
-
- float _position_min;
- float _position_max; // position in millimeters
- float _homing_position;
-
- float _pwm_pulse_min;
- float _pwm_pulse_max;
-};
-
-class Solenoid : public RcServo {
- public:
- Solenoid();
- Solenoid(uint8_t axis_index, gpio_num_t pwm_pin, float transition_poiont);
- void config_message();
- void set_location();
- void update();
- void init();
- void set_disable(bool disable);
-
- float _transition_poiont;
-};
-
-#endif
diff --git a/Grbl_Esp32/Motors/RcServoClass.cpp b/Grbl_Esp32/Motors/RcServoClass.cpp
deleted file mode 100644
index 51253138..00000000
--- a/Grbl_Esp32/Motors/RcServoClass.cpp
+++ /dev/null
@@ -1,190 +0,0 @@
-/*
- RcServoServoClass.cpp
-
- This allows an RcServo to be used like any other motor. Serrvos
- do have limitation in travel and speed, so you do need to respect that.
-
- Part of Grbl_ESP32
-
- 2020 - Bart Dring
-
- Servos have a limited travel, so they map the travel across a range in
- the current work coordinatee system. The servo can only travel as far
- as the range, but the internal axis value can keep going.
-
- Range: The range is specified in the machine definition file with...
- #define X_SERVO_RANGE_MIN 0.0
- #define X_SERVO_RANGE_MAX 5.0
-
- Direction: The direction can be changed using the $3 setting for the axis
-
- Homing: During homing, the servo will move to one of the endpoints. The
- endpoint is determined by the $23 or $HomingDirInvertMask setting for the axis.
- Do not define a homing cycle for the axis with the servo.
- You do need at least 1 homing cycle. TODO: Fix this
-
- Calibration. You can tweak the endpoints using the $10n or nStepsPerMm and
- $13n or $xMaxTravel setting, where n is the axis.
- The value is a percent. If you secify a percent outside the
- the range specified by the values below, it will be reset to 100.0 (100% ... no change)
- The calibration adjusts in direction of positive momement, so a value above 100% moves
- towards the higher axis value.
-
- #define SERVO_CAL_MIN
- #define SERVO_CAL_MAX
-
- Grbl_ESP32 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 .
-*/
-
-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;
- 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
- set_axis_name();
- 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",
- _axis_name,
- _pwm_pin,
- _position_min,
- _position_max);
-}
-
-void RcServo::_write_pwm(uint32_t duty) {
- // to prevent excessive calls to ledcWrite, make sure duty hass changed
- if (duty == _current_pwm_duty)
- return;
-
- _current_pwm_duty = duty;
-
- //grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Servo Pwm %d", _axis_name, duty);
- ledcWrite(_channel_num, duty);
-}
-
-// sets the PWM to zero. This allows most servos to be manually moved
-void RcServo::set_disable(bool disable) {
- return;
- _disabled = disable;
- if (_disabled)
- _write_pwm(0);
-}
-
-void RcServo::set_homing_mode(bool is_homing, bool isHoming) {
- float home_pos = 0.0;
-
- if (!is_homing)
- return;
-
- if (bit_istrue(homing_dir_mask->get(), bit(axis_index)))
- 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
-
-}
-
-void RcServo::update() {
- set_location();
-}
-
-void RcServo::set_location() {
- uint32_t servo_pulse_len;
- float servo_pos, mpos, offset;
- // skip location if we are in alarm mode
-
- //grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "locate");
- _get_calibration();
-
- if (sys.state == STATE_ALARM) {
- set_disable(true);
- 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
-
- // 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() {
- _get_calibration();
-}
-
-// this should change to use its own settings.
-void RcServo::_get_calibration() {
- float _cal_min = 1.0;
- float _cal_max = 1.0;
-
- //grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Read settings");
-
- // make sure the min is in range
- if ((axis_settings[axis_index]->steps_per_mm->get() < SERVO_CAL_MIN) || (axis_settings[axis_index]->steps_per_mm->get() > SERVO_CAL_MAX)) {
- grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo calibration ($10%d) value error. Reset to 100", axis_index);
- char reset_val[] = "100";
- axis_settings[axis_index]->steps_per_mm->setStringValue(reset_val);
- }
-
- // 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());
- char reset_val[] = "100";
- axis_settings[axis_index]->max_travel->setStringValue(reset_val);
- }
-
- _pwm_pulse_min = SERVO_MIN_PULSE;
- _pwm_pulse_max = SERVO_MAX_PULSE;
-
-
- 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
- _cal_min = (axis_settings[axis_index]->steps_per_mm->get() / 100.0);
- _cal_max = (axis_settings[axis_index]->max_travel->get() / 100.0);
- }
-
- _pwm_pulse_min *= _cal_min;
- _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);
-
-}
\ No newline at end of file
diff --git a/Grbl_Esp32/Motors/RcServoClass.h b/Grbl_Esp32/Motors/RcServoClass.h
deleted file mode 100644
index 0a23d6ae..00000000
--- a/Grbl_Esp32/Motors/RcServoClass.h
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- RcServoClass.h
-
- Part of Grbl_ESP32
-
- 2020 - Bart Dring
-
- 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 .
-*/
-#ifndef RCSERVOCLASS_H
-#define RCSERVOCLASS_H
-
-// 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_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_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_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_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
-
-#endif
\ No newline at end of file
diff --git a/Grbl_Esp32/Motors/StandardStepperClass.cpp b/Grbl_Esp32/Motors/StandardStepperClass.cpp
deleted file mode 100644
index f4f63820..00000000
--- a/Grbl_Esp32/Motors/StandardStepperClass.cpp
+++ /dev/null
@@ -1,107 +0,0 @@
-/*
- StandardStepperClass.cpp
-
- This is used for a stepper motor that just requires step and direction
- pins.
- TODO: Add an enable pin
-
- Part of Grbl_ESP32
-
- 2020 - Bart Dring
-
- 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 .
-*/
-
-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;
- init();
-}
-
-void StandardStepper :: init() {
- _homing_mask = 0;
- 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() {
- // 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.tx_config.carrier_duty_percent = 50;
- rmtConfig.tx_config.carrier_level = RMT_CARRIER_LEVEL_LOW;
- rmtConfig.tx_config.idle_output_en = true;
-
-
-#ifdef STEP_PULSE_DELAY
- rmtItem[0].duration0 = STEP_PULSE_DELAY * 4;
-#else
- rmtItem[0].duration0 = 1;
-#endif
-
- rmtItem[0].duration1 = 4 * pulse_microseconds->get();
- rmtItem[1].duration0 = 0;
- rmtItem[1].duration1 = 0;
-
- 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.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;
- 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
- pinMode(disable_pin, OUTPUT);
-}
-
-
-void StandardStepper :: config_message() {
- grbl_msg_sendf(CLIENT_SERIAL,
- MSG_LEVEL_INFO,
- "%s Axis standard stepper motor Step:%s Dir:%s Disable:%s",
- _axis_name,
- pinName(step_pin).c_str(),
- pinName(dir_pin).c_str(),
- pinName(disable_pin).c_str());
-}
-
-void StandardStepper :: set_direction_pins(uint8_t onMask) {
- digitalWrite(dir_pin, (onMask & bit(axis_index)));
-}
-
-void StandardStepper :: set_disable(bool disable) {
- digitalWrite(disable_pin, disable);
-}
diff --git a/Grbl_Esp32/Motors/TrinamicDriverClass.cpp b/Grbl_Esp32/Motors/TrinamicDriverClass.cpp
deleted file mode 100644
index 13628f90..00000000
--- a/Grbl_Esp32/Motors/TrinamicDriverClass.cpp
+++ /dev/null
@@ -1,242 +0,0 @@
-/*
- TrinamicDriverClass.cpp
- This is used for Trinamic SPI controlled stepper motor drivers.
-
- Part of Grbl_ESP32
- 2020 - Bart Dring
-
- 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 .
-
-*/
-#include
-#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;
-
- _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);
- else if (_driver_part_number == 5160)
- tmcstepper = new TMC5160Stepper(cs_pin, _r_sense, spi_index);
- else {
- grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Trinamic unsupported p/n:%d", _driver_part_number);
- return;
- }
-
- set_axis_name();
-
- init_step_dir_pins(); // from StandardStepper
-
- digitalWrite(cs_pin, HIGH);
- pinMode(cs_pin, OUTPUT);
-
- // use slower speed if I2S
- if (cs_pin >= I2S_OUT_PIN_BASE)
- tmcstepper->setSPISpeed(TRINAMIC_SPI_FREQ);
-
- config_message();
-
- // init() must be called later, after all TMC drivers have CS pins setup.
-}
-
-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
- set_mode(false);
-
- _homing_mask = 0;
- 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() {
- grbl_msg_sendf(CLIENT_SERIAL,
- MSG_LEVEL_INFO,
- "%s Axis Trinamic TMC%d Step:%s Dir:%s CS:%s Disable:%s Index:%d",
- _axis_name,
- _driver_part_number,
- pinName(step_pin).c_str(),
- pinName(dir_pin).c_str(),
- pinName(cs_pin).c_str(),
- pinName(disable_pin).c_str(),
- spi_index);
-}
-
-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;
- }
-}
-
-
-/*
- 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() {
- uint16_t run_i_ma = (uint16_t)(axis_settings[axis_index]->run_current->get() * 1000.0);
- float hold_i_percent;
-
- if (axis_settings[axis_index]->run_current->get() == 0)
- hold_i_percent = 0;
- else {
- hold_i_percent = axis_settings[axis_index]->hold_current->get() / axis_settings[axis_index]->run_current->get();
- if (hold_i_percent > 1.0)
- hold_i_percent = 1.0;
- }
- //grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Current run %d hold %f", _axis_name, run_i_ma, hold_i_percent);
-
- 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) {
- _homing_mask = homing_mask;
- set_mode(isHoming);
-}
-
-/*
- There are ton of settings. I'll start by grouping then into modes for now.
- 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) {
-
- if (isHoming)
- _mode = TRINAMIC_HOMING_MODE;
- else
- _mode = TRINAMIC_RUN_MODE;
-
- if (_lastMode == _mode)
- return;
- _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");
- }
-
-}
-
-/*
- This is the stallguard tuning info. It is call debug, so it could be generic across all classes.
-*/
-void TrinamicDriver :: debug_message() {
-
- uint32_t tstep = tmcstepper->TSTEP();
-
- 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
-
- grbl_msg_sendf(CLIENT_SERIAL,
- MSG_LEVEL_INFO,
- "%s Stallguard %d SG_Val: %04d Rate: %05.0f mm/min SG_Setting:%d",
- _axis_name,
- tmcstepper->stallguard(),
- tmcstepper->sg_result(),
- feedrate,
- axis_settings[axis_index]->stallguard->get());
-}
-
-// calculate a tstep from a rate
-// 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) {
- 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;
-
- 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) {
- //grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Axis disable %d", _axis_name, disable);
-
- digitalWrite(disable_pin, disable);
-
-#ifdef USE_TRINAMIC_ENABLE
- if (disable)
- tmcstepper->toff(TRINAMIC_TOFF_DISABLE);
- else {
- if (_mode == TRINAMIC_MODE_STEALTHCHOP)
- tmcstepper->toff(TRINAMIC_TOFF_STEALTHCHOP);
- else
- tmcstepper->toff(TRINAMIC_TOFF_COOLSTEP);
- }
-#endif
- // the pin based enable could be added here.
- // This would be for individual motors, not the single pin for all motors.
-}
-
diff --git a/Grbl_Esp32/Motors/TrinamicDriverClass.h b/Grbl_Esp32/Motors/TrinamicDriverClass.h
deleted file mode 100644
index b31e2195..00000000
--- a/Grbl_Esp32/Motors/TrinamicDriverClass.h
+++ /dev/null
@@ -1,64 +0,0 @@
-/*
- TrinamicDriverClass.h
-
- Part of Grbl_ESP32
-
- 2020 - Bart Dring
-
- 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 .
-*/
-
-#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 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
-
-// ==== defaults OK to define them in your machine definition ====
-#ifndef TRINAMIC_RUN_MODE
- #define TRINAMIC_RUN_MODE TRINAMIC_MODE_COOLSTEP
-#endif
-
-#ifndef TRINAMIC_HOMING_MODE
- #define TRINAMIC_HOMING_MODE TRINAMIC_RUN_MODE
-#endif
-
-
-#ifndef TRINAMIC_TOFF_DISABLE
- #define TRINAMIC_TOFF_DISABLE 0
-#endif
-
-#ifndef TRINAMIC_TOFF_STEALTHCHOP
- #define TRINAMIC_TOFF_STEALTHCHOP 5
-#endif
-
-#ifndef TRINAMIC_TOFF_COOLSTEP
- #define TRINAMIC_TOFF_COOLSTEP 3
-#endif
-
-
-
-#ifndef TRINAMICDRIVERCLASS_H
-#define TRINAMICDRIVERCLASS_H
-
-#include "MotorClass.h"
-#include // https://github.com/teemuatlut/TMCStepper
-
-#endif
diff --git a/Grbl_Esp32/Motors/UnipolarMotorClass.cpp b/Grbl_Esp32/Motors/UnipolarMotorClass.cpp
deleted file mode 100644
index cd00218c..00000000
--- a/Grbl_Esp32/Motors/UnipolarMotorClass.cpp
+++ /dev/null
@@ -1,146 +0,0 @@
-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;
-
- _half_step = true; // TODO read from settings ... microstep > 1 = half step
-
- set_axis_name();
- init();
- config_message();
-}
-
-void UnipolarMotor :: init() {
- pinMode(_pin_phase0, OUTPUT);
- pinMode(_pin_phase1, OUTPUT);
- pinMode(_pin_phase2, OUTPUT);
- pinMode(_pin_phase3, OUTPUT);
- _current_phase = 0;
-}
-
-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",
- _axis_name,
- pinName(_pin_phase0).c_str(),
- pinName(_pin_phase1).c_str(),
- pinName(_pin_phase2).c_str(),
- pinName(_pin_phase3).c_str());
-}
-
-void UnipolarMotor :: set_disable(bool disable) {
- if (disable) {
- digitalWrite(_pin_phase0, 0);
- digitalWrite(_pin_phase1, 0);
- digitalWrite(_pin_phase2, 0);
- digitalWrite(_pin_phase3, 0);
- }
- _enabled = !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_max;
-
- if (!(step_mask & bit(axis_index)))
- return; // a step is not required on this interrupt
-
- if (!_enabled)
- 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 (_current_phase == phase_max)
- _current_phase = 0;
- else
- _current_phase++;
- } else { // count down
- if (_current_phase == 0)
- _current_phase = phase_max;
- else
- _current_phase--;
- }
- /*
- 8 Step : A – AB – B – BC – C – CD – D – DA
- 4 Step : AB – BC – CD – DA
-
- Step IN4 IN3 IN2 IN1
- A 0 0 0 1
- AB 0 0 1 1
- B 0 0 1 0
- BC 0 1 1 0
- C 0 1 0 0
- CD 1 1 0 0
- D 1 0 0 0
- DA 1 0 0 1
- */
- 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;
- }
- } 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;
- }
- }
- digitalWrite(_pin_phase0, _phase[0]);
- digitalWrite(_pin_phase1, _phase[1]);
- digitalWrite(_pin_phase2, _phase[2]);
- digitalWrite(_pin_phase3, _phase[3]);
-}
diff --git a/Grbl_Esp32/SettingsClass.h b/Grbl_Esp32/SettingsClass.h
deleted file mode 100644
index a7b2c819..00000000
--- a/Grbl_Esp32/SettingsClass.h
+++ /dev/null
@@ -1,351 +0,0 @@
-#pragma once
-#include "JSONencoder.h"
-#include