mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-03 03:13:25 +02:00
Laser mode fix (#541)
* Changed header guards to #pragma once form In the Machines directory, also added // clang-format off because it will have to be done eventually and is safe, so it was easy to do systematically during this edit. * 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 * Fixed C++ includes (#518) * Moved all files to the src folder * Removed all cpp includes; fixed by including the header file where needed * Fixed build scripts and machine.h * Removed temp file. sigh. Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com> * Split motor files into separate files and introduced namespace Motors (#522) * Renamed some files to match the class name. * Split out motor class into different files. * Fixed last newline in cpp/h files Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com> * Fixed compile error with parking enabled (#524) * Fix the I2S stream generates a 3x faster pulse. (#525) I completely misunderstood the calculation of the interruption interval. Change to calculate the correct μsec interval from the tick value. * Bump build date * Eliminated unused USE_GANGED_AXES (#526) * Updated style of Spindles according to style doc. Added namespace Spindles. (#529) * Renamed spindleclass file. * Added (empty) header files; renamed SpindleClass.cpp * Moved spindle classes, introduced namespaces * Fixed forward declaration. * Removed obsolete commented out code * Fixed overrides and constructors * Applied clang-format * Fixed 10vspindle set_spindle_dir_pin and set_enable_pin. Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com> * Avoid reiterationIteration in spindle names (#530) * File name changes (#532) * Renamed files in the root folder. Haven't fixed includes yet. * Renamed SD to SDCard to avoid name conflict * Fixed all includes * Fixed some "..." / <...> includes. * Updated <Print.h> (caps!). Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com> * Move more files to WebUI (#534) Now everything with Luc's copyright is in WebUI/ * Fix file names in comment blocks The recent rename made nearly all of the file names included in header comments incorrect. * Fixed .c -> .cpp interior names * A few more interior name fixes * Added second limit switch I/O option (#537) - Added X2_LIMIT_PIN thru C2_LIMIT_PIN - The 2 switches are simply or'd in the logic - Limit pin difintion now prints in boot MSG's - Cleaned up MS3 logic to use an array and defaults like limit switches - Added a new machine definition file to test new features * Fixed Laser Mode Enablin pin was turning off, but not back on in laser mode * Added Settings - $Spindle/Enable/Invert=Off - $Spindle/Enable/OffWithSpeed=Off - $Spindle/PWM/Invert=Off * Update build date Co-authored-by: Mitch Bradley <wmb@firmworks.com> Co-authored-by: Stefan de Bruijn <atlaste@users.noreply.github.com> Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>
This commit is contained in:
92
.clang-format
Normal file
92
.clang-format
Normal 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
|
||||
|
||||
...
|
4
.editorconfig
Normal file
4
.editorconfig
Normal file
@@ -0,0 +1,4 @@
|
||||
root = true
|
||||
|
||||
[*]
|
||||
insert_final_newline = true
|
80
CodingStyle.md
Normal file
80
CodingStyle.md
Normal 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 `_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!
|
@@ -275,9 +275,7 @@ void user_defined_macro(uint8_t index) {
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
|
@@ -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,8 +62,7 @@ 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()
|
||||
{
|
||||
bool user_defined_homing() {
|
||||
// True = done with homing, false = continue with normal Grbl_ESP32 homing
|
||||
return true;
|
||||
}
|
||||
@@ -89,8 +86,7 @@ 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)
|
||||
{
|
||||
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);
|
||||
}
|
||||
@@ -109,9 +105,7 @@ bool kinematics_pre_homing(uint8_t cycle_mask))
|
||||
/*
|
||||
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,8 +115,7 @@ void kinematics_post_homing()
|
||||
|
||||
Convert the N_AXIS array of motor positions to cartesian in your code.
|
||||
*/
|
||||
void forward_kinematics(float *position)
|
||||
{
|
||||
void forward_kinematics(float* position) {
|
||||
// position[X_AXIS] =
|
||||
// position[Y_AXIS] =
|
||||
}
|
||||
@@ -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
|
||||
|
@@ -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
|
||||
@@ -63,8 +63,7 @@ special things your machine needs at startup.
|
||||
# define BED_PIN 4
|
||||
# define NOZZLE_PIN 2
|
||||
|
||||
void machine_init()
|
||||
{
|
||||
void machine_init() {
|
||||
// Enable steppers
|
||||
digitalWrite(STEPPERS_DISABLE_PIN_X, LOW); // enable
|
||||
digitalWrite(STEPPERS_DISABLE_PIN_Y, LOW); // enable
|
||||
@@ -89,8 +88,7 @@ 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()
|
||||
{
|
||||
bool user_defined_homing() {
|
||||
// True = done with homing, false = continue with normal Grbl_ESP32 homing
|
||||
return true;
|
||||
}
|
||||
@@ -114,8 +112,7 @@ 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)
|
||||
{
|
||||
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);
|
||||
}
|
||||
@@ -134,9 +131,7 @@ bool kinematics_pre_homing(uint8_t cycle_mask))
|
||||
/*
|
||||
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,8 +141,7 @@ void kinematics_post_homing()
|
||||
|
||||
Convert the N_AXIS array of motor positions to cartesian in your code.
|
||||
*/
|
||||
void forward_kinematics(float *position)
|
||||
{
|
||||
void forward_kinematics(float* position) {
|
||||
// position[X_AXIS] =
|
||||
// position[Y_AXIS] =
|
||||
}
|
||||
@@ -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
|
||||
|
@@ -54,7 +54,6 @@
|
||||
// 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);
|
||||
float abs_angle(float ang);
|
||||
|
||||
@@ -240,11 +239,9 @@ void user_defined_macro(uint8_t index) {
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
|
@@ -18,11 +18,8 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "grbl.h"
|
||||
#include "WiFi.h"
|
||||
|
||||
#include "Spindles/SpindleClass.cpp"
|
||||
#include "Motors/MotorClass.cpp"
|
||||
#include "src/Grbl.h"
|
||||
#include <WiFi.h>
|
||||
|
||||
// Declare system global variable structure
|
||||
system_t sys;
|
||||
@@ -37,9 +34,7 @@ volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bit
|
||||
volatile uint8_t sys_rt_exec_debug;
|
||||
#endif
|
||||
|
||||
Spindle *spindle;
|
||||
|
||||
|
||||
Spindles::Spindle* spindle;
|
||||
|
||||
void setup() {
|
||||
#ifdef USE_I2S_OUT
|
||||
@@ -55,11 +50,6 @@ void setup() {
|
||||
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
|
||||
@@ -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
|
||||
|
@@ -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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef MOTORCLASS_H
|
||||
#define MOTORCLASS_H
|
||||
|
||||
#include "../grbl.h"
|
||||
#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 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
|
@@ -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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
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);
|
||||
|
||||
}
|
@@ -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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#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
|
@@ -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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
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);
|
||||
}
|
@@ -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 <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#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;
|
||||
|
||||
_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.
|
||||
}
|
||||
|
@@ -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 <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 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 <TMCStepper.h> // https://github.com/teemuatlut/TMCStepper
|
||||
|
||||
#endif
|
@@ -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]);
|
||||
}
|
@@ -1,351 +0,0 @@
|
||||
#pragma once
|
||||
#include "JSONencoder.h"
|
||||
#include <map>
|
||||
#include <nvs.h>
|
||||
#include "espresponse.h"
|
||||
|
||||
// Command::List is a linked list of all settings,
|
||||
// so common code can enumerate them.
|
||||
class Command;
|
||||
// extern Command *CommandsList;
|
||||
|
||||
// This abstract class defines the generic interface that
|
||||
// is used to set and get values for all settings independent
|
||||
// of their underlying data type. The values are always
|
||||
// represented as human-readable strings. This generic
|
||||
// interface is used for managing settings via the user interface.
|
||||
|
||||
// Derived classes implement these generic functions for different
|
||||
// kinds of data. Code that accesses settings should use only these
|
||||
// generic functions and should not use derived classes directly.
|
||||
|
||||
enum {
|
||||
NO_AXIS = 255,
|
||||
};
|
||||
typedef enum : uint8_t {
|
||||
GRBL = 1, // Classic GRBL settings like $100
|
||||
EXTENDED, // Settings added by early versions of Grbl_Esp32
|
||||
WEBSET, // Settings for ESP3D_WebUI, stored in NVS
|
||||
GRBLCMD, // Non-persistent GRBL commands like $H
|
||||
WEBCMD, // ESP3D_WebUI commands that are not directly settings
|
||||
} type_t;
|
||||
typedef enum : uint8_t {
|
||||
WG, // Readable and writable as guest
|
||||
WU, // Readable and writable as user and admin
|
||||
WA, // Readable as user and admin, writable as admin
|
||||
} permissions_t;
|
||||
typedef uint8_t axis_t;
|
||||
|
||||
class Word {
|
||||
protected:
|
||||
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; }
|
||||
permissions_t getPermissions() { return _permissions; }
|
||||
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
|
||||
public:
|
||||
static Command* List;
|
||||
Command* next() { return link; }
|
||||
|
||||
~Command() {}
|
||||
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 err_t action(char* value, auth_t auth_level, ESPResponseStream* out) =0;
|
||||
};
|
||||
|
||||
class Setting : public Word {
|
||||
private:
|
||||
protected:
|
||||
static nvs_handle _handle;
|
||||
// group_t _group;
|
||||
axis_t _axis = NO_AXIS;
|
||||
Setting *link; // linked list of setting objects
|
||||
|
||||
bool (*_checker)(char *);
|
||||
const char* _keyName;
|
||||
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);
|
||||
#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) {
|
||||
nvs_entry_info_t info;
|
||||
nvs_entry_info(it, &info);
|
||||
it = nvs_entry_next(it);
|
||||
grbl_sendf(out->client(), "namespace %s key '%s', type '%d' \n", info.namespace_name, info.key, info.type);
|
||||
}
|
||||
#endif
|
||||
return STATUS_OK;
|
||||
}
|
||||
|
||||
static err_t eraseNVS(const char* value, auth_t auth_level, ESPResponseStream* out) {
|
||||
nvs_erase_all(_handle);
|
||||
// return STATUS_OK;
|
||||
return 0;
|
||||
}
|
||||
|
||||
~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 *));
|
||||
axis_t getAxis() { return _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
|
||||
// should be done infrequently, typically once at startup.
|
||||
virtual void load() {};
|
||||
virtual void setDefault() {};
|
||||
|
||||
// The default implementation of addWebui() does nothing.
|
||||
// Derived classes may override it to do something.
|
||||
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 const char* getCompatibleValue() { return getStringValue(); }
|
||||
};
|
||||
|
||||
class IntSetting : public Setting {
|
||||
private:
|
||||
int32_t _defaultValue;
|
||||
int32_t _currentValue;
|
||||
int32_t _storedValue;
|
||||
int32_t _minValue;
|
||||
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(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);
|
||||
const char* getStringValue();
|
||||
|
||||
int32_t get() { return _currentValue; }
|
||||
};
|
||||
|
||||
class AxisMaskSetting : public Setting {
|
||||
private:
|
||||
int32_t _defaultValue;
|
||||
int32_t _currentValue;
|
||||
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(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);
|
||||
const char* getCompatibleValue();
|
||||
const char* getStringValue();
|
||||
|
||||
int32_t get() { return _currentValue; }
|
||||
};
|
||||
|
||||
class FloatSetting : public Setting {
|
||||
private:
|
||||
float _defaultValue;
|
||||
float _currentValue;
|
||||
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)
|
||||
{ }
|
||||
|
||||
void load();
|
||||
void setDefault();
|
||||
// There are no Float settings in WebUI
|
||||
void addWebui(JSONencoder *) {}
|
||||
err_t setStringValue(char* value);
|
||||
const char* getStringValue();
|
||||
|
||||
float get() { return _currentValue; }
|
||||
};
|
||||
|
||||
#define MAX_SETTING_STRING 256
|
||||
class StringSetting : public Setting {
|
||||
private:
|
||||
String _defaultValue;
|
||||
String _currentValue;
|
||||
String _storedValue;
|
||||
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(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);
|
||||
const char* getStringValue();
|
||||
|
||||
const char* get() { return _currentValue.c_str(); }
|
||||
};
|
||||
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;
|
||||
|
||||
class EnumSetting : public Setting {
|
||||
private:
|
||||
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(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)
|
||||
{ }
|
||||
|
||||
void load();
|
||||
void setDefault();
|
||||
void addWebui(JSONencoder *);
|
||||
err_t setStringValue(char* value);
|
||||
const char* getStringValue();
|
||||
|
||||
int8_t get() { return _currentValue; }
|
||||
};
|
||||
|
||||
class FlagSetting : public Setting {
|
||||
private:
|
||||
bool _defaultValue;
|
||||
int8_t _storedValue;
|
||||
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)
|
||||
{ }
|
||||
|
||||
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);
|
||||
const char* getCompatibleValue();
|
||||
const char* getStringValue();
|
||||
|
||||
bool get() { return _currentValue; }
|
||||
};
|
||||
|
||||
class IPaddrSetting : public Setting {
|
||||
private:
|
||||
uint32_t _defaultValue;
|
||||
uint32_t _currentValue;
|
||||
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 *));
|
||||
|
||||
void load();
|
||||
void setDefault();
|
||||
void addWebui(JSONencoder *);
|
||||
err_t setStringValue(char* value);
|
||||
const char* getStringValue();
|
||||
|
||||
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;
|
||||
|
||||
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)) :
|
||||
Command(description, type, permissions, grblName, name),
|
||||
_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,
|
||||
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)
|
||||
{}
|
||||
|
||||
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);
|
||||
};
|
@@ -1,320 +0,0 @@
|
||||
#include "grbl.h"
|
||||
|
||||
bool motorSettingChanged = false;
|
||||
|
||||
StringSetting* startup_line_0;
|
||||
StringSetting* startup_line_1;
|
||||
StringSetting* build_info;
|
||||
|
||||
IntSetting* pulse_microseconds;
|
||||
IntSetting* stepper_idle_lock_time;
|
||||
|
||||
AxisMaskSetting* step_invert_mask;
|
||||
AxisMaskSetting* dir_invert_mask;
|
||||
// TODO Settings - need to call st_generate_step_invert_masks;
|
||||
AxisMaskSetting* homing_dir_mask;
|
||||
AxisMaskSetting* stallguard_debug_mask;
|
||||
|
||||
FlagSetting* step_enable_invert;
|
||||
FlagSetting* limit_invert;
|
||||
FlagSetting* probe_invert;
|
||||
FlagSetting* report_inches;
|
||||
FlagSetting* soft_limits;
|
||||
// TODO Settings - need to check for HOMING_ENABLE
|
||||
FlagSetting* hard_limits;
|
||||
// TODO Settings - need to call limits_init;
|
||||
FlagSetting* homing_enable;
|
||||
// TODO Settings - also need to clear, but not set, soft_limits
|
||||
FlagSetting* laser_mode;
|
||||
// TODO Settings - also need to call my_spindle->init;
|
||||
|
||||
IntSetting* status_mask;
|
||||
FloatSetting* junction_deviation;
|
||||
FloatSetting* arc_tolerance;
|
||||
|
||||
FloatSetting* homing_feed_rate;
|
||||
FloatSetting* homing_seek_rate;
|
||||
FloatSetting* homing_debounce;
|
||||
FloatSetting* homing_pulloff;
|
||||
FloatSetting* spindle_pwm_freq;
|
||||
FloatSetting* rpm_max;
|
||||
FloatSetting* rpm_min;
|
||||
FloatSetting* spindle_delay_spinup;
|
||||
FloatSetting* spindle_delay_spindown;
|
||||
|
||||
FloatSetting* spindle_pwm_off_value;
|
||||
FloatSetting* spindle_pwm_min_value;
|
||||
FloatSetting* spindle_pwm_max_value;
|
||||
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, },
|
||||
};
|
||||
|
||||
AxisSettings* x_axis_settings;
|
||||
AxisSettings* y_axis_settings;
|
||||
AxisSettings* z_axis_settings;
|
||||
AxisSettings* a_axis_settings;
|
||||
AxisSettings* b_axis_settings;
|
||||
AxisSettings* c_axis_settings;
|
||||
|
||||
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;
|
||||
} 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
|
||||
}
|
||||
};
|
||||
|
||||
// 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);
|
||||
|
||||
strcpy(retval, axisName);
|
||||
strcat(retval, "/");
|
||||
return strcat(retval, tail);
|
||||
}
|
||||
|
||||
static bool checkStartupLine(char* value) {
|
||||
if (sys.state != STATE_IDLE)
|
||||
return STATUS_IDLE_ERROR;
|
||||
return gc_execute_line(value, CLIENT_SERIAL) == 0;
|
||||
}
|
||||
|
||||
static bool checkStallguard(char* value) {
|
||||
motorSettingChanged = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool checkMicrosteps(char* value) {
|
||||
motorSettingChanged = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool checkRunCurrent(char* value) {
|
||||
motorSettingChanged = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool checkHoldcurrent(char* value) {
|
||||
motorSettingChanged = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
static bool checkStallguardDebugMask(char* val) {
|
||||
motorSettingChanged = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
// Generates a string like "122" from axisNum 2 and base 120
|
||||
static const char* makeGrblName(int axisNum, int base) {
|
||||
// To omit A,B,C axes:
|
||||
// if (axisNum > 2) return NULL;
|
||||
char buf[4];
|
||||
snprintf(buf, 4, "%d", axisNum + base);
|
||||
char* retval = (char*)malloc(strlen(buf));
|
||||
return strcpy(retval, buf);
|
||||
}
|
||||
|
||||
void make_settings() {
|
||||
Setting::init();
|
||||
|
||||
// Create the axis settings in the order that people are
|
||||
// accustomed to seeing.
|
||||
int axis;
|
||||
axis_defaults_t* def;
|
||||
for (axis = 0; axis < N_AXIS; axis++) {
|
||||
def = &axis_defaults[axis];
|
||||
axis_settings[axis] = new AxisSettings(def->name);
|
||||
}
|
||||
x_axis_settings = axis_settings[X_AXIS];
|
||||
y_axis_settings = axis_settings[Y_AXIS];
|
||||
z_axis_settings = axis_settings[Z_AXIS];
|
||||
a_axis_settings = axis_settings[A_AXIS];
|
||||
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);
|
||||
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);
|
||||
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
|
||||
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
|
||||
setting->setAxis(axis);
|
||||
axis_settings[axis]->run_current = setting;
|
||||
}
|
||||
for (axis = N_AXIS - 1; axis >= 0; axis--) {
|
||||
def = &axis_defaults[axis];
|
||||
auto setting = new FloatSetting(GRBL, WG, makeGrblName(axis, 130), makename(def->name, "MaxTravel"), def->max_travel, 1.0, 100000.0);
|
||||
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);
|
||||
setting->setAxis(axis);
|
||||
axis_settings[axis]->acceleration = setting;
|
||||
}
|
||||
for (axis = N_AXIS - 1; axis >= 0; 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);
|
||||
setting->setAxis(axis);
|
||||
axis_settings[axis]->steps_per_mm = setting;
|
||||
}
|
||||
|
||||
// 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
|
||||
// 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_delay_spindown = new FloatSetting(EXTENDED, WG, NULL, "Spindle/Delay/SpinDown", DEFAULT_SPINDLE_DELAY_SPINUP, 0, 30);
|
||||
|
||||
// GRBL Non-numbered settings
|
||||
startup_line_0 = new StringSetting(GRBL, WG, "N0", "GCode/Line0", "", checkStartupLine);
|
||||
startup_line_1 = new StringSetting(GRBL, WG, "N1", "GCode/Line1", "", checkStartupLine);
|
||||
|
||||
// GRBL Numbered Settings
|
||||
laser_mode = new FlagSetting(GRBL, WG, "32", "GCode/LaserMode", DEFAULT_LASER_MODE);
|
||||
// TODO Settings - also need to call my_spindle->init();
|
||||
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_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);
|
||||
|
||||
// TODO Settings - need to call st_generate_step_invert_masks()
|
||||
homing_dir_mask = new AxisMaskSetting(GRBL, WG, "23", "Homing/DirInvert", DEFAULT_HOMING_DIR_MASK);
|
||||
|
||||
// TODO Settings - need to call limits_init();
|
||||
homing_enable = new FlagSetting(GRBL, WG, "22", "Homing/Enable", DEFAULT_HOMING_ENABLE);
|
||||
// TODO Settings - need to check for HOMING_ENABLE
|
||||
hard_limits = new FlagSetting(GRBL, WG, "21", "Limits/Hard", DEFAULT_HARD_LIMIT_ENABLE);
|
||||
soft_limits = new FlagSetting(GRBL, WG, "20", "Limits/Soft", DEFAULT_SOFT_LIMIT_ENABLE, NULL);
|
||||
|
||||
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);
|
||||
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);
|
||||
|
||||
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);
|
||||
}
|
@@ -1,172 +0,0 @@
|
||||
/*
|
||||
10vSpindle.cpp
|
||||
|
||||
|
||||
This is basically a PWM spindle with some changes, so a separate forward and
|
||||
reverse signal can be sent.
|
||||
|
||||
The direction pins will act as enables for the 2 directions. There is usually
|
||||
a min RPM with VFDs, that speed will remain even if speed is 0. You
|
||||
must turn off both direction pins when enable is off.
|
||||
|
||||
|
||||
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 <http://www.gnu.org/licenses/>.
|
||||
|
||||
|
||||
|
||||
*/
|
||||
#include "SpindleClass.h"
|
||||
|
||||
|
||||
|
||||
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
|
||||
_forward_pin = SPINDLE_FORWARD_PIN;
|
||||
#else
|
||||
_forward_pin = UNDEFINED_PIN;
|
||||
#endif
|
||||
|
||||
#ifdef SPINDLE_REVERSE_PIN
|
||||
_reverse_pin = SPINDLE_REVERSE_PIN;
|
||||
#else
|
||||
_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
|
||||
}
|
||||
|
||||
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);
|
||||
pinMode(_forward_pin, OUTPUT);
|
||||
pinMode(_reverse_pin, OUTPUT);
|
||||
|
||||
set_rpm(0);
|
||||
|
||||
config_message();
|
||||
|
||||
is_reversable = true; // these VFDs are always reversable
|
||||
use_delays = true;
|
||||
|
||||
}
|
||||
|
||||
// prints the startup message of the spindle config
|
||||
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",
|
||||
pinName(_output_pin).c_str(),
|
||||
pinName(_enable_pin).c_str(),
|
||||
pinName(_direction_pin).c_str(),
|
||||
pinName(_forward_pin).c_str(),
|
||||
pinName(_reverse_pin).c_str(),
|
||||
_pwm_freq,
|
||||
_pwm_precision);
|
||||
}
|
||||
|
||||
uint32_t _10vSpindle::set_rpm(uint32_t rpm) {
|
||||
uint32_t pwm_value;
|
||||
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return rpm;
|
||||
|
||||
// apply speed overrides
|
||||
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))
|
||||
rpm = _max_rpm;
|
||||
else if (rpm != 0 && rpm <= _min_rpm)
|
||||
rpm = _min_rpm;
|
||||
sys.spindle_speed = rpm;
|
||||
|
||||
// determine the pwm value
|
||||
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);
|
||||
|
||||
set_output(pwm_value);
|
||||
return rpm;
|
||||
}
|
||||
/*
|
||||
void _10vSpindle::set_state(uint8_t state, uint32_t rpm) {
|
||||
if (sys.abort)
|
||||
return; // Block during abort.
|
||||
|
||||
if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
|
||||
sys.spindle_speed = 0;
|
||||
stop();
|
||||
} else {
|
||||
set_spindle_dir_pin(state == SPINDLE_ENABLE_CW);
|
||||
set_rpm(rpm);
|
||||
}
|
||||
|
||||
set_enable_pin(state != SPINDLE_DISABLE);
|
||||
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
}
|
||||
|
||||
*/
|
||||
|
||||
|
||||
uint8_t _10vSpindle::get_state() {
|
||||
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;
|
||||
return (SPINDLE_STATE_CW);
|
||||
}
|
||||
|
||||
void _10vSpindle::stop() {
|
||||
// inverts are delt with in methods
|
||||
set_enable_pin(false);
|
||||
set_output(_pwm_off_value);
|
||||
}
|
||||
|
||||
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)
|
||||
enable = false;
|
||||
|
||||
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
||||
enable = !enable;
|
||||
#endif
|
||||
digitalWrite(_enable_pin, enable);
|
||||
|
||||
// turn off anything that acts like an enable
|
||||
if (!enable) {
|
||||
digitalWrite(_direction_pin, enable);
|
||||
digitalWrite(_forward_pin, enable);
|
||||
digitalWrite(_reverse_pin, enable);
|
||||
}
|
||||
}
|
||||
|
||||
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);
|
||||
}
|
||||
|
@@ -1,122 +0,0 @@
|
||||
/*
|
||||
BESCSpindle.cpp
|
||||
|
||||
This a special type of PWM spindle for RC type Brushless DC Speed
|
||||
controllers. They use a short pulse for off and a longer pulse for
|
||||
full on. The pulse is always a small portion of the full cycle.
|
||||
Some BESCs have a special turn on procedure. This may be a one time
|
||||
procedure or must be done every time. The user must do that via gcode.
|
||||
|
||||
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 <http://www.gnu.org/licenses/>.
|
||||
|
||||
Important ESC Settings
|
||||
50 Hz this is a typical frequency for an ESC
|
||||
Some ESCs can handle higher frequencies, but there is no advantage to changing it.
|
||||
|
||||
Determine the typical min and max pulse length of your ESC
|
||||
BESC_MIN_PULSE_SECS is typically 1ms (0.001 sec) or less
|
||||
BESC_MAX_PULSE_SECS is typically 2ms (0.002 sec) or more
|
||||
|
||||
*/
|
||||
#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)
|
||||
|
||||
// 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
|
||||
#endif
|
||||
|
||||
#ifndef BESC_MAX_PULSE_SECS
|
||||
#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)
|
||||
|
||||
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
|
||||
}
|
||||
|
||||
// override some settings to what is required for a BESC
|
||||
_pwm_freq = (uint32_t)BESC_PWM_FREQ;
|
||||
_pwm_precision = 16;
|
||||
|
||||
// override these settings
|
||||
_pwm_off_value = BESC_MIN_PULSE_CNT;
|
||||
_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
|
||||
|
||||
pinMode(_enable_pin, OUTPUT);
|
||||
|
||||
set_rpm(0);
|
||||
|
||||
use_delays = true;
|
||||
|
||||
config_message();
|
||||
}
|
||||
|
||||
// prints the startup message of the spindle config
|
||||
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
|
||||
_pwm_freq,
|
||||
_pwm_precision);
|
||||
}
|
||||
|
||||
uint32_t BESCSpindle::set_rpm(uint32_t rpm) {
|
||||
uint32_t pwm_value;
|
||||
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return rpm;
|
||||
|
||||
// apply speed overrides
|
||||
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))
|
||||
rpm = _max_rpm;
|
||||
else if (rpm != 0 && rpm <= _min_rpm)
|
||||
rpm = _min_rpm;
|
||||
sys.spindle_speed = rpm;
|
||||
|
||||
// determine the pwm value
|
||||
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);
|
||||
}
|
||||
|
||||
set_output(pwm_value);
|
||||
return rpm;
|
||||
}
|
@@ -1,104 +0,0 @@
|
||||
/*
|
||||
DacSpindle.cpp
|
||||
|
||||
This uses the Analog DAC in the ESP32 to generate a voltage
|
||||
proportional to the GCode S value desired. Some spindle uses
|
||||
a 0-5V or 0-10V value to control the spindle. You would use
|
||||
an Op Amp type circuit to get from the 0.3.3V of the ESP32 to that voltage.
|
||||
|
||||
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 <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#include "SpindleClass.h"
|
||||
|
||||
// ======================================== DacSpindle ======================================
|
||||
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;
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
pinMode(_enable_pin, OUTPUT);
|
||||
pinMode(_direction_pin, OUTPUT);
|
||||
|
||||
is_reversable = (_direction_pin != UNDEFINED_PIN);
|
||||
use_delays = true;
|
||||
|
||||
config_message();
|
||||
}
|
||||
|
||||
void DacSpindle :: config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL,
|
||||
MSG_LEVEL_INFO,
|
||||
"DAC spindle Output:%s, Enbl:%s, Dir:%s, Res:8bits",
|
||||
pinName(_output_pin).c_str(),
|
||||
pinName(_enable_pin).c_str(),
|
||||
pinName(_direction_pin).c_str());
|
||||
}
|
||||
|
||||
uint32_t DacSpindle::set_rpm(uint32_t rpm) {
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return rpm;
|
||||
|
||||
uint32_t pwm_value;
|
||||
|
||||
// apply overrides and limits
|
||||
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;
|
||||
} else if (rpm <= _min_rpm) {
|
||||
if (rpm == 0) { // S0 disables spindle
|
||||
sys.spindle_speed = 0;
|
||||
pwm_value = 0;
|
||||
} else { // Set minimum PWM output
|
||||
rpm = _min_rpm;
|
||||
sys.spindle_speed = rpm;
|
||||
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) {
|
||||
if (_gpio_ok) {
|
||||
dacWrite(_output_pin, (uint8_t)duty);
|
||||
}
|
||||
}
|
@@ -1,483 +0,0 @@
|
||||
/*
|
||||
HuanyangSpindle.cpp
|
||||
|
||||
This is for a Huanyang VFD based spindle via RS485 Modbus.
|
||||
Sorry for the lengthy comments, but finding the details on this
|
||||
VFD was a PITA. I am just trying to help the next person.
|
||||
|
||||
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 <http://www.gnu.org/licenses/>.
|
||||
|
||||
WARNING!!!!
|
||||
VFDs are very dangerous. They have high voltages and are very powerful
|
||||
Remove power before changing bits.
|
||||
|
||||
==============================================================================
|
||||
|
||||
If a user changes state or RPM level, the command to do that is sent. If
|
||||
the command is not responded to a message is sent to serial that there was
|
||||
a timeout. If the Grbl is in a critical state, an alarm will be generated and
|
||||
the machine stopped.
|
||||
|
||||
If there are no commands to execute, various status items will be polled. If there
|
||||
is no response, it will behave as described above. It will stop any running jobs with
|
||||
an alarm.
|
||||
|
||||
===============================================================================
|
||||
|
||||
Protocol Details
|
||||
|
||||
VFD frequencies are in Hz. Multiply by 60 for RPM
|
||||
|
||||
before using spindle, VFD must be setup for RS485 and match your spindle
|
||||
PD001 2 RS485 Control of run commands
|
||||
PD002 2 RS485 Control of operating frequency
|
||||
PD005 400 Maximum frequency Hz (Typical for spindles)
|
||||
PD011 120 Min Speed (Recommend Aircooled=120 Water=100)
|
||||
PD014 10 Acceleration time (Test to optimize)
|
||||
PD015 10 Deceleration time (Test to optimize)
|
||||
PD023 1 Reverse run enabled
|
||||
PD142 3.7 Max current Amps (0.8kw=3.7 1.5kw=7.0, 2.2kw=??)
|
||||
PD143 2 Poles most are 2 (I think this is only used for RPM calc from Hz)
|
||||
PD163 1 RS485 Address: 1 (Typical. OK to change...see below)
|
||||
PD164 1 RS485 Baud rate: 9600 (Typical. OK to change...see below)
|
||||
PD165 3 RS485 Mode: RTU, 8N1
|
||||
|
||||
The official documentation of the RS485 is horrible. I had to piece it together from
|
||||
a lot of different sources
|
||||
|
||||
Manuals: https://github.com/RobertOlechowski/Huanyang_VFD/tree/master/Documentations/pdf
|
||||
Reference: https://github.com/Smoothieware/Smoothieware/blob/edge/src/modules/tools/spindle/HuanyangSpindleControl.cpp
|
||||
Refernece: https://gist.github.com/Bouni/803492ed0aab3f944066
|
||||
VFD settings: https://www.hobbytronics.co.za/Content/external/1159/Spindle_Settings.pdf
|
||||
Spindle Talker 2 https://github.com/GilchristT/SpindleTalker2/releases
|
||||
Python https://github.com/RobertOlechowski/Huanyang_VFD
|
||||
|
||||
=========================================================================
|
||||
|
||||
Commands
|
||||
ADDR CMD LEN DATA CRC
|
||||
0x01 0x03 0x01 0x01 0x31 0x88 Start spindle clockwise
|
||||
0x01 0x03 0x01 0x08 0xF1 0x8E Stop spindle
|
||||
0x01 0x03 0x01 0x11 0x30 0x44 Start spindle counter-clockwise
|
||||
|
||||
Return values are
|
||||
0 = run
|
||||
1 = jog
|
||||
2 = r/f
|
||||
3 = running
|
||||
4 = jogging
|
||||
5 = r/f
|
||||
6 = Braking
|
||||
7 = Track start
|
||||
|
||||
==========================================================================
|
||||
|
||||
Setting RPM
|
||||
ADDR CMD LEN DATA CRC
|
||||
0x01 0x05 0x02 0x09 0xC4 0xBF 0x0F Write Frequency (0x9C4 = 2500 = 25.00HZ)
|
||||
|
||||
Response is same as data sent
|
||||
|
||||
==========================================================================
|
||||
|
||||
Status registers
|
||||
Addr Read Len Reg DataH DataL CRC CRC
|
||||
0x01 0x04 0x03 0x00 0x00 0x00 CRC CRC // Set Frequency * 100 (25Hz = 2500)
|
||||
0x01 0x04 0x03 0x01 0x00 0x00 CRC CRC // Ouput Frequency * 100
|
||||
0x01 0x04 0x03 0x02 0x00 0x00 CRC CRC // Ouput Amps * 10
|
||||
0x01 0x04 0x03 0x03 0x00 0x00 0xF0 0x4E // Read RPM (example CRC shown)
|
||||
0x01 0x04 0x03 0x0 0x00 0x00 CRC CRC // DC voltage
|
||||
0x01 0x04 0x03 0x05 0x00 0x00 CRC CRC // AC voltage
|
||||
0x01 0x04 0x03 0x06 0x00 0x00 CRC CRC // Cont
|
||||
0x01 0x04 0x03 0x07 0x00 0x00 CRC CRC // VFD Temp
|
||||
Message is returned with requested value = (DataH * 16) + DataL (see decimal offset above)
|
||||
|
||||
TODO:
|
||||
Move CRC Calc to task to free up main task
|
||||
|
||||
|
||||
*/
|
||||
#include "SpindleClass.h"
|
||||
|
||||
#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
|
||||
|
||||
// OK to change these
|
||||
// #define them in your machine definition file if you want different values
|
||||
#ifndef HUANYANG_ADDR
|
||||
#define HUANYANG_ADDR 0x01
|
||||
#endif
|
||||
|
||||
#ifndef HUANYANG_BAUD_RATE
|
||||
#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];
|
||||
} 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_register_t;
|
||||
|
||||
QueueHandle_t hy_cmd_queue;
|
||||
|
||||
static TaskHandle_t vfd_cmdTaskHandle = 0;
|
||||
|
||||
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;
|
||||
hy_command_t next_cmd;
|
||||
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);
|
||||
|
||||
uint16_t read_length = uart_read_bytes(HUANYANG_UART_PORT, rx_message, next_cmd.rx_length, RESPONSE_WAIT_TICKS);
|
||||
|
||||
if (read_length < next_cmd.rx_length) {
|
||||
if (!unresponsive) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Spindle RS485 Unresponsive %d", read_length);
|
||||
if (next_cmd.critical) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Critical Spindle RS485 Unresponsive");
|
||||
system_set_exec_alarm(EXEC_ALARM_SPINDLE_CONTROL);
|
||||
}
|
||||
unresponsive = true;
|
||||
}
|
||||
} else {
|
||||
// success
|
||||
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);
|
||||
}
|
||||
|
||||
} else {
|
||||
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;
|
||||
}
|
||||
|
||||
}
|
||||
vTaskDelay(HUANYANG_POLL_RATE); // TODO: What is the best value here?
|
||||
}
|
||||
}
|
||||
|
||||
// ================== Class methods ==================================
|
||||
|
||||
void HuanyangSpindle :: init() {
|
||||
hy_spindle_ok = true; // initialize
|
||||
|
||||
// fail if required items are not defined
|
||||
if (!get_pins_and_settings()) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Huanyang spindle errors");
|
||||
return;
|
||||
}
|
||||
|
||||
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
|
||||
&vfd_cmdTaskHandle,
|
||||
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,
|
||||
.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_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;
|
||||
|
||||
//
|
||||
_current_rpm = 0;
|
||||
_state = SPINDLE_DISABLE;
|
||||
|
||||
config_message();
|
||||
}
|
||||
|
||||
// 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() {
|
||||
|
||||
|
||||
#ifdef HUANYANG_TXD_PIN
|
||||
_txd_pin = HUANYANG_TXD_PIN;
|
||||
#else
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Undefined HUANYANG_TXD_PIN");
|
||||
hy_spindle_ok = false;
|
||||
#endif
|
||||
|
||||
#ifdef HUANYANG_RXD_PIN
|
||||
_rxd_pin = HUANYANG_RXD_PIN;
|
||||
#else
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Undefined HUANYANG_RXD_PIN");
|
||||
hy_spindle_ok = false;
|
||||
#endif
|
||||
|
||||
#ifdef HUANYANG_RTS_PIN
|
||||
_rts_pin = HUANYANG_RTS_PIN;
|
||||
#else
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Undefined HUANYANG_RTS_PIN");
|
||||
hy_spindle_ok = false;
|
||||
#endif
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
_min_rpm = rpm_min->get();
|
||||
_max_rpm = rpm_max->get();
|
||||
|
||||
return hy_spindle_ok;
|
||||
}
|
||||
|
||||
void HuanyangSpindle :: config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL,
|
||||
MSG_LEVEL_INFO,
|
||||
"Huanyang Spindle Tx:%s Rx:%s RTS:%s",
|
||||
pinName(_txd_pin).c_str(),
|
||||
pinName(_rxd_pin).c_str(),
|
||||
pinName(_rts_pin).c_str());
|
||||
}
|
||||
|
||||
|
||||
void HuanyangSpindle :: set_state(uint8_t state, uint32_t rpm) {
|
||||
if (sys.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
|
||||
set_rpm(rpm);
|
||||
if (state == SPINDLE_DISABLE) {
|
||||
sys.spindle_speed = 0;
|
||||
if (_current_state != state)
|
||||
mc_dwell(spindle_delay_spindown->get());
|
||||
} else {
|
||||
if (_current_state != state)
|
||||
mc_dwell(spindle_delay_spinup->get());
|
||||
}
|
||||
} else {
|
||||
if (_current_rpm != rpm)
|
||||
set_rpm(rpm);
|
||||
}
|
||||
|
||||
_current_state = state; // store locally for faster get_state()
|
||||
|
||||
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;
|
||||
|
||||
hy_command_t mode_cmd;
|
||||
|
||||
mode_cmd.tx_length = 6;
|
||||
mode_cmd.rx_length = 6;
|
||||
|
||||
mode_cmd.msg[0] = HUANYANG_ADDR;
|
||||
mode_cmd.msg[1] = 0x03;
|
||||
mode_cmd.msg[2] = 0x01;
|
||||
|
||||
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)) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "VFD spindle off, queue could not be reset");
|
||||
}
|
||||
}
|
||||
|
||||
add_ModRTU_CRC(mode_cmd.msg, mode_cmd.rx_length);
|
||||
|
||||
mode_cmd.critical = critical;
|
||||
|
||||
if (xQueueSend(hy_cmd_queue, &mode_cmd, 0) != pdTRUE)
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "VFD Queue Full");
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
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)
|
||||
|
||||
// apply limits
|
||||
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm))
|
||||
rpm = _max_rpm;
|
||||
else if (rpm != 0 && rpm <= _min_rpm)
|
||||
rpm = _min_rpm;
|
||||
|
||||
sys.spindle_speed = rpm;
|
||||
|
||||
if (rpm == _current_rpm) // prevent setting same RPM twice
|
||||
return rpm;
|
||||
|
||||
_current_rpm = rpm;
|
||||
|
||||
// TODO add the speed modifiers override, linearization, etc.
|
||||
|
||||
rpm_cmd.tx_length = 7;
|
||||
rpm_cmd.rx_length = 6;
|
||||
|
||||
rpm_cmd.msg[0] = HUANYANG_ADDR;
|
||||
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)
|
||||
|
||||
rpm_cmd.msg[3] = (data & 0xFF00) >> 8;
|
||||
rpm_cmd.msg[4] = (data & 0xFF);
|
||||
|
||||
add_ModRTU_CRC(rpm_cmd.msg, rpm_cmd.tx_length);
|
||||
|
||||
rpm_cmd.critical = false;
|
||||
|
||||
if (xQueueSend(hy_cmd_queue, &rpm_cmd, 0) != pdTRUE)
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "VFD Queue Full");
|
||||
|
||||
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;
|
||||
hy_command_t read_cmd;
|
||||
uint8_t rx_message[HUANYANG_MAX_MSG_SIZE];
|
||||
|
||||
read_cmd.tx_length = 8;
|
||||
read_cmd.rx_length = 8;
|
||||
|
||||
read_cmd.msg[0] = HUANYANG_ADDR;
|
||||
read_cmd.msg[1] = 0x04;
|
||||
read_cmd.msg[2] = 0x03;
|
||||
|
||||
read_cmd.msg[3] = 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?
|
||||
|
||||
add_ModRTU_CRC(read_cmd.msg, read_cmd.tx_length);
|
||||
|
||||
if (xQueueSend(hy_cmd_queue, &read_cmd, 0) != pdTRUE)
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "VFD Queue Full");
|
||||
}
|
||||
|
||||
void HuanyangSpindle ::stop() {
|
||||
set_mode(SPINDLE_DISABLE, false);
|
||||
}
|
||||
|
||||
// state is cached rather than read right now to prevent delays
|
||||
uint8_t HuanyangSpindle :: get_state() {
|
||||
return _state;
|
||||
}
|
||||
|
||||
// Calculate the CRC on all of the byte except the last 2
|
||||
// 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) {
|
||||
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 ^= 0xA001;
|
||||
} else // Else LSB is not set
|
||||
crc >>= 1; // Just shift right
|
||||
}
|
||||
}
|
||||
// add the calculated Crc to the message
|
||||
buf[full_msg_len - 1] = (crc & 0xFF00) >> 8;
|
||||
buf[full_msg_len - 2] = (crc & 0xFF);
|
||||
}
|
@@ -1,268 +0,0 @@
|
||||
/*
|
||||
PWMSpindle.cpp
|
||||
|
||||
This is a full featured TTL PWM spindle This does not include speed/power
|
||||
compensation. Use the Laser class for that.
|
||||
|
||||
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 <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#include "SpindleClass.h"
|
||||
|
||||
// ======================= PWMSpindle ==============================
|
||||
/*
|
||||
This gets called at startup or whenever a spindle setting changes
|
||||
If the spindle is running it will stop and need to be restarted with M3Snnnn
|
||||
*/
|
||||
|
||||
//#include "grbl.h"
|
||||
|
||||
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
|
||||
}
|
||||
|
||||
if (_output_pin >= I2S_OUT_PIN_BASE) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: Spindle output pin %s cannot do PWM", pinName(_output_pin).c_str());
|
||||
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
|
||||
|
||||
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() {
|
||||
// setup all the pins
|
||||
|
||||
#ifdef SPINDLE_OUTPUT_PIN
|
||||
_output_pin = SPINDLE_OUTPUT_PIN;
|
||||
#else
|
||||
_output_pin = UNDEFINED_PIN;
|
||||
#endif
|
||||
|
||||
#ifdef INVERT_SPINDLE_OUTPUT_PIN
|
||||
_invert_pwm = true;
|
||||
#else
|
||||
_invert_pwm = false;
|
||||
#endif
|
||||
|
||||
#ifdef SPINDLE_ENABLE_PIN
|
||||
_enable_pin = SPINDLE_ENABLE_PIN;
|
||||
#ifdef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
||||
_off_with_zero_speed = true;
|
||||
#endif
|
||||
#else
|
||||
_enable_pin = UNDEFINED_PIN;
|
||||
_off_with_zero_speed = false;
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
_direction_pin = SPINDLE_DIR_PIN;
|
||||
#else
|
||||
_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);
|
||||
|
||||
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");
|
||||
|
||||
// pre-caculate some PWM count values
|
||||
_pwm_off_value = (_pwm_period * spindle_pwm_off_value->get() / 100.0);
|
||||
_pwm_min_value = (_pwm_period * spindle_pwm_min_value->get() / 100.0);
|
||||
_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;
|
||||
_piecewide_linear = true;
|
||||
#else
|
||||
_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
|
||||
|
||||
|
||||
}
|
||||
|
||||
uint32_t PWMSpindle::set_rpm(uint32_t rpm) {
|
||||
uint32_t pwm_value;
|
||||
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return 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)
|
||||
|
||||
// apply limits
|
||||
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm))
|
||||
rpm = _max_rpm;
|
||||
else if (rpm != 0 && rpm <= _min_rpm)
|
||||
rpm = _min_rpm;
|
||||
|
||||
sys.spindle_speed = rpm;
|
||||
|
||||
if (_piecewide_linear) {
|
||||
//pwm_value = piecewise_linear_fit(rpm); TODO
|
||||
pwm_value = 0;
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: Linear fit not implemented yet.");
|
||||
|
||||
} else {
|
||||
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);
|
||||
}
|
||||
|
||||
set_output(pwm_value);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void PWMSpindle::set_state(uint8_t state, uint32_t rpm) {
|
||||
if (sys.abort)
|
||||
return; // Block during abort.
|
||||
|
||||
if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
|
||||
sys.spindle_speed = 0;
|
||||
stop();
|
||||
if (use_delays && (_current_state != state)) {
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "SpinDown Start ");
|
||||
mc_dwell(spindle_delay_spindown->get());
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "SpinDown Done");
|
||||
}
|
||||
} 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
|
||||
if (use_delays && (_current_state != state)) {
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "SpinUp Start %d", rpm);
|
||||
mc_dwell(spindle_delay_spinup->get());
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "SpinUp Done");
|
||||
}
|
||||
}
|
||||
|
||||
_current_state = state;
|
||||
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
}
|
||||
|
||||
uint8_t PWMSpindle::get_state() {
|
||||
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;
|
||||
return (SPINDLE_STATE_CW);
|
||||
}
|
||||
|
||||
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() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL,
|
||||
MSG_LEVEL_INFO,
|
||||
"PWM spindle Output:%s, Enbl:%s, Dir:%s, Freq:%dHz, Res:%dbits",
|
||||
pinName(_output_pin).c_str(),
|
||||
pinName(_enable_pin).c_str(),
|
||||
pinName(_direction_pin).c_str(),
|
||||
_pwm_freq,
|
||||
_pwm_precision);
|
||||
}
|
||||
|
||||
|
||||
void PWMSpindle::set_output(uint32_t duty) {
|
||||
|
||||
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return;
|
||||
|
||||
// to prevent excessive calls to ledcWrite, make sure duty hass changed
|
||||
if (duty == _current_pwm_duty)
|
||||
return;
|
||||
|
||||
_current_pwm_duty = duty;
|
||||
|
||||
if (_invert_pwm)
|
||||
duty = (1 << _pwm_precision) - duty;
|
||||
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "set_output(%d)", duty);
|
||||
|
||||
ledcWrite(_spindle_pwm_chan_num, duty);
|
||||
}
|
||||
|
||||
void PWMSpindle::set_enable_pin(bool enable) {
|
||||
|
||||
if (_enable_pin == UNDEFINED_PIN)
|
||||
return;
|
||||
|
||||
if (_off_with_zero_speed && sys.spindle_speed == 0)
|
||||
enable = false;
|
||||
|
||||
#ifndef INVERT_SPINDLE_ENABLE_PIN
|
||||
digitalWrite(_enable_pin, enable);
|
||||
#else
|
||||
digitalWrite(_enable_pin, !enable);
|
||||
#endif
|
||||
digitalWrite(_enable_pin, enable);
|
||||
}
|
||||
|
||||
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 precision = 0;
|
||||
|
||||
// increase the precision (bits) until it exceeds allow by frequency the max or is 16
|
||||
while ((1 << precision) < (uint32_t)(80000000 / freq) && precision <= 16)
|
||||
precision++;
|
||||
|
||||
return precision - 1;
|
||||
}
|
@@ -1,70 +0,0 @@
|
||||
/*
|
||||
RelaySpindle.cpp
|
||||
|
||||
This is used for a basic on/off spindle All S Values above 0
|
||||
will turn the spindle on.
|
||||
|
||||
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 <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#include "SpindleClass.h"
|
||||
|
||||
// ========================= RelaySpindle ==================================
|
||||
/*
|
||||
This is a sub class of PWMSpindle but is a digital rather than PWM output
|
||||
*/
|
||||
void RelaySpindle::init() {
|
||||
get_pins_and_settings();
|
||||
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return;
|
||||
|
||||
pinMode(_output_pin, OUTPUT);
|
||||
pinMode(_enable_pin, OUTPUT);
|
||||
pinMode(_direction_pin, OUTPUT);
|
||||
|
||||
is_reversable = (_direction_pin != UNDEFINED_PIN);
|
||||
use_delays = true;
|
||||
|
||||
config_message();
|
||||
}
|
||||
|
||||
// prints the startup message of the spindle config
|
||||
void RelaySpindle :: config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL,
|
||||
MSG_LEVEL_INFO,
|
||||
"Relay spindle Output:%s, Enbl:%s, Dir:%s",
|
||||
pinName(_output_pin).c_str(),
|
||||
pinName(_enable_pin).c_str(),
|
||||
pinName(_direction_pin).c_str());
|
||||
}
|
||||
|
||||
uint32_t RelaySpindle::set_rpm(uint32_t rpm) {
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return rpm;
|
||||
|
||||
sys.spindle_speed = rpm;
|
||||
set_output(rpm != 0);
|
||||
|
||||
|
||||
return rpm;
|
||||
}
|
||||
|
||||
void RelaySpindle::set_output(uint32_t duty) {
|
||||
#ifdef INVERT_SPINDLE_PWM
|
||||
duty = (duty == 0); // flip duty
|
||||
#endif
|
||||
digitalWrite(_output_pin, duty > 0); // anything greater
|
||||
}
|
@@ -1,96 +0,0 @@
|
||||
/*
|
||||
SpindleClass.cpp
|
||||
|
||||
A Base class for spindles and spinsle like things such as lasers
|
||||
|
||||
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 <http://www.gnu.org/licenses/>.
|
||||
|
||||
TODO
|
||||
Add Spindle spin up/down delays
|
||||
|
||||
Get rid of dependance on machine definition #defines
|
||||
SPINDLE_OUTPUT_PIN
|
||||
SPINDLE_ENABLE_PIN
|
||||
SPINDLE_DIR_PIN
|
||||
|
||||
*/
|
||||
#include "NullSpindle.cpp"
|
||||
#include "PWMSpindle.cpp"
|
||||
#include "DacSpindle.cpp"
|
||||
#include "RelaySpindle.cpp"
|
||||
#include "Laser.cpp"
|
||||
#include "HuanyangSpindle.cpp"
|
||||
#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;
|
||||
HuanyangSpindle huanyang_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;
|
||||
}
|
||||
|
||||
spindle->init();
|
||||
}
|
||||
|
||||
// ========================= Spindle ==================================
|
||||
|
||||
bool Spindle::isRateAdjusted() {
|
||||
return false; // default for basic spindle is false
|
||||
}
|
||||
|
||||
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.
|
||||
set_state(state, rpm);
|
||||
}
|
@@ -1,229 +0,0 @@
|
||||
/*
|
||||
SpindleClass.h
|
||||
|
||||
Header file for a Spindle Class
|
||||
See SpindleClass.cpp for more details
|
||||
|
||||
Part of Grbl_ESP32
|
||||
|
||||
2020 - Bart Dring This file was modified for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
See SpindleClass.cpp for more info and references
|
||||
|
||||
*/
|
||||
|
||||
#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
|
||||
|
||||
#ifndef SPINDLE_CLASS_H
|
||||
#define SPINDLE_CLASS_H
|
||||
|
||||
#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
|
||||
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);
|
||||
|
||||
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();
|
||||
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();
|
||||
};
|
||||
|
||||
// This adds support for PWM
|
||||
class PWMSpindle : public Spindle {
|
||||
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();
|
||||
|
||||
private:
|
||||
void set_spindle_dir_pin(bool Clockwise);
|
||||
|
||||
|
||||
|
||||
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;
|
||||
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_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);
|
||||
};
|
||||
|
||||
// This is for an on/off spindle all RPMs above 0 are on
|
||||
class RelaySpindle : public PWMSpindle {
|
||||
public:
|
||||
void init();
|
||||
void config_message();
|
||||
uint32_t set_rpm(uint32_t rpm);
|
||||
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:
|
||||
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();
|
||||
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
|
||||
};
|
||||
|
||||
class HuanyangSpindle : public Spindle {
|
||||
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;
|
||||
|
||||
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);
|
||||
|
||||
protected:
|
||||
uint32_t _min_rpm;
|
||||
uint32_t _max_rpm;
|
||||
|
||||
|
||||
|
||||
};
|
||||
|
||||
class BESCSpindle : public PWMSpindle {
|
||||
public:
|
||||
void init();
|
||||
void config_message();
|
||||
uint32_t set_rpm(uint32_t rpm);
|
||||
};
|
||||
|
||||
class _10vSpindle : public PWMSpindle {
|
||||
public:
|
||||
void init();
|
||||
void config_message();
|
||||
uint32_t set_rpm(uint32_t rpm);
|
||||
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 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 HuanyangSpindle huanyang_spindle;
|
||||
extern BESCSpindle besc_spindle;
|
||||
extern _10vSpindle _10v_spindle;
|
||||
|
||||
void spindle_select();
|
||||
|
||||
// in HuanyangSpindle.cpp
|
||||
void vfd_cmd_task(void* pvParameters);
|
||||
|
||||
#endif
|
@@ -1,13 +0,0 @@
|
||||
#pragma once
|
||||
|
||||
//Authentication level
|
||||
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
|
||||
|
||||
void remove_password(char *str, auth_t& auth_level);
|
@@ -1,437 +0,0 @@
|
||||
/*
|
||||
defaults.h - defaults settings configuration file
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
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/>.
|
||||
*/
|
||||
|
||||
/* The defaults.h file serves as a central default settings selector for different machine
|
||||
types, from DIY CNC mills to CNC conversions of off-the-shelf machines. The settings
|
||||
files listed here are supplied by users, so your results may vary. However, this should
|
||||
give you a good starting point as you get to know your machine and tweak the settings for
|
||||
your nefarious needs.
|
||||
NOTE: Ensure one and only one of these DEFAULTS_XXX values is defined in config.h */
|
||||
|
||||
#ifndef defaults_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
|
||||
|
||||
#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_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_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_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_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_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_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_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_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
|
||||
|
||||
// ======== 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_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_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_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_DELAY_SPINUP
|
||||
#define DEFAULT_SPINDLE_DELAY_SPINUP 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
|
||||
|
||||
#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_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_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_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_94
|
||||
#define DEFAULT_USER_FLOAT_94 0.0 // $94 User integer setting
|
||||
#endif
|
||||
|
||||
|
||||
// =========== 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
|
||||
|
||||
// ============ 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
|
||||
|
||||
// ============== 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 ============
|
||||
|
||||
#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 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
|
||||
|
||||
// ========== 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
|
||||
|
||||
// ========== 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
|
||||
|
||||
|
||||
// ================== 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
|
||||
#endif
|
||||
|
||||
#ifndef X_DISABLE_PIN
|
||||
#define X_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Y_DISABLE_PIN
|
||||
#define Y_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Z_DISABLE_PIN
|
||||
#define Z_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef A_DISABLE_PIN
|
||||
#define A_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef B_DISABLE_PIN
|
||||
#define B_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef C_DISABLE_PIN
|
||||
#define C_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
|
||||
#ifndef X2_DISABLE_PIN
|
||||
#define X2_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Y2_DISABLE_PIN
|
||||
#define Y2_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Z2_DISABLE_PIN
|
||||
#define Z2_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef A2_DISABLE_PIN
|
||||
#define A2_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef B2_DISABLE_PIN
|
||||
#define B2_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef C2_DISABLE_PIN
|
||||
#define C2_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
|
||||
#ifndef X_LIMIT_PIN
|
||||
#define X_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Y_LIMIT_PIN
|
||||
#define Y_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Z_LIMIT_PIN
|
||||
#define Z_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef A_LIMIT_PIN
|
||||
#define A_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef B_LIMIT_PIN
|
||||
#define B_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef C_LIMIT_PIN
|
||||
#define C_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
|
||||
#endif
|
1390
Grbl_Esp32/gcode.cpp
1390
Grbl_Esp32/gcode.cpp
File diff suppressed because it is too large
Load Diff
@@ -1,268 +0,0 @@
|
||||
/*
|
||||
gcode.h - rs274/ngc parser.
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
||||
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/>.
|
||||
*/
|
||||
#ifndef gcode_h
|
||||
#define gcode_h
|
||||
|
||||
|
||||
// Define modal group internal numbers for checking multiple command violations and tracking the
|
||||
// type of command that is called in the block. A modal group is a group of g-code commands that are
|
||||
// mutually exclusive, or cannot exist on the same line, because they each toggle a state or execute
|
||||
// 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_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
|
||||
// #define OTHER_INPUT_T 16
|
||||
|
||||
// Define command actions for within execution-type modal groups (motion, stopping, non-modal). Used
|
||||
// internally by the parser to know which command to execute.
|
||||
// NOTE: Some macro values are assigned specific values to make g-code state reporting and parsing
|
||||
// compile a litte smaller. Necessary due to being completely out of flash on the 328p. Although not
|
||||
// ideal, just be careful with values that state 'do not alter' and check both report.c and gcode.c
|
||||
// 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)
|
||||
|
||||
// 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)
|
||||
|
||||
// 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)
|
||||
|
||||
// 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)
|
||||
|
||||
// Modal Group G4: Arc IJK distance mode
|
||||
#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)
|
||||
|
||||
// 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)
|
||||
|
||||
// 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)
|
||||
|
||||
// Modal Group G7: Cutter radius compensation mode
|
||||
#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)
|
||||
|
||||
// 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)
|
||||
|
||||
// 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)
|
||||
|
||||
// Modal Group M9: Override control
|
||||
#ifdef DEACTIVATE_PARKING_UPON_INIT
|
||||
#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.
|
||||
#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
|
||||
|
||||
// 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_CHANGE 1
|
||||
|
||||
// Modal Group G12: Active work coordinate system
|
||||
// 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 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 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
|
||||
#ifdef SET_CHECK_MODE_PROBE_TO_START
|
||||
#define GC_PROBE_CHECK_MODE GC_UPDATE_POS_NONE
|
||||
#else
|
||||
#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)
|
||||
|
||||
|
||||
// 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 distance_arc; // {G91.1} NOTE: Don't track. Only default supported.
|
||||
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 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}
|
||||
} 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 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
|
||||
} 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 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
|
||||
// position in mm. Loaded from EEPROM when called.
|
||||
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.
|
||||
} parser_state_t;
|
||||
extern parser_state_t gc_state;
|
||||
|
||||
|
||||
typedef struct {
|
||||
uint8_t non_modal_command;
|
||||
gc_modal_t modal;
|
||||
gc_values_t values;
|
||||
} parser_block_t;
|
||||
|
||||
|
||||
// Initialize the parser
|
||||
void gc_init();
|
||||
|
||||
// Execute one block of rs275/ngc/g-code
|
||||
uint8_t gc_execute_line(char* line, uint8_t client);
|
||||
|
||||
// Set g-code parser position. Input in steps.
|
||||
void gc_sync_position();
|
||||
|
||||
#endif
|
@@ -1,53 +0,0 @@
|
||||
/*
|
||||
* Connect the SD card to the following pins:
|
||||
*
|
||||
* SD Card | ESP32
|
||||
* D2 -
|
||||
* D3 SS
|
||||
* CMD MOSI
|
||||
* VSS GND
|
||||
* VDD 3.3V
|
||||
* CLK SCK
|
||||
* VSS GND
|
||||
* D0 MISO
|
||||
* D1 -
|
||||
*/
|
||||
|
||||
#ifndef grbl_sd_h
|
||||
#define grbl_sd_h
|
||||
|
||||
|
||||
#include "grbl.h"
|
||||
#include "FS.h"
|
||||
#include "SD.h"
|
||||
#include "SPI.h"
|
||||
|
||||
#define FILE_TYPE_COUNT 5 // number of acceptable gcode file types in array
|
||||
|
||||
#define SDCARD_DET_PIN -1
|
||||
#define SDCARD_DET_VAL 0
|
||||
|
||||
#define SDCARD_IDLE 0
|
||||
#define SDCARD_NOT_PRESENT 1
|
||||
#define SDCARD_BUSY_PRINTING 2
|
||||
#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;
|
||||
|
||||
//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();
|
||||
uint32_t sd_get_current_line_number();
|
||||
void sd_get_current_filename(char* name);
|
||||
|
||||
#endif
|
@@ -1,907 +0,0 @@
|
||||
/*
|
||||
i2s_out.cpp
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Basic GPIO expander using the ESP32 I2S peripheral (output)
|
||||
|
||||
2020 - Michiyasu Odaki
|
||||
|
||||
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_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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 this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#include "config.h"
|
||||
|
||||
#ifdef USE_I2S_OUT
|
||||
|
||||
#include <FreeRTOS.h>
|
||||
#include <driver/periph_ctrl.h>
|
||||
#include <rom/lldesc.h>
|
||||
#include <soc/i2s_struct.h>
|
||||
#include <freertos/queue.h>
|
||||
|
||||
#include <stdatomic.h>
|
||||
|
||||
#include "Pins.h"
|
||||
#include "i2s_out.h"
|
||||
|
||||
//
|
||||
// Configrations for DMA connected I2S
|
||||
//
|
||||
// One DMA buffer transfer takes about 2 ms
|
||||
// I2S_OUT_DMABUF_LEN / I2S_SAMPLE_SIZE x I2S_OUT_USEC_PER_PULSE
|
||||
// = 2000 / 4 x 4
|
||||
// = 2000us = 2ms
|
||||
// If I2S_OUT_DMABUF_COUNT is 5, it will take about 10 ms for all the DMA buffer transfers to finish.
|
||||
//
|
||||
// Increasing I2S_OUT_DMABUF_COUNT has the effect of preventing buffer underflow,
|
||||
// but on the other hand, it leads to a delay with pulse and/or non-pulse-generated I/Os.
|
||||
// The number of I2S_OUT_DMABUF_COUNT should be chosen carefully.
|
||||
//
|
||||
// Reference information:
|
||||
// FreeRTOS task time slice = portTICK_PERIOD_MS = 1 ms (ESP32 FreeRTOS port)
|
||||
//
|
||||
#define I2S_SAMPLE_SIZE 4 /* 4 bytes, 32 bits per sample */
|
||||
#define DMA_SAMPLE_COUNT I2S_OUT_DMABUF_LEN / I2S_SAMPLE_SIZE /* number of samples per buffer */
|
||||
#define SAMPLE_SAFE_COUNT (20/I2S_OUT_USEC_PER_PULSE) /* prevent buffer overrun (GRBL's $0 should be less than or equal 20) */
|
||||
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
typedef struct {
|
||||
uint32_t **buffers;
|
||||
uint32_t *current;
|
||||
uint32_t rw_pos;
|
||||
lldesc_t **desc;
|
||||
xQueueHandle queue;
|
||||
} i2s_out_dma_t;
|
||||
|
||||
static i2s_out_dma_t o_dma;
|
||||
static intr_handle_t i2s_out_isr_handle;
|
||||
#endif
|
||||
|
||||
// output value
|
||||
static atomic_uint_least32_t i2s_out_port_data = ATOMIC_VAR_INIT(0);
|
||||
|
||||
// inner lock
|
||||
static portMUX_TYPE i2s_out_spinlock = portMUX_INITIALIZER_UNLOCKED;
|
||||
#define I2S_OUT_ENTER_CRITICAL() portENTER_CRITICAL(&i2s_out_spinlock)
|
||||
#define I2S_OUT_EXIT_CRITICAL() portEXIT_CRITICAL(&i2s_out_spinlock)
|
||||
#define I2S_OUT_ENTER_CRITICAL_ISR() portENTER_CRITICAL_ISR(&i2s_out_spinlock)
|
||||
#define I2S_OUT_EXIT_CRITICAL_ISR() portEXIT_CRITICAL_ISR(&i2s_out_spinlock)
|
||||
|
||||
static int i2s_out_initialized = 0;
|
||||
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
static volatile uint32_t i2s_out_pulse_period;
|
||||
static uint32_t i2s_out_remain_time_until_next_pulse; // Time remaining until the next pulse (μsec)
|
||||
static volatile i2s_out_pulse_func_t i2s_out_pulse_func;
|
||||
#endif
|
||||
|
||||
static uint8_t i2s_out_ws_pin = 255;
|
||||
static uint8_t i2s_out_bck_pin = 255;
|
||||
static uint8_t i2s_out_data_pin = 255;
|
||||
|
||||
enum i2s_out_pulser_status_t {
|
||||
PASSTHROUGH = 0, // Static I2S mode.The i2s_out_write() reflected with very little delay
|
||||
STEPPING, // Streaming step data.
|
||||
WAITING, // Waiting for the step DMA completion
|
||||
};
|
||||
static volatile i2s_out_pulser_status_t i2s_out_pulser_status = PASSTHROUGH;
|
||||
|
||||
// outer lock
|
||||
static portMUX_TYPE i2s_out_pulser_spinlock = portMUX_INITIALIZER_UNLOCKED;
|
||||
#define I2S_OUT_PULSER_ENTER_CRITICAL() portENTER_CRITICAL(&i2s_out_pulser_spinlock)
|
||||
#define I2S_OUT_PULSER_EXIT_CRITICAL() portEXIT_CRITICAL(&i2s_out_pulser_spinlock)
|
||||
#define I2S_OUT_PULSER_ENTER_CRITICAL_ISR() portENTER_CRITICAL_ISR(&i2s_out_pulser_spinlock)
|
||||
#define I2S_OUT_PULSER_EXIT_CRITICAL_ISR() portEXIT_CRITICAL_ISR(&i2s_out_pulser_spinlock)
|
||||
|
||||
//
|
||||
// Internal functions
|
||||
//
|
||||
static inline void gpio_matrix_out_check(uint8_t gpio, uint32_t signal_idx, bool out_inv, bool oen_inv) {
|
||||
//if pin == 255, do not need to configure
|
||||
if (gpio != 255) {
|
||||
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[gpio], PIN_FUNC_GPIO);
|
||||
gpio_set_direction((gpio_num_t)gpio, (gpio_mode_t)GPIO_MODE_DEF_OUTPUT);
|
||||
gpio_matrix_out(gpio, signal_idx, out_inv, oen_inv);
|
||||
}
|
||||
}
|
||||
|
||||
static inline void i2s_out_single_data() {
|
||||
#if I2S_OUT_NUM_BITS == 16
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data);
|
||||
port_data <<= 16; // Shift needed. This specification is not spelled out in the manual.
|
||||
I2S0.conf_single_data = port_data; // Apply port data in real-time (static I2S)
|
||||
#else
|
||||
I2S0.conf_single_data = atomic_load(&i2s_out_port_data); // Apply port data in real-time (static I2S)
|
||||
#endif
|
||||
}
|
||||
|
||||
static inline void i2s_out_reset_fifo_without_lock() {
|
||||
I2S0.conf.rx_fifo_reset = 1;
|
||||
I2S0.conf.rx_fifo_reset = 0;
|
||||
I2S0.conf.tx_fifo_reset = 1;
|
||||
I2S0.conf.tx_fifo_reset = 0;
|
||||
}
|
||||
|
||||
static void IRAM_ATTR i2s_out_reset_fifo() {
|
||||
I2S_OUT_ENTER_CRITICAL();
|
||||
i2s_out_reset_fifo_without_lock();
|
||||
I2S_OUT_EXIT_CRITICAL();
|
||||
}
|
||||
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
static int IRAM_ATTR i2s_clear_dma_buffer(lldesc_t *dma_desc, uint32_t port_data) {
|
||||
|
||||
uint32_t *buf = (uint32_t*)dma_desc->buf;
|
||||
for (int i = 0; i < DMA_SAMPLE_COUNT; i++) {
|
||||
buf[i] = port_data;
|
||||
}
|
||||
// Restore the buffer length.
|
||||
// The length may have been changed short when the data was filled in to prevent buffer overrun.
|
||||
dma_desc->length = I2S_OUT_DMABUF_LEN;
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int IRAM_ATTR i2s_clear_o_dma_buffers(uint32_t port_data) {
|
||||
for (int buf_idx = 0; buf_idx < I2S_OUT_DMABUF_COUNT; buf_idx++) {
|
||||
// Initialize DMA descriptor
|
||||
o_dma.desc[buf_idx]->owner = 1;
|
||||
o_dma.desc[buf_idx]->eof = 1; // set to 1 will trigger the interrupt
|
||||
o_dma.desc[buf_idx]->sosf = 0;
|
||||
o_dma.desc[buf_idx]->length = I2S_OUT_DMABUF_LEN;
|
||||
o_dma.desc[buf_idx]->size = I2S_OUT_DMABUF_LEN;
|
||||
o_dma.desc[buf_idx]->buf = (uint8_t *) o_dma.buffers[buf_idx];
|
||||
o_dma.desc[buf_idx]->offset = 0;
|
||||
o_dma.desc[buf_idx]->qe.stqe_next = (lldesc_t *)((buf_idx < (I2S_OUT_DMABUF_COUNT - 1)) ? (o_dma.desc[buf_idx + 1]) : o_dma.desc[0]);
|
||||
i2s_clear_dma_buffer(o_dma.desc[buf_idx], port_data);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
static int IRAM_ATTR i2s_out_gpio_attach(uint8_t ws, uint8_t bck, uint8_t data) {
|
||||
// Route the i2s pins to the appropriate GPIO
|
||||
gpio_matrix_out_check(data, I2S0O_DATA_OUT23_IDX, 0, 0);
|
||||
gpio_matrix_out_check(bck, I2S0O_BCK_OUT_IDX, 0, 0);
|
||||
gpio_matrix_out_check(ws, I2S0O_WS_OUT_IDX, 0, 0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
#define I2S_OUT_DETACH_PORT_IDX 0x100
|
||||
|
||||
static int IRAM_ATTR i2s_out_gpio_detach(uint8_t ws, uint8_t bck, uint8_t data) {
|
||||
// Route the i2s pins to the appropriate GPIO
|
||||
gpio_matrix_out_check(ws, I2S_OUT_DETACH_PORT_IDX, 0, 0);
|
||||
gpio_matrix_out_check(bck, I2S_OUT_DETACH_PORT_IDX, 0, 0);
|
||||
gpio_matrix_out_check(data, I2S_OUT_DETACH_PORT_IDX, 0, 0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int IRAM_ATTR i2s_out_gpio_shiftout(uint32_t port_data) {
|
||||
__digitalWrite(i2s_out_ws_pin, LOW);
|
||||
for (int i = 0; i <I2S_OUT_NUM_BITS; i++) {
|
||||
__digitalWrite(i2s_out_data_pin, !!(port_data & bit(I2S_OUT_NUM_BITS-1 - i)));
|
||||
__digitalWrite(i2s_out_bck_pin, HIGH);
|
||||
__digitalWrite(i2s_out_bck_pin, LOW);
|
||||
}
|
||||
__digitalWrite(i2s_out_ws_pin, HIGH); // Latch
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int IRAM_ATTR i2s_out_stop() {
|
||||
I2S_OUT_ENTER_CRITICAL();
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
// Stop FIFO DMA
|
||||
I2S0.out_link.stop = 1;
|
||||
|
||||
// Disconnect DMA from FIFO
|
||||
I2S0.fifo_conf.dscr_en = 0; //Unset this bit to disable I2S DMA mode. (R/W)
|
||||
#endif
|
||||
// stop TX module
|
||||
I2S0.conf.tx_start = 0;
|
||||
|
||||
// Force WS to LOW before detach
|
||||
// This operation prevents unintended WS edge trigger when detach
|
||||
__digitalWrite(i2s_out_ws_pin, LOW);
|
||||
|
||||
// Now, detach GPIO pin from I2S
|
||||
i2s_out_gpio_detach(i2s_out_ws_pin, i2s_out_bck_pin, i2s_out_data_pin);
|
||||
|
||||
// Force BCK to LOW
|
||||
// After the TX module is stopped, BCK always seems to be in LOW.
|
||||
// However, I'm going to do it manually to ensure the BCK's LOW.
|
||||
__digitalWrite(i2s_out_bck_pin, LOW);
|
||||
|
||||
// Transmit recovery data to 74HC595
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data); // current expanded port value
|
||||
i2s_out_gpio_shiftout(port_data);
|
||||
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
//clear pending interrupt
|
||||
I2S0.int_clr.val = I2S0.int_st.val;
|
||||
#endif
|
||||
I2S_OUT_EXIT_CRITICAL();
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int IRAM_ATTR i2s_out_start() {
|
||||
if (!i2s_out_initialized) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
I2S_OUT_ENTER_CRITICAL();
|
||||
// Transmit recovery data to 74HC595
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data); // current expanded port value
|
||||
i2s_out_gpio_shiftout(port_data);
|
||||
|
||||
// Attach I2S to specified GPIO pin
|
||||
i2s_out_gpio_attach(i2s_out_ws_pin, i2s_out_bck_pin, i2s_out_data_pin);
|
||||
//start DMA link
|
||||
i2s_out_reset_fifo_without_lock();
|
||||
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
if (i2s_out_pulser_status == PASSTHROUGH) {
|
||||
I2S0.conf_chan.tx_chan_mod = 3; // 3:right+constant 4:left+constant (when tx_msb_right = 1)
|
||||
I2S0.conf_single_data = port_data;
|
||||
} else {
|
||||
I2S0.conf_chan.tx_chan_mod = 4; // 3:right+constant 4:left+constant (when tx_msb_right = 1)
|
||||
I2S0.conf_single_data = 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
//reset DMA
|
||||
I2S0.lc_conf.in_rst = 1;
|
||||
I2S0.lc_conf.in_rst = 0;
|
||||
I2S0.lc_conf.out_rst = 1;
|
||||
I2S0.lc_conf.out_rst = 0;
|
||||
|
||||
I2S0.out_link.addr = (uint32_t)o_dma.desc[0];
|
||||
#endif
|
||||
|
||||
I2S0.conf.tx_reset = 1;
|
||||
I2S0.conf.tx_reset = 0;
|
||||
I2S0.conf.rx_reset = 1;
|
||||
I2S0.conf.rx_reset = 0;
|
||||
|
||||
I2S0.conf1.tx_stop_en = 1; // BCK and WCK are suppressed while FIFO is empty
|
||||
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
// Connect DMA to FIFO
|
||||
I2S0.fifo_conf.dscr_en = 1; // Set this bit to enable I2S DMA mode. (R/W)
|
||||
|
||||
I2S0.int_clr.val = 0xFFFFFFFF;
|
||||
I2S0.out_link.start = 1;
|
||||
#endif
|
||||
I2S0.conf.tx_start = 1;
|
||||
// Wait for the first FIFO data to prevent the unintentional generation of 0 data
|
||||
ets_delay_us(20);
|
||||
I2S0.conf1.tx_stop_en = 0; // BCK and WCK are generated regardless of the FIFO status
|
||||
|
||||
I2S_OUT_EXIT_CRITICAL();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
|
||||
static int IRAM_ATTR i2s_fillout_dma_buffer(lldesc_t *dma_desc) {
|
||||
uint32_t *buf = (uint32_t*)dma_desc->buf;
|
||||
o_dma.rw_pos = 0;
|
||||
// It reuses the oldest (just transferred) buffer with the name "current"
|
||||
// and fills the buffer for later DMA.
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL(); // Lock pulser status
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
//
|
||||
// Fillout the buffer for pulse
|
||||
//
|
||||
// To avoid buffer overflow, all of the maximum pulse width (normaly about 10us)
|
||||
// is adjusted to be in a single buffer.
|
||||
// DMA_SAMPLE_SAFE_COUNT is referred to as the margin value.
|
||||
// Therefore, if a buffer is close to full and it is time to generate a pulse,
|
||||
// the generation of the buffer is interrupted (the buffer length is shortened slightly)
|
||||
// and the pulse generation is postponed until the next buffer is filled.
|
||||
//
|
||||
o_dma.rw_pos = 0;
|
||||
while (o_dma.rw_pos < (DMA_SAMPLE_COUNT - SAMPLE_SAFE_COUNT)) {
|
||||
// no data to read (buffer empty)
|
||||
if (i2s_out_remain_time_until_next_pulse < I2S_OUT_USEC_PER_PULSE) {
|
||||
// pulser status may change in pulse phase func, so I need to check it every time.
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
// fillout future DMA buffer (tail of the DMA buffer chains)
|
||||
if (i2s_out_pulse_func != NULL) {
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL(); // Temporarily unlocked status lock as it may be locked in pulse callback.
|
||||
(*i2s_out_pulse_func)(); // should be pushed into buffer max DMA_SAMPLE_SAFE_COUNT
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL(); // Lock again.
|
||||
i2s_out_remain_time_until_next_pulse = i2s_out_pulse_period;
|
||||
if (i2s_out_pulser_status == WAITING) {
|
||||
// i2s_out_set_passthrough() has called from the pulse function.
|
||||
// It needs to go into pass-through mode.
|
||||
// This DMA descriptor must be a tail of the chain.
|
||||
dma_desc->qe.stqe_next = NULL; // Cut the DMA descriptor ring. This allow us to identify the tail of the buffer.
|
||||
} else if (i2s_out_pulser_status == PASSTHROUGH) {
|
||||
// i2s_out_reset() has called during the execution of the pulse function.
|
||||
// I2S has already in static mode, and buffers has cleared to zero.
|
||||
// To prevent the pulse function from being called back,
|
||||
// we assume that the buffer is already full.
|
||||
i2s_out_remain_time_until_next_pulse = 0; // There is no need to fill the current buffer.
|
||||
o_dma.rw_pos = DMA_SAMPLE_COUNT; // The buffer is full.
|
||||
break;
|
||||
}
|
||||
continue;
|
||||
}
|
||||
}
|
||||
}
|
||||
// no pulse data in push buffer (pulse off or idle or callback is not defined)
|
||||
buf[o_dma.rw_pos++] = atomic_load(&i2s_out_port_data);
|
||||
if (i2s_out_remain_time_until_next_pulse >= I2S_OUT_USEC_PER_PULSE) {
|
||||
i2s_out_remain_time_until_next_pulse -= I2S_OUT_USEC_PER_PULSE;
|
||||
} else {
|
||||
i2s_out_remain_time_until_next_pulse = 0;
|
||||
}
|
||||
}
|
||||
// set filled length to the DMA descriptor
|
||||
dma_desc->length = o_dma.rw_pos * I2S_SAMPLE_SIZE;
|
||||
} else if (i2s_out_pulser_status == WAITING) {
|
||||
i2s_clear_dma_buffer(dma_desc, 0); // Essentially, no clearing is required. I'll make sure I know when I've written something.
|
||||
o_dma.rw_pos = 0; // If someone calls i2s_out_push_sample, make sure there is no buffer overflow
|
||||
dma_desc->qe.stqe_next = NULL; // Cut the DMA descriptor ring. This allow us to identify the tail of the buffer.
|
||||
} else {
|
||||
// Stepper paused (passthrough state, static I2S control mode)
|
||||
// In the passthrough mode, there is no need to fill the buffer with port_data.
|
||||
i2s_clear_dma_buffer(dma_desc, 0); // Essentially, no clearing is required. I'll make sure I know when I've written something.
|
||||
o_dma.rw_pos = 0; // If someone calls i2s_out_push_sample, make sure there is no buffer overflow
|
||||
}
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL(); // Unlock pulser status
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
//
|
||||
// I2S out DMA Interrupts handler
|
||||
//
|
||||
static void IRAM_ATTR i2s_out_intr_handler(void *arg) {
|
||||
lldesc_t *finish_desc;
|
||||
portBASE_TYPE high_priority_task_awoken = pdFALSE;
|
||||
|
||||
if (I2S0.int_st.out_eof || I2S0.int_st.out_total_eof) {
|
||||
if (I2S0.int_st.out_total_eof) {
|
||||
// This is tail of the DMA descriptors
|
||||
I2S_OUT_ENTER_CRITICAL_ISR();
|
||||
// Stop FIFO DMA
|
||||
I2S0.out_link.stop = 1;
|
||||
// Disconnect DMA from FIFO
|
||||
I2S0.fifo_conf.dscr_en = 0; //Unset this bit to disable I2S DMA mode. (R/W)
|
||||
// Stop TX module
|
||||
I2S0.conf.tx_start = 0;
|
||||
I2S_OUT_EXIT_CRITICAL_ISR();
|
||||
}
|
||||
// Get the descriptor of the last item in the linkedlist
|
||||
finish_desc = (lldesc_t*) I2S0.out_eof_des_addr;
|
||||
|
||||
// If the queue is full it's because we have an underflow,
|
||||
// more than buf_count isr without new data, remove the front buffer
|
||||
if (xQueueIsQueueFullFromISR(o_dma.queue)) {
|
||||
lldesc_t *front_desc;
|
||||
// Remove a descriptor from the DMA complete event queue
|
||||
xQueueReceiveFromISR(o_dma.queue, &front_desc, &high_priority_task_awoken);
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL_ISR();
|
||||
uint32_t port_data = 0;
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
port_data = atomic_load(&i2s_out_port_data);
|
||||
}
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL_ISR();
|
||||
for (int i = 0; i < DMA_SAMPLE_COUNT; i++) {
|
||||
front_desc->buf[i] = port_data;
|
||||
}
|
||||
front_desc->length = I2S_OUT_DMABUF_LEN;
|
||||
}
|
||||
|
||||
// Send a DMA complete event to the I2S bitstreamer task with finished buffer
|
||||
xQueueSendFromISR(o_dma.queue, &finish_desc, &high_priority_task_awoken);
|
||||
}
|
||||
|
||||
if (high_priority_task_awoken == pdTRUE) portYIELD_FROM_ISR();
|
||||
|
||||
// clear interrupt
|
||||
I2S0.int_clr.val = I2S0.int_st.val; //clear pending interrupt
|
||||
}
|
||||
|
||||
//
|
||||
// I2S bitstream generator task
|
||||
//
|
||||
static void IRAM_ATTR i2sOutTask(void* parameter) {
|
||||
lldesc_t *dma_desc;
|
||||
while (1) {
|
||||
// Wait a DMA complete event from I2S isr
|
||||
// (Block until a DMA transfer has complete)
|
||||
xQueueReceive(o_dma.queue, &dma_desc, portMAX_DELAY);
|
||||
o_dma.current = (uint32_t*)(dma_desc->buf);
|
||||
// It reuses the oldest (just transferred) buffer with the name "current"
|
||||
// and fills the buffer for later DMA.
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL(); // Lock pulser status
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
//
|
||||
// Fillout the buffer for pulse
|
||||
//
|
||||
// To avoid buffer overflow, all of the maximum pulse width (normaly about 10us)
|
||||
// is adjusted to be in a single buffer.
|
||||
// DMA_SAMPLE_SAFE_COUNT is referred to as the margin value.
|
||||
// Therefore, if a buffer is close to full and it is time to generate a pulse,
|
||||
// the generation of the buffer is interrupted (the buffer length is shortened slightly)
|
||||
// and the pulse generation is postponed until the next buffer is filled.
|
||||
//
|
||||
i2s_fillout_dma_buffer(dma_desc);
|
||||
dma_desc->length = o_dma.rw_pos * I2S_SAMPLE_SIZE;
|
||||
} else if (i2s_out_pulser_status == WAITING) {
|
||||
if (dma_desc->qe.stqe_next == NULL) {
|
||||
// Tail of the DMA descriptor found
|
||||
// I2S TX module has alrewdy stopped by ISR
|
||||
i2s_out_stop();
|
||||
i2s_clear_o_dma_buffers(0); // 0 for static I2S control mode (right ch. data is always 0)
|
||||
// You need to set the status before calling i2s_out_start()
|
||||
// because the process in i2s_out_start() is different depending on the status.
|
||||
i2s_out_pulser_status = PASSTHROUGH;
|
||||
i2s_out_start();
|
||||
} else {
|
||||
// Processing a buffer slightly ahead of the tail buffer.
|
||||
// We don't need to fill up the buffer by port_data any more.
|
||||
i2s_clear_dma_buffer(dma_desc, 0); // Essentially, no clearing is required. I'll make sure I know when I've written something.
|
||||
o_dma.rw_pos = 0; // If someone calls i2s_out_push_sample, make sure there is no buffer overflow
|
||||
dma_desc->qe.stqe_next = NULL; // Cut the DMA descriptor ring. This allow us to identify the tail of the buffer.
|
||||
}
|
||||
} else {
|
||||
// Stepper paused (passthrough state, static I2S control mode)
|
||||
// In the passthrough mode, there is no need to fill the buffer with port_data.
|
||||
i2s_clear_dma_buffer(dma_desc, 0); // Essentially, no clearing is required. I'll make sure I know when I've written something.
|
||||
o_dma.rw_pos = 0; // If someone calls i2s_out_push_sample, make sure there is no buffer overflow
|
||||
}
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL(); // Unlock pulser status
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
//
|
||||
// External funtions
|
||||
//
|
||||
void IRAM_ATTR i2s_out_delay() {
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL();
|
||||
if (i2s_out_pulser_status == PASSTHROUGH) {
|
||||
// Depending on the timing, it may not be reflected immediately,
|
||||
// so wait twice as long just in case.
|
||||
ets_delay_us(I2S_OUT_USEC_PER_PULSE * 2);
|
||||
} else {
|
||||
// Just wait until the data now registered in the DMA descripter
|
||||
// is reflected in the I2S TX module via FIFO.
|
||||
delay(I2S_OUT_DELAY_MS);
|
||||
}
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
#else
|
||||
ets_delay_us(I2S_OUT_USEC_PER_PULSE * 2);
|
||||
#endif
|
||||
}
|
||||
|
||||
void IRAM_ATTR i2s_out_write(uint8_t pin, uint8_t val) {
|
||||
uint32_t bit = bit(pin);
|
||||
if (val) {
|
||||
atomic_fetch_or(&i2s_out_port_data, bit);
|
||||
} else {
|
||||
atomic_fetch_and(&i2s_out_port_data, ~bit);
|
||||
}
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
// It needs a lock for access, but I've given up because I need speed.
|
||||
// This is not a problem as long as there is no overlap between the status change and digitalWrite().
|
||||
if (i2s_out_pulser_status == PASSTHROUGH) {
|
||||
i2s_out_single_data();
|
||||
}
|
||||
#else
|
||||
i2s_out_single_data();
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t IRAM_ATTR i2s_out_state(uint8_t pin) {
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data);
|
||||
return (!!(port_data & bit(pin)));
|
||||
}
|
||||
|
||||
uint32_t IRAM_ATTR i2s_out_push_sample(uint32_t num) {
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
if (num > SAMPLE_SAFE_COUNT) {
|
||||
return 0;
|
||||
}
|
||||
// push at least one sample (even if num is zero)
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data);
|
||||
uint32_t n = 0;
|
||||
do {
|
||||
o_dma.current[o_dma.rw_pos++] = port_data;
|
||||
n++;
|
||||
} while(n < num);
|
||||
return n;
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
int IRAM_ATTR i2s_out_set_passthrough() {
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL();
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
i2s_out_pulser_status = WAITING; // Start stopping the pulser
|
||||
}
|
||||
#else
|
||||
i2s_out_pulser_status = PASSTHROUGH;
|
||||
#endif
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
return 0;
|
||||
}
|
||||
|
||||
int IRAM_ATTR i2s_out_set_stepping() {
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL();
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
// Re-entered (fail safe)
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (i2s_out_pulser_status == WAITING) {
|
||||
// Wait for complete DMAs
|
||||
for(;;) {
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
delay(I2S_OUT_DELAY_DMABUF_MS);
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL();
|
||||
if (i2s_out_pulser_status == WAITING) {
|
||||
continue;
|
||||
}
|
||||
if (i2s_out_pulser_status == PASSTHROUGH) {
|
||||
// DMA completed
|
||||
break;
|
||||
}
|
||||
// Another function change the I2S state to STEPPING
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
// Change I2S state from PASSTHROUGH to STEPPING
|
||||
i2s_out_stop();
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data);
|
||||
i2s_clear_o_dma_buffers(port_data);
|
||||
|
||||
// You need to set the status before calling i2s_out_start()
|
||||
// because the process in i2s_out_start() is different depending on the status.
|
||||
i2s_out_pulser_status = STEPPING;
|
||||
i2s_out_start();
|
||||
#else
|
||||
i2s_out_pulser_status = STEPPING;
|
||||
#endif
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
return 0;
|
||||
}
|
||||
|
||||
int IRAM_ATTR i2s_out_set_pulse_period(uint32_t period) {
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
i2s_out_pulse_period = period;
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
int IRAM_ATTR i2s_out_set_pulse_callback(i2s_out_pulse_func_t func) {
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
i2s_out_pulse_func = func;
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
int IRAM_ATTR i2s_out_reset() {
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL();
|
||||
i2s_out_stop();
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data);
|
||||
i2s_clear_o_dma_buffers(port_data);
|
||||
} else if (i2s_out_pulser_status == WAITING) {
|
||||
i2s_clear_o_dma_buffers(0);
|
||||
i2s_out_pulser_status = PASSTHROUGH;
|
||||
}
|
||||
#endif
|
||||
// You need to set the status before calling i2s_out_start()
|
||||
// because the process in i2s_out_start() is different depending on the status.
|
||||
i2s_out_start();
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
return 0;
|
||||
}
|
||||
|
||||
//
|
||||
// Initialize funtion (external function)
|
||||
//
|
||||
int IRAM_ATTR i2s_out_init(i2s_out_init_t &init_param) {
|
||||
if (i2s_out_initialized) {
|
||||
// already initialized
|
||||
return -1;
|
||||
}
|
||||
|
||||
atomic_store(&i2s_out_port_data, init_param.init_val);
|
||||
|
||||
// To make sure hardware is enabled before any hardware register operations.
|
||||
periph_module_reset(PERIPH_I2S0_MODULE);
|
||||
periph_module_enable(PERIPH_I2S0_MODULE);
|
||||
|
||||
// Route the i2s pins to the appropriate GPIO
|
||||
i2s_out_gpio_attach(init_param.ws_pin, init_param.bck_pin, init_param.data_pin);
|
||||
|
||||
/**
|
||||
* Each i2s transfer will take
|
||||
* fpll = PLL_D2_CLK -- clka_en = 0
|
||||
*
|
||||
* fi2s = fpll / N + b/a -- N + b/a = clkm_div_num
|
||||
* fi2s = 160MHz / 2
|
||||
* fi2s = 80MHz
|
||||
*
|
||||
* fbclk = fi2s / M -- M = tx_bck_div_num
|
||||
* fbclk = 80MHz / 2
|
||||
* fbclk = 40MHz
|
||||
*
|
||||
* fwclk = fbclk / 32
|
||||
*
|
||||
* for fwclk = 250kHz(16-bit: 4µS pulse time), 125kHz(32-bit: 8μS pulse time)
|
||||
* N = 10, b/a = 0
|
||||
* M = 2
|
||||
* for fwclk = 500kHz(16-bit: 2µS pulse time), 250kHz(32-bit: 4μS pulse time)
|
||||
* N = 5, b/a = 0
|
||||
* M = 2
|
||||
* for fwclk = 1000kHz(16-bit: 1µS pulse time), 500kHz(32-bit: 2μS pulse time)
|
||||
* N = 2, b/a = 2/1 (N + b/a = 2.5)
|
||||
* M = 2
|
||||
*/
|
||||
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
// Allocate the array of pointers to the buffers
|
||||
o_dma.buffers = (uint32_t **)malloc(sizeof(uint32_t*) * I2S_OUT_DMABUF_COUNT);
|
||||
if (o_dma.buffers == nullptr) return -1;
|
||||
|
||||
// Allocate each buffer that can be used by the DMA controller
|
||||
for (int buf_idx = 0; buf_idx < I2S_OUT_DMABUF_COUNT; buf_idx++) {
|
||||
o_dma.buffers[buf_idx] = (uint32_t*) heap_caps_calloc(1, I2S_OUT_DMABUF_LEN, MALLOC_CAP_DMA);
|
||||
if (o_dma.buffers[buf_idx] == nullptr) return -1;
|
||||
}
|
||||
|
||||
// Allocate the array of DMA descriptors
|
||||
o_dma.desc = (lldesc_t**) malloc(sizeof(lldesc_t*) * I2S_OUT_DMABUF_COUNT);
|
||||
if (o_dma.desc == nullptr) return -1;
|
||||
|
||||
// Allocate each DMA descriptor that will be used by the DMA controller
|
||||
for (int buf_idx = 0; buf_idx < I2S_OUT_DMABUF_COUNT; buf_idx++) {
|
||||
o_dma.desc[buf_idx] = (lldesc_t*) heap_caps_malloc(sizeof(lldesc_t), MALLOC_CAP_DMA);
|
||||
if (o_dma.desc[buf_idx] == nullptr) return -1;
|
||||
}
|
||||
|
||||
// Initialize
|
||||
i2s_clear_o_dma_buffers(init_param.init_val);
|
||||
o_dma.rw_pos = 0;
|
||||
o_dma.current = NULL;
|
||||
o_dma.queue = xQueueCreate(I2S_OUT_DMABUF_COUNT, sizeof(uint32_t *));
|
||||
|
||||
// Set the first DMA descriptor
|
||||
I2S0.out_link.addr = (uint32_t)o_dma.desc[0];
|
||||
#endif
|
||||
|
||||
// stop i2s
|
||||
I2S0.out_link.stop = 1;
|
||||
I2S0.conf.tx_start = 0;
|
||||
|
||||
I2S0.int_clr.val = I2S0.int_st.val; //clear pending interrupt
|
||||
|
||||
//
|
||||
// i2s_param_config
|
||||
//
|
||||
|
||||
// configure I2S data port interface.
|
||||
i2s_out_reset_fifo();
|
||||
|
||||
//reset i2s
|
||||
I2S0.conf.tx_reset = 1;
|
||||
I2S0.conf.tx_reset = 0;
|
||||
I2S0.conf.rx_reset = 1;
|
||||
I2S0.conf.rx_reset = 0;
|
||||
|
||||
//reset dma
|
||||
I2S0.lc_conf.in_rst = 1; // Set this bit to reset in DMA FSM. (R/W)
|
||||
I2S0.lc_conf.in_rst = 0;
|
||||
I2S0.lc_conf.out_rst = 1; // Set this bit to reset out DMA FSM. (R/W)
|
||||
I2S0.lc_conf.out_rst = 0;
|
||||
|
||||
//Enable and configure DMA
|
||||
I2S0.lc_conf.check_owner = 0;
|
||||
I2S0.lc_conf.out_loop_test = 0;
|
||||
I2S0.lc_conf.out_auto_wrback = 0; // Disable auto outlink-writeback when all the data has been transmitted
|
||||
I2S0.lc_conf.out_data_burst_en = 0;
|
||||
I2S0.lc_conf.outdscr_burst_en = 0;
|
||||
I2S0.lc_conf.out_no_restart_clr = 0;
|
||||
I2S0.lc_conf.indscr_burst_en = 0;
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
I2S0.lc_conf.out_eof_mode = 1; // I2S_OUT_EOF_INT generated when DMA has popped all data from the FIFO;
|
||||
#endif
|
||||
I2S0.conf2.lcd_en = 0;
|
||||
I2S0.conf2.camera_en = 0;
|
||||
I2S0.pdm_conf.pcm2pdm_conv_en = 0;
|
||||
I2S0.pdm_conf.pdm2pcm_conv_en = 0;
|
||||
|
||||
I2S0.fifo_conf.dscr_en = 0;
|
||||
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
// Stream output mode
|
||||
I2S0.conf_chan.tx_chan_mod = 4; // 3:right+constant 4:left+constant (when tx_msb_right = 1)
|
||||
I2S0.conf_single_data = 0;
|
||||
} else {
|
||||
// Static output mode
|
||||
I2S0.conf_chan.tx_chan_mod = 3; // 3:right+constant 4:left+constant (when tx_msb_right = 1)
|
||||
I2S0.conf_single_data = init_param.init_val;
|
||||
}
|
||||
#else
|
||||
// For the static output mode
|
||||
I2S0.conf_chan.tx_chan_mod = 3; // 3:right+constant 4:left+constant (when tx_msb_right = 1)
|
||||
I2S0.conf_single_data = init_param.init_val; // initial constant value
|
||||
#endif
|
||||
#if I2S_OUT_NUM_BITS == 16
|
||||
I2S0.fifo_conf.tx_fifo_mod = 0; // 0: 16-bit dual channel data, 3: 32-bit single channel data
|
||||
I2S0.fifo_conf.rx_fifo_mod = 0; // 0: 16-bit dual channel data, 3: 32-bit single channel data
|
||||
I2S0.sample_rate_conf.tx_bits_mod = 16; // default is 16-bits
|
||||
I2S0.sample_rate_conf.rx_bits_mod = 16; // default is 16-bits
|
||||
#else
|
||||
I2S0.fifo_conf.tx_fifo_mod = 3; // 0: 16-bit dual channel data, 3: 32-bit single channel data
|
||||
I2S0.fifo_conf.rx_fifo_mod = 3; // 0: 16-bit dual channel data, 3: 32-bit single channel data
|
||||
// Data width is 32-bit. Forgetting this setting will result in a 16-bit transfer.
|
||||
I2S0.sample_rate_conf.tx_bits_mod = 32;
|
||||
I2S0.sample_rate_conf.rx_bits_mod = 32;
|
||||
#endif
|
||||
I2S0.conf.tx_mono = 0; // Set this bit to enable transmitter’s mono mode in PCM standard mode.
|
||||
|
||||
I2S0.conf_chan.rx_chan_mod = 1; // 1: right+right
|
||||
I2S0.conf.rx_mono = 0;
|
||||
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
I2S0.fifo_conf.dscr_en = 1; //connect DMA to fifo
|
||||
#endif
|
||||
I2S0.conf.tx_start = 0;
|
||||
I2S0.conf.rx_start = 0;
|
||||
|
||||
I2S0.conf.tx_msb_right = 1; // Set this bit to place right-channel data at the MSB in the transmit FIFO.
|
||||
I2S0.conf.tx_right_first = 0; // Setting this bit allows the right-channel data to be sent first.
|
||||
|
||||
I2S0.conf.tx_slave_mod = 0; // Master
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
I2S0.fifo_conf.tx_fifo_mod_force_en = 1; //The bit should always be set to 1.
|
||||
#endif
|
||||
I2S0.pdm_conf.rx_pdm_en = 0; // Set this bit to enable receiver’s PDM mode.
|
||||
I2S0.pdm_conf.tx_pdm_en = 0; // Set this bit to enable transmitter’s PDM mode.
|
||||
|
||||
// I2S_COMM_FORMAT_I2S_LSB
|
||||
I2S0.conf.tx_short_sync = 0; // Set this bit to enable transmitter in PCM standard mode.
|
||||
I2S0.conf.rx_short_sync = 0; // Set this bit to enable receiver in PCM standard mode.
|
||||
I2S0.conf.tx_msb_shift = 0; // Do not use the Philips standard to avoid bit-shifting
|
||||
I2S0.conf.rx_msb_shift = 0; // Do not use the Philips standard to avoid bit-shifting
|
||||
|
||||
//
|
||||
// i2s_set_clk
|
||||
//
|
||||
|
||||
// set clock (fi2s) 160MHz / 5
|
||||
I2S0.clkm_conf.clka_en = 0; // Use 160 MHz PLL_D2_CLK as reference
|
||||
// N + b/a = 0
|
||||
#if I2S_OUT_NUM_BITS == 16
|
||||
// N = 10
|
||||
I2S0.clkm_conf.clkm_div_num = 10; // minimum value of 2, reset value of 4, max 256 (I²S clock divider’s integral value)
|
||||
#else
|
||||
// N = 5
|
||||
I2S0.clkm_conf.clkm_div_num = 5; // minimum value of 2, reset value of 4, max 256 (I²S clock divider’s integral value)
|
||||
#endif
|
||||
// b/a = 0
|
||||
I2S0.clkm_conf.clkm_div_b = 0; // 0 at reset
|
||||
I2S0.clkm_conf.clkm_div_a = 0; // 0 at reset, what about divide by 0? (not an issue)
|
||||
|
||||
// Bit clock configuration bit in transmitter mode.
|
||||
// fbck = fi2s / tx_bck_div_num = (160 MHz / 5) / 2 = 16 MHz
|
||||
I2S0.sample_rate_conf.tx_bck_div_num = 2; // minimum value of 2 defaults to 6
|
||||
I2S0.sample_rate_conf.rx_bck_div_num = 2;
|
||||
|
||||
#ifdef USE_I2S_OUT_STREAM
|
||||
// Enable TX interrupts (DMA Interrupts)
|
||||
I2S0.int_ena.out_eof = 1; // Triggered when rxlink has finished sending a packet.
|
||||
I2S0.int_ena.out_dscr_err = 0; // Triggered when invalid rxlink descriptors are encountered.
|
||||
I2S0.int_ena.out_total_eof = 1; // Triggered when all transmitting linked lists are used up.
|
||||
I2S0.int_ena.out_done = 0; // Triggered when all transmitted and buffered data have been read.
|
||||
|
||||
// default pulse callback period (μsec)
|
||||
i2s_out_pulse_period = init_param.pulse_period;
|
||||
i2s_out_pulse_func = init_param.pulse_func;
|
||||
|
||||
// Create the task that will feed the buffer
|
||||
xTaskCreatePinnedToCore(i2sOutTask,
|
||||
"I2SOutTask",
|
||||
1024 * 10,
|
||||
NULL,
|
||||
1,
|
||||
nullptr,
|
||||
CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core
|
||||
);
|
||||
|
||||
// Allocate and Enable the I2S interrupt
|
||||
esp_intr_alloc(ETS_I2S0_INTR_SOURCE, 0, i2s_out_intr_handler, nullptr, &i2s_out_isr_handle);
|
||||
esp_intr_enable(i2s_out_isr_handle);
|
||||
#endif
|
||||
|
||||
// Remember GPIO pin numbers
|
||||
i2s_out_ws_pin = init_param.ws_pin;
|
||||
i2s_out_bck_pin = init_param.bck_pin;
|
||||
i2s_out_data_pin = init_param.data_pin;
|
||||
i2s_out_initialized = 1;
|
||||
|
||||
// Start the I2S peripheral
|
||||
i2s_out_start();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifndef I2S_OUT_WS
|
||||
#define I2S_OUT_WS GPIO_NUM_17
|
||||
#endif
|
||||
#ifndef I2S_OUT_BCK
|
||||
#define I2S_OUT_BCK GPIO_NUM_22
|
||||
#endif
|
||||
#ifndef I2S_OUT_DATA
|
||||
#define I2S_OUT_DATA GPIO_NUM_21
|
||||
#endif
|
||||
#ifndef I2S_OUT_INIT_VAL
|
||||
#define I2S_OUT_INIT_VAL 0
|
||||
#endif
|
||||
/*
|
||||
Initialize I2S out by default parameters.
|
||||
|
||||
return -1 ... already initialized
|
||||
*/
|
||||
int IRAM_ATTR i2s_out_init() {
|
||||
i2s_out_init_t default_param = {
|
||||
.ws_pin = I2S_OUT_WS,
|
||||
.bck_pin = I2S_OUT_BCK,
|
||||
.data_pin = I2S_OUT_DATA,
|
||||
.pulse_func = NULL,
|
||||
.pulse_period = I2S_OUT_USEC_PER_PULSE,
|
||||
.init_val = I2S_OUT_INIT_VAL,
|
||||
};
|
||||
return i2s_out_init(default_param);
|
||||
}
|
||||
|
||||
#endif
|
@@ -1,38 +0,0 @@
|
||||
#ifndef _machine_common_h
|
||||
#define _machine_common_h
|
||||
|
||||
#ifndef SPINDLE_TYPE
|
||||
#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
|
||||
#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 STEP_PULSE_MIN 2 // uSeconds
|
||||
#define STEP_PULSE_MAX 10 // uSeconds
|
||||
|
||||
// =============== Don't change or comment these out ======================
|
||||
// They are for legacy purposes and will not affect your I/O
|
||||
|
||||
#define STEP_MASK B111111
|
||||
|
||||
#define PROBE_MASK 1
|
||||
|
||||
#endif // _machine_common_h
|
@@ -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(" ");
|
||||
// }
|
@@ -1,54 +0,0 @@
|
||||
/*
|
||||
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/>.
|
||||
*/
|
||||
|
||||
#ifndef print_h
|
||||
#define print_h
|
||||
|
||||
|
||||
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();
|
||||
|
||||
#endif
|
@@ -1,5 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
config.h - compile time configuration
|
||||
Config.h - compile time configuration
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
@@ -35,8 +37,6 @@ Some features should not be changed. See notes below.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef config_h
|
||||
#define config_h
|
||||
#include <Arduino.h>
|
||||
|
||||
// It is no longer necessary to edit this file to choose
|
||||
@@ -83,10 +83,10 @@ Some features should not be changed. See notes below.
|
||||
|
||||
// Include the file that loads the machine-specific config file.
|
||||
// machine.h must be edited to choose the desired file.
|
||||
#include "machine.h"
|
||||
#include "Machine.h"
|
||||
|
||||
// machine_common.h contains settings that do not change
|
||||
#include "machine_common.h"
|
||||
#include "MachineCommon.h"
|
||||
|
||||
#define MAX_N_AXIS 6
|
||||
|
||||
@@ -122,7 +122,6 @@ Some features should not be changed. See notes below.
|
||||
# define WIFI_OR_BLUETOOTH
|
||||
#endif
|
||||
|
||||
|
||||
#define ENABLE_HTTP //enable HTTP and all related services
|
||||
#define ENABLE_OTA //enable OTA
|
||||
#define ENABLE_TELNET //enable telnet
|
||||
@@ -317,13 +316,6 @@ Some features should not be changed. See notes below.
|
||||
// NOTE: PLEASE DO NOT USE THIS, unless you have a situation that needs it.
|
||||
// #define INVERT_LIMIT_PIN_MASK (bit(X_AXIS)|bit(Y_AXIS)) // Default disabled. Uncomment to enable.
|
||||
|
||||
// Inverts the spindle enable pin from low-disabled/high-enabled to low-enabled/high-disabled. Useful
|
||||
// for some pre-built electronic boards.
|
||||
// #define INVERT_SPINDLE_ENABLE_PIN // Default disabled. Uncomment to enable.
|
||||
|
||||
// Inverts the spindle PWM output pin from low-disabled/high-enabled to low-enabled/high-disabled.
|
||||
// #define INVERT_SPINDLE_OUTPUT_PIN // Default disabled. Uncomment to enable.
|
||||
|
||||
// Inverts the selected coolant pin from low-disabled/high-enabled to low-enabled/high-disabled. Useful
|
||||
// for some pre-built electronic boards.
|
||||
// #define INVERT_COOLANT_FLOOD_PIN // Default disabled. Uncomment to enable.
|
||||
@@ -414,7 +406,7 @@ Some features should not be changed. See notes below.
|
||||
// smoothing the stepping of multi-axis motions. This feature smooths motion particularly at low step
|
||||
// frequencies below 10kHz, where the aliasing between axes of multi-axis motions can cause audible
|
||||
// noise and shake your machine. At even lower step frequencies, AMASS adapts and provides even better
|
||||
// step smoothing. See stepper.c for more details on the AMASS system works.
|
||||
// step smoothing. See Stepper.c for more details on the AMASS system works.
|
||||
#define ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING // Default enabled. Comment to disable.
|
||||
|
||||
// Sets the maximum step rate allowed to be written as a Grbl setting. This option enables an error
|
||||
@@ -446,13 +438,6 @@ Some features should not be changed. See notes below.
|
||||
// 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.
|
||||
|
||||
// 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.
|
||||
|
||||
// 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
|
||||
// sent upon a line buffer overflow, but should for all normal lines sent to Grbl. For example, if a user
|
||||
@@ -505,7 +490,6 @@ Some features should not be changed. See notes below.
|
||||
// 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)
|
||||
|
||||
|
||||
// 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
|
||||
// pulse in one operation.
|
||||
@@ -728,5 +712,3 @@ Some features should not be changed. See notes below.
|
||||
#define RPM_LINE_B2 4.754411e+01
|
||||
#define RPM_LINE_A3 9.528342e-03
|
||||
#define RPM_LINE_B3 3.306286e+01
|
||||
|
||||
#endif
|
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
coolant_control.c - coolant control methods
|
||||
CoolantControl.cpp - coolant control methods
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
@@ -21,8 +21,7 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
#include "Grbl.h"
|
||||
|
||||
void coolant_init() {
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
@@ -34,7 +33,6 @@ 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;
|
||||
@@ -59,7 +57,6 @@ uint8_t coolant_get_state() {
|
||||
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() {
|
||||
@@ -79,13 +76,13 @@ void coolant_stop() {
|
||||
#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 {
|
||||
@@ -111,11 +108,11 @@ void coolant_set_state(uint8_t mode) {
|
||||
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;
|
||||
if (sys.state == STATE_CHECK_MODE)
|
||||
return;
|
||||
protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
|
||||
coolant_set_state(mode);
|
||||
}
|
@@ -1,5 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
coolant_control.h - spindle control methods
|
||||
CoolantControl.h - spindle control methods
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
@@ -21,9 +23,6 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef coolant_control_h
|
||||
#define coolant_control_h
|
||||
|
||||
#define COOLANT_NO_SYNC false
|
||||
#define COOLANT_FORCE_SYNC true
|
||||
|
||||
@@ -31,7 +30,6 @@
|
||||
#define COOLANT_STATE_FLOOD bit(0)
|
||||
#define COOLANT_STATE_MIST bit(1)
|
||||
|
||||
|
||||
// Initializes coolant control pins.
|
||||
void coolant_init();
|
||||
|
||||
@@ -46,5 +44,3 @@ void coolant_set_state(uint8_t mode);
|
||||
|
||||
// G-code parser entry-point for setting coolant states. Checks for and executes additional conditions.
|
||||
void coolant_sync(uint8_t mode);
|
||||
|
||||
#endif
|
@@ -1,7 +1,7 @@
|
||||
// This file loads custom code from the Custom/ subdirectory if
|
||||
// CUSTOM_CODE_FILENAME is defined.
|
||||
|
||||
#include "grbl.h"
|
||||
#include "Grbl.h"
|
||||
|
||||
#ifdef CUSTOM_CODE_FILENAME
|
||||
# include CUSTOM_CODE_FILENAME
|
501
Grbl_Esp32/src/Defaults.h
Normal file
501
Grbl_Esp32/src/Defaults.h
Normal file
@@ -0,0 +1,501 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
Defaults.h - defaults settings configuration file
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
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/>.
|
||||
*/
|
||||
|
||||
/* The defaults.h file serves as a central default settings selector for different machine
|
||||
types, from DIY CNC mills to CNC conversions of off-the-shelf machines. The settings
|
||||
files listed here are supplied by users, so your results may vary. However, this should
|
||||
give you a good starting point as you get to know your machine and tweak the settings for
|
||||
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
|
||||
|
||||
#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_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_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_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_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_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_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_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_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
|
||||
|
||||
// ======== 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_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_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_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_DELAY_SPINUP
|
||||
# define DEFAULT_SPINDLE_DELAY_SPINUP 0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_SPINDLE_DELAY_SPINDOWN
|
||||
# define DEFAULT_SPINDLE_DELAY_SPINDOWN 0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_INVERT_SPINDLE_OUTPUT_PIN
|
||||
# define DEFAULT_INVERT_SPINDLE_OUTPUT_PIN 0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_INVERT_SPINDLE_ENABLE_PIN
|
||||
# define DEFAULT_INVERT_SPINDLE_ENABLE_PIN 0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
||||
# define DEFAULT_SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED 0
|
||||
#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_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_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_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_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
|
||||
|
||||
// =========== 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
|
||||
|
||||
// ============ 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
|
||||
|
||||
// ============== 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 ============
|
||||
|
||||
#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 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
|
||||
|
||||
// ========== 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
|
||||
|
||||
// ========== 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
|
||||
|
||||
// ================== 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
|
||||
#endif
|
||||
|
||||
#ifndef X_DISABLE_PIN
|
||||
# define X_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Y_DISABLE_PIN
|
||||
# define Y_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Z_DISABLE_PIN
|
||||
# define Z_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef A_DISABLE_PIN
|
||||
# define A_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef B_DISABLE_PIN
|
||||
# define B_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef C_DISABLE_PIN
|
||||
# define C_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
|
||||
#ifndef X2_DISABLE_PIN
|
||||
# define X2_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Y2_DISABLE_PIN
|
||||
# define Y2_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Z2_DISABLE_PIN
|
||||
# define Z2_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef A2_DISABLE_PIN
|
||||
# define A2_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef B2_DISABLE_PIN
|
||||
# define B2_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef C2_DISABLE_PIN
|
||||
# define C2_DISABLE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
|
||||
#ifndef X_LIMIT_PIN
|
||||
# define X_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Y_LIMIT_PIN
|
||||
# define Y_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Z_LIMIT_PIN
|
||||
# define Z_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef A_LIMIT_PIN
|
||||
# define A_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef B_LIMIT_PIN
|
||||
# define B_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef C_LIMIT_PIN
|
||||
# define C_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef X2_LIMIT_PIN
|
||||
# define X2_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Y2_LIMIT_PIN
|
||||
# define Y2_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Z2_LIMIT_PIN
|
||||
# define Z2_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef A2_LIMIT_PIN
|
||||
# define A2_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef B2_LIMIT_PIN
|
||||
# define B2_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef C2_LIMIT_PIN
|
||||
# define C2_LIMIT_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
|
||||
// assigned all MS3 (microstep pin 3) to UNDEFINED_PIN
|
||||
|
||||
#ifndef X_STEPPER_MS3
|
||||
# define X_STEPPER_MS3 UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Y_STEPPER_MS3
|
||||
# define Y_STEPPER_MS3 UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Z_STEPPER_MS3
|
||||
# define Z_STEPPER_MS3 UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef A_STEPPER_MS3
|
||||
# define A_STEPPER_MS3 UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef B_STEPPER_MS3
|
||||
# define B_STEPPER_MS3 UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef C_STEPPER_MS3
|
||||
# define C_STEPPER_MS3 UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef X2_STEPPER_MS3
|
||||
# define X2_STEPPER_MS3 UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Y2_STEPPER_MS3
|
||||
# define Y2_STEPPER_MS3 UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef Z2_STEPPER_MS3
|
||||
# define Z2_STEPPER_MS3 UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef A2_STEPPER_MS3
|
||||
# define A2_STEPPER_MS3 UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef B2_STEPPER_MS3
|
||||
# define B2_STEPPER_MS3 UNDEFINED_PIN
|
||||
#endif
|
||||
#ifndef C2_STEPPER_MS3
|
||||
# define C2_STEPPER_MS3 UNDEFINED_PIN
|
||||
#endif
|
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
eeprom.cpp - Header for system level commands and real-time processes
|
||||
Eeprom.cpp - Header for system level commands and real-time processes
|
||||
Part of Grbl
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
@@ -18,7 +18,7 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "grbl.h"
|
||||
#include "Grbl.h"
|
||||
|
||||
void memcpy_to_eeprom_with_checksum(unsigned int destination, const char* source, unsigned int size) {
|
||||
unsigned char checksum = 0;
|
@@ -1,5 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
eeprom.h - Header for system level commands and real-time processes
|
||||
Eeprom.h - Header for system level commands and real-time processes
|
||||
Part of Grbl
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
@@ -18,14 +20,9 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef eeprom_memcpy_h
|
||||
#define eeprom_memcpy_h
|
||||
|
||||
#include "grbl.h"
|
||||
#include "Grbl.h"
|
||||
|
||||
//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);
|
||||
|
||||
#endif
|
1365
Grbl_Esp32/src/GCode.cpp
Normal file
1365
Grbl_Esp32/src/GCode.cpp
Normal file
File diff suppressed because it is too large
Load Diff
261
Grbl_Esp32/src/GCode.h
Normal file
261
Grbl_Esp32/src/GCode.h
Normal file
@@ -0,0 +1,261 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
GCode.h - rs274/ngc parser.
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
||||
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/>.
|
||||
*/
|
||||
|
||||
// Define modal group internal numbers for checking multiple command violations and tracking the
|
||||
// type of command that is called in the block. A modal group is a group of g-code commands that are
|
||||
// mutually exclusive, or cannot exist on the same line, because they each toggle a state or execute
|
||||
// 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_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
|
||||
// #define OTHER_INPUT_T 16
|
||||
|
||||
// Define command actions for within execution-type modal groups (motion, stopping, non-modal). Used
|
||||
// internally by the parser to know which command to execute.
|
||||
// NOTE: Some macro values are assigned specific values to make g-code state reporting and parsing
|
||||
// compile a litte smaller. Necessary due to being completely out of flash on the 328p. Although not
|
||||
// ideal, just be careful with values that state 'do not alter' and check both report.c and gcode.c
|
||||
// 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)
|
||||
|
||||
// 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)
|
||||
|
||||
// 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)
|
||||
|
||||
// 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)
|
||||
|
||||
// Modal Group G4: Arc IJK distance mode
|
||||
#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)
|
||||
|
||||
// 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)
|
||||
|
||||
// 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)
|
||||
|
||||
// Modal Group G7: Cutter radius compensation mode
|
||||
#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)
|
||||
|
||||
// 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)
|
||||
|
||||
// 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)
|
||||
|
||||
// Modal Group M9: Override control
|
||||
#ifdef DEACTIVATE_PARKING_UPON_INIT
|
||||
# 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.
|
||||
#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
|
||||
|
||||
// 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_CHANGE 1
|
||||
|
||||
// Modal Group G12: Active work coordinate system
|
||||
// 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 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 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
|
||||
#ifdef SET_CHECK_MODE_PROBE_TO_START
|
||||
# define GC_PROBE_CHECK_MODE GC_UPDATE_POS_NONE
|
||||
#else
|
||||
# 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)
|
||||
|
||||
// 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 distance_arc; // {G91.1} NOTE: Don't track. Only default supported.
|
||||
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 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}
|
||||
} 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 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
|
||||
} 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 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
|
||||
// position in mm. Loaded from EEPROM when called.
|
||||
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.
|
||||
} parser_state_t;
|
||||
extern parser_state_t gc_state;
|
||||
|
||||
typedef struct {
|
||||
uint8_t non_modal_command;
|
||||
gc_modal_t modal;
|
||||
gc_values_t values;
|
||||
} parser_block_t;
|
||||
|
||||
// Initialize the parser
|
||||
void gc_init();
|
||||
|
||||
// Execute one block of rs275/ngc/g-code
|
||||
uint8_t gc_execute_line(char* line, uint8_t client);
|
||||
|
||||
// Set g-code parser position. Input in steps.
|
||||
void gc_sync_position();
|
@@ -1,5 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
grbl.h - Header for system level commands and real-time processes
|
||||
Grbl.h - Header for system level commands and real-time processes
|
||||
Part of Grbl
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
@@ -18,12 +20,10 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
// Grbl versioning system
|
||||
|
||||
#define GRBL_VERSION "1.3a"
|
||||
#define GRBL_VERSION_BUILD "20200727"
|
||||
|
||||
#define GRBL_VERSION_BUILD "20200812"
|
||||
|
||||
//#include <sdkconfig.h>
|
||||
#include <Arduino.h>
|
||||
@@ -33,72 +33,66 @@
|
||||
#include <freertos/task.h>
|
||||
#include <Preferences.h>
|
||||
|
||||
#include "driver/timer.h"
|
||||
#include <driver/timer.h>
|
||||
|
||||
// Define the Grbl system include files. NOTE: Do not alter organization.
|
||||
#include "config.h"
|
||||
#include "nuts_bolts.h"
|
||||
#include "tdef.h"
|
||||
#include "Config.h"
|
||||
#include "NutsBolts.h"
|
||||
|
||||
#include "defaults.h"
|
||||
#include "settings.h"
|
||||
#include "authentication.h"
|
||||
#include "system.h"
|
||||
#include "Defaults.h"
|
||||
#include "SettingsStorage.h"
|
||||
#include "WebUI/Authentication.h"
|
||||
#include "WebUI/Commands.h"
|
||||
#include "System.h"
|
||||
|
||||
#include "planner.h"
|
||||
#include "coolant_control.h"
|
||||
#include "grbl_eeprom.h"
|
||||
#include "gcode.h"
|
||||
#include "grbl_limits.h"
|
||||
#include "motion_control.h"
|
||||
#include "print.h"
|
||||
#include "probe.h"
|
||||
#include "protocol.h"
|
||||
#include "report.h"
|
||||
#include "serial.h"
|
||||
#include "Planner.h"
|
||||
#include "CoolantControl.h"
|
||||
#include "Eeprom.h"
|
||||
#include "GCode.h"
|
||||
#include "Limits.h"
|
||||
#include "MotionControl.h"
|
||||
#include "Probe.h"
|
||||
#include "Protocol.h"
|
||||
#include "Report.h"
|
||||
#include "Serial.h"
|
||||
#include "Pins.h"
|
||||
#include "Spindles/SpindleClass.h"
|
||||
#include "Motors/MotorClass.h"
|
||||
#include "stepper.h"
|
||||
#include "jog.h"
|
||||
#include "inputbuffer.h"
|
||||
#include "commands.h"
|
||||
#include "SettingsClass.h"
|
||||
#include "Spindles/Spindle.h"
|
||||
#include "Motors/Motors.h"
|
||||
#include "Stepper.h"
|
||||
#include "Jog.h"
|
||||
#include "WebUI/InputBuffer.h"
|
||||
#include "Settings.h"
|
||||
#include "SettingsDefinitions.h"
|
||||
#include "WebSettings.h"
|
||||
#include "WebUI/WebSettings.h"
|
||||
|
||||
// Do not guard this because it is needed for local files too
|
||||
#include "grbl_sd.h"
|
||||
#include "SDCard.h"
|
||||
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
#include "BTconfig.h"
|
||||
# include "WebUI/BTConfig.h"
|
||||
#endif
|
||||
|
||||
#ifdef ENABLE_WIFI
|
||||
#include "wificonfig.h"
|
||||
# include "WebUI/WifiConfig.h"
|
||||
# ifdef ENABLE_HTTP
|
||||
#include "serial2socket.h"
|
||||
# include "WebUI/Serial2Socket.h"
|
||||
# endif
|
||||
# ifdef ENABLE_TELNET
|
||||
#include "telnet_server.h"
|
||||
# include "WebUI/TelnetServer.h"
|
||||
# endif
|
||||
# ifdef ENABLE_NOTIFICATIONS
|
||||
#include "notifications_service.h"
|
||||
# include "WebUI/NotificationsService.h"
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#include "solenoid_pen.h"
|
||||
#include "SolenoidPen.h"
|
||||
|
||||
#ifdef USE_SERVO_AXES
|
||||
#include "servo_axis.h"
|
||||
#endif
|
||||
|
||||
#ifdef USE_UNIPOLAR
|
||||
#include "grbl_unipolar.h"
|
||||
# include "ServoAxis.h"
|
||||
#endif
|
||||
|
||||
#ifdef USE_I2S_OUT
|
||||
#include "i2s_out.h"
|
||||
# include "I2SOut.h"
|
||||
#endif
|
||||
|
||||
// Called if USE_MACHINE_INIT is defined
|
914
Grbl_Esp32/src/I2SOut.cpp
Normal file
914
Grbl_Esp32/src/I2SOut.cpp
Normal file
@@ -0,0 +1,914 @@
|
||||
/*
|
||||
I2SOut.cpp
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Basic GPIO expander using the ESP32 I2S peripheral (output)
|
||||
|
||||
2020 - Michiyasu Odaki
|
||||
|
||||
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_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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 this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#include "Config.h"
|
||||
|
||||
#ifdef USE_I2S_OUT
|
||||
|
||||
# include <FreeRTOS.h>
|
||||
# include <driver/periph_ctrl.h>
|
||||
# include <rom/lldesc.h>
|
||||
# include <soc/i2s_struct.h>
|
||||
# include <freertos/queue.h>
|
||||
|
||||
# include <stdatomic.h>
|
||||
|
||||
# include "Pins.h"
|
||||
# include "I2SOut.h"
|
||||
|
||||
//
|
||||
// Configrations for DMA connected I2S
|
||||
//
|
||||
// One DMA buffer transfer takes about 2 ms
|
||||
// I2S_OUT_DMABUF_LEN / I2S_SAMPLE_SIZE x I2S_OUT_USEC_PER_PULSE
|
||||
// = 2000 / 4 x 4
|
||||
// = 2000us = 2ms
|
||||
// If I2S_OUT_DMABUF_COUNT is 5, it will take about 10 ms for all the DMA buffer transfers to finish.
|
||||
//
|
||||
// Increasing I2S_OUT_DMABUF_COUNT has the effect of preventing buffer underflow,
|
||||
// but on the other hand, it leads to a delay with pulse and/or non-pulse-generated I/Os.
|
||||
// The number of I2S_OUT_DMABUF_COUNT should be chosen carefully.
|
||||
//
|
||||
// Reference information:
|
||||
// FreeRTOS task time slice = portTICK_PERIOD_MS = 1 ms (ESP32 FreeRTOS port)
|
||||
//
|
||||
# define I2S_SAMPLE_SIZE 4 /* 4 bytes, 32 bits per sample */
|
||||
# define DMA_SAMPLE_COUNT I2S_OUT_DMABUF_LEN / I2S_SAMPLE_SIZE /* number of samples per buffer */
|
||||
# define SAMPLE_SAFE_COUNT (20 / I2S_OUT_USEC_PER_PULSE) /* prevent buffer overrun (GRBL's $0 should be less than or equal 20) */
|
||||
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
typedef struct {
|
||||
uint32_t** buffers;
|
||||
uint32_t* current;
|
||||
uint32_t rw_pos;
|
||||
lldesc_t** desc;
|
||||
xQueueHandle queue;
|
||||
} i2s_out_dma_t;
|
||||
|
||||
static i2s_out_dma_t o_dma;
|
||||
static intr_handle_t i2s_out_isr_handle;
|
||||
# endif
|
||||
|
||||
// output value
|
||||
static atomic_uint_least32_t i2s_out_port_data = ATOMIC_VAR_INIT(0);
|
||||
|
||||
// inner lock
|
||||
static portMUX_TYPE i2s_out_spinlock = portMUX_INITIALIZER_UNLOCKED;
|
||||
# define I2S_OUT_ENTER_CRITICAL() portENTER_CRITICAL(&i2s_out_spinlock)
|
||||
# define I2S_OUT_EXIT_CRITICAL() portEXIT_CRITICAL(&i2s_out_spinlock)
|
||||
# define I2S_OUT_ENTER_CRITICAL_ISR() portENTER_CRITICAL_ISR(&i2s_out_spinlock)
|
||||
# define I2S_OUT_EXIT_CRITICAL_ISR() portEXIT_CRITICAL_ISR(&i2s_out_spinlock)
|
||||
|
||||
static int i2s_out_initialized = 0;
|
||||
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
static volatile uint64_t i2s_out_pulse_period;
|
||||
static uint64_t i2s_out_remain_time_until_next_pulse; // Time remaining until the next pulse (μsec)
|
||||
static volatile i2s_out_pulse_func_t i2s_out_pulse_func;
|
||||
# endif
|
||||
|
||||
static uint8_t i2s_out_ws_pin = 255;
|
||||
static uint8_t i2s_out_bck_pin = 255;
|
||||
static uint8_t i2s_out_data_pin = 255;
|
||||
|
||||
enum i2s_out_pulser_status_t {
|
||||
PASSTHROUGH = 0, // Static I2S mode.The i2s_out_write() reflected with very little delay
|
||||
STEPPING, // Streaming step data.
|
||||
WAITING, // Waiting for the step DMA completion
|
||||
};
|
||||
static volatile i2s_out_pulser_status_t i2s_out_pulser_status = PASSTHROUGH;
|
||||
|
||||
// outer lock
|
||||
static portMUX_TYPE i2s_out_pulser_spinlock = portMUX_INITIALIZER_UNLOCKED;
|
||||
# define I2S_OUT_PULSER_ENTER_CRITICAL() portENTER_CRITICAL(&i2s_out_pulser_spinlock)
|
||||
# define I2S_OUT_PULSER_EXIT_CRITICAL() portEXIT_CRITICAL(&i2s_out_pulser_spinlock)
|
||||
# define I2S_OUT_PULSER_ENTER_CRITICAL_ISR() portENTER_CRITICAL_ISR(&i2s_out_pulser_spinlock)
|
||||
# define I2S_OUT_PULSER_EXIT_CRITICAL_ISR() portEXIT_CRITICAL_ISR(&i2s_out_pulser_spinlock)
|
||||
|
||||
//
|
||||
// Internal functions
|
||||
//
|
||||
static inline void gpio_matrix_out_check(uint8_t gpio, uint32_t signal_idx, bool out_inv, bool oen_inv) {
|
||||
//if pin == 255, do not need to configure
|
||||
if (gpio != 255) {
|
||||
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[gpio], PIN_FUNC_GPIO);
|
||||
gpio_set_direction((gpio_num_t)gpio, (gpio_mode_t)GPIO_MODE_DEF_OUTPUT);
|
||||
gpio_matrix_out(gpio, signal_idx, out_inv, oen_inv);
|
||||
}
|
||||
}
|
||||
|
||||
static inline void i2s_out_single_data() {
|
||||
# if I2S_OUT_NUM_BITS == 16
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data);
|
||||
port_data <<= 16; // Shift needed. This specification is not spelled out in the manual.
|
||||
I2S0.conf_single_data = port_data; // Apply port data in real-time (static I2S)
|
||||
# else
|
||||
I2S0.conf_single_data = atomic_load(&i2s_out_port_data); // Apply port data in real-time (static I2S)
|
||||
# endif
|
||||
}
|
||||
|
||||
static inline void i2s_out_reset_fifo_without_lock() {
|
||||
I2S0.conf.rx_fifo_reset = 1;
|
||||
I2S0.conf.rx_fifo_reset = 0;
|
||||
I2S0.conf.tx_fifo_reset = 1;
|
||||
I2S0.conf.tx_fifo_reset = 0;
|
||||
}
|
||||
|
||||
static void IRAM_ATTR i2s_out_reset_fifo() {
|
||||
I2S_OUT_ENTER_CRITICAL();
|
||||
i2s_out_reset_fifo_without_lock();
|
||||
I2S_OUT_EXIT_CRITICAL();
|
||||
}
|
||||
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
static int IRAM_ATTR i2s_clear_dma_buffer(lldesc_t* dma_desc, uint32_t port_data) {
|
||||
uint32_t* buf = (uint32_t*)dma_desc->buf;
|
||||
for (int i = 0; i < DMA_SAMPLE_COUNT; i++) {
|
||||
buf[i] = port_data;
|
||||
}
|
||||
// Restore the buffer length.
|
||||
// The length may have been changed short when the data was filled in to prevent buffer overrun.
|
||||
dma_desc->length = I2S_OUT_DMABUF_LEN;
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int IRAM_ATTR i2s_clear_o_dma_buffers(uint32_t port_data) {
|
||||
for (int buf_idx = 0; buf_idx < I2S_OUT_DMABUF_COUNT; buf_idx++) {
|
||||
// Initialize DMA descriptor
|
||||
o_dma.desc[buf_idx]->owner = 1;
|
||||
o_dma.desc[buf_idx]->eof = 1; // set to 1 will trigger the interrupt
|
||||
o_dma.desc[buf_idx]->sosf = 0;
|
||||
o_dma.desc[buf_idx]->length = I2S_OUT_DMABUF_LEN;
|
||||
o_dma.desc[buf_idx]->size = I2S_OUT_DMABUF_LEN;
|
||||
o_dma.desc[buf_idx]->buf = (uint8_t*)o_dma.buffers[buf_idx];
|
||||
o_dma.desc[buf_idx]->offset = 0;
|
||||
o_dma.desc[buf_idx]->qe.stqe_next = (lldesc_t*)((buf_idx < (I2S_OUT_DMABUF_COUNT - 1)) ? (o_dma.desc[buf_idx + 1]) : o_dma.desc[0]);
|
||||
i2s_clear_dma_buffer(o_dma.desc[buf_idx], port_data);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
# endif
|
||||
|
||||
static int IRAM_ATTR i2s_out_gpio_attach(uint8_t ws, uint8_t bck, uint8_t data) {
|
||||
// Route the i2s pins to the appropriate GPIO
|
||||
gpio_matrix_out_check(data, I2S0O_DATA_OUT23_IDX, 0, 0);
|
||||
gpio_matrix_out_check(bck, I2S0O_BCK_OUT_IDX, 0, 0);
|
||||
gpio_matrix_out_check(ws, I2S0O_WS_OUT_IDX, 0, 0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
# define I2S_OUT_DETACH_PORT_IDX 0x100
|
||||
|
||||
static int IRAM_ATTR i2s_out_gpio_detach(uint8_t ws, uint8_t bck, uint8_t data) {
|
||||
// Route the i2s pins to the appropriate GPIO
|
||||
gpio_matrix_out_check(ws, I2S_OUT_DETACH_PORT_IDX, 0, 0);
|
||||
gpio_matrix_out_check(bck, I2S_OUT_DETACH_PORT_IDX, 0, 0);
|
||||
gpio_matrix_out_check(data, I2S_OUT_DETACH_PORT_IDX, 0, 0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int IRAM_ATTR i2s_out_gpio_shiftout(uint32_t port_data) {
|
||||
__digitalWrite(i2s_out_ws_pin, LOW);
|
||||
for (int i = 0; i < I2S_OUT_NUM_BITS; i++) {
|
||||
__digitalWrite(i2s_out_data_pin, !!(port_data & bit(I2S_OUT_NUM_BITS - 1 - i)));
|
||||
__digitalWrite(i2s_out_bck_pin, HIGH);
|
||||
__digitalWrite(i2s_out_bck_pin, LOW);
|
||||
}
|
||||
__digitalWrite(i2s_out_ws_pin, HIGH); // Latch
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int IRAM_ATTR i2s_out_stop() {
|
||||
I2S_OUT_ENTER_CRITICAL();
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
// Stop FIFO DMA
|
||||
I2S0.out_link.stop = 1;
|
||||
|
||||
// Disconnect DMA from FIFO
|
||||
I2S0.fifo_conf.dscr_en = 0; //Unset this bit to disable I2S DMA mode. (R/W)
|
||||
# endif
|
||||
// stop TX module
|
||||
I2S0.conf.tx_start = 0;
|
||||
|
||||
// Force WS to LOW before detach
|
||||
// This operation prevents unintended WS edge trigger when detach
|
||||
__digitalWrite(i2s_out_ws_pin, LOW);
|
||||
|
||||
// Now, detach GPIO pin from I2S
|
||||
i2s_out_gpio_detach(i2s_out_ws_pin, i2s_out_bck_pin, i2s_out_data_pin);
|
||||
|
||||
// Force BCK to LOW
|
||||
// After the TX module is stopped, BCK always seems to be in LOW.
|
||||
// However, I'm going to do it manually to ensure the BCK's LOW.
|
||||
__digitalWrite(i2s_out_bck_pin, LOW);
|
||||
|
||||
// Transmit recovery data to 74HC595
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data); // current expanded port value
|
||||
i2s_out_gpio_shiftout(port_data);
|
||||
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
//clear pending interrupt
|
||||
I2S0.int_clr.val = I2S0.int_st.val;
|
||||
# endif
|
||||
I2S_OUT_EXIT_CRITICAL();
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int IRAM_ATTR i2s_out_start() {
|
||||
if (!i2s_out_initialized) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
I2S_OUT_ENTER_CRITICAL();
|
||||
// Transmit recovery data to 74HC595
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data); // current expanded port value
|
||||
i2s_out_gpio_shiftout(port_data);
|
||||
|
||||
// Attach I2S to specified GPIO pin
|
||||
i2s_out_gpio_attach(i2s_out_ws_pin, i2s_out_bck_pin, i2s_out_data_pin);
|
||||
//start DMA link
|
||||
i2s_out_reset_fifo_without_lock();
|
||||
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
if (i2s_out_pulser_status == PASSTHROUGH) {
|
||||
I2S0.conf_chan.tx_chan_mod = 3; // 3:right+constant 4:left+constant (when tx_msb_right = 1)
|
||||
I2S0.conf_single_data = port_data;
|
||||
} else {
|
||||
I2S0.conf_chan.tx_chan_mod = 4; // 3:right+constant 4:left+constant (when tx_msb_right = 1)
|
||||
I2S0.conf_single_data = 0;
|
||||
}
|
||||
# endif
|
||||
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
//reset DMA
|
||||
I2S0.lc_conf.in_rst = 1;
|
||||
I2S0.lc_conf.in_rst = 0;
|
||||
I2S0.lc_conf.out_rst = 1;
|
||||
I2S0.lc_conf.out_rst = 0;
|
||||
|
||||
I2S0.out_link.addr = (uint32_t)o_dma.desc[0];
|
||||
# endif
|
||||
|
||||
I2S0.conf.tx_reset = 1;
|
||||
I2S0.conf.tx_reset = 0;
|
||||
I2S0.conf.rx_reset = 1;
|
||||
I2S0.conf.rx_reset = 0;
|
||||
|
||||
I2S0.conf1.tx_stop_en = 1; // BCK and WCK are suppressed while FIFO is empty
|
||||
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
// Connect DMA to FIFO
|
||||
I2S0.fifo_conf.dscr_en = 1; // Set this bit to enable I2S DMA mode. (R/W)
|
||||
|
||||
I2S0.int_clr.val = 0xFFFFFFFF;
|
||||
I2S0.out_link.start = 1;
|
||||
# endif
|
||||
I2S0.conf.tx_start = 1;
|
||||
// Wait for the first FIFO data to prevent the unintentional generation of 0 data
|
||||
ets_delay_us(20);
|
||||
I2S0.conf1.tx_stop_en = 0; // BCK and WCK are generated regardless of the FIFO status
|
||||
|
||||
I2S_OUT_EXIT_CRITICAL();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
|
||||
static int IRAM_ATTR i2s_fillout_dma_buffer(lldesc_t* dma_desc) {
|
||||
uint32_t* buf = (uint32_t*)dma_desc->buf;
|
||||
o_dma.rw_pos = 0;
|
||||
// It reuses the oldest (just transferred) buffer with the name "current"
|
||||
// and fills the buffer for later DMA.
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL(); // Lock pulser status
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
//
|
||||
// Fillout the buffer for pulse
|
||||
//
|
||||
// To avoid buffer overflow, all of the maximum pulse width (normaly about 10us)
|
||||
// is adjusted to be in a single buffer.
|
||||
// DMA_SAMPLE_SAFE_COUNT is referred to as the margin value.
|
||||
// Therefore, if a buffer is close to full and it is time to generate a pulse,
|
||||
// the generation of the buffer is interrupted (the buffer length is shortened slightly)
|
||||
// and the pulse generation is postponed until the next buffer is filled.
|
||||
//
|
||||
o_dma.rw_pos = 0;
|
||||
while (o_dma.rw_pos < (DMA_SAMPLE_COUNT - SAMPLE_SAFE_COUNT)) {
|
||||
// no data to read (buffer empty)
|
||||
if (i2s_out_remain_time_until_next_pulse < I2S_OUT_USEC_PER_PULSE) {
|
||||
// pulser status may change in pulse phase func, so I need to check it every time.
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
// fillout future DMA buffer (tail of the DMA buffer chains)
|
||||
if (i2s_out_pulse_func != NULL) {
|
||||
uint32_t old_rw_pos = o_dma.rw_pos;
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL(); // Temporarily unlocked status lock as it may be locked in pulse callback.
|
||||
(*i2s_out_pulse_func)(); // should be pushed into buffer max DMA_SAMPLE_SAFE_COUNT
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL(); // Lock again.
|
||||
// Calculate pulse period. About magic number 2, refer to the st_wake_up(). (Ad hoc delay value)
|
||||
i2s_out_remain_time_until_next_pulse = i2s_out_pulse_period - I2S_OUT_USEC_PER_PULSE * (o_dma.rw_pos - old_rw_pos) + 2;
|
||||
if (i2s_out_pulser_status == WAITING) {
|
||||
// i2s_out_set_passthrough() has called from the pulse function.
|
||||
// It needs to go into pass-through mode.
|
||||
// This DMA descriptor must be a tail of the chain.
|
||||
dma_desc->qe.stqe_next = NULL; // Cut the DMA descriptor ring. This allow us to identify the tail of the buffer.
|
||||
} else if (i2s_out_pulser_status == PASSTHROUGH) {
|
||||
// i2s_out_reset() has called during the execution of the pulse function.
|
||||
// I2S has already in static mode, and buffers has cleared to zero.
|
||||
// To prevent the pulse function from being called back,
|
||||
// we assume that the buffer is already full.
|
||||
i2s_out_remain_time_until_next_pulse = 0; // There is no need to fill the current buffer.
|
||||
o_dma.rw_pos = DMA_SAMPLE_COUNT; // The buffer is full.
|
||||
break;
|
||||
}
|
||||
continue;
|
||||
}
|
||||
}
|
||||
}
|
||||
// no pulse data in push buffer (pulse off or idle or callback is not defined)
|
||||
buf[o_dma.rw_pos++] = atomic_load(&i2s_out_port_data);
|
||||
if (i2s_out_remain_time_until_next_pulse >= I2S_OUT_USEC_PER_PULSE) {
|
||||
i2s_out_remain_time_until_next_pulse -= I2S_OUT_USEC_PER_PULSE;
|
||||
} else {
|
||||
i2s_out_remain_time_until_next_pulse = 0;
|
||||
}
|
||||
}
|
||||
// set filled length to the DMA descriptor
|
||||
dma_desc->length = o_dma.rw_pos * I2S_SAMPLE_SIZE;
|
||||
} else if (i2s_out_pulser_status == WAITING) {
|
||||
i2s_clear_dma_buffer(dma_desc, 0); // Essentially, no clearing is required. I'll make sure I know when I've written something.
|
||||
o_dma.rw_pos = 0; // If someone calls i2s_out_push_sample, make sure there is no buffer overflow
|
||||
dma_desc->qe.stqe_next = NULL; // Cut the DMA descriptor ring. This allow us to identify the tail of the buffer.
|
||||
} else {
|
||||
// Stepper paused (passthrough state, static I2S control mode)
|
||||
// In the passthrough mode, there is no need to fill the buffer with port_data.
|
||||
i2s_clear_dma_buffer(dma_desc, 0); // Essentially, no clearing is required. I'll make sure I know when I've written something.
|
||||
o_dma.rw_pos = 0; // If someone calls i2s_out_push_sample, make sure there is no buffer overflow
|
||||
}
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL(); // Unlock pulser status
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
//
|
||||
// I2S out DMA Interrupts handler
|
||||
//
|
||||
static void IRAM_ATTR i2s_out_intr_handler(void* arg) {
|
||||
lldesc_t* finish_desc;
|
||||
portBASE_TYPE high_priority_task_awoken = pdFALSE;
|
||||
|
||||
if (I2S0.int_st.out_eof || I2S0.int_st.out_total_eof) {
|
||||
if (I2S0.int_st.out_total_eof) {
|
||||
// This is tail of the DMA descriptors
|
||||
I2S_OUT_ENTER_CRITICAL_ISR();
|
||||
// Stop FIFO DMA
|
||||
I2S0.out_link.stop = 1;
|
||||
// Disconnect DMA from FIFO
|
||||
I2S0.fifo_conf.dscr_en = 0; //Unset this bit to disable I2S DMA mode. (R/W)
|
||||
// Stop TX module
|
||||
I2S0.conf.tx_start = 0;
|
||||
I2S_OUT_EXIT_CRITICAL_ISR();
|
||||
}
|
||||
// Get the descriptor of the last item in the linkedlist
|
||||
finish_desc = (lldesc_t*)I2S0.out_eof_des_addr;
|
||||
|
||||
// If the queue is full it's because we have an underflow,
|
||||
// more than buf_count isr without new data, remove the front buffer
|
||||
if (xQueueIsQueueFullFromISR(o_dma.queue)) {
|
||||
lldesc_t* front_desc;
|
||||
// Remove a descriptor from the DMA complete event queue
|
||||
xQueueReceiveFromISR(o_dma.queue, &front_desc, &high_priority_task_awoken);
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL_ISR();
|
||||
uint32_t port_data = 0;
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
port_data = atomic_load(&i2s_out_port_data);
|
||||
}
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL_ISR();
|
||||
for (int i = 0; i < DMA_SAMPLE_COUNT; i++) {
|
||||
front_desc->buf[i] = port_data;
|
||||
}
|
||||
front_desc->length = I2S_OUT_DMABUF_LEN;
|
||||
}
|
||||
|
||||
// Send a DMA complete event to the I2S bitstreamer task with finished buffer
|
||||
xQueueSendFromISR(o_dma.queue, &finish_desc, &high_priority_task_awoken);
|
||||
}
|
||||
|
||||
if (high_priority_task_awoken == pdTRUE)
|
||||
portYIELD_FROM_ISR();
|
||||
|
||||
// clear interrupt
|
||||
I2S0.int_clr.val = I2S0.int_st.val; //clear pending interrupt
|
||||
}
|
||||
|
||||
//
|
||||
// I2S bitstream generator task
|
||||
//
|
||||
static void IRAM_ATTR i2sOutTask(void* parameter) {
|
||||
lldesc_t* dma_desc;
|
||||
while (1) {
|
||||
// Wait a DMA complete event from I2S isr
|
||||
// (Block until a DMA transfer has complete)
|
||||
xQueueReceive(o_dma.queue, &dma_desc, portMAX_DELAY);
|
||||
o_dma.current = (uint32_t*)(dma_desc->buf);
|
||||
// It reuses the oldest (just transferred) buffer with the name "current"
|
||||
// and fills the buffer for later DMA.
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL(); // Lock pulser status
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
//
|
||||
// Fillout the buffer for pulse
|
||||
//
|
||||
// To avoid buffer overflow, all of the maximum pulse width (normaly about 10us)
|
||||
// is adjusted to be in a single buffer.
|
||||
// DMA_SAMPLE_SAFE_COUNT is referred to as the margin value.
|
||||
// Therefore, if a buffer is close to full and it is time to generate a pulse,
|
||||
// the generation of the buffer is interrupted (the buffer length is shortened slightly)
|
||||
// and the pulse generation is postponed until the next buffer is filled.
|
||||
//
|
||||
i2s_fillout_dma_buffer(dma_desc);
|
||||
dma_desc->length = o_dma.rw_pos * I2S_SAMPLE_SIZE;
|
||||
} else if (i2s_out_pulser_status == WAITING) {
|
||||
if (dma_desc->qe.stqe_next == NULL) {
|
||||
// Tail of the DMA descriptor found
|
||||
// I2S TX module has alrewdy stopped by ISR
|
||||
i2s_out_stop();
|
||||
i2s_clear_o_dma_buffers(0); // 0 for static I2S control mode (right ch. data is always 0)
|
||||
// You need to set the status before calling i2s_out_start()
|
||||
// because the process in i2s_out_start() is different depending on the status.
|
||||
i2s_out_pulser_status = PASSTHROUGH;
|
||||
i2s_out_start();
|
||||
} else {
|
||||
// Processing a buffer slightly ahead of the tail buffer.
|
||||
// We don't need to fill up the buffer by port_data any more.
|
||||
i2s_clear_dma_buffer(dma_desc, 0); // Essentially, no clearing is required. I'll make sure I know when I've written something.
|
||||
o_dma.rw_pos = 0; // If someone calls i2s_out_push_sample, make sure there is no buffer overflow
|
||||
dma_desc->qe.stqe_next = NULL; // Cut the DMA descriptor ring. This allow us to identify the tail of the buffer.
|
||||
}
|
||||
} else {
|
||||
// Stepper paused (passthrough state, static I2S control mode)
|
||||
// In the passthrough mode, there is no need to fill the buffer with port_data.
|
||||
i2s_clear_dma_buffer(dma_desc, 0); // Essentially, no clearing is required. I'll make sure I know when I've written something.
|
||||
o_dma.rw_pos = 0; // If someone calls i2s_out_push_sample, make sure there is no buffer overflow
|
||||
}
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL(); // Unlock pulser status
|
||||
}
|
||||
}
|
||||
# endif
|
||||
|
||||
//
|
||||
// External funtions
|
||||
//
|
||||
void IRAM_ATTR i2s_out_delay() {
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL();
|
||||
if (i2s_out_pulser_status == PASSTHROUGH) {
|
||||
// Depending on the timing, it may not be reflected immediately,
|
||||
// so wait twice as long just in case.
|
||||
ets_delay_us(I2S_OUT_USEC_PER_PULSE * 2);
|
||||
} else {
|
||||
// Just wait until the data now registered in the DMA descripter
|
||||
// is reflected in the I2S TX module via FIFO.
|
||||
delay(I2S_OUT_DELAY_MS);
|
||||
}
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
# else
|
||||
ets_delay_us(I2S_OUT_USEC_PER_PULSE * 2);
|
||||
# endif
|
||||
}
|
||||
|
||||
void IRAM_ATTR i2s_out_write(uint8_t pin, uint8_t val) {
|
||||
uint32_t bit = bit(pin);
|
||||
if (val) {
|
||||
atomic_fetch_or(&i2s_out_port_data, bit);
|
||||
} else {
|
||||
atomic_fetch_and(&i2s_out_port_data, ~bit);
|
||||
}
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
// It needs a lock for access, but I've given up because I need speed.
|
||||
// This is not a problem as long as there is no overlap between the status change and digitalWrite().
|
||||
if (i2s_out_pulser_status == PASSTHROUGH) {
|
||||
i2s_out_single_data();
|
||||
}
|
||||
# else
|
||||
i2s_out_single_data();
|
||||
# endif
|
||||
}
|
||||
|
||||
uint8_t IRAM_ATTR i2s_out_state(uint8_t pin) {
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data);
|
||||
return (!!(port_data & bit(pin)));
|
||||
}
|
||||
|
||||
uint32_t IRAM_ATTR i2s_out_push_sample(uint32_t num) {
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
if (num > SAMPLE_SAFE_COUNT) {
|
||||
return 0;
|
||||
}
|
||||
// push at least one sample (even if num is zero)
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data);
|
||||
uint32_t n = 0;
|
||||
do {
|
||||
o_dma.current[o_dma.rw_pos++] = port_data;
|
||||
n++;
|
||||
} while (n < num);
|
||||
return n;
|
||||
# else
|
||||
return 0;
|
||||
# endif
|
||||
}
|
||||
|
||||
int IRAM_ATTR i2s_out_set_passthrough() {
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL();
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
i2s_out_pulser_status = WAITING; // Start stopping the pulser
|
||||
}
|
||||
# else
|
||||
i2s_out_pulser_status = PASSTHROUGH;
|
||||
# endif
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
return 0;
|
||||
}
|
||||
|
||||
int IRAM_ATTR i2s_out_set_stepping() {
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL();
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
// Re-entered (fail safe)
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (i2s_out_pulser_status == WAITING) {
|
||||
// Wait for complete DMAs
|
||||
for (;;) {
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
delay(I2S_OUT_DELAY_DMABUF_MS);
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL();
|
||||
if (i2s_out_pulser_status == WAITING) {
|
||||
continue;
|
||||
}
|
||||
if (i2s_out_pulser_status == PASSTHROUGH) {
|
||||
// DMA completed
|
||||
break;
|
||||
}
|
||||
// Another function change the I2S state to STEPPING
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
// Change I2S state from PASSTHROUGH to STEPPING
|
||||
i2s_out_stop();
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data);
|
||||
i2s_clear_o_dma_buffers(port_data);
|
||||
|
||||
// You need to set the status before calling i2s_out_start()
|
||||
// because the process in i2s_out_start() is different depending on the status.
|
||||
i2s_out_pulser_status = STEPPING;
|
||||
i2s_out_start();
|
||||
# else
|
||||
i2s_out_pulser_status = STEPPING;
|
||||
# endif
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
return 0;
|
||||
}
|
||||
|
||||
int IRAM_ATTR i2s_out_set_pulse_period(uint64_t period) {
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
// Use 64-bit values to avoid overflowing during the calculation.
|
||||
i2s_out_pulse_period = period * 1000000 / F_STEPPER_TIMER;
|
||||
# endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
int IRAM_ATTR i2s_out_set_pulse_callback(i2s_out_pulse_func_t func) {
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
i2s_out_pulse_func = func;
|
||||
# endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
int IRAM_ATTR i2s_out_reset() {
|
||||
I2S_OUT_PULSER_ENTER_CRITICAL();
|
||||
i2s_out_stop();
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
uint32_t port_data = atomic_load(&i2s_out_port_data);
|
||||
i2s_clear_o_dma_buffers(port_data);
|
||||
} else if (i2s_out_pulser_status == WAITING) {
|
||||
i2s_clear_o_dma_buffers(0);
|
||||
i2s_out_pulser_status = PASSTHROUGH;
|
||||
}
|
||||
# endif
|
||||
// You need to set the status before calling i2s_out_start()
|
||||
// because the process in i2s_out_start() is different depending on the status.
|
||||
i2s_out_start();
|
||||
I2S_OUT_PULSER_EXIT_CRITICAL();
|
||||
return 0;
|
||||
}
|
||||
|
||||
//
|
||||
// Initialize funtion (external function)
|
||||
//
|
||||
int IRAM_ATTR i2s_out_init(i2s_out_init_t& init_param) {
|
||||
if (i2s_out_initialized) {
|
||||
// already initialized
|
||||
return -1;
|
||||
}
|
||||
|
||||
atomic_store(&i2s_out_port_data, init_param.init_val);
|
||||
|
||||
// To make sure hardware is enabled before any hardware register operations.
|
||||
periph_module_reset(PERIPH_I2S0_MODULE);
|
||||
periph_module_enable(PERIPH_I2S0_MODULE);
|
||||
|
||||
// Route the i2s pins to the appropriate GPIO
|
||||
i2s_out_gpio_attach(init_param.ws_pin, init_param.bck_pin, init_param.data_pin);
|
||||
|
||||
/**
|
||||
* Each i2s transfer will take
|
||||
* fpll = PLL_D2_CLK -- clka_en = 0
|
||||
*
|
||||
* fi2s = fpll / N + b/a -- N + b/a = clkm_div_num
|
||||
* fi2s = 160MHz / 2
|
||||
* fi2s = 80MHz
|
||||
*
|
||||
* fbclk = fi2s / M -- M = tx_bck_div_num
|
||||
* fbclk = 80MHz / 2
|
||||
* fbclk = 40MHz
|
||||
*
|
||||
* fwclk = fbclk / 32
|
||||
*
|
||||
* for fwclk = 250kHz(16-bit: 4µS pulse time), 125kHz(32-bit: 8μS pulse time)
|
||||
* N = 10, b/a = 0
|
||||
* M = 2
|
||||
* for fwclk = 500kHz(16-bit: 2µS pulse time), 250kHz(32-bit: 4μS pulse time)
|
||||
* N = 5, b/a = 0
|
||||
* M = 2
|
||||
* for fwclk = 1000kHz(16-bit: 1µS pulse time), 500kHz(32-bit: 2μS pulse time)
|
||||
* N = 2, b/a = 2/1 (N + b/a = 2.5)
|
||||
* M = 2
|
||||
*/
|
||||
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
// Allocate the array of pointers to the buffers
|
||||
o_dma.buffers = (uint32_t**)malloc(sizeof(uint32_t*) * I2S_OUT_DMABUF_COUNT);
|
||||
if (o_dma.buffers == nullptr)
|
||||
return -1;
|
||||
|
||||
// Allocate each buffer that can be used by the DMA controller
|
||||
for (int buf_idx = 0; buf_idx < I2S_OUT_DMABUF_COUNT; buf_idx++) {
|
||||
o_dma.buffers[buf_idx] = (uint32_t*)heap_caps_calloc(1, I2S_OUT_DMABUF_LEN, MALLOC_CAP_DMA);
|
||||
if (o_dma.buffers[buf_idx] == nullptr)
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Allocate the array of DMA descriptors
|
||||
o_dma.desc = (lldesc_t**)malloc(sizeof(lldesc_t*) * I2S_OUT_DMABUF_COUNT);
|
||||
if (o_dma.desc == nullptr)
|
||||
return -1;
|
||||
|
||||
// Allocate each DMA descriptor that will be used by the DMA controller
|
||||
for (int buf_idx = 0; buf_idx < I2S_OUT_DMABUF_COUNT; buf_idx++) {
|
||||
o_dma.desc[buf_idx] = (lldesc_t*)heap_caps_malloc(sizeof(lldesc_t), MALLOC_CAP_DMA);
|
||||
if (o_dma.desc[buf_idx] == nullptr)
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Initialize
|
||||
i2s_clear_o_dma_buffers(init_param.init_val);
|
||||
o_dma.rw_pos = 0;
|
||||
o_dma.current = NULL;
|
||||
o_dma.queue = xQueueCreate(I2S_OUT_DMABUF_COUNT, sizeof(uint32_t*));
|
||||
|
||||
// Set the first DMA descriptor
|
||||
I2S0.out_link.addr = (uint32_t)o_dma.desc[0];
|
||||
# endif
|
||||
|
||||
// stop i2s
|
||||
I2S0.out_link.stop = 1;
|
||||
I2S0.conf.tx_start = 0;
|
||||
|
||||
I2S0.int_clr.val = I2S0.int_st.val; //clear pending interrupt
|
||||
|
||||
//
|
||||
// i2s_param_config
|
||||
//
|
||||
|
||||
// configure I2S data port interface.
|
||||
i2s_out_reset_fifo();
|
||||
|
||||
//reset i2s
|
||||
I2S0.conf.tx_reset = 1;
|
||||
I2S0.conf.tx_reset = 0;
|
||||
I2S0.conf.rx_reset = 1;
|
||||
I2S0.conf.rx_reset = 0;
|
||||
|
||||
//reset dma
|
||||
I2S0.lc_conf.in_rst = 1; // Set this bit to reset in DMA FSM. (R/W)
|
||||
I2S0.lc_conf.in_rst = 0;
|
||||
I2S0.lc_conf.out_rst = 1; // Set this bit to reset out DMA FSM. (R/W)
|
||||
I2S0.lc_conf.out_rst = 0;
|
||||
|
||||
//Enable and configure DMA
|
||||
I2S0.lc_conf.check_owner = 0;
|
||||
I2S0.lc_conf.out_loop_test = 0;
|
||||
I2S0.lc_conf.out_auto_wrback = 0; // Disable auto outlink-writeback when all the data has been transmitted
|
||||
I2S0.lc_conf.out_data_burst_en = 0;
|
||||
I2S0.lc_conf.outdscr_burst_en = 0;
|
||||
I2S0.lc_conf.out_no_restart_clr = 0;
|
||||
I2S0.lc_conf.indscr_burst_en = 0;
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
I2S0.lc_conf.out_eof_mode = 1; // I2S_OUT_EOF_INT generated when DMA has popped all data from the FIFO;
|
||||
# endif
|
||||
I2S0.conf2.lcd_en = 0;
|
||||
I2S0.conf2.camera_en = 0;
|
||||
I2S0.pdm_conf.pcm2pdm_conv_en = 0;
|
||||
I2S0.pdm_conf.pdm2pcm_conv_en = 0;
|
||||
|
||||
I2S0.fifo_conf.dscr_en = 0;
|
||||
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
if (i2s_out_pulser_status == STEPPING) {
|
||||
// Stream output mode
|
||||
I2S0.conf_chan.tx_chan_mod = 4; // 3:right+constant 4:left+constant (when tx_msb_right = 1)
|
||||
I2S0.conf_single_data = 0;
|
||||
} else {
|
||||
// Static output mode
|
||||
I2S0.conf_chan.tx_chan_mod = 3; // 3:right+constant 4:left+constant (when tx_msb_right = 1)
|
||||
I2S0.conf_single_data = init_param.init_val;
|
||||
}
|
||||
# else
|
||||
// For the static output mode
|
||||
I2S0.conf_chan.tx_chan_mod = 3; // 3:right+constant 4:left+constant (when tx_msb_right = 1)
|
||||
I2S0.conf_single_data = init_param.init_val; // initial constant value
|
||||
# endif
|
||||
# if I2S_OUT_NUM_BITS == 16
|
||||
I2S0.fifo_conf.tx_fifo_mod = 0; // 0: 16-bit dual channel data, 3: 32-bit single channel data
|
||||
I2S0.fifo_conf.rx_fifo_mod = 0; // 0: 16-bit dual channel data, 3: 32-bit single channel data
|
||||
I2S0.sample_rate_conf.tx_bits_mod = 16; // default is 16-bits
|
||||
I2S0.sample_rate_conf.rx_bits_mod = 16; // default is 16-bits
|
||||
# else
|
||||
I2S0.fifo_conf.tx_fifo_mod = 3; // 0: 16-bit dual channel data, 3: 32-bit single channel data
|
||||
I2S0.fifo_conf.rx_fifo_mod = 3; // 0: 16-bit dual channel data, 3: 32-bit single channel data
|
||||
// Data width is 32-bit. Forgetting this setting will result in a 16-bit transfer.
|
||||
I2S0.sample_rate_conf.tx_bits_mod = 32;
|
||||
I2S0.sample_rate_conf.rx_bits_mod = 32;
|
||||
# endif
|
||||
I2S0.conf.tx_mono = 0; // Set this bit to enable transmitter’s mono mode in PCM standard mode.
|
||||
|
||||
I2S0.conf_chan.rx_chan_mod = 1; // 1: right+right
|
||||
I2S0.conf.rx_mono = 0;
|
||||
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
I2S0.fifo_conf.dscr_en = 1; //connect DMA to fifo
|
||||
# endif
|
||||
I2S0.conf.tx_start = 0;
|
||||
I2S0.conf.rx_start = 0;
|
||||
|
||||
I2S0.conf.tx_msb_right = 1; // Set this bit to place right-channel data at the MSB in the transmit FIFO.
|
||||
I2S0.conf.tx_right_first = 0; // Setting this bit allows the right-channel data to be sent first.
|
||||
|
||||
I2S0.conf.tx_slave_mod = 0; // Master
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
I2S0.fifo_conf.tx_fifo_mod_force_en = 1; //The bit should always be set to 1.
|
||||
# endif
|
||||
I2S0.pdm_conf.rx_pdm_en = 0; // Set this bit to enable receiver’s PDM mode.
|
||||
I2S0.pdm_conf.tx_pdm_en = 0; // Set this bit to enable transmitter’s PDM mode.
|
||||
|
||||
// I2S_COMM_FORMAT_I2S_LSB
|
||||
I2S0.conf.tx_short_sync = 0; // Set this bit to enable transmitter in PCM standard mode.
|
||||
I2S0.conf.rx_short_sync = 0; // Set this bit to enable receiver in PCM standard mode.
|
||||
I2S0.conf.tx_msb_shift = 0; // Do not use the Philips standard to avoid bit-shifting
|
||||
I2S0.conf.rx_msb_shift = 0; // Do not use the Philips standard to avoid bit-shifting
|
||||
|
||||
//
|
||||
// i2s_set_clk
|
||||
//
|
||||
|
||||
// set clock (fi2s) 160MHz / 5
|
||||
I2S0.clkm_conf.clka_en = 0; // Use 160 MHz PLL_D2_CLK as reference
|
||||
// N + b/a = 0
|
||||
# if I2S_OUT_NUM_BITS == 16
|
||||
// N = 10
|
||||
I2S0.clkm_conf.clkm_div_num = 10; // minimum value of 2, reset value of 4, max 256 (I²S clock divider’s integral value)
|
||||
# else
|
||||
// N = 5
|
||||
I2S0.clkm_conf.clkm_div_num = 5; // minimum value of 2, reset value of 4, max 256 (I²S clock divider’s integral value)
|
||||
# endif
|
||||
// b/a = 0
|
||||
I2S0.clkm_conf.clkm_div_b = 0; // 0 at reset
|
||||
I2S0.clkm_conf.clkm_div_a = 0; // 0 at reset, what about divide by 0? (not an issue)
|
||||
|
||||
// Bit clock configuration bit in transmitter mode.
|
||||
// fbck = fi2s / tx_bck_div_num = (160 MHz / 5) / 2 = 16 MHz
|
||||
I2S0.sample_rate_conf.tx_bck_div_num = 2; // minimum value of 2 defaults to 6
|
||||
I2S0.sample_rate_conf.rx_bck_div_num = 2;
|
||||
|
||||
# ifdef USE_I2S_OUT_STREAM
|
||||
// Enable TX interrupts (DMA Interrupts)
|
||||
I2S0.int_ena.out_eof = 1; // Triggered when rxlink has finished sending a packet.
|
||||
I2S0.int_ena.out_dscr_err = 0; // Triggered when invalid rxlink descriptors are encountered.
|
||||
I2S0.int_ena.out_total_eof = 1; // Triggered when all transmitting linked lists are used up.
|
||||
I2S0.int_ena.out_done = 0; // Triggered when all transmitted and buffered data have been read.
|
||||
|
||||
// default pulse callback period (μsec)
|
||||
i2s_out_pulse_period = init_param.pulse_period;
|
||||
i2s_out_pulse_func = init_param.pulse_func;
|
||||
|
||||
// Create the task that will feed the buffer
|
||||
xTaskCreatePinnedToCore(i2sOutTask,
|
||||
"I2SOutTask",
|
||||
1024 * 10,
|
||||
NULL,
|
||||
1,
|
||||
nullptr,
|
||||
CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core
|
||||
);
|
||||
|
||||
// Allocate and Enable the I2S interrupt
|
||||
esp_intr_alloc(ETS_I2S0_INTR_SOURCE, 0, i2s_out_intr_handler, nullptr, &i2s_out_isr_handle);
|
||||
esp_intr_enable(i2s_out_isr_handle);
|
||||
# endif
|
||||
|
||||
// Remember GPIO pin numbers
|
||||
i2s_out_ws_pin = init_param.ws_pin;
|
||||
i2s_out_bck_pin = init_param.bck_pin;
|
||||
i2s_out_data_pin = init_param.data_pin;
|
||||
i2s_out_initialized = 1;
|
||||
|
||||
// Start the I2S peripheral
|
||||
i2s_out_start();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
# ifndef I2S_OUT_WS
|
||||
# define I2S_OUT_WS GPIO_NUM_17
|
||||
# endif
|
||||
# ifndef I2S_OUT_BCK
|
||||
# define I2S_OUT_BCK GPIO_NUM_22
|
||||
# endif
|
||||
# ifndef I2S_OUT_DATA
|
||||
# define I2S_OUT_DATA GPIO_NUM_21
|
||||
# endif
|
||||
# ifndef I2S_OUT_INIT_VAL
|
||||
# define I2S_OUT_INIT_VAL 0
|
||||
# endif
|
||||
/*
|
||||
Initialize I2S out by default parameters.
|
||||
|
||||
return -1 ... already initialized
|
||||
*/
|
||||
int IRAM_ATTR i2s_out_init() {
|
||||
i2s_out_init_t default_param = {
|
||||
.ws_pin = I2S_OUT_WS,
|
||||
.bck_pin = I2S_OUT_BCK,
|
||||
.data_pin = I2S_OUT_DATA,
|
||||
.pulse_func = NULL,
|
||||
.pulse_period = I2S_OUT_USEC_PER_PULSE,
|
||||
.init_val = I2S_OUT_INIT_VAL,
|
||||
};
|
||||
return i2s_out_init(default_param);
|
||||
}
|
||||
|
||||
#endif
|
@@ -1,5 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
i2s_out.h
|
||||
I2SOut.h
|
||||
Part of Grbl_ESP32
|
||||
Header for basic GPIO expander using the ESP32 I2S peripheral
|
||||
2020 - Michiyasu Odaki
|
||||
@@ -35,11 +37,9 @@
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#ifndef i2s_out_h
|
||||
#define i2s_out_h
|
||||
|
||||
// It should be included at the outset to know the machine configuration.
|
||||
#include "config.h"
|
||||
#include "Config.h"
|
||||
|
||||
// If USE_I2S_OUT_STREAM is defined
|
||||
// but the prerequisite USE_I2S_OUT is not defined,
|
||||
@@ -164,10 +164,10 @@ int i2s_out_set_stepping();
|
||||
void i2s_out_delay();
|
||||
|
||||
/*
|
||||
Set the pulse callback period in microseconds
|
||||
(like the timer period for the ISR)
|
||||
Set the pulse callback period in ISR ticks.
|
||||
(same value of the timer period for the ISR)
|
||||
*/
|
||||
int i2s_out_set_pulse_period(uint32_t period);
|
||||
int i2s_out_set_pulse_period(uint64_t period);
|
||||
|
||||
/*
|
||||
Register a callback function to generate pulse data
|
||||
@@ -188,4 +188,3 @@ int i2s_out_reset();
|
||||
Reference: "ESP32 Technical Reference Manual" by Espressif Systems
|
||||
https://www.espressif.com/sites/default/files/documentation/esp32_technical_reference_manual_en.pdf
|
||||
*/
|
||||
#endif
|
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
jog.h - Jogging methods
|
||||
Jog.cpp - Jogging methods
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
@@ -21,8 +21,7 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
#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) {
|
||||
@@ -34,7 +33,8 @@ 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);
|
@@ -1,5 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
jog.h - Jogging methods
|
||||
Jog.h - Jogging methods
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
@@ -20,16 +22,10 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef jog_h
|
||||
#define jog_h
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
#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);
|
||||
|
||||
#endif
|
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
limits.c - code pertaining to limit-switches and performing the homing cycle
|
||||
Limits.cpp - code pertaining to limit-switches and performing the homing cycle
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
@@ -25,7 +25,7 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "grbl.h"
|
||||
#include "Grbl.h"
|
||||
|
||||
uint8_t n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE;
|
||||
|
||||
@@ -75,7 +75,8 @@ 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;
|
||||
@@ -95,7 +96,8 @@ void limits_go_home(uint8_t cycle_mask) {
|
||||
// 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.
|
||||
@@ -132,11 +134,15 @@ 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];
|
||||
@@ -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
|
||||
@@ -173,13 +181,17 @@ void limits_go_home(uint8_t cycle_mask) {
|
||||
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 (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.
|
||||
@@ -261,14 +273,8 @@ void limits_go_home(uint8_t cycle_mask) {
|
||||
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,
|
||||
};
|
||||
uint8_t limit_pins[MAX_N_AXIS][2] = { { X_LIMIT_PIN, X2_LIMIT_PIN }, { Y_LIMIT_PIN, Y2_LIMIT_PIN }, { Z_LIMIT_PIN, Z2_LIMIT_PIN },
|
||||
{ A_LIMIT_PIN, A2_LIMIT_PIN }, { B_LIMIT_PIN, B2_LIMIT_PIN }, { C_LIMIT_PIN, C2_LIMIT_PIN } };
|
||||
|
||||
uint8_t limit_mask = 0;
|
||||
|
||||
@@ -278,18 +284,28 @@ void limits_init() {
|
||||
#ifdef DISABLE_LIMIT_PIN_PULL_UP
|
||||
mode = INPUT;
|
||||
#endif
|
||||
for (int i=0; i<N_AXIS; i++) {
|
||||
for (int axis = 0; axis < N_AXIS; axis++) {
|
||||
for (int gang_index = 0; gang_index < 2; gang_index++) {
|
||||
uint8_t pin;
|
||||
if ((pin = limit_pins[i]) != UNDEFINED_PIN) {
|
||||
limit_mask |= bit(i);
|
||||
if ((pin = limit_pins[axis][gang_index]) != UNDEFINED_PIN) {
|
||||
pinMode(pin, mode);
|
||||
limit_mask |= bit(axis);
|
||||
if (hard_limits->get()) {
|
||||
attachInterrupt(pin, isr_limit_switches, CHANGE);
|
||||
} else {
|
||||
detachInterrupt(pin);
|
||||
}
|
||||
grbl_msg_sendf(CLIENT_SERIAL,
|
||||
MSG_LEVEL_INFO,
|
||||
"%c%s Axis limit switch on pin %s",
|
||||
report_get_axis_letter(axis),
|
||||
gang_index ? "2" : " ",
|
||||
pinName(pin).c_str());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Limit Mask %d", limit_mask);
|
||||
|
||||
// setup task used for debouncing
|
||||
limit_sw_queue = xQueueCreate(10, sizeof(int));
|
||||
@@ -303,9 +319,12 @@ void limits_init() {
|
||||
|
||||
// Disables hard limits.
|
||||
void limits_disable() {
|
||||
for (int i=0; i<N_AXIS; i++) {
|
||||
if (limit_pins[i] != UNDEFINED_PIN) {
|
||||
detachInterrupt(i);
|
||||
for (int axis = 0; axis < N_AXIS; axis++) {
|
||||
for (int gang_index = 0; gang_index < 2; gang_index++) {
|
||||
uint8_t pin = limit_pins[axis][gang_index];
|
||||
if (pin != UNDEFINED_PIN) {
|
||||
detachInterrupt(pin);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -315,10 +334,12 @@ 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++) {
|
||||
uint8_t pin;
|
||||
if ((pin = limit_pins[i]) != UNDEFINED_PIN) {
|
||||
pinMask += digitalRead(pin) << i;
|
||||
for (int axis = 0; axis < N_AXIS; axis++) {
|
||||
for (int gang_index = 0; gang_index < 2; gang_index++) {
|
||||
uint8_t pin = limit_pins[axis][gang_index];
|
||||
if (pin != UNDEFINED_PIN) {
|
||||
pinMask |= (digitalRead(pin) << axis);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -352,7 +373,8 @@ 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.
|
||||
@@ -371,7 +393,7 @@ void limitCheckTask(void* pvParameters) {
|
||||
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);
|
||||
//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
|
||||
}
|
@@ -1,5 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
limits.h - code pertaining to limit-switches and performing the homing cycle
|
||||
Limits.h - code pertaining to limit-switches and performing the homing cycle
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
@@ -25,9 +27,6 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef grbl_limits_h
|
||||
#define grbl_limits_h
|
||||
|
||||
extern uint8_t n_homing_locate_cycle;
|
||||
|
||||
#define SQUARING_MODE_DUAL 0 // both motors run
|
||||
@@ -55,5 +54,3 @@ bool axis_is_squared(uint8_t axis_mask);
|
||||
|
||||
// A task that runs after a limit switch interrupt.
|
||||
void limitCheckTask(void* pvParameters);
|
||||
|
||||
#endif
|
@@ -1,17 +1,8 @@
|
||||
#pragma once
|
||||
|
||||
// This file is where you choose the machine type, by including
|
||||
// one or more machine definition files as described below.
|
||||
|
||||
#ifndef _machine_h
|
||||
#define _machine_h
|
||||
|
||||
/*
|
||||
PWM
|
||||
Tested on arc_arrow.nc
|
||||
|
||||
|
||||
|
||||
*/
|
||||
|
||||
#ifndef MACHINE_FILENAME
|
||||
|
||||
// !!! For initial testing, start with test_drive.h which disables
|
||||
@@ -48,10 +39,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) <src/Machines/name>
|
||||
|
||||
# include MACHINE_PATHNAME_QUOTED(MACHINE_FILENAME)
|
||||
|
||||
#endif // MACHINE_FILENAME
|
||||
|
||||
#endif // _machine_h
|
35
Grbl_Esp32/src/MachineCommon.h
Normal file
35
Grbl_Esp32/src/MachineCommon.h
Normal file
@@ -0,0 +1,35 @@
|
||||
#pragma once
|
||||
|
||||
#ifndef SPINDLE_TYPE
|
||||
# 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
|
||||
#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 STEP_PULSE_MIN 2 // uSeconds
|
||||
#define STEP_PULSE_MAX 10 // uSeconds
|
||||
|
||||
// =============== Don't change or comment these out ======================
|
||||
// They are for legacy purposes and will not affect your I/O
|
||||
|
||||
#define STEP_MASK B111111
|
||||
|
||||
#define PROBE_MASK 1
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
3axis_v3.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
3axis_v4.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
3axis_xyx.h
|
||||
Part of Grbl_ESP32
|
@@ -1,5 +1,8 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
4axis_external_driver_4x.h
|
||||
4axis_external_driver.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the buildlog.net 4-axis external driver board
|
95
Grbl_Esp32/src/Machines/6_pack_MPCNC_stepstick_v1.h
Normal file
95
Grbl_Esp32/src/Machines/6_pack_MPCNC_stepstick_v1.h
Normal file
@@ -0,0 +1,95 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
6_pack_MPCNC_stepstick_v1.h
|
||||
|
||||
Covers all V1 versions V1p0, V1p1, etc
|
||||
|
||||
Part of Grbl_ESP32
|
||||
Pin assignments for the ESP32 I2S 6-axis board
|
||||
2018 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
2020 - Michiyasu Odaki
|
||||
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_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#define MACHINE_NAME "6 Pack MPCNC XYZXY V1 (StepStick)"
|
||||
|
||||
#ifdef N_AXIS
|
||||
#undef N_AXIS
|
||||
#endif
|
||||
#define N_AXIS 3
|
||||
|
||||
#ifdef ENABLE_SD_CARD
|
||||
#undef ENABLE_SD_CARD
|
||||
#endif
|
||||
|
||||
// === Special Features
|
||||
|
||||
// I2S (steppers & other output-only pins)
|
||||
#define USE_I2S_OUT
|
||||
// Define USE_I2S_OUT_STREAM if buffering is used.
|
||||
// (there will be a delay between the specified I/O operation and the actual I/O execution)
|
||||
#define USE_I2S_OUT_STREAM
|
||||
#undef USE_RMT_STEPS
|
||||
|
||||
#define USE_STEPSTICK // makes sure MS1,2,3 !reset and !sleep are set
|
||||
|
||||
#define I2S_OUT_BCK GPIO_NUM_22
|
||||
#define I2S_OUT_WS GPIO_NUM_17
|
||||
#define I2S_OUT_DATA GPIO_NUM_21
|
||||
|
||||
|
||||
#define X_STEPPER_MS3 I2SO(3) // Labeled X_CS
|
||||
#define Y_STEPPER_MS3 I2SO(6) // Y_CS
|
||||
#define Z_STEPPER_MS3 I2SO(11) // Z_CS
|
||||
#define X2_STEPPER_MS3 I2SO(14) // A_CS
|
||||
#define Y2_STEPPER_MS3 I2SO(19) // B_CS
|
||||
|
||||
#define STEPPER_RESET GPIO_NUM_19
|
||||
|
||||
#define X_DISABLE_PIN I2SO(0)
|
||||
#define X_DIRECTION_PIN I2SO(1)
|
||||
#define X_STEP_PIN I2SO(2)
|
||||
#define X_AXIS_SQUARING
|
||||
|
||||
#define Y_DIRECTION_PIN I2SO(4)
|
||||
#define Y_STEP_PIN I2SO(5)
|
||||
#define Y_DISABLE_PIN I2SO(7)
|
||||
#define Y_AXIS_SQUARING
|
||||
|
||||
#define Z_DISABLE_PIN I2SO(8)
|
||||
#define Z_DIRECTION_PIN I2SO(9)
|
||||
#define Z_STEP_PIN I2SO(10)
|
||||
|
||||
// labeled A on controller
|
||||
#define X2_DIRECTION_PIN I2SO(12)
|
||||
#define X2_STEP_PIN I2SO(13)
|
||||
#define X2_DISABLE_PIN I2SO(15)
|
||||
|
||||
// labeled B on controller
|
||||
#define Y2_DISABLE_PIN I2SO(16)
|
||||
#define Y2_DIRECTION_PIN I2SO(17)
|
||||
#define Y2_STEP_PIN I2SO(18)
|
||||
|
||||
// stepper C unused
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_33
|
||||
#define Y_LIMIT_PIN GPIO_NUM_32
|
||||
#define Z_LIMIT_PIN GPIO_NUM_35
|
||||
#define X2_LIMIT_PIN GPIO_NUM_34 // labeled A
|
||||
#define Y2_LIMIT_PIN GPIO_NUM_39 // labeled B
|
||||
|
||||
|
||||
|
||||
// === Default settings
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS I2S_OUT_USEC_PER_PULSE
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
6_pack_stepstick_v1.h
|
||||
|
||||
@@ -46,12 +49,12 @@
|
||||
#define I2S_OUT_DATA GPIO_NUM_21
|
||||
|
||||
|
||||
#define STEPPER_X_MS3 I2SO(3) // X_CS
|
||||
#define STEPPER_Y_MS3 I2SO(6) // Y_CS
|
||||
#define STEPPER_Z_MS3 I2SO(11) // Z_CS
|
||||
#define STEPPER_A_MS3 I2SO(14) // A_CS
|
||||
#define STEPPER_B_MS3 I2SO(19) // B_CS
|
||||
#define STEPPER_C_MS3 I2SO(22) // C_CS
|
||||
#define X_STEPPER_MS3 I2SO(3) // X_CS
|
||||
#define Y_STEPPER_MS3 I2SO(6) // Y_CS
|
||||
#define Z_STEPPER_MS3 I2SO(11) // Z_CS
|
||||
#define A_STEPPER_MS3 I2SO(14) // A_CS
|
||||
#define B_STEPPER_MS3 I2SO(19) // B_CS
|
||||
#define C_STEPPER_MS3 I2SO(22) // C_CS
|
||||
|
||||
#define STEPPER_RESET GPIO_NUM_19
|
||||
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
6_pack_trinamic_V1.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
atari_1020.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
esp32_printer_controller.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
espduino.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
foo_6axis.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
i2s_out_xxyyzz.h
|
||||
Part of Grbl_ESP32
|
||||
@@ -16,6 +19,7 @@
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#define MACHINE_NAME "ESP32 I2S XXYYZZ Axis Driver Board (StepStick)"
|
||||
|
||||
#ifdef N_AXIS
|
||||
@@ -55,8 +59,6 @@
|
||||
|
||||
#define STEPPER_RESET GPIO_NUM_19
|
||||
|
||||
#define USE_GANGED_AXES // allow two motors on an axis
|
||||
|
||||
#define X_DISABLE_PIN I2SO(0)
|
||||
#define X_DIRECTION_PIN I2SO(1)
|
||||
#define X_STEP_PIN I2SO(2)
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
i2s_out_xyzabc.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
i2s_out_xyzabc_trinamic.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
lowrider_v1p2.h
|
||||
Part of Grbl_ESP32
|
||||
@@ -19,19 +22,15 @@
|
||||
along with Grbl_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
|
||||
#define MACHINE_NAME "LOWRIDER_V1P2"
|
||||
|
||||
#define USE_GANGED_AXES // allow two motors on an axis
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_27 // use Z labeled connector
|
||||
#define X_DIRECTION_PIN GPIO_NUM_33 // use Z labeled connector
|
||||
|
||||
#define Y_STEP_PIN GPIO_NUM_14 // use Y labeled connector
|
||||
#define Y2_STEP_PIN GPIO_NUM_21 // ganged motor
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_25 // use Y labeled connector
|
||||
#define Y2_DIRECTION_PIN X_DIRECTION_PIN
|
||||
#define Y2_DIRECTION_PIN Y_DIRECTION_PIN
|
||||
#define Y_AXIS_SQUARING
|
||||
|
||||
#define Z_STEP_PIN GPIO_NUM_12 // use X labeled connector
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
midtbot.h
|
||||
Part of Grbl_ESP32
|
@@ -1,5 +1,8 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
mpcnc.h
|
||||
mpcnc_v1p1.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the Buildlog.net MPCNC controller
|
||||
@@ -27,8 +30,6 @@
|
||||
|
||||
#define MACHINE_NAME "MPCNC_V1P1"
|
||||
|
||||
#define USE_GANGED_AXES // allow two motors on an axis
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X2_STEP_PIN GPIO_NUM_22 // ganged motor
|
||||
#define X_AXIS_SQUARING
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
mpcnc_v1p2.h
|
||||
Part of Grbl_ESP32
|
||||
@@ -28,8 +31,6 @@
|
||||
|
||||
#define MACHINE_NAME "MPCNC_V1P2"
|
||||
|
||||
#define USE_GANGED_AXES // allow two motors on an axis
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X2_STEP_PIN GPIO_NUM_22 // ganged motor
|
||||
#define X_AXIS_SQUARING
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
pen_laser.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
polar_coaster.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
spi_daisy_4axis_xyyz.h
|
||||
Part of Grbl_ESP32
|
||||
@@ -39,9 +42,6 @@
|
||||
// The hardware enable pin is tied to ground
|
||||
#define USE_TRINAMIC_ENABLE
|
||||
|
||||
// allow two motors on an axis
|
||||
#define USE_GANGED_AXES
|
||||
|
||||
// Y motor connects to the 1st driver
|
||||
#define X_TRINAMIC_DRIVER 2130 // Which Driver Type?
|
||||
#define X_RSENSE TMC2130_RSENSE_DEFAULT
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
spi_daisy_4axis_xyz.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
spi_daisy_4axis_xyza.h
|
||||
Part of Grbl_ESP32
|
||||
@@ -70,17 +73,7 @@
|
||||
#define SPINDLE_OUTPUT_PIN GPIO_NUM_25
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_4
|
||||
|
||||
// Relay operation
|
||||
// Install Jumper near relay
|
||||
// For PWM remove jumper to prevent relay damage
|
||||
// Interlock jumper along top edge needs to be installed for both versions
|
||||
#define USE_RELAY // comment out to use PWM
|
||||
|
||||
#ifdef USE_RELAY
|
||||
#define SPINDLE_TYPE SPINDLE_TYPE_RELAY
|
||||
#else
|
||||
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
|
||||
#endif
|
||||
#define SPINDLE_TYPE SPINDLE_TYPE_RELAY // default use $Spindle/Type=PWM or $Spindle/Type=Laser
|
||||
|
||||
#define PROBE_PIN GPIO_NUM_22
|
||||
|
@@ -1,5 +1,8 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
3axis_v4.h
|
||||
spindle_class_test.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the ESP32 Development Controller, v4.1 and later.
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
template.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
test_drive.h
|
||||
Part of Grbl_ESP32
|
@@ -1,3 +1,6 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
tmc2130_pen.h
|
||||
Part of Grbl_ESP32
|
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
motion_control.c - high level interface for issuing motion commands
|
||||
MotionControl.cpp - high level interface for issuing motion commands
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
@@ -22,7 +22,7 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "grbl.h"
|
||||
#include "Grbl.h"
|
||||
|
||||
// M_PI is not defined in standard C/C++ but some compilers
|
||||
// support it anyway. The following suppresses Intellisense
|
||||
@@ -33,7 +33,6 @@
|
||||
|
||||
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
|
||||
@@ -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
|
||||
@@ -76,16 +77,18 @@ void mc_line(float* target, plan_line_data_t* pl_data) {
|
||||
// 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;
|
||||
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,8 +96,15 @@ 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
|
||||
@@ -110,16 +120,17 @@ void mc_arc(float* target, plan_line_data_t* pl_data, float* position, float* of
|
||||
// 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 (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
|
||||
@@ -193,7 +204,8 @@ void mc_arc(float* target, plan_line_data_t* pl_data, float* position, float* of
|
||||
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.
|
||||
@@ -229,7 +240,7 @@ void mc_homing_cycle(uint8_t cycle_mask) {
|
||||
#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.
|
||||
// TODO: Move the pin-specific LIMIT_PIN call to Limits.cpp 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.
|
||||
@@ -335,15 +346,16 @@ 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);
|
||||
@@ -365,13 +377,16 @@ 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.
|
||||
}
|
||||
@@ -386,15 +401,17 @@ uint8_t mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_
|
||||
// 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);
|
||||
@@ -404,7 +421,8 @@ void mc_parking_motion(float* parking_target, plan_line_data_t* pl_data) {
|
||||
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.
|
||||
} else {
|
||||
@@ -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
|
||||
@@ -453,8 +471,10 @@ void mc_reset() {
|
||||
if ((sys.state & (STATE_CYCLE | STATE_HOMING | STATE_JOG)) ||
|
||||
(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);
|
||||
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
|
||||
@@ -464,5 +484,3 @@ void mc_reset() {
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
@@ -1,5 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
motion_control.h - high level interface for issuing motion commands
|
||||
MotionControl.h - high level interface for issuing motion commands
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
||||
@@ -22,13 +24,7 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
|
||||
#ifndef motion_control_h
|
||||
#define motion_control_h
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
#include "Grbl.h"
|
||||
|
||||
// System motion commands must have a line number of zero.
|
||||
#define HOMING_CYCLE_LINE_NUMBER 0
|
||||
@@ -42,7 +38,6 @@
|
||||
#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
|
||||
// (1 minute)/feed_rate time.
|
||||
@@ -53,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);
|
||||
@@ -73,5 +75,3 @@ void mc_parking_motion(float* parking_target, plan_line_data_t* pl_data);
|
||||
|
||||
// Performs system reset. If in motion state, kills all motion and sets system alarm.
|
||||
void mc_reset();
|
||||
|
||||
#endif
|
53
Grbl_Esp32/src/Motors/Motor.cpp
Normal file
53
Grbl_Esp32/src/Motors/Motor.cpp
Normal file
@@ -0,0 +1,53 @@
|
||||
/*
|
||||
Motor.cpp
|
||||
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 <http://www.gnu.org/licenses/>.
|
||||
TODO
|
||||
Make sure public/private/protected is cleaned up.
|
||||
Only a few Unipolar axes have been setup in init()
|
||||
Get rid of Z_SERVO, just reply on Z_SERVO_PIN
|
||||
Deal with custom machine ... machine_trinamic_setup();
|
||||
Class is ready to deal with non SPI pins, but they have not been needed yet.
|
||||
It would be nice in the config message though
|
||||
Testing
|
||||
Done (success)
|
||||
3 Axis (3 Standard Steppers)
|
||||
MPCNC (ganged with shared direction pin)
|
||||
TMC2130 Pen Laser (trinamics, stallguard tuning)
|
||||
Unipolar
|
||||
TODO
|
||||
4 Axis SPI (Daisy Chain, Ganged with unique direction pins)
|
||||
Reference
|
||||
TMC2130 Datasheet https://www.trinamic.com/fileadmin/assets/Products/ICs_Documents/TMC2130_datasheet.pdf
|
||||
*/
|
||||
|
||||
#include "Motor.h"
|
||||
|
||||
namespace Motors {
|
||||
Motor::Motor() { type_id = MOTOR; }
|
||||
|
||||
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::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) { _homing_mask = homing_mask; }
|
||||
}
|
65
Grbl_Esp32/src/Motors/Motor.h
Normal file
65
Grbl_Esp32/src/Motors/Motor.h
Normal file
@@ -0,0 +1,65 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
Motor.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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "Motors.h"
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
namespace Motors {
|
||||
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"
|
||||
};
|
||||
}
|
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
MotorClass.cpp
|
||||
Motors.cpp
|
||||
Part of Grbl_ESP32
|
||||
2020 - Bart Dring
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
@@ -31,14 +31,18 @@
|
||||
TMC2130 Datasheet https://www.trinamic.com/fileadmin/assets/Products/ICs_Documents/TMC2130_datasheet.pdf
|
||||
*/
|
||||
|
||||
#include "../grbl.h"
|
||||
#include "TrinamicDriverClass.cpp"
|
||||
#include "StandardStepperClass.cpp"
|
||||
#include "UnipolarMotorClass.cpp"
|
||||
#include "RcServoClass.cpp"
|
||||
//#include "SolenoidClass.cpp"
|
||||
#include "Motors.h"
|
||||
|
||||
Motor* myMotor[MAX_AXES][MAX_GANGED]; // number of axes (normal and ganged)
|
||||
#include "Motor.h"
|
||||
#include "../Grbl.h"
|
||||
|
||||
#include "NullMotor.h"
|
||||
#include "StandardStepper.h"
|
||||
#include "UnipolarMotor.h"
|
||||
#include "RcServo.h"
|
||||
#include "TrinamicDriver.h"
|
||||
|
||||
Motors::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;
|
||||
|
||||
@@ -49,10 +53,13 @@ rmt_config_t rmtConfig;
|
||||
bool motor_class_steps; // true if at least one motor class is handling steps
|
||||
|
||||
void init_motors() {
|
||||
using namespace 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 +71,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 +83,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 +98,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 +110,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 +125,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 +139,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 +152,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 +166,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 +179,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 +193,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 +206,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,41 +218,23 @@ 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
|
||||
digitalWrite(STEPPER_MS1, HIGH);
|
||||
pinMode(STEPPER_MS1, OUTPUT);
|
||||
#endif
|
||||
#ifdef STEPPER_MS2
|
||||
digitalWrite(STEPPER_MS2, HIGH);
|
||||
pinMode(STEPPER_MS2, OUTPUT);
|
||||
#endif
|
||||
#ifdef STEPPER_X_MS3
|
||||
digitalWrite(STEPPER_X_MS3, HIGH);
|
||||
pinMode(STEPPER_X_MS3, OUTPUT);
|
||||
#endif
|
||||
#ifdef STEPPER_Y_MS3
|
||||
digitalWrite(STEPPER_Y_MS3, HIGH);
|
||||
pinMode(STEPPER_Y_MS3, OUTPUT);
|
||||
#endif
|
||||
#ifdef STEPPER_Z_MS3
|
||||
digitalWrite(STEPPER_Z_MS3, HIGH);
|
||||
pinMode(STEPPER_Z_MS3, OUTPUT);
|
||||
#endif
|
||||
#ifdef STEPPER_A_MS3
|
||||
digitalWrite(STEPPER_A_MS3, HIGH);
|
||||
pinMode(STEPPER_A_MS3, OUTPUT);
|
||||
#endif
|
||||
#ifdef STEPPER_B_MS3
|
||||
digitalWrite(STEPPER_B_MS3, HIGH);
|
||||
pinMode(STEPPER_B_MS3, OUTPUT);
|
||||
#endif
|
||||
#ifdef STEPPER_C_MS3
|
||||
digitalWrite(STEPPER_C_MS3, HIGH);
|
||||
pinMode(STEPPER_C_MS3, OUTPUT);
|
||||
#endif
|
||||
|
||||
uint8_t ms3_pins[MAX_N_AXIS][2] = { { X_STEPPER_MS3, X2_STEPPER_MS3 }, { Y_STEPPER_MS3, Y2_STEPPER_MS3 }, { Z_STEPPER_MS3, Z2_STEPPER_MS3 },
|
||||
{ A_STEPPER_MS3, A2_STEPPER_MS3 }, { B_STEPPER_MS3, B2_STEPPER_MS3 }, { C_STEPPER_MS3, C2_STEPPER_MS3 } };
|
||||
|
||||
for (int axis = 0; axis < N_AXIS; axis++) {
|
||||
for (int gang_index = 0; gang_index < 2; gang_index++) {
|
||||
uint8_t pin = ms3_pins[axis][gang_index];
|
||||
if (pin != UNDEFINED_PIN) {
|
||||
digitalWrite(pin, HIGH);
|
||||
pinMode(pin, OUTPUT);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
# ifdef STEPPER_RESET
|
||||
// !RESET pin on steppers (MISO On Schematic)
|
||||
digitalWrite(STEPPER_RESET, HIGH);
|
||||
@@ -247,16 +245,12 @@ void init_motors() {
|
||||
|
||||
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));
|
||||
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;
|
||||
|
||||
@@ -296,13 +290,10 @@ void init_motors() {
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
void servoUpdateTask(void* pvParameters) {
|
||||
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
|
||||
|
||||
@@ -328,7 +319,6 @@ bool motors_have_type_id(motor_class_id_t id) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
void motors_set_disable(bool disable) {
|
||||
static bool previous_state = false;
|
||||
|
||||
@@ -369,7 +359,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)
|
||||
@@ -434,7 +423,6 @@ void readSgTask(void* pvParameters) {
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#ifdef USE_I2S_OUT
|
||||
//
|
||||
// Override default function and insert a short delay
|
||||
@@ -444,32 +432,3 @@ void TMC2130Stepper::switchCSpin(bool state) {
|
||||
i2s_out_delay();
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
// ============================== Class Methods ================================================
|
||||
|
||||
Motor :: Motor() {
|
||||
type_id = MOTOR;
|
||||
}
|
||||
|
||||
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 :: 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) {
|
||||
_homing_mask = homing_mask;
|
||||
}
|
53
Grbl_Esp32/src/Motors/Motors.h
Normal file
53
Grbl_Esp32/src/Motors/Motors.h
Normal file
@@ -0,0 +1,53 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
Motors.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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "../Grbl.h"
|
||||
#include <TMCStepper.h> // https://github.com/teemuatlut/TMCStepper
|
||||
|
||||
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
|
7
Grbl_Esp32/src/Motors/NullMotor.h
Normal file
7
Grbl_Esp32/src/Motors/NullMotor.h
Normal file
@@ -0,0 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "Motor.h"
|
||||
|
||||
namespace Motors {
|
||||
class Nullmotor : public Motor {};
|
||||
}
|
189
Grbl_Esp32/src/Motors/RcServo.cpp
Normal file
189
Grbl_Esp32/src/Motors/RcServo.cpp
Normal file
@@ -0,0 +1,189 @@
|
||||
/*
|
||||
RcServo.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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "RcServo.h"
|
||||
|
||||
namespace Motors {
|
||||
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);
|
||||
}
|
||||
}
|
55
Grbl_Esp32/src/Motors/RcServo.h
Normal file
55
Grbl_Esp32/src/Motors/RcServo.h
Normal file
@@ -0,0 +1,55 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
RcServo.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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "Motor.h"
|
||||
|
||||
#include "RcServoSettings.h"
|
||||
|
||||
namespace Motors {
|
||||
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;
|
||||
};
|
||||
}
|
26
Grbl_Esp32/src/Motors/RcServoSettings.h
Normal file
26
Grbl_Esp32/src/Motors/RcServoSettings.h
Normal file
@@ -0,0 +1,26 @@
|
||||
#pragma once
|
||||
|
||||
// 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
|
18
Grbl_Esp32/src/Motors/Solenoid.h
Normal file
18
Grbl_Esp32/src/Motors/Solenoid.h
Normal file
@@ -0,0 +1,18 @@
|
||||
#pragma once
|
||||
|
||||
#include "RcServo.h"
|
||||
|
||||
namespace Motors {
|
||||
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;
|
||||
};
|
||||
}
|
103
Grbl_Esp32/src/Motors/StandardStepper.cpp
Normal file
103
Grbl_Esp32/src/Motors/StandardStepper.cpp
Normal file
@@ -0,0 +1,103 @@
|
||||
/*
|
||||
StandardStepper.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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "StandardStepper.h"
|
||||
|
||||
namespace Motors {
|
||||
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); }
|
||||
}
|
23
Grbl_Esp32/src/Motors/StandardStepper.h
Normal file
23
Grbl_Esp32/src/Motors/StandardStepper.h
Normal file
@@ -0,0 +1,23 @@
|
||||
#pragma once
|
||||
|
||||
#include "Motor.h"
|
||||
|
||||
namespace Motors {
|
||||
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;
|
||||
};
|
||||
}
|
235
Grbl_Esp32/src/Motors/TrinamicDriver.cpp
Normal file
235
Grbl_Esp32/src/Motors/TrinamicDriver.cpp
Normal file
@@ -0,0 +1,235 @@
|
||||
/*
|
||||
TrinamicDriver.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 <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#include "TrinamicDriver.h"
|
||||
|
||||
#include <TMCStepper.h>
|
||||
|
||||
namespace Motors {
|
||||
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.
|
||||
}
|
||||
}
|
98
Grbl_Esp32/src/Motors/TrinamicDriver.h
Normal file
98
Grbl_Esp32/src/Motors/TrinamicDriver.h
Normal file
@@ -0,0 +1,98 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
TrinamicDriver.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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "Motor.h"
|
||||
#include "StandardStepper.h"
|
||||
#include <TMCStepper.h> // https://github.com/teemuatlut/TMCStepper
|
||||
|
||||
#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
|
||||
|
||||
namespace Motors {
|
||||
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;
|
||||
};
|
||||
}
|
139
Grbl_Esp32/src/Motors/UnipolarMotor.cpp
Normal file
139
Grbl_Esp32/src/Motors/UnipolarMotor.cpp
Normal file
@@ -0,0 +1,139 @@
|
||||
#include "UnipolarMotor.h"
|
||||
|
||||
namespace Motors {
|
||||
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]);
|
||||
}
|
||||
}
|
24
Grbl_Esp32/src/Motors/UnipolarMotor.h
Normal file
24
Grbl_Esp32/src/Motors/UnipolarMotor.h
Normal file
@@ -0,0 +1,24 @@
|
||||
#pragma once
|
||||
|
||||
#include "Motor.h"
|
||||
|
||||
namespace Motors {
|
||||
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;
|
||||
};
|
||||
}
|
@@ -1,5 +1,5 @@
|
||||
/*
|
||||
nuts_bolts.c - Shared functions
|
||||
NutsBolts.cpp - Shared functions
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
@@ -22,10 +22,7 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
|
||||
|
||||
#include "Grbl.h"
|
||||
|
||||
#define MAX_INT_DIGITS 8 // Maximum number of digits in int32 (and float)
|
||||
|
||||
@@ -58,10 +55,12 @@ uint8_t read_float(const char* line, uint8_t* char_counter, float* float_ptr) {
|
||||
if (c <= 9) {
|
||||
ndigit++;
|
||||
if (ndigit <= MAX_INT_DIGITS) {
|
||||
if (isdecimal) exp--;
|
||||
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))
|
||||
isdecimal = true;
|
||||
@@ -70,7 +69,9 @@ uint8_t read_float(const char* line, uint8_t* char_counter, float* float_ptr) {
|
||||
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;
|
||||
@@ -106,21 +107,24 @@ 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
|
||||
// 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
|
||||
}
|
||||
}
|
||||
|
||||
// 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;
|
||||
@@ -131,7 +135,8 @@ float convert_delta_vector_to_unit_vector(float* vector) {
|
||||
}
|
||||
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);
|
||||
}
|
||||
|
||||
@@ -183,5 +188,3 @@ 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');
|
||||
}
|
||||
|
||||
|
@@ -1,5 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
nuts_bolts.h - Header for system level commands and real-time processes
|
||||
NutsBolts.h - Header for system level commands and real-time processes
|
||||
Part of Grbl
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
@@ -18,10 +20,7 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef nuts_bolts_h
|
||||
#define nuts_bolts_h
|
||||
|
||||
#include "config.h"
|
||||
#include "Config.h"
|
||||
|
||||
#define false 0
|
||||
#define true 1
|
||||
@@ -56,8 +55,6 @@
|
||||
#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)
|
||||
@@ -107,8 +104,9 @@ 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;
|
||||
}
|
||||
|
||||
#endif
|
@@ -1,5 +1,5 @@
|
||||
#include "grbl.h"
|
||||
#include "i2s_out.h"
|
||||
#include "Grbl.h"
|
||||
#include "I2SOut.h"
|
||||
|
||||
String pinName(uint8_t pin) {
|
||||
if (pin == UNDEFINED_PIN) {
|
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user