1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-08-31 10:01:48 +02:00
* Fixed various small bugs (#605)

* Fixed various small bugs

* Fixed potential cast bug

* Fixed double reporting of errors

Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>

* Stallguard tuning (#607)

* Devt (#571)

* Handles Tranimic drivers errors better

- If an unsupported driver is specified, it will give a message and not crash.

* Cleaned up unused files

Got rid of old unipolar files
Got rid of servo axis feature - it is a motor class now
Got rid of solenoid pen feature - never really used and it should be a motor class if it is.

* Fix ENABLE_AUTHENTICATION (#569)

* Fixed authentication code.

* Removed another const cast

Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>

* Fix step leakage with inverted steps (#570)

* Fix step leakage with inverted steps

* Update build date for merge

Co-authored-by: Bart Dring <bdring@buildlog.net>

Co-authored-by: Stefan de Bruijn <atlaste@users.noreply.github.com>
Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>
Co-authored-by: Mitch Bradley <wmb@firmworks.com>
Co-authored-by: Bart Dring <bdring@buildlog.net>

* Update platformio.ini

Per PR 583

* Created an enum for mode

* Removing some unused machine defs

* Added test machine definition

* Clean up for PR

* Remove test machine def.

Co-authored-by: Stefan de Bruijn <atlaste@users.noreply.github.com>
Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>
Co-authored-by: Mitch Bradley <wmb@firmworks.com>
Co-authored-by: Bart Dring <bdring@buildlog.net>

* Basic testing Complete

* Made state variable volatile.

* Homing cycle settings (#613)

* Initial Tests Complete

* Update Grbl.h

* Update variables

Co-authored-by: Mitch Bradley <wmb@firmworks.com>

* fixed dual switches when inverted (#614)

* fixed dual switches when inverted

* Removed debug message

* Cleaning up the machine defs

Removed unused #defines.

* Store coordinate offsets in NVS (#611)

* Store coordinate offsets in NVS

* Handle both old Eeprom formats

* Implementing fixes (#616)

- Stop creating additional tasks when limit_init() gets called again from homing and resets
- Explicitly delete an object that was causing a memory loss.

* Update Grbl.h

* Tweak memory fix and add $H check for $Homing/Cycles

* Fix G28.1 and G30.1

* Update Grbl.h

* Homing cycle defaults (#624)

* Changed to add homing cycle defaults

There needs to be a way to set the homing cycle defaults in a machine definition.
There will likely be a better way to do this in the future.

* Update 10vSpindle.cpp

Had wrong error message

* Fixed typos and removed obsolete #defines

* Probe cleanup (#625)

* Cleanup probing code

* Update Grbl.h

* Update after review

* Update error_codes_en_US.csv

* More sd_close() to free memory (#622)

* Changed buffer sizes to 256 throughout various parts of the program. (#626)

This is a patch necessary for F360 personal users, because they decided to add a very lengthy comment...

Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>

* $sd/show and handle settings in SD files (#629)

* $sd/show and handle settings in SD files

* Added $LocalFs/Show and fixed $LocalFs/Run output

* Infer / at beginning of SD path name

The LocalFS path processing code already inserts
a / at the beginning of the path is one isn't
present.  This patch does the same for SD files.

* Show $ command responses in WebUI console

* Added $Settings/ListChanged AKA $SC

This is useful for saving settings in a compact form that
leaves defaults unchanged.

* $sd/show works in idle or alarm state

* Apply idle/alarm checks to SPIFFS files too

* Changed sd_close to SD.end()

sd_close was a temporary function to check for memory usage

* Big BUILD_INFO fix (#632)

-- Changes that affect behavior

Fixed the bugs with report_build_info()

Build info is no longer stored in the fixed "EEPROM" section; instead it
is a proper Setting named $Firmware/Build .  You can change it in the
usual way with $Firmware/Build=<whatever>

$I without the = still works.

-- Changes that affect configurability for developers

Converted a couple more #defines into enums - SETTINGS_RESTORE_*
and BITFLAG_RT_STATUS_* .  A side effect of this is that it is
no longer possible to configure the behavior of $RST=* by defining
SETTINGS_RESTORE_ALL to include only a subset.  I think it is
a bad idea from a customer support perspective to have the meaning
of this command be different for different builds.

Changed some of the #define ENABLE_ names to eliminate "EEPROM"

-- Changes that are purely cosmetic

Clarified descriptions in Config.h, to eliminate spurious/incorrect mentions
of "EEPROM"

Eliminated all mentions of the name "EEPROM" except the ones
that truly mean the EEPROM section, as opposed to generalized
non-volatile storage.

The contents of SettingsStorage.h and SettingsStorage.cpp, which
were really related to coordinate storage in Eeprom, not proper
settings, were moved to Eeprom.h and Eeprom.cpp.  The SettingsStorage
files are gone.

Got rid of get_step_pin_mask() and get_direction_pin_mask() because
they were just aliases for bit().  That eliminated some junk from
the SettingsStorage/Eeprom files.  Those files now tightly contain
only the residual stuff related to the storage of coordinate data
in EEPROM.

* Most #defines are gone (#595)

* Many more #defines bite the dust

* Fixed botch in rt accessory logic

* Update Probe.cpp

* Update System.cpp

* Typo

* Fixed WebUI crash (#633)

While eliminating a redundant definition of is_realtime_command(),
I inadvertently introduced a recursion due to the similarity of
the names "is_realtime_command()" and "is_realtime_cmd()".  The
solution is to eliminate the latter entirely.

* Fix i2s probing hang (#608)

* Fix I2S stepper hung just after the completion of motor moving

* Fix recompile issue

Fixed a problem with the recompile not being recompiled even if the files under the Custom folder are changed.

* More comment for macOS in debug.ini

* Fix the timing of calling I2S out's exclusion function and reset sequence

The reset sequence did not seem to be correct, so I changed it.
According to the ESP-IDF PR, the correct sequence is as follows:
1)TX module
2)DMA
3)FIFO
c7f33524b4 (diff-27688c6b3c29373d2a2b142b8471981c)

* Changed the message level for I2S swtiching from warning to debug

* Add some comments

* Implement stepping through Motors class (#636)

* Implement stepping through Motors class

WIP for discussion and review - not ready to merge yet

* Document Motor methods and variables

.. and remove some unused ones and move some
that are subclass-specific

* Move position_min/max to Limits.cpp

... and coalesced other uses thereof into a unified scheme.

* Call motor ->init() explicitly instead of implicitly

This makes it possible to inherit constructors without
spurious config messages.

* Fixed problems with I2S

* Changes in class method override syntax per atlaste

* Fixed oops

* More Motors simplification

a) Eliminated can_home() in favor of a return value from
set_homing_mode()
b) Eliminated axis_name() in favor of reportAxisNameMsg()

* Fixes to RcServo and Trinamic

- RC Servo was not handling disable ... probably old issue
- Display test after config

* More tweaks

* Define that variable!

* Move functions from Motors.cpp to subclasses

Created a Servo base class from which RcServo and
Dynamixel2 are derived.  This gets the servo update
task out of Motors.  It also eliminates the need for
type_id.  Now all of the functions that are specific
to particular kinds of motors are within their subclasses

* Adding Dynamixel to ABC axes.

* Removed second #ifndef SPINDLE_TYPE

* Fixed potential leak in Report.cpp

as reported by @atlaste

* Some servo cleanup. Has errors!

* min should be max

* Removed test rcservo machine definition.

* Removed obsolete #defines in machine defs for RcServo cal

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

* Cleaned up AMASS code (#635)

* Cleaned up AMASS code

More #defines gone
74 lines shorter

Tested by comparing the result of original AMASS computation code to
the new code with values surrounding all of the cutoff frequencies.

* I2SOut tick calculation

* Sorted out units for stepper pulse periods

I tried to make it clear what the units are
at different places in the code, and to use
argument datatypes that clearly show the
value range at different points, instead of
relying on implicit type promotion.  Hopefully
this will make it easier to understand when,
where, and why unit conversions occur.

* Update Stepper.h

* Deleted AMASS Config.h option

... as it is no longer optional

* Use less memory (#644)

a) closeFile() now does SD.end() to release memory
after running a file from SD.
b) Several task stacks are smaller
c) All tasks now check their free space if DEBUG_REPORT_STACK_FREE
is defined.  platformio.ini has a commented-out line that can be
uncommented to turn that on.
d) Similarly, platformio.ini can turn on DEBUG_REPORT_HEAP_SIZE
e) Fixed a small leak that occurred when listing local files.

With these changes, the heap size tends to hover around 53K, dropping
to about 37K when running a file from SD.

* Add coolant pin messages to startup (#647)

* Add coolant pin messages to startup

Help with user support.

* Removing incorrect STEPPER_RESET definition

* Fix laser mode startup message

* cleanup

- coolant_init() will behave as before
- update build date
- return default machine to test_drive

* Move CoreXY out of main Grbl (#653)

* Created branch

* WIP

* Update parallel_delta.cpp

* Wip

* WIP

* Wip

* Still working on kinematics

- Added an interface into the jogging section

* WIP

* WIP

* wip

* WIP

* WIP

* Wip

* WIP

* WIP

* Wip

* Update machine defs

* Created branch

* WIP

* Update parallel_delta.cpp

* Wip

* WIP

* Wip

* Still working on kinematics

- Added an interface into the jogging section

* WIP

* WIP

* wip

* WIP

* WIP

* Wip

* WIP

* WIP

* Wip

* Update machine defs

* Machine def change. Moved switches to module 1

* WIP

* Cleanup before P.R.

- Fixed ranges for delta geometry
- Added post homing delay option for servos
- renamed and removed old machine defs.

* Fixing initialization problem when not in USE_KINEMATICS mode

* Fixing Git Mess

* Publishing Branch

- Not ready yet. Issues with Z axis
- Need to add midTbot option

* WIP

- Seems to be fully functional now.
- Need to add midTbot option.

* Update CoreXY.cpp

* I think it is ready for PR

- fixed $RST=#
- added midTbot geometry factor

* Fine tune midtbot definition

* Removed more unneeded corexy code.

* Fixed doubled #define in machine def file.

* Update after review comments

* Added $A AKA Alarms/List command (#654)

* Added $A AKA Alarms/List command

Similar to $E AKA Errors/List

$E used to be AKA ErrorCodes/List

Also added $Errors/Verbose setting to display
full error text instead of the error number.
It defaults to true because it works with every
sender I have tried so far - cncjs, UGS, and Chrome
GCode Sender.  If you have problems with some sender
you can set it to false.

* Added static_assert per atlaste's comment

* Added a default and fixed Authentication issue

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

* TMC2130 plotter machine servo config update (#657)

* TMC2130 plotter machine servo config update

based on Slack conversation https://buildlog.slack.com/archives/CBZKZ8LHL/p1604243530253000

* Update Grbl.h

* Trinamic reporting (#656)

* Enhanced reporting of errors

* Change "motor" to "driver" for clarity.

* Added better way to show changed Setting values from Mitch

* Update build date

* Machine Definition Cleanup (#658)

- Removed machine definitions to speed up testing.
- Moved 6 pack CS/MS3 pins with other axis pins to help them stay in sync with the aixs letters

* Spindle delay and Telnet Fix (#676)

* Removed early saving of old state

Was causing later tests to be wrong

* Update Grbl.h

* Update TelnetServer.cpp

Remove filtering of '\r' character.

* ABC Bresenham counter init fix

* Rst responses (#679)

* Added verification of changes from $RST command

When sending $RST=$ you only get these responses.
[MSG:WiFi reset done]
[MSG:BT reset done]
Added the other things that change.
[MSG:WiFi reset done]
[MSG:BT reset done]
[MSG:Settings reset done]
[MSG:Postion offsets reset done]

* Update ProcessSettings.cpp

* Update Grbl.h

* Update ProcessSettings.cpp

* Fix Spindle State broken in earlier PR

* Update Grbl.h

* Spindle and laser (#683)

* WIP

* Updates

* Updates

- Added Laser/FullPower
- Move some stuff from PWM to Laser

* WIP

* Used the stop function before resetiing pins.

* Updates from discussion

- Reset_pins is now deinit()
- VFD task is now deleted when ... deinit()
- Added a Motor/Disable command

* Added Mitch's gambit

* Cleanup

- Finished VFD
- Fixed Settings (Thanks Brian!)
- changed task cores.

* Update VFDSpindle.cpp

* Update Laser.cpp

* Fixing reset

- gpio_reset_pin sets a pullup, which could turn on a device

* Changed Spindle messages to CLIENT_ALL

* Update Grbl.h

* Updates after review

* P.R. Cleanup

* Most spindle settings cause a new init()

* Laser mode (#692)

* Update Machine.h

* spindles now say if in laser mode

* name fix

* Updates

* Getting rid of crosstalk

* Update PWMSpindle.cpp

* Reset some values at spindle init()

* Update SettingsDefinitions.cpp

* Update Grbl.h

* Return to test_drive.h

* User macro button (#685)

* Test Macro Button Idea

* Updates

* Formating

* Changed macro pin reporting to be a single character

* Sd Web UI issues (#698)

* Updates

* returned reportTaskStackSize(uxHighWaterMark);

In a #ifdef DEBUG_TASK_STACK guard

* Disallow web commands unless idle or alarm state

* merging stuff after review

* Handle SD busy state in webserver handler (#697)

* Handle SD busy state in webserver handler

* Update index.html.gz

* Fixed reporting

* Add case for SD not enabled.

* Prevent Web commands except in idle or alarm

* Return authentication to the default

Co-authored-by: Mitch Bradley <wmb@firmworks.com>
Co-authored-by: Luc <8822552+luc-github@users.noreply.github.com>

* Update axis squaring checking (#699)

* Reverting some spindle changes...

CLIENT_ALL caused queue issues

* Rate Adjusting Fix

* Fix SD card hanging on bad gcode

* Fix hang on error 20 from SD/Run (#701)

* Fixed strange WCO values on first load (#702)

When loading Grbl_Esp32 into a fresh ESP32, the WCOs
would often have strange, very large, values.  The problem
was the code that tries to propagate data from the old
"Eeprom" storage format into the new NVS scheme.  The old
format had a broken checksum computation that made the
checksum so weak that if succeeds about half the time on
random data.

The solution is to get rid of all that old code.  The downside
is that migration from a build that uses the old format will
lose the WCO values.  The user will have to reestablish them.
Subsequent updates between different versions that both use
the new NVS format will propagate WCO values correctly.

* Fixes to homing (#706)

* Fixes to homing

* Update Grbl.h

* Clean up after code review.

* Trinamic uart (#700)

* WIP

* WIP

* Updates

* Update Grbl.h

* Removing some test machine definitions

* TMC5160 Drivers were not in tests

* Fix a few issues with VFDSpindle critical error handling (#705)

If a command is critical and fails to receive a response, it should trigger an Alarm. However, because the critical check was only evaluated if the spindle was not already unresponsive, it meant that a critical command failure would be silently ignored if a non-critical command failed before it (putting the VFDSpindle in unresponsive state). Therefore, I've moved the critical check to occur regardless of whether the spindle was already unresponsive.

Second, I believe that setting `sys_rt_exec_alarm` is not sufficient to stop the machine and put it into alarm state. Other alarm conditions (such as hard limits) also run an `mc_reset()` to stop motion first. It appears that without this, motion will not be stopped, and in fact, the alarm appears to get cleared if it occurs during motion!

* Update per P.R. #704 on main

Co-authored-by: Stefan de Bruijn <atlaste@users.noreply.github.com>
Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>
Co-authored-by: Mitch Bradley <wmb@firmworks.com>
Co-authored-by: Bart Dring <bdring@buildlog.net>
Co-authored-by: odaki <odaki@mars.dti.ne.jp>
Co-authored-by: Pete Wildsmith <pete@weargoggles.co.uk>
Co-authored-by: Luc <8822552+luc-github@users.noreply.github.com>
Co-authored-by: Scott Bezek <scottbez1@gmail.com>
This commit is contained in:
bdring
2020-12-15 15:32:35 -06:00
committed by GitHub
parent a3c35b4e33
commit f765079939
58 changed files with 1353 additions and 410 deletions

View File

@@ -51,9 +51,15 @@ float three_axis_dist(float* point1, float* point2);
void machine_init() {
// print a startup message to show the kinematics are enable
#ifdef MIDTBOT
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "CoreXY (midTbot) Kinematics Init");
#else
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "CoreXY Kinematics Init");
#endif
}
// Cycle mask is 0 unless the user sends a single axis command like $HZ
// This will always return true to prevent the normal Grbl homing cycle
bool user_defined_homing(uint8_t cycle_mask) {
uint8_t n_cycle; // each home is a multi cycle operation approach, pulloff, approach.....
@@ -61,12 +67,6 @@ bool user_defined_homing(uint8_t cycle_mask) {
float max_travel;
uint8_t axis;
// check for single axis homing
if (cycle_mask != 0) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "CoreXY Single axis homing not allowed. Use $H only");
return true;
}
// check for multi axis homing per cycle ($Homing/Cycle0=XY type)...not allowed in CoreXY
bool setting_error = false;
for (int cycle = 0; cycle < 3; cycle++) {
@@ -90,9 +90,21 @@ bool user_defined_homing(uint8_t cycle_mask) {
pl_data->motion.systemMotion = 1;
pl_data->motion.noFeedOverride = 1;
for (int cycle = 0; cycle < 3; cycle++) {
AxisMask mask = homing_cycle[cycle]->get();
uint8_t cycle_count = (cycle_mask == 0) ? 3 : 1; // if we have a cycle_mask, we are only going to do one axis
AxisMask mask = 0;
for (int cycle = 0; cycle < cycle_count; cycle++) {
// if we have a cycle_mask, do that. Otherwise get the cycle from the settings
mask = cycle_mask ? cycle_mask : homing_cycle[cycle]->get();
// If not X or Y do a normal home
if (!(bitnum_istrue(mask, X_AXIS) || bitnum_istrue(mask, Y_AXIS))) {
limits_go_home(mask); // Homing cycle 0
continue; // continue to next item in for loop
}
mask = motors_set_homing_mode(mask, true); // non standard homing motors will do their own thing and get removed from the mask
for (uint8_t axis = X_AXIS; axis <= Z_AXIS; axis++) {
if (bit(axis) == mask) {
// setup for the homing of this axis
@@ -190,7 +202,7 @@ bool user_defined_homing(uint8_t cycle_mask) {
} while (n_cycle-- > 0);
}
}
}
} // for
// after sussefully setting X & Y axes, we set the current positions

View File

@@ -57,7 +57,8 @@ void machine_init() {
NULL, // parameters
1, // priority
&solenoidSyncTaskHandle,
0 // core
CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core
// core
);
// setup a task that will do the custom homing sequence
xTaskCreatePinnedToCore(atari_home_task, // task
@@ -66,7 +67,8 @@ void machine_init() {
NULL, // parameters
1, // priority
&atariHomingTaskHandle,
0 // core
CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core
// core
);
}

View File

@@ -47,14 +47,16 @@ Some features should not be changed. See notes below.
// that the machine file might choose to undefine.
// Note: HOMING_CYCLES are now settings
#define SUPPORT_TASK_CORE 1 // Reference: CONFIG_ARDUINO_RUNNING_CORE = 1
// Inverts pin logic of the control command pins based on a mask. This essentially means you can use
// normally-closed switches on the specified pins, rather than the default normally-open switches.
// The mask order is Cycle Start | Feed Hold | Reset | Safety Door
// The mask order is ...
// Macro3 | Macro2 | Macro 1| Macr0 |Cycle Start | Feed Hold | Reset | Safety Door
// For example B1101 will invert the function of the Reset pin.
#define INVERT_CONTROL_PIN_MASK B1111
#define INVERT_CONTROL_PIN_MASK B00001111
#define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
// #define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
#define CONTROL_SW_DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
#define USE_RMT_STEPS

View File

@@ -159,6 +159,10 @@
# define DEFAULT_LASER_MODE 0 // false
#endif
#ifndef DEFAULT_LASER_FULL_POWER
# define DEFAULT_LASER_FULL_POWER 1000
#endif
#ifndef DEFAULT_SPINDLE_RPM_MAX // $30
# define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
#endif
@@ -457,6 +461,10 @@
// This can eliminate checking to see if the pin is defined because
// the overridden pinMode and digitalWrite functions will deal with it.
#ifndef SDCARD_DET_PIN
# define SDCARD_DET_PIN UNDEFINED_PIN
#endif
#ifndef STEPPERS_DISABLE_PIN
# define STEPPERS_DISABLE_PIN UNDEFINED_PIN
#endif
@@ -643,3 +651,19 @@
#ifndef USER_ANALOG_PIN_3_FREQ
# define USER_ANALOG_PIN_3_FREQ 5000
#endif
#ifndef DEFAULT_USER_MACRO0
# define DEFAULT_USER_MACRO0 ""
#endif
#ifndef DEFAULT_USER_MACRO1
# define DEFAULT_USER_MACRO1 ""
#endif
#ifndef DEFAULT_USER_MACRO2
# define DEFAULT_USER_MACRO2 ""
#endif
#ifndef DEFAULT_USER_MACRO3
# define DEFAULT_USER_MACRO3 ""
#endif

View File

@@ -1,81 +0,0 @@
/*
Eeprom.cpp - Coordinate data stored in EEPROM
Part of Grbl
Copyright (c) 2014-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/>.
*/
#include "Grbl.h"
void memcpy_to_eeprom_with_checksum(unsigned int destination, const char* source, unsigned int size) {
unsigned char checksum = 0;
for (; size > 0; size--) {
unsigned char data = static_cast<unsigned char>(*source++);
// Note: This checksum calculation is broken as described below.
checksum = (checksum << 1) || (checksum >> 7);
checksum += data;
EEPROM.write(destination++, *(source++));
}
EEPROM.write(destination, checksum);
EEPROM.commit();
}
int memcpy_from_eeprom_with_old_checksum(char* destination, unsigned int source, unsigned int size) {
unsigned char data, checksum = 0;
for (; size > 0; size--) {
data = EEPROM.read(source++);
// Note: This checksum calculation is broken - the || should be just | -
// thus making the checksum very weak.
// We leave it as-is so we can read old data after a firmware upgrade.
// The new storage format uses the tagged NVS mechanism, avoiding this bug.
checksum = (checksum << 1) || (checksum >> 7);
checksum += data;
*(destination++) = data;
}
return (checksum == EEPROM.read(source));
}
int memcpy_from_eeprom_with_checksum(char* destination, unsigned int source, unsigned int size) {
unsigned char data, checksum = 0;
for (; size > 0; size--) {
data = EEPROM.read(source++);
checksum = (checksum << 1) | (checksum >> 7);
checksum += data;
*(destination++) = data;
}
return (checksum == EEPROM.read(source));
}
// Read selected coordinate data from EEPROM. Updates pointed coord_data value.
// This is now a compatibility routine that is used to propagate coordinate data
// in the old EEPROM format to the new tagged NVS format.
bool old_settings_read_coord_data(uint8_t coord_select, float* coord_data) {
uint32_t addr = coord_select * (sizeof(float) * N_AXIS + 1) + EEPROM_ADDR_PARAMETERS;
if (!(memcpy_from_eeprom_with_old_checksum((char*)coord_data, addr, sizeof(float) * N_AXIS)) &&
!(memcpy_from_eeprom_with_checksum((char*)coord_data, addr, sizeof(float) * MAX_N_AXIS))) {
// Reset with default zero vector
clear_vector_float(coord_data);
// The old code used to rewrite the zeroed data but now that is done
// elsewhere, in a different format.
return false;
}
return true;
}
// Allow iteration over CoordIndex values
CoordIndex& operator ++ (CoordIndex& i) {
i = static_cast<CoordIndex>(static_cast<uint8_t>(i) + 1);
return i;
}

View File

@@ -1,61 +0,0 @@
#pragma once
/*
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
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"
// Define EEPROM memory address location values for saved coordinate data.
const int EEPROM_SIZE = 1024U;
const int EEPROM_ADDR_PARAMETERS = 512U;
//unsigned char eeprom_get_char(unsigned int addr);
//void eeprom_put_char(unsigned int addr, unsigned char new_value);
void memcpy_to_eeprom_with_checksum(unsigned int destination, const char* source, unsigned int size);
int memcpy_from_eeprom_with_checksum(char* destination, unsigned int source, unsigned int size);
int memcpy_from_eeprom_with_old_checksum(char* destination, unsigned int source, unsigned int size);
// Reads selected coordinate data from EEPROM
bool old_settings_read_coord_data(uint8_t coord_select, float* coord_data);
// Various places in the code access saved coordinate system data
// by a small integer index according to the values below.
enum CoordIndex : uint8_t{
Begin = 0,
G54 = Begin,
G55,
G56,
G57,
G58,
G59,
// To support 9 work coordinate systems it would be necessary to define
// the following 3 and modify GCode.cpp to support G59.1, G59.2, G59.3
// G59_1,
// G59_2,
// G59_3,
NWCSystems,
G28 = NWCSystems,
G30,
// G92_2,
// G92_3,
End,
};
// Allow iteration over CoordIndex values
CoordIndex& operator ++ (CoordIndex& i);

View File

@@ -79,4 +79,5 @@ std::map<Error, const char*> ErrorNames = {
{ Error::NvsSetFailed, "Failed to store setting" },
{ Error::NvsGetStatsFailed, "Failed to get setting status" },
{ Error::AuthenticationFailed, "Authentication failed!" },
{ Error::AnotherInterfaceBusy, "Another interface is busy"},
};

View File

@@ -83,6 +83,7 @@ enum class Error : uint8_t {
NvsGetStatsFailed = 101,
AuthenticationFailed = 110,
Eol = 111,
AnotherInterfaceBusy = 120,
};
extern std::map<Error, const char*> ErrorNames;

View File

@@ -24,6 +24,12 @@
#include "Grbl.h"
// Allow iteration over CoordIndex values
CoordIndex& operator++(CoordIndex& i) {
i = static_cast<CoordIndex>(static_cast<uint8_t>(i) + 1);
return i;
}
// NOTE: Max line number is defined by the g-code standard to be 99999. It seems to be an
// arbitrary value, and some GUIs may require more. So we increased it based on a max safe
// value when converting a float (7.2 digit precision)s to an integer.
@@ -473,9 +479,10 @@ Error gc_execute_line(char* line, uint8_t client) {
gc_block.modal.spindle = SpindleState::Cw;
break;
case 4: // Supported if SPINDLE_DIR_PIN is defined or laser mode is on.
if (spindle->is_reversable || laser_mode->get()) {
if (spindle->is_reversable || spindle->inLaserMode()) {
gc_block.modal.spindle = SpindleState::Ccw;
} else {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "M4 requires laser mode or a reversable spindle");
FAIL(Error::GcodeUnsupportedCommand);
}
break;
@@ -1290,7 +1297,7 @@ Error gc_execute_line(char* line, uint8_t client) {
return status;
}
// If in laser mode, setup laser power based on current and past parser conditions.
if (laser_mode->get()) {
if (spindle->inLaserMode()) {
if (!((gc_block.modal.motion == Motion::Linear) || (gc_block.modal.motion == Motion::CwArc) ||
(gc_block.modal.motion == Motion::CcwArc))) {
gc_parser_flags |= GCParserLaserDisable;

View File

@@ -232,6 +232,32 @@ enum GCParserFlags {
GCParserLaserIsMotion = bit(7),
};
// Various places in the code access saved coordinate system data
// by a small integer index according to the values below.
enum CoordIndex : uint8_t{
Begin = 0,
G54 = Begin,
G55,
G56,
G57,
G58,
G59,
// To support 9 work coordinate systems it would be necessary to define
// the following 3 and modify GCode.cpp to support G59.1, G59.2, G59.3
// G59_1,
// G59_2,
// G59_3,
NWCSystems,
G28 = NWCSystems,
G30,
// G92_2,
// G92_3,
End,
};
// Allow iteration over CoordIndex values
CoordIndex& operator ++ (CoordIndex& i);
// NOTE: When this struct is zeroed, the 0 values in the above types set the system defaults.
typedef struct {
Motion motion; // {G0,G1,G2,G3,G38.2,G80}

View File

@@ -23,7 +23,7 @@
// Grbl versioning system
const char* const GRBL_VERSION = "1.3a";
const char* const GRBL_VERSION_BUILD = "20201124";
const char* const GRBL_VERSION_BUILD = "20201212";
//#include <sdkconfig.h>
#include <Arduino.h>
@@ -41,7 +41,6 @@ const char* const GRBL_VERSION_BUILD = "20201124";
#include "Defaults.h"
#include "Error.h"
#include "Eeprom.h"
#include "WebUI/Authentication.h"
#include "WebUI/Commands.h"
#include "Probe.h"

View File

@@ -526,7 +526,9 @@ static void IRAM_ATTR i2sOutTask(void* parameter) {
I2S_OUT_PULSER_EXIT_CRITICAL(); // Unlock pulser status
static UBaseType_t uxHighWaterMark = 0;
# ifdef DEBUG_TASK_STACK
reportTaskStackSize(uxHighWaterMark);
# endif
}
}
#endif

View File

@@ -372,7 +372,9 @@ void limitCheckTask(void* pvParameters) {
sys_rt_exec_alarm = ExecAlarm::HardLimit; // Indicate hard limit critical event
}
static UBaseType_t uxHighWaterMark = 0;
#ifdef DEBUG_TASK_STACK
reportTaskStackSize(uxHighWaterMark);
#endif
}
}

View File

@@ -106,19 +106,38 @@ Socket #5
#define Z_LIMIT_PIN GPIO_NUM_35
// // 4x Input Module in Socket #2
// // https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
// #define X_LIMIT_PIN GPIO_NUM_2
// #define Y_LIMIT_PIN GPIO_NUM_25
// #define Z_LIMIT_PIN GPIO_NUM_39
#define MACRO_BUTTON_0_PIN GPIO_NUM_2
#define MACRO_BUTTON_1_PIN GPIO_NUM_25
#define MACRO_BUTTON_2_PIN GPIO_NUM_39
#define MACRO_BUTTON_3_PIN GPIO_NUM_36
// // 4x Input Module in Socket #3
// // https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
// #define CONTROL_CYCLE_START_PIN GPIO_NUM_26
// #define CONTROL_FEED_HOLD_PIN GPIO_NUM_4
// #define CONTROL_RESET_PIN GPIO_NUM_16
// #define CONTROL_SAFETY_DOOR_PIN GPIO_NUM_27
// //#define INVERT_CONTROL_PIN_MASK B0000
// 5V output CNC module in socket #4
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-5V-Buffered-Output-Module
#define SPINDLE_TYPE SpindleType::PWM
#define SPINDLE_OUTPUT_PIN GPIO_NUM_14
#define SPINDLE_ENABLE_PIN GPIO_NUM_13 // optional
#define LASER_OUTPUT_PIN GPIO_NUM_15 // optional
#define LASER_ENABLE_PIN GPIO_NUM_12
// // RS485 Modbus In socket #3
// // https://github.com/bdring/6-Pack_CNC_Controller/wiki/RS485-Modbus-Module
// #define VFD_RS485_TXD_PIN GPIO_NUM_26
// #define VFD_RS485_RTS_PIN GPIO_NUM_4
// #define VFD_RS485_RXD_PIN GPIO_NUM_16
// Example (4x) 5V Buffer Output on socket #5
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-5V-Buffered-Output-Module
#define USER_DIGITAL_PIN_0 I2SO(24) // No PWM
#define USER_DIGITAL_PIN_1 I2SO(25)
#define USER_DIGITAL_PIN_2 I2SO(26) // M7 on M9 Off
#define USER_DIGITAL_PIN_3 I2SO(27) // M8 on M9 Off
// ================= Setting Defaults ==========================
#define DEFAULT_X_STEPS_PER_MM 800

View File

@@ -0,0 +1,81 @@
#pragma once
// clang-format off
/*
fystec_e4.h
https://github.com/FYSETC/FYSETC-E4
2020-12-03 B. Dring
This is a machine definition file to use the FYSTEC E4 3D Printer controller
This is a 4 motor controller. This is setup for XYZA, but XYYZ, could also be used.
There are 5 inputs
The controller has outputs for a Fan, Hotbed and Extruder. There are mapped to
spindle, mist and flood coolant to drive an external relay.
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 "FYSTEC E4 3D Printer Controller"
#define N_AXIS 4
#define TRINAMIC_RUN_MODE TrinamicMode :: StealthChop
#define TRINAMIC_HOMING_MODE TrinamicMode :: StealthChop
#define TMC_UART UART_NUM_1
#define TMC_UART_RX GPIO_NUM_21
#define TMC_UART_TX GPIO_NUM_22
#define X_TRINAMIC_DRIVER 2209
#define X_STEP_PIN GPIO_NUM_27
#define X_DIRECTION_PIN GPIO_NUM_26
#define X_RSENSE TMC2209_RSENSE_DEFAULT
#define X_DRIVER_ADDRESS 1
#define DEFAULT_X_MICROSTEPS 16
#define Y_TRINAMIC_DRIVER 2209
#define Y_STEP_PIN GPIO_NUM_33
#define Y_DIRECTION_PIN GPIO_NUM_32
#define Y_RSENSE TMC2209_RSENSE_DEFAULT
#define Y_DRIVER_ADDRESS 3
#define DEFAULT_Y_MICROSTEPS 16
#define Z_TRINAMIC_DRIVER 2209
#define Z_STEP_PIN GPIO_NUM_14
#define Z_DIRECTION_PIN GPIO_NUM_12
#define Z_RSENSE TMC2209_RSENSE_DEFAULT
#define Z_DRIVER_ADDRESS 0
#define DEFAULT_Z_MICROSTEPS 16
#define A_TRINAMIC_DRIVER 2209
#define A_STEP_PIN GPIO_NUM_16
#define A_DIRECTION_PIN GPIO_NUM_17
#define A_RSENSE TMC2209_RSENSE_DEFAULT
#define A_DRIVER_ADDRESS 2
#define DEFAULT_A_MICROSTEPS 16
#define X_LIMIT_PIN GPIO_NUM_34
#define Y_LIMIT_PIN GPIO_NUM_35
#define Z_LIMIT_PIN GPIO_NUM_15
#define A_LIMIT_PIN GPIO_NUM_36 // Labeled TB
#define PROBE_PIN GPIO_NUM_39 // Labeled TE
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_25
#define SPINDLE_TYPE SpindleType::RELAY
#define SPINDLE_OUTPUT_PIN GPIO_NUM_13 // labeled Fan
#define COOLANT_MIST_PIN GPIO_NUM_2 // Labeled Hotbed
#define COOLANT_FLOOD_PIN GPIO_NUM_4 // Labeled Heater

View File

@@ -53,8 +53,8 @@
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#define SPINDLE_TYPE SpindleType::PWM
#define SPINDLE_OUTPUT_PIN GPIO_NUM_16
#define SPINDLE_TYPE SpindleType::LASER
#define LASER_OUTPUT_PIN GPIO_NUM_16
#define COOLANT_MIST_PIN GPIO_NUM_2

View File

@@ -246,16 +246,17 @@ static bool mask_is_single_axis(uint8_t axis_mask) {
return axis_mask && ((axis_mask & (axis_mask - 1)) == 0);
}
// return true if the axis is defined as a squared axis
// Squaring: is used on gantry type axes that have two motors
// Each motor with touch off its own switch to square the axis
static bool mask_has_squared_axis(uint8_t axis_mask) {
return axis_mask & homing_squared_axes->get();
static bool axis_is_squared(uint8_t axis_mask) {
// Squaring can only be done if it is the only axis in the mask
if (axis_mask & homing_squared_axes->get()) {
if (mask_is_single_axis(axis_mask)) {
return true;
}
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Cannot multi-axis home with squared axes. Homing normally");
return false;
}
// return true if axis_mask refers to a single squared axis
static bool axis_is_squared(uint8_t axis_mask) {
return mask_is_single_axis(axis_mask) && mask_has_squared_axis(axis_mask);
return false;
}
#ifdef USE_I2S_STEPS

View File

@@ -42,6 +42,7 @@
#include "RcServo.h"
#include "Dynamixel2.h"
#include "TrinamicDriver.h"
#include "TrinamicUartDriver.h"
Motors::Motor* myMotor[MAX_AXES][MAX_GANGED]; // number of axes (normal and ganged)
void init_motors() {
@@ -51,8 +52,19 @@ void init_motors() {
if (n_axis >= 1) {
#ifdef X_TRINAMIC_DRIVER
myMotor[X_AXIS][0] = new Motors::TrinamicDriver(
X_AXIS, X_STEP_PIN, X_DIRECTION_PIN, X_DISABLE_PIN, X_CS_PIN, X_TRINAMIC_DRIVER, X_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[X_AXIS][0] =
new Motors::TrinamicDriver(X_AXIS, X_STEP_PIN, X_DIRECTION_PIN, X_DISABLE_PIN, X_CS_PIN, X_TRINAMIC_DRIVER, X_RSENSE);
}
# elif (X_TRINAMIC_DRIVER == 2208 || X_TRINAMIC_DRIVER == 2209)
{
myMotor[X_AXIS][0] = new Motors::TrinamicUartDriver(
X_AXIS, X_STEP_PIN, X_DIRECTION_PIN, X_DISABLE_PIN, X_TRINAMIC_DRIVER, X_RSENSE, X_DRIVER_ADDRESS);
}
# else
# error X Axis undefined motor p/n
# endif
#elif defined(X_SERVO_PIN)
myMotor[X_AXIS][0] = new Motors::RcServo(X_AXIS, X_SERVO_PIN);
#elif defined(X_UNIPOLAR)
@@ -66,8 +78,19 @@ void init_motors() {
#endif
#ifdef X2_TRINAMIC_DRIVER
myMotor[X_AXIS][1] = new Motors::TrinamicDriver(
X2_AXIS, X2_STEP_PIN, X2_DIRECTION_PIN, X2_DISABLE_PIN, X2_CS_PIN, X2_TRINAMIC_DRIVER, X2_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[X_AXIS][1] =
new Motors::TrinamicDriver(X2_AXIS, X2_STEP_PIN, X2_DIRECTION_PIN, X2_DISABLE_PIN, X2_CS_PIN, X2_TRINAMIC_DRIVER, X2_RSENSE);
}
# elif (X2_TRINAMIC_DRIVER == 2208 || X2_TRINAMIC_DRIVER == 2209)
{
myMotor[X_AXIS][1] = new Motors::TrinamicUartDriver(
X2_AXIS, X2_STEP_PIN, X2_DIRECTION_PIN, X2_DISABLE_PIN, X2_TRINAMIC_DRIVER, X2_RSENSE, X2_DRIVER_ADDRESS);
}
# else
# error X2 Axis undefined motor p/n
# endif
#elif defined(X2_UNIPOLAR)
myMotor[X_AXIS][1] = new Motors::UnipolarMotor(X2_AXIS, X2_PIN_PHASE_0, X2_PIN_PHASE_1, X2_PIN_PHASE_2, X2_PIN_PHASE_3);
#elif defined(X2_STEP_PIN)
@@ -83,8 +106,19 @@ void init_motors() {
if (n_axis >= 2) {
// this WILL be done better with settings
#ifdef Y_TRINAMIC_DRIVER
myMotor[Y_AXIS][0] = new Motors::TrinamicDriver(
Y_AXIS, Y_STEP_PIN, Y_DIRECTION_PIN, Y_DISABLE_PIN, Y_CS_PIN, Y_TRINAMIC_DRIVER, Y_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[Y_AXIS][0] =
new Motors::TrinamicDriver(Y_AXIS, Y_STEP_PIN, Y_DIRECTION_PIN, Y_DISABLE_PIN, Y_CS_PIN, Y_TRINAMIC_DRIVER, Y_RSENSE);
}
# elif (Y_TRINAMIC_DRIVER == 2208 || Y_TRINAMIC_DRIVER == 2209)
{
myMotor[Y_AXIS][0] = new Motors::TrinamicUartDriver(
Y_AXIS, Y_STEP_PIN, Y_DIRECTION_PIN, Y_DISABLE_PIN, Y_TRINAMIC_DRIVER, Y_RSENSE, Y_DRIVER_ADDRESS);
}
# else
# error Y Axis undefined motor p/n
# endif
#elif defined(Y_SERVO_PIN)
myMotor[Y_AXIS][0] = new Motors::RcServo(Y_AXIS, Y_SERVO_PIN);
#elif defined(Y_UNIPOLAR)
@@ -98,8 +132,19 @@ void init_motors() {
#endif
#ifdef Y2_TRINAMIC_DRIVER
myMotor[Y_AXIS][1] = new Motors::TrinamicDriver(
Y2_AXIS, Y2_STEP_PIN, Y2_DIRECTION_PIN, Y2_DISABLE_PIN, Y2_CS_PIN, Y2_TRINAMIC_DRIVER, Y2_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[Y_AXIS][1] =
new Motors::TrinamicDriver(Y2_AXIS, Y2_STEP_PIN, Y2_DIRECTION_PIN, Y2_DISABLE_PIN, Y2_CS_PIN, Y2_TRINAMIC_DRIVER, Y2_RSENSE);
}
# elif (Y2_TRINAMIC_DRIVER == 2208 || Y2_TRINAMIC_DRIVER == 2209)
{
myMotor[Y_AXIS][1] = new Motors::TrinamicUartDriver(
Y2_AXIS, Y2_STEP_PIN, Y2_DIRECTION_PIN, Y2_DISABLE_PIN, Y2_TRINAMIC_DRIVER, Y2_RSENSE, Y2_DRIVER_ADDRESS);
}
# else
# error Y2 Axis undefined motor p/n
# endif
#elif defined(Y2_UNIPOLAR)
myMotor[Y_AXIS][1] = new Motors::UnipolarMotor(Y2_AXIS, Y2_PIN_PHASE_0, Y2_PIN_PHASE_1, Y2_PIN_PHASE_2, Y2_PIN_PHASE_3);
#elif defined(Y2_STEP_PIN)
@@ -115,8 +160,19 @@ void init_motors() {
if (n_axis >= 3) {
// this WILL be done better with settings
#ifdef Z_TRINAMIC_DRIVER
myMotor[Z_AXIS][0] = new Motors::TrinamicDriver(
Z_AXIS, Z_STEP_PIN, Z_DIRECTION_PIN, Z_DISABLE_PIN, Z_CS_PIN, Z_TRINAMIC_DRIVER, Z_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[Z_AXIS][0] =
new Motors::TrinamicDriver(Z_AXIS, Z_STEP_PIN, Z_DIRECTION_PIN, Z_DISABLE_PIN, Z_CS_PIN, Z_TRINAMIC_DRIVER, Z_RSENSE);
}
# elif (Z_TRINAMIC_DRIVER == 2208 || Z_TRINAMIC_DRIVER == 2209)
{
myMotor[Z_AXIS][0] = new Motors::TrinamicUartDriver(
Z_AXIS, Z_STEP_PIN, Z_DIRECTION_PIN, Z_DISABLE_PIN, Z_TRINAMIC_DRIVER, Z_RSENSE, Z_DRIVER_ADDRESS);
}
# else
# error Z Axis undefined motor p/n
# endif
#elif defined(Z_SERVO_PIN)
myMotor[Z_AXIS][0] = new Motors::RcServo(Z_AXIS, Z_SERVO_PIN);
#elif defined(Z_UNIPOLAR)
@@ -130,8 +186,19 @@ void init_motors() {
#endif
#ifdef Z2_TRINAMIC_DRIVER
myMotor[Z_AXIS][1] = new Motors::TrinamicDriver(
Z2_AXIS, Z2_STEP_PIN, Z2_DIRECTION_PIN, Z2_DISABLE_PIN, Z2_CS_PIN, Z2_TRINAMIC_DRIVER, Z2_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[Z_AXIS][1] =
new Motors::TrinamicDriver(Z2_AXIS, Z2_STEP_PIN, Z2_DIRECTION_PIN, Z2_DISABLE_PIN, Z2_CS_PIN, Z2_TRINAMIC_DRIVER, Z2_RSENSE);
}
# elif (Z2_TRINAMIC_DRIVER == 2208 || Z2_TRINAMIC_DRIVER == 2209)
{
myMotor[Z_AXIS][1] = new Motors::TrinamicUartDriver(
Z2_AXIS, Z2_STEP_PIN, Z2_DIRECTION_PIN, Z2_DISABLE_PIN, Z2_TRINAMIC_DRIVER, Z2_RSENSE, Z2_DRIVER_ADDRESS);
}
# else
# error Z2 Axis undefined motor p/n
# endif
#elif defined(Z2_UNIPOLAR)
myMotor[Z_AXIS][1] = new Motors::UnipolarMotor(Z2_AXIS, Z2_PIN_PHASE_0, Z2_PIN_PHASE_1, Z2_PIN_PHASE_2, Z2_PIN_PHASE_3);
#elif defined(Z2_STEP_PIN)
@@ -147,8 +214,19 @@ void init_motors() {
if (n_axis >= 4) {
// this WILL be done better with settings
#ifdef A_TRINAMIC_DRIVER
myMotor[A_AXIS][0] = new Motors::TrinamicDriver(
A_AXIS, A_STEP_PIN, A_DIRECTION_PIN, A_DISABLE_PIN, A_CS_PIN, A_TRINAMIC_DRIVER, A_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[A_AXIS][1] =
new Motors::TrinamicDriver(A_AXIS, A_STEP_PIN, A_DIRECTION_PIN, A_DISABLE_PIN, A_CS_PIN, A_TRINAMIC_DRIVER, A_RSENSE);
}
# elif (A_TRINAMIC_DRIVER == 2208 || A_TRINAMIC_DRIVER == 2209)
{
myMotor[A_AXIS][0] = new Motors::TrinamicUartDriver(
A_AXIS, A_STEP_PIN, A_DIRECTION_PIN, A_DISABLE_PIN, A_TRINAMIC_DRIVER, A_RSENSE, A_DRIVER_ADDRESS);
}
# else
# error A Axis undefined motor p/n
# endif
#elif defined(A_SERVO_PIN)
myMotor[A_AXIS][0] = new Motors::RcServo(A_AXIS, A_SERVO_PIN);
#elif defined(A_UNIPOLAR)
@@ -162,8 +240,19 @@ void init_motors() {
#endif
#ifdef A2_TRINAMIC_DRIVER
myMotor[A_AXIS][1] = new Motors::TrinamicDriver(
A2_AXIS, A2_STEP_PIN, A2_DIRECTION_PIN, A2_DISABLE_PIN, A2_CS_PIN, A2_TRINAMIC_DRIVER, A2_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[A_AXIS][1] =
new Motors::TrinamicDriver(A2_AXIS, A2_STEP_PIN, A2_DIRECTION_PIN, A2_DISABLE_PIN, A2_CS_PIN, A2_TRINAMIC_DRIVER, A2_RSENSE);
}
# elif (A2_TRINAMIC_DRIVER == 2208 || A2_TRINAMIC_DRIVER == 2209)
{
myMotor[A_AXIS][1] = new Motors::TrinamicUartDriver(
A2_AXIS, A2_STEP_PIN, A2_DIRECTION_PIN, A2_DISABLE_PIN, A2_TRINAMIC_DRIVER, A2_RSENSE, A2_DRIVER_ADDRESS);
}
# else
# error A2 Axis undefined motor p/n
# endif
#elif defined(A2_UNIPOLAR)
myMotor[A_AXIS][1] = new Motors::UnipolarMotor(A2_AXIS, A2_PIN_PHASE_0, A2_PIN_PHASE_1, A2_PIN_PHASE_2, A2_PIN_PHASE_3);
#elif defined(A2_STEP_PIN)
@@ -179,8 +268,19 @@ void init_motors() {
if (n_axis >= 5) {
// this WILL be done better with settings
#ifdef B_TRINAMIC_DRIVER
myMotor[B_AXIS][0] = new Motors::TrinamicDriver(
B_AXIS, B_STEP_PIN, B_DIRECTION_PIN, B_DISABLE_PIN, B_CS_PIN, B_TRINAMIC_DRIVER, B_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[B_AXIS][1] =
new Motors::TrinamicDriver(B_AXIS, B_STEP_PIN, B_DIRECTION_PIN, B_DISABLE_PIN, B_CS_PIN, B_TRINAMIC_DRIVER, B_RSENSE);
}
# elif (B_TRINAMIC_DRIVER == 2208 || B_TRINAMIC_DRIVER == 2209)
{
myMotor[B_AXIS][0] = new Motors::TrinamicUartDriver(
B_AXIS, B_STEP_PIN, B_DIRECTION_PIN, B_DISABLE_PIN, B_TRINAMIC_DRIVER, B_RSENSE, B_DRIVER_ADDRESS);
}
# else
# error B Axis undefined motor p/n
# endif
#elif defined(B_SERVO_PIN)
myMotor[B_AXIS][0] = new Motors::RcServo(B_AXIS, B_SERVO_PIN);
#elif defined(B_UNIPOLAR)
@@ -194,8 +294,19 @@ void init_motors() {
#endif
#ifdef B2_TRINAMIC_DRIVER
myMotor[B_AXIS][1] = new Motors::TrinamicDriver(
B2_AXIS, B2_STEP_PIN, B2_DIRECTION_PIN, B2_DISABLE_PIN, B2_CS_PIN, B2_TRINAMIC_DRIVER, B2_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[B_AXIS][1] =
new Motors::TrinamicDriver(B2_AXIS, B2_STEP_PIN, B2_DIRECTION_PIN, B2_DISABLE_PIN, B2_CS_PIN, B2_TRINAMIC_DRIVER, B2_RSENSE);
}
# elif (B2_TRINAMIC_DRIVER == 2208 || B2_TRINAMIC_DRIVER == 2209)
{
myMotor[B_AXIS][1] = new Motors::TrinamicUartDriver(
B2_AXIS, B2_STEP_PIN, B2_DIRECTION_PIN, B2_DISABLE_PIN, B2_TRINAMIC_DRIVER, B2_RSENSE, B2_DRIVER_ADDRESS);
}
# else
# error B2 Axis undefined motor p/n
# endif
#elif defined(B2_UNIPOLAR)
myMotor[B_AXIS][1] = new Motors::UnipolarMotor(B2_AXIS, B2_PIN_PHASE_0, B2_PIN_PHASE_1, B2_PIN_PHASE_2, B2_PIN_PHASE_3);
#elif defined(B2_STEP_PIN)
@@ -211,8 +322,19 @@ void init_motors() {
if (n_axis >= 6) {
// this WILL be done better with settings
#ifdef C_TRINAMIC_DRIVER
myMotor[C_AXIS][0] = new Motors::TrinamicDriver(
C_AXIS, C_STEP_PIN, C_DIRECTION_PIN, C_DISABLE_PIN, C_CS_PIN, C_TRINAMIC_DRIVER, C_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[C_AXIS][1] =
new Motors::TrinamicDriver(C_AXIS, C_STEP_PIN, C_DIRECTION_PIN, C_DISABLE_PIN, C_CS_PIN, C_TRINAMIC_DRIVER, C_RSENSE);
}
# elif (C_TRINAMIC_DRIVER == 2208 || C_TRINAMIC_DRIVER == 2209)
{
myMotor[C_AXIS][0] = new Motors::TrinamicUartDriver(
C_AXIS, C_STEP_PIN, C_DIRECTION_PIN, C_DISABLE_PIN, C_TRINAMIC_DRIVER, C_RSENSE, C_DRIVER_ADDRESS);
}
# else
# error C Axis undefined motor p/n
# endif
#elif defined(C_SERVO_PIN)
myMotor[C_AXIS][0] = new Motors::RcServo(C_AXIS, C_SERVO_PIN);
#elif defined(C_UNIPOLAR)
@@ -226,8 +348,19 @@ void init_motors() {
#endif
#ifdef C2_TRINAMIC_DRIVER
myMotor[C_AXIS][1] = new Motors::TrinamicDriver(
C2_AXIS, C2_STEP_PIN, C2_DIRECTION_PIN, C2_DISABLE_PIN, C2_CS_PIN, C2_TRINAMIC_DRIVER, C2_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[C_AXIS][1] =
new Motors::TrinamicDriver(C2_AXIS, C2_STEP_PIN, C2_DIRECTION_PIN, C2_DISABLE_PIN, C2_CS_PIN, C2_TRINAMIC_DRIVER, C2_RSENSE);
}
# elif (C2_TRINAMIC_DRIVER == 2208 || C2_TRINAMIC_DRIVER == 2209)
{
myMotor[C_AXIS][1] = new Motors::TrinamicUartDriver(
C2_AXIS, C2_STEP_PIN, C2_DIRECTION_PIN, C2_DISABLE_PIN, C2_TRINAMIC_DRIVER, C2_RSENSE, C2_DRIVER_ADDRESS);
}
# else
# error C2 Axis undefined motor p/n
# endif
#elif defined(C2_UNIPOLAR)
myMotor[C_AXIS][1] = new Motors::UnipolarMotor(C2_AXIS, C2_PIN_PHASE_0, C2_PIN_PHASE_1, C2_PIN_PHASE_2, C2_PIN_PHASE_3);
#elif defined(C2_STEP_PIN)
@@ -279,25 +412,18 @@ void init_motors() {
}
}
void motors_set_disable(bool disable) {
void motors_set_disable(bool disable, uint8_t mask) {
static bool previous_state = true;
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Motors disable %d", disable);
/*
if (previous_state == disable) {
return;
}
previous_state = disable;
*/
// now loop through all the motors to see if they can individually disable
auto n_axis = number_axis->get();
for (uint8_t gang_index = 0; gang_index < MAX_GANGED; gang_index++) {
for (uint8_t axis = X_AXIS; axis < n_axis; axis++) {
if (bitnum_istrue(mask, axis)) {
myMotor[axis][gang_index]->set_disable(disable);
}
}
}
// invert only inverts the global stepper disable pin.
if (step_enable_invert->get()) {

View File

@@ -39,7 +39,7 @@ void motors_read_settings();
// The return value is a bitmask of axes that can home
uint8_t motors_set_homing_mode(uint8_t homing_mask, bool isHoming);
void motors_set_disable(bool disable);
void motors_set_disable(bool disable, uint8_t mask = B11111111); // default is all axes
void motors_step(uint8_t step_mask, uint8_t dir_mask);
void motors_unstep();

View File

@@ -40,6 +40,7 @@ namespace Motors {
}
void Servo::startUpdateTask() {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Servo Update Task Started");
if (this == List) {
xTaskCreatePinnedToCore(updateTask, // task
"servoUpdateTask", // name for task
@@ -47,7 +48,7 @@ namespace Motors {
NULL, // parameters
1, // priority
NULL, // handle
0 // core
SUPPORT_TASK_CORE // core
);
}
}
@@ -67,7 +68,9 @@ namespace Motors {
vTaskDelayUntil(&xLastWakeTime, xUpdate);
static UBaseType_t uxHighWaterMark = 0;
#ifdef DEBUG_TASK_STACK
reportTaskStackSize(uxHighWaterMark);
#endif
}
}

View File

@@ -44,10 +44,14 @@ namespace Motors {
}
void StandardStepper::init() {
init_step_dir_pins();
read_settings();
config_message();
}
void StandardStepper::read_settings() {
init_step_dir_pins();
}
void StandardStepper::init_step_dir_pins() {
_invert_step_pin = bitnum_istrue(step_invert_mask->get(), _axis_index);
_invert_dir_pin = bitnum_istrue(dir_invert_mask->get(), _axis_index);

View File

@@ -15,6 +15,7 @@ namespace Motors {
void set_direction(bool) override;
void step() override;
void unstep() override;
void read_settings() override;
void init_step_dir_pins();

View File

@@ -68,7 +68,6 @@ namespace Motors {
}
_has_errors = false;
init_step_dir_pins(); // from StandardStepper
digitalWrite(_cs_pin, HIGH);
pinMode(_cs_pin, OUTPUT);
@@ -115,7 +114,8 @@ namespace Motors {
NULL, // parameters
1, // priority
NULL,
0 // core
SUPPORT_TASK_CORE // must run the task on same core
// core
);
}
}
@@ -210,6 +210,8 @@ namespace Motors {
}
tmcstepper->microsteps(axis_settings[_axis_index]->microsteps->get());
tmcstepper->rms_current(run_i_ma, hold_i_percent);
init_step_dir_pins();
}
bool TrinamicDriver::set_homing_mode(bool isHoming) {
@@ -353,10 +355,6 @@ namespace Motors {
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) { // don't ever return from this or the task dies
if (motorSettingChanged) {
motors_read_settings();
motorSettingChanged = false;
}
if (stallguard_debug_mask->get() != 0) {
if (sys.state == State::Cycle || sys.state == State::Homing || sys.state == State::Jog) {
for (TrinamicDriver* p = List; p; p = p->link) {
@@ -371,7 +369,9 @@ namespace Motors {
vTaskDelayUntil(&xLastWakeTime, xreadSg);
static UBaseType_t uxHighWaterMark = 0;
#ifdef DEBUG_TASK_STACK
reportTaskStackSize(uxHighWaterMark);
#endif
}
}

View File

@@ -0,0 +1,131 @@
#pragma once
/*
TrinamicUartDriver.h
Part of Grbl_ESP32
2020 - The Ant Team
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
const float TMC2208_RSENSE_DEFAULT = 0.11f;
const float TMC2209_RSENSE_DEFAULT = 0.11f;
const double TRINAMIC_UART_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_UART_RUN_MODE
# define TRINAMIC_UART_RUN_MODE TrinamicUartMode ::StealthChop
#endif
#ifndef TRINAMIC_UART_HOMING_MODE
# define TRINAMIC_UART_HOMING_MODE TRINAMIC_UART_RUN_MODE
#endif
#ifndef TRINAMIC_UART_TOFF_DISABLE
# define TRINAMIC_UART_TOFF_DISABLE 0
#endif
#ifndef TRINAMIC_UART_TOFF_STEALTHCHOP
# define TRINAMIC_UART_TOFF_STEALTHCHOP 5
#endif
#ifndef TRINAMIC_UART_TOFF_COOLSTEP
# define TRINAMIC_UART_TOFF_COOLSTEP 3
#endif
#ifndef TMC_UART
# define TMC_UART UART_NUM_2
#endif
#ifndef TMC_UART_RX
# define TMC_UART_RX UNDEFINED_PIN
#endif
#ifndef TMC_UART_TX
# define TMC_UART_TX UNDEFINED_PIN
#endif
extern HardwareSerial tmc_serial;
namespace Motors {
enum class TrinamicUartMode : uint8_t {
None = 0, // not for machine defs!
StealthChop = 1,
CoolStep = 2,
StallGuard = 3,
};
class TrinamicUartDriver : public StandardStepper {
public:
TrinamicUartDriver(uint8_t axis_index,
uint8_t step_pin,
uint8_t dir_pin,
uint8_t disable_pin,
uint16_t driver_part_number,
float r_senseS,
uint8_t address);
void config_message();
void hw_serial_init();
void init();
void set_mode();
void read_settings();
void debug_message();
bool set_homing_mode(bool is_homing) override;
void set_disable(bool disable) override;
uint8_t addr;
private:
uint32_t calc_tstep(float speed, float percent); //TODO: see if this is useful/used.
TMC2208Stepper* tmcstepper; // all other driver types are subclasses of this one
TrinamicUartMode _homing_mode;
uint16_t _driver_part_number; // example: use 2209 for TMC2209
float _r_sense;
bool _has_errors;
bool _disabled;
TrinamicUartMode _mode = TrinamicUartMode::None;
bool test();
void set_mode(bool isHoming);
void trinamic_test_response();
void trinamic_stepper_enable(bool enable);
bool report_open_load(TMC2208_n ::DRV_STATUS_t status);
bool report_short_to_ground(TMC2208_n ::DRV_STATUS_t status);
bool report_over_temp(TMC2208_n ::DRV_STATUS_t status);
bool report_short_to_ps(TMC2208_n ::DRV_STATUS_t status);
uint8_t get_next_index();
// Linked list of Trinamic driver instances, used by the
// StallGuard reporting task. TODO: verify if this is really used/useful.
static TrinamicUartDriver* List;
TrinamicUartDriver* link;
static void readSgTask(void*);
protected:
// void config_message() override;
};
}

View File

@@ -0,0 +1,370 @@
/*
TrinamicUartDriverClass.cpp
This is used for Trinamic UART controlled stepper motor drivers.
Part of Grbl_ESP32
2020 - The Ant Team
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 "TrinamicUartDriver.h"
#include <TMCStepper.h>
HardwareSerial tmc_serial(TMC_UART);
namespace Motors {
/* HW Serial Constructor. */
TrinamicUartDriver::TrinamicUartDriver(
uint8_t axis_index, uint8_t step_pin, uint8_t dir_pin, uint8_t disable_pin, uint16_t driver_part_number, float r_sense, uint8_t addr) :
StandardStepper(axis_index, step_pin, dir_pin, disable_pin) {
_driver_part_number = driver_part_number;
_has_errors = false;
_r_sense = r_sense;
this->addr = addr;
uart_set_pin(TMC_UART, TMC_UART_TX, TMC_UART_RX, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
tmc_serial.begin(115200, SERIAL_8N1, TMC_UART_RX, TMC_UART_TX);
tmc_serial.setRxBufferSize(128);
hw_serial_init();
}
void TrinamicUartDriver::hw_serial_init() {
if (_driver_part_number == 2208)
// TMC 2208 does not use address, this field is 0
tmcstepper = new TMC2208Stepper(&tmc_serial, _r_sense);
else if (_driver_part_number == 2209)
tmcstepper = new TMC2209Stepper(&tmc_serial, _r_sense, addr);
else {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Unsupported Trinamic motor p/n:%d", _driver_part_number);
return;
}
}
void TrinamicUartDriver ::init() {
if (_has_errors) {
return;
}
init_step_dir_pins(); // from StandardStepper
config_message();
tmcstepper->begin();
_has_errors = !test(); // Try communicating with motor. Prints an error if there is a problem.
/* If communication with the driver is working, read the
main settings, apply new driver settings and then read
them back. */
if (!_has_errors) { //TODO: verify if this is the right way to set the Irun/IHold and microsteps.
read_settings();
set_mode(false);
}
}
/*
This is the startup message showing the basic definition.
*/
void TrinamicUartDriver::config_message() { //TODO: The RX/TX pin could be added to the msg.
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s motor Trinamic TMC%d Step:%s Dir:%s Disable:%s UART%d Rx:%s Tx:%s Addr:%d R:%0.3f %s",
reportAxisNameMsg(_axis_index, _dual_axis_index),
_driver_part_number,
pinName(_step_pin).c_str(),
pinName(_dir_pin).c_str(),
pinName(_disable_pin).c_str(),
TMC_UART,
pinName(TMC_UART_RX),
pinName(TMC_UART_TX),
this->addr,
_r_sense,
reportAxisLimitsMsg(_axis_index));
}
bool TrinamicUartDriver::test() {
if (_has_errors) {
return false;
}
switch (tmcstepper->test_connection()) {
case 1:
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s driver test failed. Check connection",
reportAxisNameMsg(_axis_index, _dual_axis_index));
return false;
case 2:
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s driver test failed. Check motor power",
reportAxisNameMsg(_axis_index, _dual_axis_index));
return false;
default:
// driver responded, so check for other errors from the DRV_STATUS register
TMC2208_n ::DRV_STATUS_t status { 0 }; // a useful struct to access the bits.
status.sr = tmcstepper->DRV_STATUS();
bool err = false;
// look for errors
if (report_short_to_ground(status)) {
err = true;
}
if (report_over_temp(status)) {
err = true;
}
if (report_short_to_ps(status)) {
err = true;
}
if (err) {
return false;
}
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "%s driver test passed", reportAxisNameMsg(_axis_index, _dual_axis_index));
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 TrinamicUartDriver::read_settings() {
if (_has_errors) {
return;
}
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;
}
tmcstepper->microsteps(axis_settings[_axis_index]->microsteps->get());
tmcstepper->rms_current(run_i_ma, hold_i_percent);
// grbl_msg_sendf(CLIENT_SERIAL,
// MsgLevel::Info,
// "Setting current of driver %s, target: %u, read irun: %d, hold percent: %f, usteps: %d",
// reportAxisNameMsg(_axis_index, _dual_axis_index), run_i_ma, tmcstepper->rms_current(), hold_i_percent, axis_settings[_axis_index]->microsteps->get());
}
bool TrinamicUartDriver::set_homing_mode(bool isHoming) {
set_mode(isHoming);
return true;
}
/*
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 TrinamicUartDriver::set_mode(bool isHoming) {
if (_has_errors) {
return;
}
TrinamicUartMode newMode = isHoming ? TRINAMIC_UART_HOMING_MODE : TRINAMIC_UART_RUN_MODE;
if (newMode == _mode) {
return;
}
_mode = newMode;
switch (_mode) {
case TrinamicUartMode ::StealthChop:
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "StealthChop");
// tmcstepper->en_pwm_mode(true); //TODO: check if this is present in TMC2208/09
tmcstepper->en_spreadCycle(false);
tmcstepper->pwm_autoscale(true);
// if (_driver_part_number == 2209) {
// tmcstepper->diag1_stall(false); //TODO: check the equivalent in TMC2209
// }
break;
case TrinamicUartMode ::CoolStep:
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Coolstep");
// tmcstepper->en_pwm_mode(false); //TODO: check if this is present in TMC2208/09
tmcstepper->en_spreadCycle(true);
tmcstepper->pwm_autoscale(false);
if (_driver_part_number == 2209) {
// tmcstepper->TCOOLTHRS(NORMAL_TCOOLTHRS); // when to turn on coolstep //TODO: add this solving compilation issue.
// tmcstepper->THIGH(NORMAL_THIGH); //TODO: this does not exist in TMC2208/09. verify and eventually remove.
}
break;
case TrinamicUartMode ::StallGuard: //TODO: check all configurations for stallguard
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Stallguard");
// tmcstepper->en_pwm_mode(false); //TODO: check if this is present in TMC2208/09
tmcstepper->en_spreadCycle(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, MsgLevel::Info, "Unknown Trinamic mode:d", _mode);
}
}
/*
This is the stallguard tuning info. It is call debug, so it could be generic across all classes.
*/
void TrinamicUartDriver::debug_message() {
if (_has_errors) {
return;
}
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,
MsgLevel::Info,
"%s Stallguard %d SG_Val: %04d Rate: %05.0f mm/min SG_Setting:%d",
reportAxisNameMsg(_axis_index, _dual_axis_index),
0, // tmcstepper->stallguard(), // TODO: add this again solving the compilation issues
0, // tmcstepper->sg_result(),
feedrate,
axis_settings[_axis_index]->stallguard->get());
TMC2208_n ::DRV_STATUS_t status { 0 }; // a useful struct to access the bits.
status.sr = tmcstepper->DRV_STATUS();
// these only report if there is a fault condition
report_open_load(status);
report_short_to_ground(status);
report_over_temp(status);
report_short_to_ps(status);
// grbl_msg_sendf(CLIENT_SERIAL,
// MsgLevel::Info,
// "%s Status Register %08x GSTAT %02x",
// reportAxisNameMsg(_axis_index, _dual_axis_index),
// status.sr,
// tmcstepper->GSTAT());
}
// calculate a tstep from a rate
// tstep = TRINAMIC_UART_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 TrinamicUartDriver::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_UART_FCLK / tstep * percent / 100.0;
return static_cast<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 TrinamicUartDriver::set_disable(bool disable) {
if (_has_errors) {
return;
}
if (_disabled == disable) {
return;
}
_disabled = disable;
digitalWrite(_disable_pin, _disabled);
#ifdef USE_TRINAMIC_ENABLE
if (_disabled) {
tmcstepper->toff(TRINAMIC_UART_TOFF_DISABLE);
} else {
if (_mode == TrinamicUartMode::StealthChop) {
tmcstepper->toff(TRINAMIC_UART_TOFF_STEALTHCHOP);
} else {
tmcstepper->toff(TRINAMIC_UART_TOFF_COOLSTEP);
}
}
#endif
// the pin based enable could be added here.
// This would be for individual motors, not the single pin for all motors.
}
// =========== Reporting functions ========================
bool TrinamicUartDriver::report_open_load(TMC2208_n ::DRV_STATUS_t status) {
if (status.ola || status.olb) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s Driver open load A:%s B:%s",
reportAxisNameMsg(_axis_index, _dual_axis_index),
status.ola ? "Y" : "N",
status.olb ? "Y" : "N");
return true;
}
return false; // no error
}
bool TrinamicUartDriver::report_short_to_ground(TMC2208_n ::DRV_STATUS_t status) {
if (status.s2ga || status.s2gb) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s Driver shorted coil A:%s B:%s",
reportAxisNameMsg(_axis_index, _dual_axis_index),
status.s2ga ? "Y" : "N",
status.s2gb ? "Y" : "N");
return true;
}
return false; // no error
}
bool TrinamicUartDriver::report_over_temp(TMC2208_n ::DRV_STATUS_t status) {
if (status.ot || status.otpw) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s Driver temp Warning:%s Fault:%s",
reportAxisNameMsg(_axis_index, _dual_axis_index),
status.otpw ? "Y" : "N",
status.ot ? "Y" : "N");
return true;
}
return false; // no error
}
bool TrinamicUartDriver::report_short_to_ps(TMC2208_n ::DRV_STATUS_t status) {
// check for short to power supply
if ((status.sr & bit(12)) || (status.sr & bit(13))) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s Driver short vsa:%s vsb:%s",
reportAxisNameMsg(_axis_index, _dual_axis_index),
(status.sr & bit(12)) ? "Y" : "N",
(status.sr & bit(13)) ? "Y" : "N");
return true;
}
return false; // no error
}
}

View File

@@ -79,7 +79,6 @@ namespace WebUI {
}
void settings_init() {
EEPROM.begin(EEPROM_SIZE);
make_settings();
WebUI::make_web_settings();
make_grbl_commands();
@@ -389,13 +388,45 @@ Error listErrors(const char* value, WebUI::AuthenticationLevel auth_level, WebUI
return Error::Ok;
}
Error motor_disable(const char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
char* s;
if (value == NULL) {
value = "\0";
}
s = strdup(value);
s = trim(s);
int32_t convertedValue;
char* endptr;
if (*s == '\0') {
convertedValue = 255; // all axes
} else {
convertedValue = strtol(s, &endptr, 10);
if (endptr == s || *endptr != '\0') {
// Try to convert as an axis list
convertedValue = 0;
auto axisNames = String("XYZABC");
while (*s) {
int index = axisNames.indexOf(toupper(*s++));
if (index < 0) {
return Error::BadNumberFormat;
}
convertedValue |= bit(index);
}
}
}
motors_set_disable(true, convertedValue);
return Error::Ok;
}
static bool anyState() {
return false;
}
static bool idleOrJog() {
return sys.state != State::Idle && sys.state != State::Jog;
}
static bool idleOrAlarm() {
bool idleOrAlarm() {
return sys.state != State::Idle && sys.state != State::Alarm;
}
static bool notCycleOrHold() {
@@ -427,6 +458,8 @@ void make_grbl_commands() {
new GrblCommand("V", "Settings/Stats", Setting::report_nvs_stats, idleOrAlarm);
new GrblCommand("#", "GCode/Offsets", report_ngc, idleOrAlarm);
new GrblCommand("H", "Home", home_all, idleOrAlarm);
new GrblCommand("MD", "Motor/Disable", motor_disable, idleOrAlarm);
#ifdef HOMING_SINGLE_AXIS_COMMANDS
new GrblCommand("HX", "Home/X", home_x, idleOrAlarm);
new GrblCommand("HY", "Home/Y", home_y, idleOrAlarm);

View File

@@ -96,7 +96,7 @@ bool can_park() {
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
sys.override_ctrl == Override::ParkingMotion &&
#endif
homing_enable->get() && !laser_mode->get();
homing_enable->get() && !spindle->inLaserMode();
}
/*
@@ -558,7 +558,7 @@ static void protocol_exec_rt_suspend() {
restore_spindle_speed = block->spindle_speed;
}
#ifdef DISABLE_LASER_DURING_HOLD
if (laser_mode->get()) {
if (spindle->inLaserMode()) {
sys_rt_exec_accessory_override.bit.spindleOvrStop = true;
}
#endif
@@ -661,7 +661,7 @@ static void protocol_exec_rt_suspend() {
if (gc_state.modal.spindle != SpindleState::Disable) {
// Block if safety door re-opened during prior restore actions.
if (!sys.suspend.bit.restartRetract) {
if (laser_mode->get()) {
if (spindle->inLaserMode()) {
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
sys.step_control.updateSpindleRpm = true;
} else {
@@ -717,7 +717,7 @@ static void protocol_exec_rt_suspend() {
} else if (sys.spindle_stop_ovr.bit.restore || sys.spindle_stop_ovr.bit.restoreCycle) {
if (gc_state.modal.spindle != SpindleState::Disable) {
report_feedback_message(Message::SpindleRestore);
if (laser_mode->get()) {
if (spindle->inLaserMode()) {
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
sys.step_control.updateSpindleRpm = true;
} else {

View File

@@ -239,6 +239,7 @@ void report_status_message(Error status_code, uint8_t client) {
grbl_sendf(client, "error:%d\r\n", status_code); // most senders seem to tolerate this error and keep on going
grbl_sendf(CLIENT_ALL, "error:%d in SD file at line %d\r\n", status_code, sd_get_current_line_number());
// don't close file
SD_ready_next = true; // flag so system_execute_line() will send the next line
} else {
grbl_notifyf("SD print error", "Error:%d during SD file at line: %d", status_code, sd_get_current_line_number());
grbl_sendf(CLIENT_ALL, "error:%d in SD file at line %d\r\n", status_code, sd_get_current_line_number());
@@ -753,16 +754,16 @@ void report_realtime_status(uint8_t client) {
strcat(status, "S");
}
if (ctrl_pin_state.bit.macro0) {
strcat(status, "M0");
strcat(status, "0");
}
if (ctrl_pin_state.bit.macro1) {
strcat(status, "M1");
strcat(status, "1");
}
if (ctrl_pin_state.bit.macro2) {
strcat(status, "M2");
strcat(status, "2");
}
if (ctrl_pin_state.bit.macro3) {
strcat(status, "M3");
strcat(status, "3");
}
}
}

View File

@@ -128,13 +128,14 @@ uint32_t sd_get_current_line_number() {
uint8_t sd_state = SDCARD_IDLE;
uint8_t get_sd_state(bool refresh) {
#if defined(SDCARD_DET_PIN) && SDCARD_SD_PIN != -1
//no need to go further if SD detect is not correct
if (!((digitalRead(SDCARD_DET_PIN) == SDCARD_DET_VAL) ? true : false)) {
if (SDCARD_DET_PIN != UNDEFINED_PIN) {
if (digitalRead(SDCARD_DET_PIN) != SDCARD_DET_VAL) {
sd_state = SDCARD_NOT_PRESENT;
return sd_state;
//no need to go further if SD detect is not correct
}
#endif
}
//if busy doing something return state
if (!((sd_state == SDCARD_NOT_PRESENT) || (sd_state == SDCARD_IDLE))) {
return sd_state;

View File

@@ -20,8 +20,8 @@
#include <SD.h>
#include <SPI.h>
#define SDCARD_DET_PIN -1
const int SDCARD_DET_VAL = 0;
//#define SDCARD_DET_PIN -1
const int SDCARD_DET_VAL = 0; // for now, CD is close to ground
const int SDCARD_IDLE = 0;
const int SDCARD_NOT_PRESENT = 1;

View File

@@ -79,7 +79,9 @@ void heapCheckTask(void* pvParameters) {
vTaskDelay(3000 / portTICK_RATE_MS); // Yield to other tasks
static UBaseType_t uxHighWaterMark = 0;
#ifdef DEBUG_TASK_STACK
reportTaskStackSize(uxHighWaterMark);
#endif
}
}
@@ -104,7 +106,8 @@ void serial_init() {
NULL, // parameters
1, // priority
&serialCheckTaskHandle,
1 // core
SUPPORT_TASK_CORE // must run the task on same core
// core
);
}
@@ -156,9 +159,16 @@ void serialCheckTask(void* pvParameters) {
if (is_realtime_command(data)) {
execute_realtime_command(static_cast<Cmd>(data), client);
} else {
if (get_sd_state(false) == SDCARD_IDLE) {
vTaskEnterCritical(&myMutex);
client_buffer[client].write(data);
vTaskExitCritical(&myMutex);
} else {
if (data == '\r' || data == '\n') {
grbl_sendf(client, "error %d\r\n", Error::AnotherInterfaceBusy);
grbl_msg_sendf(client, MsgLevel::Info, "SD card job running");
}
}
}
} // if something available
WebUI::COMMANDS::handle();
@@ -174,8 +184,10 @@ void serialCheckTask(void* pvParameters) {
vTaskDelay(1 / portTICK_RATE_MS); // Yield to other tasks
static UBaseType_t uxHighWaterMark = 0;
#ifdef DEBUG_TASK_STACK
reportTaskStackSize(uxHighWaterMark);
} // while(true)
#endif
}
}
void serial_reset_read_buffer(uint8_t client) {

View File

@@ -8,8 +8,10 @@ Word::Word(type_t type, permissions_t permissions, const char* description, cons
Command* Command::List = NULL;
Command::Command(const char* description, type_t type, permissions_t permissions, const char* grblName, const char* fullName) :
Word(type, permissions, description, grblName, fullName) {
Command::Command(
const char* description, type_t type, permissions_t permissions, const char* grblName, const char* fullName, bool (*cmdChecker)()) :
Word(type, permissions, description, grblName, fullName),
_cmdChecker(cmdChecker) {
link = List;
List = this;
}
@@ -126,6 +128,7 @@ Error IntSetting::setStringValue(char* s) {
_storedValue = convertedValue;
}
}
check(NULL);
return Error::Ok;
}
@@ -223,6 +226,7 @@ Error AxisMaskSetting::setStringValue(char* s) {
_storedValue = _currentValue;
}
}
check(NULL);
return Error::Ok;
}
@@ -323,6 +327,7 @@ Error FloatSetting::setStringValue(char* s) {
_storedValue = _currentValue;
}
}
check(NULL);
return Error::Ok;
}
@@ -412,6 +417,7 @@ Error StringSetting::setStringValue(char* s) {
_storedValue = _currentValue;
}
}
check(NULL);
return Error::Ok;
}
@@ -442,11 +448,15 @@ void StringSetting::addWebui(WebUI::JSONencoder* j) {
typedef std::map<const char*, int8_t, cmp_str> enum_opt_t;
EnumSetting::EnumSetting(
const char* description, type_t type, permissions_t permissions, const char* grblName, const char* name, int8_t defVal, enum_opt_t* opts)
// No checker function because enumerations have an exact set of value
:
Setting(description, type, permissions, grblName, name, NULL),
EnumSetting::EnumSetting(const char* description,
type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
int8_t defVal,
enum_opt_t* opts,
bool (*checker)(char*) = NULL) :
Setting(description, type, permissions, grblName, name, checker),
_defaultValue(defVal), _options(opts) {}
void EnumSetting::load() {
@@ -472,6 +482,10 @@ void EnumSetting::setDefault() {
// for setting.
Error EnumSetting::setStringValue(char* s) {
s = trim(s);
Error err = check(s);
if (err != Error::Ok) {
return err;
}
enum_opt_t::iterator it = _options->find(s);
if (it == _options->end()) {
// If we don't find the value in keys, look for it in the numeric values
@@ -497,7 +511,7 @@ Error EnumSetting::setStringValue(char* s) {
}
_currentValue = it->second;
if (_storedValue != _currentValue) {
if (_storedValue == _defaultValue) {
if (_currentValue == _defaultValue) {
nvs_erase_key(_handle, _keyName);
} else {
if (nvs_set_i8(_handle, _keyName, _currentValue)) {
@@ -506,6 +520,7 @@ Error EnumSetting::setStringValue(char* s) {
_storedValue = _currentValue;
}
}
check(NULL);
return Error::Ok;
}
@@ -585,6 +600,7 @@ Error FlagSetting::setStringValue(char* s) {
_storedValue = _currentValue;
}
}
check(NULL);
return Error::Ok;
}
const char* FlagSetting::getDefaultString() {
@@ -665,6 +681,7 @@ Error IPaddrSetting::setStringValue(char* s) {
_storedValue = _currentValue;
}
}
check(NULL);
return Error::Ok;
}
@@ -689,7 +706,7 @@ void IPaddrSetting::addWebui(WebUI::JSONencoder* j) {
AxisSettings::AxisSettings(const char* axisName) : name(axisName) {}
Error GrblCommand::action(char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
if (_checker && _checker()) {
if (_cmdChecker && _cmdChecker()) {
return Error::IdleError;
}
return _action((const char*)value, auth_level, out);

View File

@@ -75,12 +75,13 @@ public:
class Command : public Word {
protected:
Command* link; // linked list of setting objects
bool (*_cmdChecker)();
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);
Command(const char* description, type_t type, permissions_t permissions, const char* grblName, const char* fullName, bool (*cmcChecker)());
// The default implementation of addWebui() does nothing.
// Derived classes may override it to do something.
@@ -343,10 +344,17 @@ public:
const char* grblName,
const char* name,
int8_t defVal,
enum_opt_t* opts);
enum_opt_t* opts,
bool (*checker)(char*));
EnumSetting(type_t type, permissions_t permissions, const char* grblName, const char* name, int8_t defVal, enum_opt_t* opts) :
EnumSetting(NULL, type, permissions, grblName, name, defVal, opts) {}
EnumSetting(type_t type,
permissions_t permissions,
const char* grblName,
const char* name,
int8_t defVal,
enum_opt_t* opts,
bool (*checker)(char*) = NULL) :
EnumSetting(NULL, type, permissions, grblName, name, defVal, opts, checker) {}
void load();
void setDefault();
@@ -435,6 +443,9 @@ public:
AxisSettings(const char* axisName);
};
extern bool idleOrAlarm();
class WebCommand : public Command {
private:
Error (*_action)(char*, WebUI::AuthenticationLevel);
@@ -447,7 +458,10 @@ public:
const char* grblName,
const char* name,
Error (*action)(char*, WebUI::AuthenticationLevel)) :
Command(description, type, permissions, grblName, name),
// At some point we might want to be more subtle, but for now we block
// all web commands in Cycle and Hold states, to avoid crashing a
// running job.
Command(description, type, permissions, grblName, name, idleOrAlarm),
_action(action) {}
Error action(char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* response);
};
@@ -455,22 +469,21 @@ public:
class GrblCommand : public Command {
private:
Error (*_action)(const char*, WebUI::AuthenticationLevel, WebUI::ESPResponseStream*);
bool (*_checker)();
public:
GrblCommand(const char* grblName,
const char* name,
Error (*action)(const char*, WebUI::AuthenticationLevel, WebUI::ESPResponseStream*),
bool (*checker)(),
bool (*cmdChecker)(),
permissions_t auth) :
Command(NULL, GRBLCMD, auth, grblName, name),
_action(action), _checker(checker) {}
Command(NULL, GRBLCMD, auth, grblName, name, cmdChecker),
_action(action) {}
GrblCommand(const char* grblName,
const char* name,
Error (*action)(const char*, WebUI::AuthenticationLevel, WebUI::ESPResponseStream*),
bool (*checker)(void)) :
GrblCommand(grblName, name, action, checker, WG) {}
bool (*cmdChecker)()) :
GrblCommand(grblName, name, action, cmdChecker, WG) {}
Error action(char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* response);
};

View File

@@ -1,7 +1,5 @@
#include "Grbl.h"
bool motorSettingChanged = false;
FlagSetting* verbose_errors;
FakeSetting<int>* number_axis;
@@ -32,6 +30,7 @@ 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* laser_full_power;
IntSetting* status_mask;
FloatSetting* junction_deviation;
@@ -81,6 +80,11 @@ AxisSettings* c_axis_settings;
AxisSettings* axis_settings[MAX_N_AXIS];
StringSetting* user_macro0;
StringSetting* user_macro1;
StringSetting* user_macro2;
StringSetting* user_macro3;
typedef struct {
const char* name;
float steps_per_mm;
@@ -166,34 +170,37 @@ static const char* makename(const char* axisName, const char* tail) {
}
static bool checkStartupLine(char* value) {
if (!value) { // No POST functionality
return true;
}
if (sys.state != State::Idle) {
return false;
}
return gc_execute_line(value, CLIENT_SERIAL) == Error::Ok;
}
static bool checkStallguard(char* value) {
motorSettingChanged = true;
static bool postMotorSetting(char* value) {
if (!value) {
motors_read_settings();
}
return true;
}
static bool checkMicrosteps(char* value) {
motorSettingChanged = true;
static bool checkSpindleChange(char* val) {
if (!val) {
// if not in disable (M5) ...
if (gc_state.modal.spindle != SpindleState::Disable) {
gc_state.modal.spindle = SpindleState::Disable;
if (spindle->use_delays && spindle_delay_spindown->get() != 0) { // old spindle
vTaskDelay(spindle_delay_spindown->get() * 1000);
}
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Spindle turned off with setting change");
}
gc_state.spindle_speed = 0; // Set S value to 0
spindle->deinit(); // old spindle
Spindles::Spindle::select(); // get new spindle
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;
}
@@ -212,17 +219,7 @@ void make_coordinate(CoordIndex index, const char* name) {
auto coord = new Coordinates(name);
coords[index] = coord;
if (!coord->load()) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Propagating %s data to NVS format", coord->getName());
// If coord->load() returns false it means that no entry
// was present in non-volatile storage. In that case we
// first look for an old-format entry in the EEPROM section.
// If an entry is present some number of float values at
// the beginning of coord_data will be overwritten with
// the EEPROM data, and the rest will remain at 0.0.
// If no old-format entry is present, all will remain 0.0
// Regardless, we create a new entry with that data.
(void)old_settings_read_coord_data(index, coord_data);
coords[index]->set(coord_data);
coords[index]->setDefault();
}
}
void make_settings() {
@@ -260,29 +257,29 @@ void make_settings() {
c_axis_settings = axis_settings[C_AXIS];
for (axis = MAX_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);
auto setting =
new IntSetting(EXTENDED, WG, makeGrblName(axis, 170), makename(def->name, "StallGuard"), def->stallguard, -64, 63, postMotorSetting);
setting->setAxis(axis);
axis_settings[axis]->stallguard = setting;
}
for (axis = MAX_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);
auto setting =
new IntSetting(EXTENDED, WG, makeGrblName(axis, 160), makename(def->name, "Microsteps"), def->microsteps, 0, 256, postMotorSetting);
setting->setAxis(axis);
axis_settings[axis]->microsteps = setting;
}
for (axis = MAX_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
EXTENDED, WG, makeGrblName(axis, 150), makename(def->name, "Current/Hold"), def->hold_current, 0.05, 20.0, postMotorSetting); // Amps
setting->setAxis(axis);
axis_settings[axis]->hold_current = setting;
}
for (axis = MAX_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
EXTENDED, WG, makeGrblName(axis, 140), makename(def->name, "Current/Run"), def->run_current, 0.0, 20.0, postMotorSetting); // Amps
setting->setAxis(axis);
axis_settings[axis]->run_current = setting;
}
@@ -322,21 +319,26 @@ void make_settings() {
}
// Spindle Settings
spindle_pwm_max_value = new FloatSetting(EXTENDED, WG, "36", "Spindle/PWM/Max", DEFAULT_SPINDLE_MAX_VALUE, 0.0, 100.0);
spindle_pwm_min_value = new FloatSetting(EXTENDED, WG, "35", "Spindle/PWM/Min", DEFAULT_SPINDLE_MIN_VALUE, 0.0, 100.0);
spindle_pwm_off_value =
new FloatSetting(EXTENDED, WG, "34", "Spindle/PWM/Off", DEFAULT_SPINDLE_OFF_VALUE, 0.0, 100.0); // these are percentages
spindle_type =
new EnumSetting(NULL, EXTENDED, WG, NULL, "Spindle/Type", static_cast<int8_t>(SPINDLE_TYPE), &spindleTypes, checkSpindleChange);
spindle_pwm_max_value =
new FloatSetting(EXTENDED, WG, "36", "Spindle/PWM/Max", DEFAULT_SPINDLE_MAX_VALUE, 0.0, 100.0, checkSpindleChange);
spindle_pwm_min_value =
new FloatSetting(EXTENDED, WG, "35", "Spindle/PWM/Min", DEFAULT_SPINDLE_MIN_VALUE, 0.0, 100.0, checkSpindleChange);
spindle_pwm_off_value = new FloatSetting(
EXTENDED, WG, "34", "Spindle/PWM/Off", DEFAULT_SPINDLE_OFF_VALUE, 0.0, 100.0, checkSpindleChange); // 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_output_invert = new FlagSetting(GRBL, WG, NULL, "Spindle/PWM/Invert", DEFAULT_INVERT_SPINDLE_OUTPUT_PIN);
spindle_pwm_freq = new FloatSetting(EXTENDED, WG, "33", "Spindle/PWM/Frequency", DEFAULT_SPINDLE_FREQ, 0, 100000, checkSpindleChange);
spindle_output_invert = new FlagSetting(GRBL, WG, NULL, "Spindle/PWM/Invert", DEFAULT_INVERT_SPINDLE_OUTPUT_PIN, checkSpindleChange);
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);
spindle_enbl_off_with_zero_speed =
new FlagSetting(GRBL, WG, NULL, "Spindle/Enable/OffWithSpeed", DEFAULT_SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED);
new FlagSetting(GRBL, WG, NULL, "Spindle/Enable/OffWithSpeed", DEFAULT_SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED, checkSpindleChange);
spindle_enable_invert = new FlagSetting(GRBL, WG, NULL, "Spindle/Enable/Invert", DEFAULT_INVERT_SPINDLE_ENABLE_PIN);
spindle_enable_invert = new FlagSetting(GRBL, WG, NULL, "Spindle/Enable/Invert", DEFAULT_INVERT_SPINDLE_ENABLE_PIN, checkSpindleChange);
// GRBL Non-numbered settings
startup_line_0 = new StringSetting(GRBL, WG, "N0", "GCode/Line0", "", checkStartupLine);
@@ -344,9 +346,11 @@ void make_settings() {
// GRBL Numbered Settings
laser_mode = new FlagSetting(GRBL, WG, "32", "GCode/LaserMode", DEFAULT_LASER_MODE);
laser_full_power = new IntSetting(EXTENDED, WG, NULL, "Laser/FullPower", DEFAULT_LASER_FULL_POWER, 0, 10000, checkSpindleChange);
// 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);
rpm_min = new FloatSetting(GRBL, WG, "31", "GCode/MinS", DEFAULT_SPINDLE_RPM_MIN, 0, 100000, checkSpindleChange);
rpm_max = new FloatSetting(GRBL, WG, "30", "GCode/MaxS", DEFAULT_SPINDLE_RPM_MAX, 0, 100000, checkSpindleChange);
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);
@@ -373,17 +377,22 @@ void make_settings() {
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);
dir_invert_mask = new AxisMaskSetting(GRBL, WG, "3", "Stepper/DirInvert", DEFAULT_DIRECTION_INVERT_MASK, postMotorSetting);
step_invert_mask = new AxisMaskSetting(GRBL, WG, "2", "Stepper/StepInvert", DEFAULT_STEPPING_INVERT_MASK, postMotorSetting);
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", static_cast<int8_t>(SPINDLE_TYPE), &spindleTypes);
stallguard_debug_mask = new AxisMaskSetting(EXTENDED, WG, NULL, "Report/StallGuard", 0, checkStallguardDebugMask);
homing_cycle[0] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle0", DEFAULT_HOMING_CYCLE_0);
homing_cycle[1] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle1", DEFAULT_HOMING_CYCLE_1);
homing_cycle[2] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle2", DEFAULT_HOMING_CYCLE_2);
homing_cycle[3] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle3", DEFAULT_HOMING_CYCLE_3);
homing_cycle[4] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle4", DEFAULT_HOMING_CYCLE_4);
stallguard_debug_mask = new AxisMaskSetting(EXTENDED, WG, NULL, "Report/StallGuard", 0, postMotorSetting);
homing_cycle[5] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle5", DEFAULT_HOMING_CYCLE_5);
homing_cycle[4] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle4", DEFAULT_HOMING_CYCLE_4);
homing_cycle[3] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle3", DEFAULT_HOMING_CYCLE_3);
homing_cycle[2] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle2", DEFAULT_HOMING_CYCLE_2);
homing_cycle[1] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle1", DEFAULT_HOMING_CYCLE_1);
homing_cycle[0] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle0", DEFAULT_HOMING_CYCLE_0);
user_macro3 = new StringSetting(EXTENDED, WG, NULL, "User/Macro3", DEFAULT_USER_MACRO3);
user_macro2 = new StringSetting(EXTENDED, WG, NULL, "User/Macro2", DEFAULT_USER_MACRO2);
user_macro1 = new StringSetting(EXTENDED, WG, NULL, "User/Macro1", DEFAULT_USER_MACRO1);
user_macro0 = new StringSetting(EXTENDED, WG, NULL, "User/Macro0", DEFAULT_USER_MACRO0);
}

View File

@@ -1,7 +1,5 @@
#pragma once
extern bool motorSettingChanged;
extern FlagSetting* verbose_errors;
extern FakeSetting<int>* number_axis;
@@ -35,6 +33,7 @@ extern FlagSetting* soft_limits;
extern FlagSetting* hard_limits;
extern FlagSetting* homing_enable;
extern FlagSetting* laser_mode;
extern IntSetting* laser_full_power;
extern IntSetting* status_mask;
extern FloatSetting* junction_deviation;
@@ -61,3 +60,8 @@ extern IntSetting* spindle_pwm_bit_precision;
extern EnumSetting* spindle_type;
extern AxisMaskSetting* stallguard_debug_mask;
extern StringSetting* user_macro0;
extern StringSetting* user_macro1;
extern StringSetting* user_macro2;
extern StringSetting* user_macro3;

View File

@@ -44,7 +44,7 @@ namespace Spindles {
#endif
if (_output_pin == UNDEFINED_PIN) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Warning: Spindle output pin not defined");
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Warning: Spindle output pin not defined");
return; // We cannot continue without the output pin
}
@@ -66,7 +66,7 @@ namespace Spindles {
// prints the startup message of the spindle config
void _10v::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
grbl_msg_sendf(CLIENT_ALL,
MsgLevel::Info,
"0-10V spindle Out:%s Enbl:%s, Dir:%s, Fwd:%s, Rev:%s, Freq:%dHz Res:%dbits",
pinName(_output_pin).c_str(),
@@ -144,7 +144,6 @@ namespace Spindles {
}
void _10v::set_enable_pin(bool enable) {
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Spindle::_10v::set_enable_pin");
if (_off_with_zero_speed && sys.spindle_speed == 0) {
enable = false;
}
@@ -164,9 +163,33 @@ namespace Spindles {
}
void _10v::set_dir_pin(bool Clockwise) {
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Spindle::_10v::set_dir_pin");
digitalWrite(_direction_pin, Clockwise);
digitalWrite(_forward_pin, Clockwise);
digitalWrite(_reverse_pin, !Clockwise);
}
void _10v::deinit() {
#ifdef SPINDLE_OUTPUT_PIN
gpio_reset_pin(SPINDLE_OUTPUT_PIN);
pinMode(SPINDLE_OUTPUT_PIN, INPUT);
#endif
#ifdef SPINDLE_ENABLE_PIN
gpio_reset_pin(SPINDLE_ENABLE_PIN);
pinMode(SPINDLE_ENABLE_PIN, INPUT);
#endif
#ifdef SPINDLE_DIR_PIN
gpio_reset_pin(SPINDLE_DIR_PIN);
pinMode(SPINDLE_DIR_PIN, INPUT);
#endif
#ifdef SPINDLE_FORWARD_PIN
gpio_reset_pin(SPINDLE_FORWARD_PIN);
pinMode(SPINDLE_FORWARD_PIN, INPUT);
#endif
#ifdef SPINDLE_REVERSE_PIN
gpio_reset_pin(SPINDLE_FORWARD_PIN);
pinMode(SPINDLE_FORWARD_PIN, INPUT);
#endif
}
}

View File

@@ -45,6 +45,7 @@ namespace Spindles {
SpindleState get_state() override;
void stop() override;
void deinit() override;
virtual ~_10v() {}

View File

@@ -55,7 +55,7 @@ namespace Spindles {
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, MsgLevel::Info, "Warning: BESC output pin not defined");
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Warning: BESC output pin not defined");
return; // We cannot continue without the output pin
}
@@ -82,7 +82,7 @@ namespace Spindles {
// prints the startup message of the spindle config
void BESC::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
grbl_msg_sendf(CLIENT_ALL,
MsgLevel::Info,
"BESC spindle on Pin:%s Min:%0.2fms Max:%0.2fms Freq:%dHz Res:%dbits",
pinName(_output_pin).c_str(),

View File

@@ -40,7 +40,7 @@ namespace Spindles {
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, MsgLevel::Info, "DAC spindle pin invalid GPIO_NUM_%d (pin 25 or 26 only)", _output_pin);
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "DAC spindle pin invalid GPIO_NUM_%d (pin 25 or 26 only)", _output_pin);
return;
}
@@ -54,7 +54,7 @@ namespace Spindles {
}
void Dac::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
grbl_msg_sendf(CLIENT_ALL,
MsgLevel::Info,
"DAC spindle Output:%s, Enbl:%s, Dir:%s, Res:8bits",
pinName(_output_pin).c_str(),
@@ -85,7 +85,7 @@ namespace Spindles {
rpm = _min_rpm;
sys.spindle_speed = rpm;
pwm_value = 0;
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Spindle RPM less than min RPM:%5.2f %d", rpm, pwm_value);
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Spindle RPM less than min RPM:%5.2f %d", rpm, pwm_value);
}
} else {
// Compute intermediate PWM value with linear spindle speed model.

View File

@@ -24,19 +24,78 @@
// ===================================== Laser ==============================================
namespace Spindles {
bool Laser::isRateAdjusted() {
return true; // can use M4 (CCW) laser mode.
bool Laser::inLaserMode() {
return laser_mode->get(); // can use M4 (CCW) laser mode.
}
void Laser::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
grbl_msg_sendf(CLIENT_ALL,
MsgLevel::Info,
"Laser spindle on Pin:%s, Freq:%dHz, Res:%dbits Laser mode:%s",
"Laser spindle on Pin:%s, Enbl:%s, Freq:%dHz, Res:%dbits Laser mode:%s",
pinName(_output_pin).c_str(),
pinName(_enable_pin).c_str(),
_pwm_freq,
_pwm_precision,
laser_mode->getStringValue()); // the current mode
use_delays = false; // this will override the value set in Spindle::PWM::init()
}
// Get the GPIO from the machine definition
void Laser::get_pins_and_settings() {
// setup all the pins
#ifdef LASER_OUTPUT_PIN
_output_pin = LASER_OUTPUT_PIN;
#else
_output_pin = UNDEFINED_PIN;
#endif
_invert_pwm = spindle_output_invert->get();
#ifdef LASER_ENABLE_PIN
_enable_pin = LASER_ENABLE_PIN;
#else
_enable_pin = UNDEFINED_PIN;
#endif
if (_output_pin == UNDEFINED_PIN) {
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Warning: LASER_OUTPUT_PIN not defined");
return; // We cannot continue without the output pin
}
_off_with_zero_speed = spindle_enbl_off_with_zero_speed->get();
_direction_pin = UNDEFINED_PIN;
is_reversable = false;
_pwm_freq = spindle_pwm_freq->get();
_pwm_precision = calc_pwm_precision(_pwm_freq); // detewrmine the best precision
_pwm_period = (1 << _pwm_precision);
// pre-caculate some PWM count values
_pwm_off_value = 0;
_pwm_min_value = 0;
_pwm_max_value = _pwm_period;
_min_rpm = 0;
_max_rpm = laser_full_power->get();
_piecewide_linear = false;
_pwm_chan_num = 0; // Channel 0 is reserved for spindle use
}
void Laser::deinit() {
stop();
#ifdef LASER_OUTPUT_PIN
gpio_reset_pin(LASER_OUTPUT_PIN);
pinMode(LASER_OUTPUT_PIN, INPUT);
#endif
#ifdef LASER_ENABLE_PIN
gpio_reset_pin(LASER_ENABLE_PIN);
pinMode(LASER_ENABLE_PIN, INPUT);
#endif
}
}

View File

@@ -34,8 +34,10 @@ namespace Spindles {
Laser& operator=(const Laser&) = delete;
Laser& operator=(Laser&&) = delete;
bool isRateAdjusted() override;
bool inLaserMode() override;
void config_message() override;
void get_pins_and_settings() override;
void deinit() override;
virtual ~Laser() {}
};

View File

@@ -40,5 +40,5 @@ namespace Spindles {
}
SpindleState Null::get_state() { return _current_state; }
void Null::stop() {}
void Null::config_message() { grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "No spindle"); }
void Null::config_message() { grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "No spindle"); }
}

View File

@@ -34,23 +34,23 @@ namespace Spindles {
get_pins_and_settings();
if (_output_pin == UNDEFINED_PIN) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::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, MsgLevel::Info, "Warning: Spindle output pin %s cannot do PWM", pinName(_output_pin).c_str());
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Warning: Spindle output pin %s cannot do PWM", pinName(_output_pin).c_str());
return;
}
_current_state = SpindleState::Disable;
_current_pwm_duty = 0;
use_delays = true;
ledcSetup(_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
ledcAttachPin(_output_pin, _pwm_chan_num); // attach the PWM to the pin
pinMode(_enable_pin, OUTPUT);
pinMode(_direction_pin, OUTPUT);
use_delays = true;
config_message();
}
@@ -80,6 +80,11 @@ namespace Spindles {
_direction_pin = UNDEFINED_PIN;
#endif
if (_output_pin == UNDEFINED_PIN) {
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Warning: SPINDLE_OUTPUT_PIN not defined");
return; // We cannot continue without the output pin
}
is_reversable = (_direction_pin != UNDEFINED_PIN);
_pwm_freq = spindle_pwm_freq->get();
@@ -87,7 +92,7 @@ namespace Spindles {
_pwm_period = (1 << _pwm_precision);
if (spindle_pwm_min_value->get() > spindle_pwm_min_value->get()) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Warning: Spindle min pwm is greater than max. Check $35 and $36");
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Warning: Spindle min pwm is greater than max. Check $35 and $36");
}
// pre-caculate some PWM count values
@@ -117,8 +122,6 @@ namespace Spindles {
return rpm;
}
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "set_rpm(%d)", rpm);
// apply override
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (uint8_t percent)
@@ -134,7 +137,7 @@ namespace Spindles {
if (_piecewide_linear) {
//pwm_value = piecewise_linear_fit(rpm); TODO
pwm_value = 0;
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Warning: Linear fit not implemented yet.");
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Warning: Linear fit not implemented yet.");
} else {
if (rpm == 0) {
@@ -144,7 +147,7 @@ namespace Spindles {
}
}
set_enable_pin(_current_state != SpindleState::Disable);
set_enable_pin(gc_state.modal.spindle != SpindleState::Disable);
set_output(pwm_value);
return 0;
@@ -159,18 +162,14 @@ namespace Spindles {
sys.spindle_speed = 0;
stop();
if (use_delays && (_current_state != state)) {
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "SpinDown Start ");
mc_dwell(spindle_delay_spindown->get());
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "SpinDown Done");
}
} else {
set_dir_pin(state == SpindleState::Cw);
set_rpm(rpm);
set_enable_pin(state != SpindleState::Disable); // must be done after setting rpm for enable features to work
if (use_delays && (_current_state != state)) {
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "SpinUp Start %d", rpm);
mc_dwell(spindle_delay_spinup->get());
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "SpinUp Done");
}
}
@@ -197,7 +196,7 @@ namespace Spindles {
// prints the startup message of the spindle config
void PWM::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
grbl_msg_sendf(CLIENT_ALL,
MsgLevel::Info,
"PWM spindle Output:%s, Enbl:%s, Dir:%s, Freq:%dHz, Res:%dbits",
pinName(_output_pin).c_str(),
@@ -223,12 +222,18 @@ namespace Spindles {
duty = (1 << _pwm_precision) - duty;
}
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "set_output(%d)", duty);
ledcWrite(_pwm_chan_num, duty);
}
void PWM::set_enable_pin(bool enable) {
// static bool prev_enable = false;
// if (prev_enable == enable) {
// return;
// }
// prev_enable = enable;
if (_enable_pin == UNDEFINED_PIN) {
return;
}
@@ -262,4 +267,21 @@ namespace Spindles {
return precision - 1;
}
void PWM::deinit() {
stop();
#ifdef SPINDLE_OUTPUT_PIN
gpio_reset_pin(SPINDLE_OUTPUT_PIN);
pinMode(SPINDLE_OUTPUT_PIN, INPUT);
#endif
#ifdef SPINDLE_ENABLE_PIN
gpio_reset_pin(SPINDLE_ENABLE_PIN);
pinMode(SPINDLE_ENABLE_PIN, INPUT);
#endif
#ifdef SPINDLE_DIR_PIN
gpio_reset_pin(SPINDLE_DIR_PIN);
pinMode(SPINDLE_DIR_PIN, INPUT);
#endif
}
}

View File

@@ -65,8 +65,9 @@ namespace Spindles {
virtual void set_dir_pin(bool Clockwise);
virtual void set_output(uint32_t duty);
virtual void set_enable_pin(bool enable_pin);
virtual void deinit();
void get_pins_and_settings();
virtual void get_pins_and_settings();
uint8_t calc_pwm_precision(uint32_t freq);
};
}

View File

@@ -46,7 +46,7 @@ namespace Spindles {
// prints the startup message of the spindle config
void Relay ::config_message() {
grbl_msg_sendf(CLIENT_SERIAL,
grbl_msg_sendf(CLIENT_ALL,
MsgLevel::Info,
"Relay spindle Output:%s, Enbl:%s, Dir:%s",
pinName(_output_pin).c_str(),

View File

@@ -89,7 +89,7 @@ namespace Spindles {
// ========================= Spindle ==================================
bool Spindle::isRateAdjusted() {
bool Spindle::inLaserMode() {
return false; // default for basic spindle is false
}
@@ -100,6 +100,8 @@ namespace Spindles {
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
set_state(state, rpm);
}
void Spindle::deinit() { stop(); }
}
Spindles::Spindle* spindle;

View File

@@ -64,8 +64,9 @@ namespace Spindles {
virtual SpindleState get_state() = 0;
virtual void stop() = 0;
virtual void config_message() = 0;
virtual bool isRateAdjusted();
virtual bool inLaserMode();
virtual void sync(SpindleState state, uint32_t rpm);
virtual void deinit();
virtual ~Spindle() {}

View File

@@ -194,12 +194,13 @@ namespace Spindles {
if (retry_count == MAX_RETRIES) {
if (!unresponsive) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Spindle RS485 Unresponsive %d", next_cmd.rx_length);
unresponsive = true;
}
if (next_cmd.critical) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Critical Spindle RS485 Unresponsive");
mc_reset();
sys_rt_exec_alarm = ExecAlarm::SpindleControl;
}
unresponsive = true;
}
}
vTaskDelay(VFD_RS485_POLL_RATE); // TODO: What is the best value here?
@@ -274,7 +275,7 @@ namespace Spindles {
this, // parameters
1, // priority
&vfd_cmdTaskHandle,
0 // core
SUPPORT_TASK_CORE // core
);
_task_running = true;
}

View File

@@ -22,6 +22,8 @@
#include <driver/uart.h>
// #define VFD_DEBUG_MODE
namespace Spindles {
class VFD : public Spindle {

View File

@@ -551,7 +551,9 @@ void st_prep_buffer() {
prep.current_speed = sqrt(pl_block->entry_speed_sqr);
}
if (spindle->isRateAdjusted()) { // laser_mode->get() {
st_prep_block->is_pwm_rate_adjusted = false; // set default value
// prep.inv_rate is only used if is_pwm_rate_adjusted is true
if (spindle->inLaserMode()) { //
if (pl_block->spindle == SpindleState::Ccw) {
// Pre-compute inverse programmed rate to speed up PWM updating per step segment.
prep.inv_rate = 1.0 / pl_block->programmed_rate;

View File

@@ -63,22 +63,22 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
attachInterrupt(digitalPinToInterrupt(CONTROL_CYCLE_START_PIN), isr_control_inputs, CHANGE);
#endif
#ifdef MACRO_BUTTON_0_PIN
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 0");
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 0 %s", pinName(MACRO_BUTTON_0_PIN).c_str());
pinMode(MACRO_BUTTON_0_PIN, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_0_PIN), isr_control_inputs, CHANGE);
#endif
#ifdef MACRO_BUTTON_1_PIN
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 1");
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 1 %s", pinName(MACRO_BUTTON_1_PIN).c_str());
pinMode(MACRO_BUTTON_1_PIN, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_1_PIN), isr_control_inputs, CHANGE);
#endif
#ifdef MACRO_BUTTON_2_PIN
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 2");
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 2 %s", pinName(MACRO_BUTTON_2_PIN).c_str());
pinMode(MACRO_BUTTON_2_PIN, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_2_PIN), isr_control_inputs, CHANGE);
#endif
#ifdef MACRO_BUTTON_3_PIN
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 3");
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 3 %s", pinName(MACRO_BUTTON_3_PIN).c_str());
pinMode(MACRO_BUTTON_3_PIN, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_3_PIN), isr_control_inputs, CHANGE);
#endif
@@ -87,7 +87,7 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
control_sw_queue = xQueueCreate(10, sizeof(int));
xTaskCreate(controlCheckTask,
"controlCheckTask",
2048,
3096,
NULL,
5, // priority
NULL);
@@ -125,7 +125,9 @@ void controlCheckTask(void* pvParameters) {
debouncing = false;
static UBaseType_t uxHighWaterMark = 0;
# ifdef DEBUG_TASK_STACK
reportTaskStackSize(uxHighWaterMark);
# endif
}
}
#endif
@@ -332,4 +334,39 @@ uint8_t sys_calc_pwm_precision(uint32_t freq) {
return precision - 1;
}
void __attribute__((weak)) user_defined_macro(uint8_t index);
void __attribute__((weak)) user_defined_macro(uint8_t index) {
// must be in Idle
if (sys.state != State::Idle) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro button only permitted in idle");
return;
}
String user_macro;
char line[255];
switch (index) {
case 0:
user_macro = user_macro0->get();
break;
case 1:
user_macro = user_macro1->get();
break;
case 2:
user_macro = user_macro2->get();
break;
case 3:
user_macro = user_macro3->get();
break;
default:
return;
}
if (user_macro == "") {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro User/Macro%d empty", index);
return;
}
user_macro.replace('&', '\n');
user_macro.toCharArray(line, 255, 0);
strcat(line, "\r");
WebUI::inputBuffer.push(line);
}

View File

@@ -86,6 +86,9 @@ namespace WebUI {
bool BTConfig::isBTnameValid(const char* hostname) {
//limited size
if (!hostname) {
return true;
}
char c;
// length is checked automatically by string setting
//only letter and digit

View File

@@ -43,6 +43,9 @@ namespace WebUI {
}
bool COMMANDS::isLocalPasswordValid(char* password) {
if (!password) {
return true;
}
char c;
//limited size
if ((strlen(password) > MAX_LOCAL_PASSWORD_LENGTH) || (strlen(password) < MIN_LOCAL_PASSWORD_LENGTH)) {

View File

@@ -1221,9 +1221,13 @@ namespace WebUI {
bool list_files = true;
uint64_t totalspace = 0;
uint64_t usedspace = 0;
if (get_sd_state(true) != SDCARD_IDLE) {
int8_t state = get_sd_state(true);
if (state != SDCARD_IDLE) {
String status = "{\"status\":\"";
if(state == SDCARD_NOT_PRESENT)status+="No SD Card\"}";
else status+="Busy\"}";
_webserver->sendHeader("Cache-Control", "no-cache");
_webserver->send(200, "application/json", "{\"status\":\"No SD Card\"}");
_webserver->send(200, "application/json", status);
return;
}
set_sd_state(SDCARD_BUSY_PARSING);

View File

@@ -163,6 +163,9 @@ namespace WebUI {
}
Error WebCommand::action(char* value, WebUI::AuthenticationLevel auth_level, WebUI::ESPResponseStream* out) {
if (_cmdChecker && _cmdChecker()) {
return Error::AnotherInterfaceBusy;
}
char empty = '\0';
if (!value) {
value = &empty;
@@ -716,6 +719,10 @@ namespace WebUI {
static Error runSDFile(char* parameter, AuthenticationLevel auth_level) { // ESP220
Error err;
if (sys.state == State::Alarm) {
webPrintln("Alarm");
return Error::IdleError;
}
if (sys.state != State::Idle) {
webPrintln("Busy");
return Error::IdleError;
@@ -859,6 +866,8 @@ namespace WebUI {
default:
resp = "Busy";
}
#else
resp = "SD card not enabled";
#endif
webPrintln(resp);
return Error::Ok;
@@ -1084,8 +1093,8 @@ namespace WebUI {
MIN_NOTIFICATION_TOKEN_LENGTH,
MAX_NOTIFICATION_TOKEN_LENGTH,
NULL);
notification_type =
new EnumSetting("Notification type", WEBSET, WA, NULL, "Notification/Type", DEFAULT_NOTIFICATION_TYPE, &notificationOptions);
notification_type = new EnumSetting(
"Notification type", WEBSET, WA, NULL, "Notification/Type", DEFAULT_NOTIFICATION_TYPE, &notificationOptions, NULL);
#endif
#ifdef ENABLE_AUTHENTICATION
user_password = new StringSetting("User password",
@@ -1121,16 +1130,16 @@ namespace WebUI {
#ifdef WIFI_OR_BLUETOOTH
// user+ to get, admin to set
wifi_radio_mode = new EnumSetting("Radio mode", WEBSET, WA, "ESP110", "Radio/Mode", DEFAULT_RADIO_MODE, &radioEnabledOptions);
wifi_radio_mode = new EnumSetting("Radio mode", WEBSET, WA, "ESP110", "Radio/Mode", DEFAULT_RADIO_MODE, &radioEnabledOptions, NULL);
#endif
#ifdef ENABLE_WIFI
telnet_port = new IntSetting(
"Telnet Port", WEBSET, WA, "ESP131", "Telnet/Port", DEFAULT_TELNETSERVER_PORT, MIN_TELNET_PORT, MAX_TELNET_PORT, NULL);
telnet_enable = new EnumSetting("Telnet Enable", WEBSET, WA, "ESP130", "Telnet/Enable", DEFAULT_TELNET_STATE, &onoffOptions);
telnet_enable = new EnumSetting("Telnet Enable", WEBSET, WA, "ESP130", "Telnet/Enable", DEFAULT_TELNET_STATE, &onoffOptions, NULL);
http_port =
new IntSetting("HTTP Port", WEBSET, WA, "ESP121", "Http/Port", DEFAULT_WEBSERVER_PORT, MIN_HTTP_PORT, MAX_HTTP_PORT, NULL);
http_enable = new EnumSetting("HTTP Enable", WEBSET, WA, "ESP120", "Http/Enable", DEFAULT_HTTP_STATE, &onoffOptions);
http_enable = new EnumSetting("HTTP Enable", WEBSET, WA, "ESP120", "Http/Enable", DEFAULT_HTTP_STATE, &onoffOptions, NULL);
wifi_hostname = new StringSetting("Hostname",
WEBSET,
WA,
@@ -1158,7 +1167,7 @@ namespace WebUI {
wifi_sta_netmask = new IPaddrSetting("Station Static Mask", WEBSET, WA, NULL, "Sta/Netmask", DEFAULT_STA_MK, NULL);
wifi_sta_gateway = new IPaddrSetting("Station Static Gateway", WEBSET, WA, NULL, "Sta/Gateway", DEFAULT_STA_GW, NULL);
wifi_sta_ip = new IPaddrSetting("Station Static IP", WEBSET, WA, NULL, "Sta/IP", DEFAULT_STA_IP, NULL);
wifi_sta_mode = new EnumSetting("Station IP Mode", WEBSET, WA, "ESP102", "Sta/IPMode", DEFAULT_STA_IP_MODE, &staModeOptions);
wifi_sta_mode = new EnumSetting("Station IP Mode", WEBSET, WA, "ESP102", "Sta/IPMode", DEFAULT_STA_IP_MODE, &staModeOptions, NULL);
// no get, admin to set
wifi_sta_password = new StringSetting("Station Password",
WEBSET,

View File

@@ -115,6 +115,9 @@ namespace WebUI {
bool WiFiConfig::isHostnameValid(const char* hostname) {
//limited size
if (!hostname) {
return true;
}
char c;
// length is checked automatically by string setting
//only letter and digit
@@ -139,6 +142,9 @@ namespace WebUI {
//char c;
// length is checked automatically by string setting
//only printable
if (!ssid) {
return true;
}
for (int i = 0; i < strlen(ssid); i++) {
if (!isPrintable(ssid[i])) {
return false;
@@ -152,6 +158,9 @@ namespace WebUI {
*/
bool WiFiConfig::isPasswordValid(const char* password) {
if (!password) {
return true;
}
if (strlen(password) == 0) {
return true; //open network
}

Binary file not shown.