mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-01-17 22:28:29 +01:00
Merge remote-tracking branch 'upstream/Devt' into travis-ci-with-platformio
This commit is contained in:
commit
4b5c286c61
5
.gitignore
vendored
5
.gitignore
vendored
@ -5,3 +5,8 @@ Thumbs.db
|
||||
*.orig
|
||||
embedded/node_modules
|
||||
embedded/dist
|
||||
*~
|
||||
.pio/
|
||||
.vscode/
|
||||
.history/
|
||||
*.pyc
|
||||
|
@ -34,7 +34,7 @@ BluetoothSerial SerialBT;
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
const uint8_t *esp_bt_dev_get_address(void);
|
||||
const uint8_t* esp_bt_dev_get_address(void);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
@ -42,79 +42,72 @@ const uint8_t *esp_bt_dev_get_address(void);
|
||||
String BTConfig::_btname = "";
|
||||
String BTConfig::_btclient = "";
|
||||
|
||||
BTConfig::BTConfig(){
|
||||
BTConfig::BTConfig() {
|
||||
}
|
||||
|
||||
BTConfig::~BTConfig(){
|
||||
|
||||
BTConfig::~BTConfig() {
|
||||
end();
|
||||
}
|
||||
|
||||
static void my_spp_cb(esp_spp_cb_event_t event, esp_spp_cb_param_t *param)
|
||||
{
|
||||
switch (event)
|
||||
{
|
||||
case ESP_SPP_SRV_OPEN_EVT://Server connection open
|
||||
{
|
||||
static void my_spp_cb(esp_spp_cb_event_t event, esp_spp_cb_param_t* param) {
|
||||
switch (event) {
|
||||
case ESP_SPP_SRV_OPEN_EVT: { //Server connection open
|
||||
char str[18];
|
||||
str[17]='\0';
|
||||
uint8_t * addr = param->srv_open.rem_bda;
|
||||
str[17] = '\0';
|
||||
uint8_t* addr = param->srv_open.rem_bda;
|
||||
sprintf(str, "%02X:%02X:%02X:%02X:%02X:%02X", addr[0], addr[1], addr[2], addr[3], addr[4], addr[5]);
|
||||
BTConfig::_btclient = str;
|
||||
grbl_sendf(CLIENT_ALL,"[MSG:BT Connected with %s]\r\n", str);
|
||||
}
|
||||
break;
|
||||
|
||||
grbl_sendf(CLIENT_ALL, "[MSG:BT Connected with %s]\r\n", str);
|
||||
}
|
||||
break;
|
||||
case ESP_SPP_CLOSE_EVT://Client connection closed
|
||||
grbl_send(CLIENT_ALL,"[MSG:BT Disconnected]\r\n");
|
||||
BTConfig::_btclient="";
|
||||
grbl_send(CLIENT_ALL, "[MSG:BT Disconnected]\r\n");
|
||||
BTConfig::_btclient = "";
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
const char *BTConfig::info(){
|
||||
const char* BTConfig::info() {
|
||||
static String result;
|
||||
String tmp;
|
||||
result = "[MSG:";
|
||||
if(Is_BT_on()) {
|
||||
if (Is_BT_on()) {
|
||||
result += "Mode=BT:Name=";
|
||||
result += _btname;
|
||||
result += "(";
|
||||
result += device_address();
|
||||
result += "):Status=";
|
||||
if (SerialBT.hasClient()){
|
||||
if (SerialBT.hasClient())
|
||||
result += "Connected with " + _btclient;
|
||||
} else result += "Not connected";
|
||||
}
|
||||
else result+="No BT";
|
||||
result+= "]\r\n";
|
||||
else result += "Not connected";
|
||||
} else result += "No BT";
|
||||
result += "]\r\n";
|
||||
return result.c_str();
|
||||
}
|
||||
/**
|
||||
* Check if BlueTooth string is valid
|
||||
*/
|
||||
|
||||
bool BTConfig::isBTnameValid (const char * hostname){
|
||||
bool BTConfig::isBTnameValid(const char* hostname) {
|
||||
//limited size
|
||||
char c;
|
||||
if (strlen (hostname) > MAX_BTNAME_LENGTH || strlen (hostname) < MIN_BTNAME_LENGTH) {
|
||||
if (strlen(hostname) > MAX_BTNAME_LENGTH || strlen(hostname) < MIN_BTNAME_LENGTH)
|
||||
return false;
|
||||
}
|
||||
//only letter and digit
|
||||
for (int i = 0; i < strlen (hostname); i++) {
|
||||
for (int i = 0; i < strlen(hostname); i++) {
|
||||
c = hostname[i];
|
||||
if (! (isdigit (c) || isalpha (c) || c == '_') ) {
|
||||
if (!(isdigit(c) || isalpha(c) || c == '_'))
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
const char* BTConfig::device_address(){
|
||||
const char* BTConfig::device_address() {
|
||||
const uint8_t* point = esp_bt_dev_get_address();
|
||||
static char str[18];
|
||||
str[17]='\0';
|
||||
str[17] = '\0';
|
||||
sprintf(str, "%02X:%02X:%02X:%02X:%02X:%02X", (int)point[0], (int)point[1], (int)point[2], (int)point[3], (int)point[4], (int)point[5]);
|
||||
return str;
|
||||
}
|
||||
@ -134,19 +127,16 @@ void BTConfig::begin() {
|
||||
prefs.end();
|
||||
if (wifiMode == ESP_BT) {
|
||||
if (!SerialBT.begin(_btname))
|
||||
{
|
||||
report_status_message(STATUS_BT_FAIL_BEGIN, CLIENT_ALL);
|
||||
} else {
|
||||
report_status_message(STATUS_BT_FAIL_BEGIN, CLIENT_ALL);
|
||||
else {
|
||||
SerialBT.register_callback(&my_spp_cb);
|
||||
grbl_sendf(CLIENT_ALL,"[MSG:BT Started with %s]\r\n", _btname.c_str());
|
||||
grbl_sendf(CLIENT_ALL, "[MSG:BT Started with %s]\r\n", _btname.c_str());
|
||||
}
|
||||
|
||||
}else end();
|
||||
|
||||
} else end();
|
||||
}
|
||||
|
||||
/**
|
||||
* End WiFi
|
||||
* End WiFi
|
||||
*/
|
||||
void BTConfig::end() {
|
||||
SerialBT.end();
|
||||
@ -155,32 +145,29 @@ void BTConfig::end() {
|
||||
/**
|
||||
* Reset ESP
|
||||
*/
|
||||
void BTConfig::reset_settings(){
|
||||
void BTConfig::reset_settings() {
|
||||
Preferences prefs;
|
||||
prefs.begin(NAMESPACE, false);
|
||||
String sval;
|
||||
int8_t bbuf;
|
||||
bool error = false;
|
||||
sval = DEFAULT_BT_NAME;
|
||||
if (prefs.putString(BT_NAME_ENTRY, sval) == 0){
|
||||
if (prefs.putString(BT_NAME_ENTRY, sval) == 0)
|
||||
error = true;
|
||||
}
|
||||
bbuf = DEFAULT_RADIO_MODE;
|
||||
if (prefs.putChar(ESP_RADIO_MODE, bbuf) ==0 ) {
|
||||
if (prefs.putChar(ESP_RADIO_MODE, bbuf) == 0)
|
||||
error = true;
|
||||
}
|
||||
prefs.end();
|
||||
if (error) {
|
||||
grbl_send(CLIENT_ALL,"[MSG:BT reset error]\r\n");
|
||||
} else {
|
||||
grbl_send(CLIENT_ALL,"[MSG:BT reset done]\r\n");
|
||||
}
|
||||
if (error)
|
||||
grbl_send(CLIENT_ALL, "[MSG:BT reset error]\r\n");
|
||||
else
|
||||
grbl_send(CLIENT_ALL, "[MSG:BT reset done]\r\n");
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if BT is on and working
|
||||
*/
|
||||
bool BTConfig::Is_BT_on(){
|
||||
bool BTConfig::Is_BT_on() {
|
||||
return btStarted();
|
||||
}
|
||||
|
||||
@ -188,8 +175,8 @@ bool BTConfig::Is_BT_on(){
|
||||
* Handle not critical actions that must be done in sync environement
|
||||
*/
|
||||
void BTConfig::handle() {
|
||||
//If needed
|
||||
COMMANDS::wait(0);
|
||||
//If needed
|
||||
COMMANDS::wait(0);
|
||||
}
|
||||
|
||||
|
||||
|
@ -18,7 +18,7 @@
|
||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*/
|
||||
#if !defined(CONFIG_BT_ENABLED) || !defined(CONFIG_BLUEDROID_ENABLED)
|
||||
#error Bluetooth is not enabled! Please run `make menuconfig` to and enable it
|
||||
#error Bluetooth is not enabled! Please run `make menuconfig` to and enable it
|
||||
#endif
|
||||
|
||||
//Preferences entries
|
||||
@ -42,13 +42,13 @@
|
||||
extern BluetoothSerial SerialBT;
|
||||
|
||||
class BTConfig {
|
||||
public:
|
||||
public:
|
||||
BTConfig();
|
||||
~BTConfig();
|
||||
static const char *info();
|
||||
static const char* info();
|
||||
static void BTEvent(uint8_t event);
|
||||
static bool isBTnameValid (const char * hostname);
|
||||
static String BTname(){return _btname;}
|
||||
static bool isBTnameValid(const char* hostname);
|
||||
static String BTname() {return _btname;}
|
||||
static const char* device_address();
|
||||
static void begin();
|
||||
static void end();
|
||||
@ -56,7 +56,7 @@ public:
|
||||
static void reset_settings();
|
||||
static bool Is_BT_on();
|
||||
static String _btclient;
|
||||
private :
|
||||
private :
|
||||
static String _btname;
|
||||
};
|
||||
|
||||
|
345
Grbl_Esp32/Custom/atari_1020.cpp
Normal file
345
Grbl_Esp32/Custom/atari_1020.cpp
Normal file
@ -0,0 +1,345 @@
|
||||
/*
|
||||
atari_1020.cpp
|
||||
Part of Grbl_ESP32
|
||||
|
||||
copyright (c) 2018 - Bart Dring This file was modified for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
--------------------------------------------------------------
|
||||
|
||||
This contains all the special features required to control an
|
||||
Atari 1010 Pen Plotter
|
||||
*/
|
||||
|
||||
// This file is enabled by defining CUSTOM_CODE_FILENAME "atari_1020.cpp"
|
||||
// in Machines/atari_1020.h, thus causing this file to be included
|
||||
// from ../custom_code.cpp
|
||||
|
||||
#define HOMING_PHASE_FULL_APPROACH 0 // move to right end
|
||||
#define HOMING_PHASE_CHECK 1 // check reed switch
|
||||
#define HOMING_PHASE_RETRACT 2 // retract
|
||||
#define HOMING_PHASE_SHORT_APPROACH 3 // retract
|
||||
|
||||
static TaskHandle_t solenoidSyncTaskHandle = 0;
|
||||
static TaskHandle_t atariHomingTaskHandle = 0;
|
||||
uint16_t solenoid_pull_count;
|
||||
bool atari_homing = false;
|
||||
uint8_t homing_phase = HOMING_PHASE_FULL_APPROACH;
|
||||
uint8_t current_tool;
|
||||
|
||||
void machine_init()
|
||||
{
|
||||
solenoid_pull_count = 0; // initialize
|
||||
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Atari 1020 Solenoid");
|
||||
|
||||
// setup PWM channel
|
||||
ledcSetup(SOLENOID_CHANNEL_NUM, SOLENOID_PWM_FREQ, SOLENOID_PWM_RES_BITS);
|
||||
ledcAttachPin(SOLENOID_PEN_PIN, SOLENOID_CHANNEL_NUM);
|
||||
|
||||
pinMode(SOLENOID_DIRECTION_PIN, OUTPUT); // this sets the direction of the solenoid current
|
||||
pinMode(REED_SW_PIN, INPUT_PULLUP); // external pullup required
|
||||
|
||||
// setup a task that will calculate solenoid position
|
||||
xTaskCreatePinnedToCore(solenoidSyncTask, // task
|
||||
"solenoidSyncTask", // name for task
|
||||
4096, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&solenoidSyncTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
// setup a task that will do the custom homing sequence
|
||||
xTaskCreatePinnedToCore(atari_home_task, // task
|
||||
"atari_home_task", // name for task
|
||||
4096, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&atariHomingTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
}
|
||||
|
||||
// this task tracks the Z position and sets the solenoid
|
||||
void solenoidSyncTask(void *pvParameters)
|
||||
{
|
||||
int32_t current_position[N_AXIS]; // copy of current location
|
||||
float m_pos[N_AXIS]; // machine position in mm
|
||||
TickType_t xLastWakeTime;
|
||||
const TickType_t xSolenoidFrequency = SOLENOID_TASK_FREQ; // in ticks (typically ms)
|
||||
|
||||
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
|
||||
while (true)
|
||||
{ // don't ever return from this or the task dies
|
||||
|
||||
memcpy(current_position, sys_position, sizeof(sys_position)); // get current position in step
|
||||
system_convert_array_steps_to_mpos(m_pos, current_position); // convert to millimeters
|
||||
calc_solenoid(m_pos[Z_AXIS]); // calculate kinematics and move the servos
|
||||
|
||||
vTaskDelayUntil(&xLastWakeTime, xSolenoidFrequency);
|
||||
}
|
||||
}
|
||||
|
||||
// to do...have this return a true or false. This could be used by the normal homing feature to
|
||||
// continue with regular homing after setup
|
||||
// return true if this completes homing
|
||||
|
||||
bool user_defined_homing()
|
||||
{
|
||||
// create and start a task to do the special homing
|
||||
homing_phase = HOMING_PHASE_FULL_APPROACH;
|
||||
atari_homing = true;
|
||||
return true; // this does it...skip the rest of mc_homing_cycle(...)
|
||||
}
|
||||
|
||||
/*
|
||||
Do a custom homing routine.
|
||||
|
||||
A task is used because it needs to wait until until idle after each move.
|
||||
|
||||
1) Do a full travel move to the right. OK to stall if the pen started closer
|
||||
2) Check for pen 1
|
||||
3) If fail Retract
|
||||
4) move to right end
|
||||
5) Check...
|
||||
....repeat up to 12 times to try to find pen one
|
||||
|
||||
TODO can the retract, move back be 1 phase rather than 2?
|
||||
|
||||
*/
|
||||
void atari_home_task(void *pvParameters)
|
||||
{
|
||||
uint8_t homing_attempt = 0; // how many times have we tried to home
|
||||
TickType_t xLastWakeTime;
|
||||
const TickType_t xHomingTaskFrequency = 100; // in ticks (typically ms) .... need to make sure there is enough time to get out of idle
|
||||
char gcode_line[20];
|
||||
|
||||
while (true)
|
||||
{ // this task will only last as long as it is homing
|
||||
|
||||
if (atari_homing)
|
||||
{
|
||||
// must be in idle or alarm state
|
||||
if (sys.state == STATE_IDLE)
|
||||
{
|
||||
switch (homing_phase)
|
||||
{
|
||||
case HOMING_PHASE_FULL_APPROACH: // a full width move to insure it hits left end
|
||||
inputBuffer.push("G90G0Z1\r"); // lift the pen
|
||||
sprintf(gcode_line, "G91G0X%3.2f\r", -ATARI_PAPER_WIDTH + ATARI_HOME_POS - 3.0); // plus a little extra
|
||||
inputBuffer.push(gcode_line);
|
||||
homing_attempt = 1;
|
||||
homing_phase = HOMING_PHASE_CHECK;
|
||||
break;
|
||||
case HOMING_PHASE_CHECK: // check the limits switch
|
||||
if (digitalRead(REED_SW_PIN) == 0)
|
||||
{ // see if reed switch is grounded
|
||||
inputBuffer.push("G4P0.1\n"); // dramtic pause
|
||||
|
||||
sys_position[X_AXIS] = ATARI_HOME_POS * settings.steps_per_mm[X_AXIS];
|
||||
sys_position[Y_AXIS] = 0.0;
|
||||
sys_position[Z_AXIS] = 1.0 * settings.steps_per_mm[Y_AXIS];
|
||||
|
||||
gc_sync_position();
|
||||
plan_sync_position();
|
||||
|
||||
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls
|
||||
inputBuffer.push(gcode_line);
|
||||
|
||||
current_tool = 1; // local copy for reference...until actual M6 change
|
||||
gc_state.tool = current_tool;
|
||||
atari_homing = false; // done with homing sequence
|
||||
}
|
||||
else
|
||||
{
|
||||
homing_phase = HOMING_PHASE_RETRACT;
|
||||
homing_attempt++;
|
||||
}
|
||||
break;
|
||||
case HOMING_PHASE_RETRACT:
|
||||
sprintf(gcode_line, "G0X%3.2f\r", -ATARI_HOME_POS);
|
||||
inputBuffer.push(gcode_line);
|
||||
sprintf(gcode_line, "G0X%3.2f\r", ATARI_HOME_POS);
|
||||
inputBuffer.push(gcode_line);
|
||||
homing_phase = HOMING_PHASE_CHECK;
|
||||
break;
|
||||
default:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Homing phase error %d", homing_phase);
|
||||
atari_homing = false;
|
||||
; // kills task
|
||||
break;
|
||||
}
|
||||
|
||||
if (homing_attempt > ATARI_HOMING_ATTEMPTS)
|
||||
{ // try all positions plus 1
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Atari homing failed");
|
||||
inputBuffer.push("G90\r");
|
||||
atari_homing = false;
|
||||
;
|
||||
}
|
||||
}
|
||||
}
|
||||
vTaskDelayUntil(&xLastWakeTime, xHomingTaskFrequency);
|
||||
}
|
||||
}
|
||||
|
||||
// calculate and set the PWM value for the servo
|
||||
void calc_solenoid(float penZ)
|
||||
{
|
||||
bool isPenUp;
|
||||
static bool previousPenState = false;
|
||||
uint32_t solenoid_pen_pulse_len; // duty cycle of solenoid
|
||||
|
||||
isPenUp = ((penZ > 0) || (sys.state == STATE_ALARM)); // is pen above Z0 or is there an alarm
|
||||
|
||||
// if the state has not change, we only count down to the pull time
|
||||
if (previousPenState == isPenUp)
|
||||
{ // if state is unchanged
|
||||
if (solenoid_pull_count > 0)
|
||||
{
|
||||
solenoid_pull_count--;
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_PULL; // stay at full power while counting down
|
||||
}
|
||||
else
|
||||
{
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_HOLD; // pull in delay has expired so lower duty cycle
|
||||
}
|
||||
}
|
||||
else
|
||||
{ // pen direction has changed
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_PULL; // go to full power
|
||||
solenoid_pull_count = SOLENOID_PULL_DURATION; // set the time to count down
|
||||
}
|
||||
|
||||
previousPenState = isPenUp; // save the prev state
|
||||
|
||||
digitalWrite(SOLENOID_DIRECTION_PIN, isPenUp);
|
||||
|
||||
// skip setting value if it is unchanged
|
||||
if (ledcRead(SOLENOID_CHANNEL_NUM) == solenoid_pen_pulse_len)
|
||||
return;
|
||||
|
||||
// update the PWM value
|
||||
// ledcWrite appears to have issues with interrupts, so make this a critical section
|
||||
portMUX_TYPE myMutex = portMUX_INITIALIZER_UNLOCKED;
|
||||
portENTER_CRITICAL(&myMutex);
|
||||
ledcWrite(SOLENOID_CHANNEL_NUM, solenoid_pen_pulse_len);
|
||||
portEXIT_CRITICAL(&myMutex);
|
||||
}
|
||||
|
||||
/*
|
||||
A tool (pen) change is done by bumping the carriage against the right edge 3 times per
|
||||
position change. Pen 1-4 is valid range.
|
||||
*/
|
||||
void user_tool_change(uint8_t new_tool)
|
||||
{
|
||||
uint8_t move_count;
|
||||
char gcode_line[20];
|
||||
|
||||
protocol_buffer_synchronize(); // wait for all previous moves to complete
|
||||
|
||||
if ((new_tool < 1) || (new_tool > MAX_PEN_NUMBER))
|
||||
{
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Requested Pen#%d is out of 1-4 range", new_tool);
|
||||
return;
|
||||
}
|
||||
|
||||
if (new_tool == current_tool)
|
||||
return;
|
||||
|
||||
if (new_tool > current_tool)
|
||||
{
|
||||
move_count = BUMPS_PER_PEN_CHANGE * (new_tool - current_tool);
|
||||
}
|
||||
else
|
||||
{
|
||||
move_count = BUMPS_PER_PEN_CHANGE * ((MAX_PEN_NUMBER - current_tool) + new_tool);
|
||||
}
|
||||
sprintf(gcode_line, "G0Z%3.2f\r", ATARI_TOOL_CHANGE_Z); // go to tool change height
|
||||
inputBuffer.push(gcode_line);
|
||||
for (uint8_t i = 0; i < move_count; i++)
|
||||
{
|
||||
sprintf(gcode_line, "G0X%3.2f\r", ATARI_HOME_POS); //
|
||||
inputBuffer.push(gcode_line);
|
||||
inputBuffer.push("G0X0\r");
|
||||
}
|
||||
|
||||
current_tool = new_tool;
|
||||
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Change to Pen#%d", current_tool);
|
||||
}
|
||||
|
||||
// move from current tool to next tool....
|
||||
void atari_next_pen()
|
||||
{
|
||||
if (current_tool < MAX_PEN_NUMBER)
|
||||
{
|
||||
gc_state.tool = current_tool + 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
gc_state.tool = 1;
|
||||
}
|
||||
user_tool_change(gc_state.tool);
|
||||
}
|
||||
|
||||
// Polar coaster has macro buttons, this handles those button pushes.
|
||||
void user_defined_macro(uint8_t index)
|
||||
{
|
||||
char gcode_line[20];
|
||||
|
||||
switch (index)
|
||||
{
|
||||
#ifdef MACRO_BUTTON_0_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_0:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Pen switch");
|
||||
inputBuffer.push("$H\r");
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef MACRO_BUTTON_1_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_1:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Color switch");
|
||||
atari_next_pen();
|
||||
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls
|
||||
inputBuffer.push(gcode_line);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef MACRO_BUTTON_2_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_2:
|
||||
// feed out some paper and reset the Y 0
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Paper switch");
|
||||
inputBuffer.push("G0Y-25\r");
|
||||
inputBuffer.push("G4P0.1\r"); // sync...forces wait for planner to clear
|
||||
sys_position[Y_AXIS] = 0.0; // reset the Y position
|
||||
gc_sync_position();
|
||||
plan_sync_position();
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Unknown Switch %d", index);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void user_m30()
|
||||
{
|
||||
char gcode_line[20];
|
||||
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); //
|
||||
inputBuffer.push(gcode_line);
|
||||
}
|
172
Grbl_Esp32/Custom/custom_code_template.cpp
Normal file
172
Grbl_Esp32/Custom/custom_code_template.cpp
Normal file
@ -0,0 +1,172 @@
|
||||
/*
|
||||
custom_code_template.cpp (copy and use your machine name)
|
||||
Part of Grbl_ESP32
|
||||
|
||||
copyright (c) 2020 - Bart Dring. This file was intended for use on the ESP32
|
||||
|
||||
...add your date and name here.
|
||||
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
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_ESP32 is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
=======================================================================
|
||||
|
||||
This is a template for user-defined C++ code functions. Grbl can be
|
||||
configured to call some optional functions, enabled by #define statements
|
||||
in the machine definition .h file. Implement the functions thus enabled
|
||||
herein. The possible functions are listed and described below.
|
||||
|
||||
To use this file, copy it to a name of your own choosing, and also copy
|
||||
Machines/template.h to a similar name.
|
||||
|
||||
Example:
|
||||
Machines/my_machine.h
|
||||
Custom/my_machine.cpp
|
||||
|
||||
Edit machine.h to include your Machines/my_machine.h file
|
||||
|
||||
Edit Machines/my_machine.h according to the instructions therein.
|
||||
|
||||
Fill in the function definitions below for the functions that you have
|
||||
enabled with USE_ defines in Machines/my_machine.h
|
||||
|
||||
===============================================================================
|
||||
|
||||
*/
|
||||
|
||||
#ifdef USE_MACHINE_INIT
|
||||
/*
|
||||
machine_init() is called when Grbl_ESP32 first starts. You can use it to do any
|
||||
special things your machine needs at startup.
|
||||
*/
|
||||
void machine_init()
|
||||
{
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_CUSTOM_HOMING
|
||||
/*
|
||||
user_defined_homing() is called at the begining of the normal Grbl_ESP32 homing
|
||||
sequence. If user_defined_homing() returns false, the rest of normal Grbl_ESP32
|
||||
homing is skipped if it returns false, other normal homing continues. For
|
||||
example, if you need to manually prep the machine for homing, you could implement
|
||||
user_defined_homing() to wait for some button to be pressed, then return true.
|
||||
*/
|
||||
bool user_defined_homing()
|
||||
{
|
||||
// True = done with homing, false = continue with normal Grbl_ESP32 homing
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_KINEMATICS
|
||||
/*
|
||||
Inverse Kinematics converts X,Y,Z cartesian coordinate to the steps
|
||||
on your "joint" motors. It requires the following three functions:
|
||||
*/
|
||||
|
||||
/*
|
||||
inverse_kinematics() looks at incoming move commands and modifies
|
||||
them before Grbl_ESP32 puts them in the motion planner.
|
||||
|
||||
Grbl_ESP32 processes arcs by converting them into tiny little line segments.
|
||||
Kinematics in Grbl_ESP32 works the same way. Search for this function across
|
||||
Grbl_ESP32 for examples. You are basically converting cartesian X,Y,Z... targets to
|
||||
|
||||
target = an N_AXIS array of target positions (where the move is supposed to go)
|
||||
pl_data = planner data (see the definition of this type to see what it is)
|
||||
position = an N_AXIS array of where the machine is starting from for this move
|
||||
*/
|
||||
void inverse_kinematics(float *target, plan_line_data_t *pl_data, float *position)
|
||||
{
|
||||
// this simply moves to the target. Replace with your kinematics.
|
||||
mc_line(target, pl_data);
|
||||
}
|
||||
|
||||
/*
|
||||
kinematics_pre_homing() is called before normal homing
|
||||
You can use it to do special homing or just to set stuff up
|
||||
|
||||
cycle_mask is a bit mask of the axes being homed this time.
|
||||
*/
|
||||
bool kinematics_pre_homing(uint8_t cycle_mask))
|
||||
{
|
||||
return false; // finish normal homing cycle
|
||||
}
|
||||
|
||||
/*
|
||||
kinematics_post_homing() is called at the end of normal homing
|
||||
*/
|
||||
void kinematics_post_homing()
|
||||
{
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_FWD_KINEMATIC
|
||||
/*
|
||||
The status command uses forward_kinematics() to convert
|
||||
your motor positions to cartesian X,Y,Z... coordinates.
|
||||
|
||||
Convert the N_AXIS array of motor positions to cartesian in your code.
|
||||
*/
|
||||
void forward_kinematics(float *position)
|
||||
{
|
||||
// position[X_AXIS] =
|
||||
// position[Y_AXIS] =
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_TOOL_CHANGE
|
||||
/*
|
||||
user_tool_change() is called when tool change gcode is received,
|
||||
to perform appropriate actions for your machine.
|
||||
*/
|
||||
void user_tool_change(uint8_t new_tool)
|
||||
{
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(MACRO_BUTTON_0_PIN) || defined(MACRO_BUTTON_1_PIN) || defined(MACRO_BUTTON_2_PIN)
|
||||
/*
|
||||
options. user_defined_macro() is called with the button number to
|
||||
perform whatever actions you choose.
|
||||
*/
|
||||
void user_defined_macro(uint8_t index)
|
||||
{
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_M30
|
||||
/*
|
||||
user_m30() is called when an M30 gcode signals the end of a gcode file.
|
||||
*/
|
||||
void user_m30()
|
||||
{
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_MACHINE_TRINAMIC_INIT
|
||||
/*
|
||||
machine_triaminic_setup() replaces the normal setup of trinamic
|
||||
drivers with your own code. For example, you could setup StallGuard
|
||||
*/
|
||||
void machine_trinamic_setup()
|
||||
{
|
||||
}
|
||||
#endif
|
||||
|
||||
// If you add any additional functions specific to your machine that
|
||||
// require calls from common code, guard their calls in the common code with
|
||||
// #ifdef USE_WHATEVER and add function prototypes (also guarded) to grbl.h
|
258
Grbl_Esp32/Custom/polar_coaster.cpp
Normal file
258
Grbl_Esp32/Custom/polar_coaster.cpp
Normal file
@ -0,0 +1,258 @@
|
||||
/*
|
||||
polar_coaster.cpp - Implements simple inverse kinematics for Grbl_ESP32
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Copyright (c) 2019 Barton Dring @buildlog
|
||||
|
||||
|
||||
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/>.
|
||||
|
||||
Inverse kinematics determine the joint parameters required to get to a position
|
||||
in 3D space. Grbl will still work as 3 axes of steps, but these steps could
|
||||
represent angles, etc instead of linear units.
|
||||
|
||||
Unless forward kinematics are applied to the reporting, Grbl will report raw joint
|
||||
values instead of the normal Cartesian positions
|
||||
|
||||
How it works...
|
||||
|
||||
If you tell it to go to X10 Y10 Z10 in Cartesian space, for example, the equations
|
||||
will convert those values to the required joint values. In the case of a polar machine, X represents the radius,
|
||||
Y represents the polar degrees and Z would be unchanged.
|
||||
|
||||
In most cases, a straight line in Cartesian space could cause a curve in the new system.
|
||||
To fix this, the line is broken into very small segments and each segment is converted
|
||||
to the new space. While each segment is also distorted, the amount is so small it cannot be seen.
|
||||
|
||||
This segmentation is how normal Grbl draws arcs.
|
||||
|
||||
Feed Rate
|
||||
|
||||
Feed rate is given in steps/time. Due to the new coordinate units and non linearity issues, the
|
||||
feed rate may need to be adjusted. The ratio of the step distances in the original coordinate system
|
||||
determined and applied to the feed rate.
|
||||
|
||||
TODO:
|
||||
Add y offset, for completeness
|
||||
Add ZERO_NON_HOMED_AXES option
|
||||
|
||||
|
||||
*/
|
||||
|
||||
// This file is enabled by defining CUSTOM_CODE_FILENAME "polar_coaster.cpp"
|
||||
// in Machines/polar_coaster.h, thus causing this file to be included
|
||||
// from ../custom_code.cpp
|
||||
|
||||
|
||||
void calc_polar(float *target_xyz, float *polar, float last_angle);
|
||||
float abs_angle(float ang);
|
||||
|
||||
static float last_angle = 0;
|
||||
static float last_radius = 0;
|
||||
|
||||
// this get called before homing
|
||||
// return false to complete normal home
|
||||
// return true to exit normal homing
|
||||
bool kinematics_pre_homing(uint8_t cycle_mask) {
|
||||
// cycle mask not used for polar coaster
|
||||
// zero the axes that are not homed
|
||||
sys_position[Y_AXIS] = 0.0f;
|
||||
sys_position[Z_AXIS] = SERVO_Z_RANGE_MAX * settings.steps_per_mm[Z_AXIS]; // Move pen up.
|
||||
return false; // finish normal homing cycle
|
||||
}
|
||||
|
||||
void kinematics_post_homing() {
|
||||
// sync the X axis (do not need sync but make it for the fail safe)
|
||||
last_radius = sys_position[X_AXIS];
|
||||
// reset the internal angle value
|
||||
last_angle = 0;
|
||||
}
|
||||
|
||||
/*
|
||||
Apply inverse kinematics for a polar system
|
||||
|
||||
float target: The desired target location in machine space
|
||||
plan_line_data_t *pl_data: Plan information like feed rate, etc
|
||||
float *position: The previous "from" location of the move
|
||||
|
||||
Note: It is assumed only the radius axis (X) is homed and only X and Z have offsets
|
||||
|
||||
|
||||
*/
|
||||
void inverse_kinematics(float *target, plan_line_data_t *pl_data, float *position) {
|
||||
//static float last_angle = 0;
|
||||
//static float last_radius = 0;
|
||||
float dx, dy, dz; // distances in each cartesian axis
|
||||
float p_dx, p_dy, p_dz; // distances in each polar axis
|
||||
float dist, polar_dist; // the distances in both systems...used to determine feed rate
|
||||
uint32_t segment_count; // number of segments the move will be broken in to.
|
||||
float seg_target[N_AXIS]; // The target of the current segment
|
||||
float polar[N_AXIS]; // target location in polar coordinates
|
||||
float x_offset = gc_state.coord_system[X_AXIS] + gc_state.coord_offset[X_AXIS]; // offset from machine coordinate system
|
||||
float z_offset = gc_state.coord_system[Z_AXIS] + gc_state.coord_offset[Z_AXIS]; // offset from machine coordinate system
|
||||
//grbl_sendf(CLIENT_SERIAL, "Position: %4.2f %4.2f %4.2f \r\n", position[X_AXIS] - x_offset, position[Y_AXIS], position[Z_AXIS]);
|
||||
//grbl_sendf(CLIENT_SERIAL, "Target: %4.2f %4.2f %4.2f \r\n", target[X_AXIS] - x_offset, target[Y_AXIS], target[Z_AXIS]);
|
||||
// calculate cartesian move distance for each axis
|
||||
dx = target[X_AXIS] - position[X_AXIS];
|
||||
dy = target[Y_AXIS] - position[Y_AXIS];
|
||||
dz = target[Z_AXIS] - position[Z_AXIS];
|
||||
// calculate the total X,Y axis move distance
|
||||
// Z axis is the same in both coord systems, so it is ignored
|
||||
dist = sqrt((dx * dx) + (dy * dy) + (dz * dz));
|
||||
if (pl_data->condition & PL_COND_FLAG_RAPID_MOTION) {
|
||||
segment_count = 1; // rapid G0 motion is not used to draw, so skip the segmentation
|
||||
} else {
|
||||
segment_count = ceil(dist / SEGMENT_LENGTH); // determine the number of segments we need ... round up so there is at least 1
|
||||
}
|
||||
dist /= segment_count; // segment distance
|
||||
for (uint32_t segment = 1; segment <= segment_count; segment++) {
|
||||
// determine this segment's target
|
||||
seg_target[X_AXIS] = position[X_AXIS] + (dx / float(segment_count) * segment) - x_offset;
|
||||
seg_target[Y_AXIS] = position[Y_AXIS] + (dy / float(segment_count) * segment);
|
||||
seg_target[Z_AXIS] = position[Z_AXIS] + (dz / float(segment_count) * segment) - z_offset;
|
||||
calc_polar(seg_target, polar, last_angle);
|
||||
// begin determining new feed rate
|
||||
// calculate move distance for each axis
|
||||
p_dx = polar[RADIUS_AXIS] - last_radius;
|
||||
p_dy = polar[POLAR_AXIS] - last_angle;
|
||||
p_dz = dz;
|
||||
polar_dist = sqrt((p_dx * p_dx) + (p_dy * p_dy) + (p_dz * p_dz)); // calculate the total move distance
|
||||
float polar_rate_multiply = 1.0; // fail safe rate
|
||||
if (polar_dist == 0 || dist == 0) {
|
||||
// prevent 0 feed rate and division by 0
|
||||
polar_rate_multiply = 1.0; // default to same feed rate
|
||||
} else {
|
||||
// calc a feed rate multiplier
|
||||
polar_rate_multiply = polar_dist / dist;
|
||||
if (polar_rate_multiply < 0.5) {
|
||||
// prevent much slower speed
|
||||
polar_rate_multiply = 0.5;
|
||||
}
|
||||
}
|
||||
pl_data->feed_rate *= polar_rate_multiply; // apply the distance ratio between coord systems
|
||||
// end determining new feed rate
|
||||
polar[RADIUS_AXIS] += x_offset;
|
||||
polar[Z_AXIS] += z_offset;
|
||||
last_radius = polar[RADIUS_AXIS];
|
||||
last_angle = polar[POLAR_AXIS];
|
||||
mc_line(polar, pl_data);
|
||||
}
|
||||
// TO DO don't need a feedrate for rapids
|
||||
}
|
||||
|
||||
/*
|
||||
Forward kinematics converts position back to the original cartesian system. It is
|
||||
typically used for reporting
|
||||
|
||||
For example, on a polar machine, you tell it to go to a place like X10Y10. It
|
||||
converts to a radius and angle using inverse kinematics. The machine posiiton is now
|
||||
in those units X14.14 (radius) and Y45 (degrees). If you want to report those units as
|
||||
X10,Y10, you would use forward kinematics
|
||||
|
||||
position = the current machine position
|
||||
converted = position with forward kinematics applied.
|
||||
|
||||
*/
|
||||
void forward_kinematics(float *position) {
|
||||
float original_position[N_AXIS]; // temporary storage of original
|
||||
float print_position[N_AXIS];
|
||||
int32_t current_position[N_AXIS]; // Copy current state of the system position variable
|
||||
memcpy(current_position, sys_position, sizeof(sys_position));
|
||||
system_convert_array_steps_to_mpos(print_position, current_position);
|
||||
original_position[X_AXIS] = print_position[X_AXIS] - gc_state.coord_system[X_AXIS] + gc_state.coord_offset[X_AXIS];
|
||||
original_position[Y_AXIS] = print_position[Y_AXIS] - gc_state.coord_system[Y_AXIS] + gc_state.coord_offset[Y_AXIS];
|
||||
original_position[Z_AXIS] = print_position[Z_AXIS] - gc_state.coord_system[Z_AXIS] + gc_state.coord_offset[Z_AXIS];
|
||||
position[X_AXIS] = cos(radians(original_position[Y_AXIS])) * original_position[X_AXIS] * -1;
|
||||
position[Y_AXIS] = sin(radians(original_position[Y_AXIS])) * original_position[X_AXIS];
|
||||
position[Z_AXIS] = original_position[Z_AXIS]; // unchanged
|
||||
}
|
||||
|
||||
// helper functions
|
||||
|
||||
/*******************************************
|
||||
* Calculate polar values from Cartesian values
|
||||
* float target_xyz: An array of target axis positions in Cartesian (xyz) space
|
||||
* float polar: An array to return the polar values
|
||||
* float last_angle: The polar angle of the "from" point.
|
||||
*
|
||||
* Angle calculated is 0 to 360, but you don't want a line to go from 350 to 10. This would
|
||||
* be a long line backwards. You want it to go from 350 to 370. The same is true going the other way.
|
||||
*
|
||||
* This means the angle could accumulate to very high positive or negative values over the coarse of
|
||||
* a long job.
|
||||
*
|
||||
*/
|
||||
void calc_polar(float *target_xyz, float *polar, float last_angle) {
|
||||
float delta_ang; // the difference from the last and next angle
|
||||
polar[RADIUS_AXIS] = hypot_f(target_xyz[X_AXIS], target_xyz[Y_AXIS]);
|
||||
if (polar[RADIUS_AXIS] == 0) {
|
||||
polar[POLAR_AXIS] = last_angle; // don't care about angle at center
|
||||
} else {
|
||||
polar[POLAR_AXIS] = atan2(target_xyz[Y_AXIS], target_xyz[X_AXIS]) * 180.0 / M_PI;
|
||||
// no negative angles...we want the absolute angle not -90, use 270
|
||||
polar[POLAR_AXIS] = abs_angle(polar[POLAR_AXIS]);
|
||||
}
|
||||
polar[Z_AXIS] = target_xyz[Z_AXIS]; // Z is unchanged
|
||||
delta_ang = polar[POLAR_AXIS] - abs_angle(last_angle);
|
||||
// if the delta is above 180 degrees it means we are crossing the 0 degree line
|
||||
if (fabs(delta_ang) <= 180.0)
|
||||
polar[POLAR_AXIS] = last_angle + delta_ang;
|
||||
else {
|
||||
if (delta_ang > 0.0) {
|
||||
// crossing zero counter clockwise
|
||||
polar[POLAR_AXIS] = last_angle - (360.0 - delta_ang);
|
||||
} else
|
||||
polar[POLAR_AXIS] = last_angle + delta_ang + 360.0;
|
||||
}
|
||||
}
|
||||
|
||||
// Return a 0-360 angle ... fix above 360 and below zero
|
||||
float abs_angle(float ang) {
|
||||
ang = fmod(ang, 360.0); // 0-360 or 0 to -360
|
||||
if (ang < 0.0)
|
||||
ang = 360.0 + ang;
|
||||
return ang;
|
||||
}
|
||||
|
||||
// Polar coaster has macro buttons, this handles those button pushes.
|
||||
void user_defined_macro(uint8_t index) {
|
||||
switch (index) {
|
||||
#ifdef MACRO_BUTTON_0_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_0:
|
||||
inputBuffer.push("$H\r"); // home machine
|
||||
break;
|
||||
#endif
|
||||
#ifdef MACRO_BUTTON_1_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_1:
|
||||
inputBuffer.push("[ESP220]/1.nc\r"); // run SD card file 1.nc
|
||||
break;
|
||||
#endif
|
||||
#ifdef MACRO_BUTTON_2_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_2:
|
||||
inputBuffer.push("[ESP220]/2.nc\r"); // run SD card file 2.nc
|
||||
break;
|
||||
#endif
|
||||
#ifdef MACRO_BUTTON_3_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_3:
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// handle the M30 command
|
||||
void user_m30() {
|
||||
inputBuffer.push("$H\r");
|
||||
}
|
@ -2,10 +2,10 @@
|
||||
Grbl_ESP32.ino - 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 modified for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
@ -31,67 +31,61 @@ volatile uint8_t sys_rt_exec_alarm; // Global realtime executor bitflag variab
|
||||
volatile uint8_t sys_rt_exec_motion_override; // Global realtime executor bitflag variable for motion-based overrides.
|
||||
volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bitflag variable for spindle/coolant overrides.
|
||||
#ifdef DEBUG
|
||||
volatile uint8_t sys_rt_exec_debug;
|
||||
volatile uint8_t sys_rt_exec_debug;
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
void setup() {
|
||||
WiFi.persistent(false);
|
||||
WiFi.disconnect(true);
|
||||
WiFi.enableSTA (false);
|
||||
WiFi.enableAP (false);
|
||||
WiFi.mode (WIFI_OFF);
|
||||
|
||||
serial_init(); // Setup serial baud rate and interrupts
|
||||
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Compiled with ESP32 SDK:%s", ESP.getSdkVersion()); // print the SDK version
|
||||
|
||||
#ifdef CPU_MAP_NAME // show the map name at startup
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Using cpu_map:%s", CPU_MAP_NAME);
|
||||
#endif
|
||||
|
||||
settings_init(); // Load Grbl settings from EEPROM
|
||||
|
||||
stepper_init(); // Configure stepper pins and interrupt timers
|
||||
system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files)
|
||||
|
||||
memset(sys_position,0,sizeof(sys_position)); // Clear machine position.
|
||||
|
||||
#ifdef USE_PEN_SERVO
|
||||
servo_init();
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERVO_AXES
|
||||
init_servos();
|
||||
#endif
|
||||
|
||||
#ifdef USE_PEN_SOLENOID
|
||||
solenoid_init();
|
||||
#endif
|
||||
|
||||
#ifdef USE_MACHINE_INIT
|
||||
machine_init(); // user supplied function for special initialization
|
||||
#endif
|
||||
|
||||
// Initialize system state.
|
||||
#ifdef FORCE_INITIALIZATION_ALARM
|
||||
WiFi.persistent(false);
|
||||
WiFi.disconnect(true);
|
||||
WiFi.enableSTA(false);
|
||||
WiFi.enableAP(false);
|
||||
WiFi.mode(WIFI_OFF);
|
||||
serial_init(); // Setup serial baud rate and interrupts
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Grbl_ESP32 Ver %s Date %s", GRBL_VERSION, GRBL_VERSION_BUILD); // print grbl_esp32 verion info
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Compiled with ESP32 SDK:%s", ESP.getSdkVersion()); // print the SDK version
|
||||
#ifdef MACHINE_NAME // show the map name at startup
|
||||
#ifdef MACHINE_EXTRA
|
||||
#define MACHINE_STRING MACHINE_NAME MACHINE_EXTRA
|
||||
#else
|
||||
#define MACHINE_STRING MACHINE_NAME
|
||||
#endif
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Using machine:%s", MACHINE_STRING);
|
||||
#endif
|
||||
settings_init(); // Load Grbl settings from EEPROM
|
||||
stepper_init(); // Configure stepper pins and interrupt timers
|
||||
system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files)
|
||||
memset(sys_position, 0, sizeof(sys_position)); // Clear machine position.
|
||||
#ifdef USE_PEN_SERVO
|
||||
servo_init();
|
||||
#endif
|
||||
#ifdef USE_SERVO_AXES
|
||||
init_servos();
|
||||
#endif
|
||||
#ifdef USE_PEN_SOLENOID
|
||||
solenoid_init();
|
||||
#endif
|
||||
#ifdef USE_MACHINE_INIT
|
||||
machine_init(); // user supplied function for special initialization
|
||||
#endif
|
||||
// Initialize system state.
|
||||
#ifdef FORCE_INITIALIZATION_ALARM
|
||||
// Force Grbl into an ALARM state upon a power-cycle or hard reset.
|
||||
sys.state = STATE_ALARM;
|
||||
#else
|
||||
#else
|
||||
sys.state = STATE_IDLE;
|
||||
#endif
|
||||
|
||||
// Check for power-up and set system alarm if homing is enabled to force homing cycle
|
||||
// by setting Grbl's alarm state. Alarm locks out all g-code commands, including the
|
||||
// startup scripts, but allows access to settings and internal commands. Only a homing
|
||||
// cycle '$H' or kill alarm locks '$X' will disable the alarm.
|
||||
// NOTE: The startup script will run after successful completion of the homing cycle, but
|
||||
// not after disabling the alarm locks. Prevents motion startup blocks from crashing into
|
||||
// things uncontrollably. Very bad.
|
||||
#ifdef HOMING_INIT_LOCK
|
||||
if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) { sys.state = STATE_ALARM; }
|
||||
#endif
|
||||
#endif
|
||||
// Check for power-up and set system alarm if homing is enabled to force homing cycle
|
||||
// by setting Grbl's alarm state. Alarm locks out all g-code commands, including the
|
||||
// startup scripts, but allows access to settings and internal commands. Only a homing
|
||||
// cycle '$H' or kill alarm locks '$X' will disable the alarm.
|
||||
// NOTE: The startup script will run after successful completion of the homing cycle, but
|
||||
// not after disabling the alarm locks. Prevents motion startup blocks from crashing into
|
||||
// things uncontrollably. Very bad.
|
||||
#ifdef HOMING_INIT_LOCK
|
||||
if (bit_istrue(settings.flags, BITFLAG_HOMING_ENABLE)) sys.state = STATE_ALARM;
|
||||
#endif
|
||||
#ifdef ENABLE_WIFI
|
||||
wifi_config.begin();
|
||||
#endif
|
||||
@ -101,44 +95,34 @@ void setup() {
|
||||
inputBuffer.begin();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
// Reset system variables.
|
||||
uint8_t prior_state = sys.state;
|
||||
memset(&sys, 0, sizeof(system_t)); // Clear system struct variable.
|
||||
sys.state = prior_state;
|
||||
sys.f_override = DEFAULT_FEED_OVERRIDE; // Set to 100%
|
||||
sys.r_override = DEFAULT_RAPID_OVERRIDE; // Set to 100%
|
||||
sys.spindle_speed_ovr = DEFAULT_SPINDLE_SPEED_OVERRIDE; // Set to 100%
|
||||
memset(sys_probe_position,0,sizeof(sys_probe_position)); // Clear probe position.
|
||||
sys_probe_state = 0;
|
||||
sys_rt_exec_state = 0;
|
||||
sys_rt_exec_alarm = 0;
|
||||
sys_rt_exec_motion_override = 0;
|
||||
sys_rt_exec_accessory_override = 0;
|
||||
|
||||
// Reset Grbl primary systems.
|
||||
serial_reset_read_buffer(CLIENT_ALL); // Clear serial read buffer
|
||||
|
||||
gc_init(); // Set g-code parser to default state
|
||||
|
||||
spindle_init();
|
||||
coolant_init();
|
||||
limits_init();
|
||||
probe_init();
|
||||
|
||||
plan_reset(); // Clear block buffer and planner variables
|
||||
st_reset(); // Clear stepper subsystem variables
|
||||
// Sync cleared gcode and planner positions to current system position.
|
||||
plan_sync_position();
|
||||
gc_sync_position();
|
||||
|
||||
|
||||
|
||||
// put your main code here, to run repeatedly:
|
||||
report_init_message(CLIENT_ALL);
|
||||
|
||||
// Start Grbl main loop. Processes program inputs and executes them.
|
||||
protocol_main_loop();
|
||||
|
||||
void loop() {
|
||||
// Reset system variables.
|
||||
uint8_t prior_state = sys.state;
|
||||
memset(&sys, 0, sizeof(system_t)); // Clear system struct variable.
|
||||
sys.state = prior_state;
|
||||
sys.f_override = DEFAULT_FEED_OVERRIDE; // Set to 100%
|
||||
sys.r_override = DEFAULT_RAPID_OVERRIDE; // Set to 100%
|
||||
sys.spindle_speed_ovr = DEFAULT_SPINDLE_SPEED_OVERRIDE; // Set to 100%
|
||||
memset(sys_probe_position, 0, sizeof(sys_probe_position)); // Clear probe position.
|
||||
sys_probe_state = 0;
|
||||
sys_rt_exec_state = 0;
|
||||
sys_rt_exec_alarm = 0;
|
||||
sys_rt_exec_motion_override = 0;
|
||||
sys_rt_exec_accessory_override = 0;
|
||||
// Reset Grbl primary systems.
|
||||
serial_reset_read_buffer(CLIENT_ALL); // Clear serial read buffer
|
||||
gc_init(); // Set g-code parser to default state
|
||||
spindle_init();
|
||||
coolant_init();
|
||||
limits_init();
|
||||
probe_init();
|
||||
plan_reset(); // Clear block buffer and planner variables
|
||||
st_reset(); // Clear stepper subsystem variables
|
||||
// Sync cleared gcode and planner positions to current system position.
|
||||
plan_sync_position();
|
||||
gc_sync_position();
|
||||
// put your main code here, to run repeatedly:
|
||||
report_init_message(CLIENT_ALL);
|
||||
// Start Grbl main loop. Processes program inputs and executes them.
|
||||
protocol_main_loop();
|
||||
}
|
||||
|
52
Grbl_Esp32/Machines/3axis_v3.h
Normal file
52
Grbl_Esp32/Machines/3axis_v3.h
Normal file
@ -0,0 +1,52 @@
|
||||
/*
|
||||
3axis_v3.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the ESP32 Development Controller, v3.5.
|
||||
https://github.com/bdring/Grbl_ESP32_Development_Controller
|
||||
https://www.tindie.com/products/33366583/grbl_esp32-cnc-development-board-v35/
|
||||
|
||||
2018 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "MACHINE_ESP32_V3.5"
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||
#define Y_STEP_PIN GPIO_NUM_14
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||
#define Z_STEP_PIN GPIO_NUM_27
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_33
|
||||
|
||||
#define LIMIT_MASK B111
|
||||
#define X_LIMIT_PIN GPIO_NUM_2 // labeled X Limit
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4 // labeled Y Limit
|
||||
#define Z_LIMIT_PIN GPIO_NUM_15 // labeled Z Limit
|
||||
|
||||
// OK to comment out to use pin for other features
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_17 // labeled SpinPWM
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_22 // labeled SpinEnbl
|
||||
#define COOLANT_MIST_PIN GPIO_NUM_21 // labeled Mist
|
||||
#define COOLANT_FLOOD_PIN GPIO_NUM_16 // labeled Flood
|
||||
#define PROBE_PIN GPIO_NUM_32 // labeled Probe
|
||||
|
||||
#define CONTROL_SAFETY_DOOR_PIN GPIO_NUM_35 // labeled Door, needs external pullup
|
||||
#define CONTROL_RESET_PIN GPIO_NUM_34 // labeled Reset, needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // labeled Hold, needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // labeled Start, needs external pullup
|
52
Grbl_Esp32/Machines/3axis_v4.h
Normal file
52
Grbl_Esp32/Machines/3axis_v4.h
Normal file
@ -0,0 +1,52 @@
|
||||
/*
|
||||
3axis_v4.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the ESP32 Development Controller, v4.1 and later.
|
||||
https://github.com/bdring/Grbl_ESP32_Development_Controller
|
||||
https://www.tindie.com/products/33366583/grbl_esp32-cnc-development-board-v35/
|
||||
|
||||
2018 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "MACHINE_ESP32_V4"
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X_DIRECTION_PIN GPIO_NUM_14
|
||||
#define Y_STEP_PIN GPIO_NUM_26
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_15
|
||||
#define Z_STEP_PIN GPIO_NUM_27
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_33
|
||||
|
||||
#define LIMIT_MASK B111
|
||||
#define X_LIMIT_PIN GPIO_NUM_17
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||
#define Z_LIMIT_PIN GPIO_NUM_16
|
||||
|
||||
// OK to comment out to use pin for other features
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_2 // labeled SpinPWM
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_22 // labeled SpinEnbl
|
||||
#define MIST_PIN GPIO_NUM_21 // labeled Mist
|
||||
#define FLOOD_PIN GPIO_NUM_25 // labeled Flood
|
||||
#define PROBE_PIN GPIO_NUM_32 // labeled Probe
|
||||
|
||||
#define CONTROL_SAFETY_DOOR_PIN GPIO_NUM_35 // labeled Door, needs external pullup
|
||||
#define CONTROL_RESET_PIN GPIO_NUM_34 // labeled Reset, needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // labeled Hold, needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // labeled Start, needs external pullup
|
55
Grbl_Esp32/Machines/3axis_xyx.h
Normal file
55
Grbl_Esp32/Machines/3axis_xyx.h
Normal file
@ -0,0 +1,55 @@
|
||||
/*
|
||||
3axis_xyx.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the ESP32 Development Controller
|
||||
used to drive a dual motor gantry where the drivers
|
||||
labeled X, Y and Z drive the machine axes X, Y and X.
|
||||
https://github.com/bdring/Grbl_ESP32_Development_Controller
|
||||
https://www.tindie.com/products/33366583/grbl_esp32-cnc-development-board-v35/
|
||||
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "MACHINE_ESP32_V4_XYX"
|
||||
#define X_STEP_PIN GPIO_NUM_26 /* labeled Y */
|
||||
#define X_DIRECTION_PIN GPIO_NUM_15 /* labeled Y */
|
||||
#define Y_STEP_PIN GPIO_NUM_12 /* labeled X */
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_14 /* labeled X */
|
||||
#define Y2_STEP_PIN GPIO_NUM_27 /* labeled Z */
|
||||
#define Y2_DIRECTION_PIN GPIO_NUM_33 /* labeled Z */
|
||||
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_2
|
||||
|
||||
#define LIMIT_MASK B11
|
||||
#define X_LIMIT_PIN GPIO_NUM_17
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||
// #define Z_LIMIT_PIN GPIO_NUM_16
|
||||
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
#define COOLANT_MIST_PIN GPIO_NUM_21
|
||||
#define COOLANT_FLOOD_PIN GPIO_NUM_25
|
||||
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
|
||||
|
||||
// see versions for X and Z
|
||||
#define PROBE_PIN GPIO_NUM_32
|
||||
|
||||
#define CONTROL_SAFETY_DOOR_PIN GPIO_NUM_35 // needs external pullup
|
||||
#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup
|
62
Grbl_Esp32/Machines/4axis_external_driver.h
Normal file
62
Grbl_Esp32/Machines/4axis_external_driver.h
Normal file
@ -0,0 +1,62 @@
|
||||
/*
|
||||
external_driver_4x.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the buildlog.net 4-axis external driver board
|
||||
https://github.com/bdring/4_Axis_SPI_CNC
|
||||
|
||||
2018 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "External 4 Axis Driver Board"
|
||||
|
||||
#ifdef N_AXIS
|
||||
#undef N_AXIS
|
||||
#endif
|
||||
#define N_AXIS 4
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_0
|
||||
#define X_DIRECTION_PIN GPIO_NUM_2
|
||||
#define Y_STEP_PIN GPIO_NUM_26
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_15
|
||||
#define Z_STEP_PIN GPIO_NUM_27
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_33
|
||||
#define A_STEP_PIN GPIO_NUM_14
|
||||
#define A_DIRECTION_PIN GPIO_NUM_12
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_25
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
|
||||
|
||||
#define MODBUS_TX GPIO_NUM_17
|
||||
#define MODBUS_RX GPIO_NUM_4
|
||||
#define MODBUS_CTRL GPIO_NUM_16
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_34
|
||||
#define Y_LIMIT_PIN GPIO_NUM_35
|
||||
#define Z_LIMIT_PIN GPIO_NUM_36
|
||||
|
||||
#if (N_AXIS == 3)
|
||||
#define LIMIT_MASK B0111
|
||||
#else
|
||||
#define A_LIMIT_PIN GPIO_NUM_39
|
||||
#define LIMIT_MASK B1111
|
||||
#endif
|
||||
|
||||
#define PROBE_PIN GPIO_NUM_32
|
||||
#define COOLANT_MIST_PIN GPIO_NUM_21
|
61
Grbl_Esp32/Machines/add_esc_spindle.h
Normal file
61
Grbl_Esp32/Machines/add_esc_spindle.h
Normal file
@ -0,0 +1,61 @@
|
||||
/*
|
||||
add_esc_spindle.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
This is an additional configuration fragment that can be
|
||||
included after a base configuration file. The base file
|
||||
establishes most settings and the add-on changes a few things.
|
||||
For example, in machines.h, you would write:
|
||||
#include "Machines/3axis_v4.h" // Basic pin assignments
|
||||
#include "Machines/add_esc_spindle.h" // Add-ons for ESC spindle
|
||||
|
||||
This uses a Brushless DC Hobby motor as a spindle motor. See:
|
||||
https://github.com/bdring/Grbl_Esp32/wiki/BESC-Spindle-Feature
|
||||
|
||||
2019 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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/>.
|
||||
*/
|
||||
|
||||
|
||||
// MACHINE_EXTRA is appended to MACHINE_NAME for startup message display
|
||||
#define MACHINE_EXTRA "_ESC_SPINDLE"
|
||||
|
||||
#define SHOW_EXTENDED_SETTINGS
|
||||
|
||||
#define SPINDLE_PWM_BIT_PRECISION 16 // 16 bit recommended for ESC (don't change)
|
||||
|
||||
/*
|
||||
Important ESC Settings
|
||||
$33=50 // Hz this is the typical good frequency for an ESC
|
||||
#define DEFAULT_SPINDLE_FREQ 5000.0 // $33 Hz (extended set)
|
||||
|
||||
Determine the typical min and max pulse length of your ESC
|
||||
min_pulse is typically 1ms (0.001 sec) or less
|
||||
max_pulse is typically 2ms (0.002 sec) or more
|
||||
|
||||
determine PWM_period. It is (1/freq) if freq = 50...period = 0.02
|
||||
|
||||
determine pulse length for min_pulse and max_pulse in percent.
|
||||
|
||||
(pulse / PWM_period)
|
||||
min_pulse = (0.001 / 0.02) = 0.05 = 5% so ... $34 and $35 = 5.0
|
||||
max_pulse = (0.002 / .02) = 0.1 = 10% so ... $36=10
|
||||
*/
|
||||
|
||||
#define DEFAULT_SPINDLE_FREQ 50.0
|
||||
#define DEFAULT_SPINDLE_OFF_VALUE 5.0
|
||||
#define DEFAULT_SPINDLE_MIN_VALUE 5.0
|
||||
#define DEFAULT_SPINDLE_MAX_VALUE 10.0
|
170
Grbl_Esp32/Machines/atari_1020.h
Normal file
170
Grbl_Esp32/Machines/atari_1020.h
Normal file
@ -0,0 +1,170 @@
|
||||
/*
|
||||
atari_1020.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments and other configuration for an Atari 1020 pen plotter
|
||||
|
||||
The pen plotter uses several special options, including unipolar
|
||||
motors, custom homing and tool changing. The file atari_1020.cpp
|
||||
defines custom functions to handle the special features. As such,
|
||||
this file defines not only pin assignments but also many other
|
||||
things that are necessary to override default choices that are
|
||||
inappropriate for this particular machine.
|
||||
|
||||
2019 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "MACHINE_ATARI_1020"
|
||||
|
||||
#define CUSTOM_CODE_FILENAME "Custom/atari_1020.cpp"
|
||||
|
||||
#ifdef USE_RMT_STEPS
|
||||
#undef USE_RMT_STEPS
|
||||
#endif
|
||||
|
||||
#define USE_UNIPOLAR
|
||||
|
||||
#define X_UNIPOLAR
|
||||
#define X_PIN_PHASE_0 GPIO_NUM_13
|
||||
#define X_PIN_PHASE_1 GPIO_NUM_21
|
||||
#define X_PIN_PHASE_2 GPIO_NUM_16
|
||||
#define X_PIN_PHASE_3 GPIO_NUM_22
|
||||
|
||||
#define Y_UNIPOLAR
|
||||
#define Y_PIN_PHASE_0 GPIO_NUM_25
|
||||
#define Y_PIN_PHASE_1 GPIO_NUM_27
|
||||
#define Y_PIN_PHASE_2 GPIO_NUM_26
|
||||
#define Y_PIN_PHASE_3 GPIO_NUM_32
|
||||
|
||||
#define SOLENOID_DIRECTION_PIN GPIO_NUM_4
|
||||
#define SOLENOID_PEN_PIN GPIO_NUM_2
|
||||
#define SOLENOID_CHANNEL_NUM 6
|
||||
|
||||
#ifdef HOMING_CYCLE_0
|
||||
#undef HOMING_CYCLE_0
|
||||
#endif
|
||||
#define HOMING_CYCLE_0 (1 << X_AXIS) // this 'bot only homes the X axis
|
||||
#ifdef HOMING_CYCLE_1
|
||||
#undef HOMING_CYCLE_1
|
||||
#endif
|
||||
#ifdef HOMING_CYCLE_2
|
||||
#undef HOMING_CYCLE_2
|
||||
#endif
|
||||
|
||||
#define REED_SW_PIN GPIO_NUM_17
|
||||
#define LIMIT_MASK 0
|
||||
|
||||
#ifdef IGNORE_CONTROL_PINS // maybe set in config.h
|
||||
#undef IGNORE_CONTROL_PINS
|
||||
#endif
|
||||
|
||||
#ifndef ENABLE_CONTROL_SW_DEBOUNCE
|
||||
#define ENABLE_CONTROL_SW_DEBOUNCE
|
||||
#endif
|
||||
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef INVERT_CONTROL_PIN_MASK
|
||||
#endif
|
||||
#define INVERT_CONTROL_PIN_MASK B01110000
|
||||
|
||||
#define MACRO_BUTTON_0_PIN GPIO_NUM_34 // Pen Switch
|
||||
#define MACRO_BUTTON_1_PIN GPIO_NUM_35 // Color Switch
|
||||
#define MACRO_BUTTON_2_PIN GPIO_NUM_36 // Paper Switch
|
||||
|
||||
#ifdef DEFAULTS_GENERIC
|
||||
#undef DEFAULTS_GENERIC // undefine generic then define each default below
|
||||
#endif
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 200 // 200ms
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||
#define DEFAULT_REPORT_INCHES 0 // false
|
||||
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||
|
||||
#define DEFAULT_HOMING_ENABLE 1
|
||||
#define DEFAULT_HOMING_DIR_MASK 0
|
||||
#define DEFAULT_HOMING_FEED_RATE 3000.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 3000.0 // mm/min
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||
#define DEFAULT_HOMING_PULLOFF 2.0 // mm
|
||||
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
|
||||
#define DEFAULT_LASER_MODE 0 // false
|
||||
|
||||
#define DEFAULT_X_STEPS_PER_MM 10
|
||||
#define DEFAULT_Y_STEPS_PER_MM 10
|
||||
#define DEFAULT_Z_STEPS_PER_MM 100.0 // This is percent in servo mode
|
||||
|
||||
#define DEFAULT_X_MAX_RATE 5000.0 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE 5000.0 // mm/min
|
||||
#define DEFAULT_Z_MAX_RATE 200000.0 // mm/min
|
||||
|
||||
#define DEFAULT_X_ACCELERATION (500.0 * 60 * 60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (500.0 * 60 * 60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (500.0 * 60 * 60)
|
||||
|
||||
#define DEFAULT_X_MAX_TRAVEL 120.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Y_MAX_TRAVEL 20000.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Z_MAX_TRAVEL 10.0 // This is percent in servo mode
|
||||
|
||||
#define ATARI_1020
|
||||
|
||||
#define SOLENOID_PWM_FREQ 5000
|
||||
#define SOLENOID_PWM_RES_BITS 8
|
||||
|
||||
#define SOLENOID_PULSE_LEN_PULL 255
|
||||
#define SOLENOID_PULL_DURATION 50 // in task counts...after this delay power will change to hold level see SOLENOID_TASK_FREQ
|
||||
#define SOLENOID_PULSE_LEN_HOLD 40 // solenoid hold level ... typically a lower value to prevent overheating
|
||||
|
||||
#define SOLENOID_TASK_FREQ 50 // this is milliseconds
|
||||
|
||||
#define MAX_PEN_NUMBER 4
|
||||
#define BUMPS_PER_PEN_CHANGE 3
|
||||
|
||||
#define ATARI_HOME_POS -10.0f // this amound to the left of the paper 0
|
||||
#define ATARI_PAPER_WIDTH 100.0f //
|
||||
#define ATARI_HOMING_ATTEMPTS 13
|
||||
|
||||
// tells grbl we have some special functions to call
|
||||
#define USE_MACHINE_INIT
|
||||
#define USE_CUSTOM_HOMING
|
||||
#define USE_TOOL_CHANGE
|
||||
#define ATARI_TOOL_CHANGE_Z 5.0
|
||||
#define USE_M30 // use the user defined end of program
|
||||
|
||||
#ifndef atari_h
|
||||
#define atari_h
|
||||
|
||||
void solenoid_disable();
|
||||
void solenoidSyncTask(void *pvParameters);
|
||||
void calc_solenoid(float penZ);
|
||||
void atari_home_task(void *pvParameters);
|
||||
void atari_next_pen();
|
||||
#endif
|
1
Grbl_Esp32/Machines/custom_machine_template.h
Normal file
1
Grbl_Esp32/Machines/custom_machine_template.h
Normal file
@ -0,0 +1 @@
|
||||
// See template.h
|
58
Grbl_Esp32/Machines/espduino.h
Normal file
58
Grbl_Esp32/Machines/espduino.h
Normal file
@ -0,0 +1,58 @@
|
||||
/*
|
||||
espduino.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for ESPDUINO-32 Boards and Protoneer V3 boards
|
||||
Note: Probe pin is mapped, but will require a 10k external pullup to 3.3V to work.
|
||||
|
||||
Rebooting...See this issue https://github.com/bdring/Grbl_Esp32/issues/314
|
||||
!!!! Experimental Untested !!!!!
|
||||
|
||||
2019 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "MACHINE_ESPDUINO_32"
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_26
|
||||
#define X_DIRECTION_PIN GPIO_NUM_16
|
||||
|
||||
#define Y_STEP_PIN GPIO_NUM_25
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_27
|
||||
|
||||
#define Z_STEP_PIN GPIO_NUM_17
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_14
|
||||
|
||||
// OK to comment out to use pin for other features
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_12
|
||||
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_19
|
||||
#define SPINDLE_DIR_PIN GPIO_NUM_18
|
||||
|
||||
#define COOLANT_FLOOD_PIN GPIO_NUM_34
|
||||
#define COOLANT_MIST_PIN GPIO_NUM_36
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_13
|
||||
#define Y_LIMIT_PIN GPIO_NUM_5
|
||||
#define Z_LIMIT_PIN GPIO_NUM_19
|
||||
#define LIMIT_MASK B111
|
||||
|
||||
#define PROBE_PIN GPIO_NUM_39
|
||||
|
||||
// comment out #define IGNORE_CONTROL_PINS in config.h to use control pins
|
||||
#define CONTROL_RESET_PIN GPIO_NUM_2
|
||||
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_4
|
||||
#define CONTROL_CYCLE_START_PIN GPIO_NUM_35 // ESP32 needs external pullup
|
161
Grbl_Esp32/Machines/foo_6axis.h
Normal file
161
Grbl_Esp32/Machines/foo_6axis.h
Normal file
@ -0,0 +1,161 @@
|
||||
/*
|
||||
foo_6axis.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for a 6-axis system
|
||||
|
||||
2019 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "MACHINE_FOO_6X"
|
||||
|
||||
// Be sure to change to N_AXIS 6 in nuts_bolts.h
|
||||
#ifdef N_AXIS
|
||||
#undef N_AXIS
|
||||
#endif
|
||||
#define N_AXIS 6
|
||||
|
||||
// stepper motors
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||
|
||||
#define Y_STEP_PIN GPIO_NUM_14
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||
|
||||
// Z is a servo
|
||||
|
||||
#define A_STEP_PIN GPIO_NUM_27
|
||||
#define A_DIRECTION_PIN GPIO_NUM_33
|
||||
|
||||
#define B_STEP_PIN GPIO_NUM_15
|
||||
#define B_DIRECTION_PIN GPIO_NUM_32
|
||||
|
||||
// C is a servo
|
||||
|
||||
// servos
|
||||
#define USE_SERVO_AXES
|
||||
#define SERVO_Z_PIN GPIO_NUM_22
|
||||
#define SERVO_Z_CHANNEL_NUM 6
|
||||
#define SERVO_Z_RANGE_MIN 0.0
|
||||
#define SERVO_Z_RANGE_MAX 5.0
|
||||
#define SERVO_Z_HOMING_TYPE SERVO_HOMING_TARGET // during homing it will instantly move to a target value
|
||||
#define SERVO_Z_HOME_POS SERVO_Z_RANGE_MAX // move to max during homing
|
||||
#define SERVO_Z_MPOS false // will not use mpos, uses work coordinates
|
||||
|
||||
#define SERVO_C_PIN GPIO_NUM_2
|
||||
#define SERVO_C_CHANNEL_NUM 7
|
||||
#define SERVO_C_RANGE_MIN 0.0
|
||||
#define SERVO_C_RANGE_MAX 5.0
|
||||
#define SERVO_C_HOMING_TYPE SERVO_HOMING_TARGET // during homing it will instantly move to a target value
|
||||
#define SERVO_C_HOME_POS SERVO_C_RANGE_MAX // move to max during homing
|
||||
#define SERVO_C_MPOS false // will not use mpos, uses work coordinates
|
||||
|
||||
// limit switches
|
||||
#define X_LIMIT_PIN GPIO_NUM_21
|
||||
#define Y_LIMIT_PIN GPIO_NUM_17
|
||||
#define A_LIMIT_PIN GPIO_NUM_16
|
||||
#define B_LIMIT_PIN GPIO_NUM_4
|
||||
#define LIMIT_MASK B11011
|
||||
|
||||
// OK to comment out to use pin for other features
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
#ifdef HOMING_CYCLE_0 // undefine from config.h
|
||||
#undef HOMING_CYCLE_0
|
||||
#endif
|
||||
//#define HOMING_CYCLE_0 (1<<X_AXIS)
|
||||
#define HOMING_CYCLE_0 ((1<<X_AXIS)|(1<<Y_AXIS))
|
||||
//#define HOMING_CYCLE_0 ((1<<X_AXIS)|(1<<Y_AXIS) |(1<<A_AXIS)|(1<<B_AXIS))
|
||||
|
||||
#ifdef HOMING_CYCLE_1 // undefine from config.h
|
||||
#undef HOMING_CYCLE_1
|
||||
#endif
|
||||
//#define HOMING_CYCLE_1 (1<<A_AXIS)
|
||||
#define HOMING_CYCLE_1 ((1<<A_AXIS)|(1<<B_AXIS))
|
||||
|
||||
#ifdef HOMING_CYCLE_2 // undefine from config.h
|
||||
#undef HOMING_CYCLE_2
|
||||
#endif
|
||||
/*
|
||||
#define HOMING_CYCLE_2 (1<<Y_AXIS)
|
||||
|
||||
#ifdef HOMING_CYCLE_3 // undefine from config.h
|
||||
#undef HOMING_CYCLE_3
|
||||
#endif
|
||||
#define HOMING_CYCLE_3 (1<<B_AXIS)
|
||||
*/
|
||||
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 200 // 200ms
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 2 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||
#define DEFAULT_REPORT_INCHES 0 // false
|
||||
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||
|
||||
#define DEFAULT_HOMING_ENABLE 1
|
||||
#define DEFAULT_HOMING_DIR_MASK 17
|
||||
#define DEFAULT_HOMING_FEED_RATE 200.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 2000.0 // mm/min
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||
#define DEFAULT_HOMING_PULLOFF 3.0 // mm
|
||||
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
|
||||
#define DEFAULT_LASER_MODE 0 // false
|
||||
|
||||
#define DEFAULT_X_STEPS_PER_MM 400.0
|
||||
#define DEFAULT_Y_STEPS_PER_MM 400.0
|
||||
#define DEFAULT_Z_STEPS_PER_MM 100.0 // This is percent in servo mode
|
||||
#define DEFAULT_A_STEPS_PER_MM 400.0
|
||||
#define DEFAULT_B_STEPS_PER_MM 400.0
|
||||
#define DEFAULT_C_STEPS_PER_MM 100.0 // This is percent in servo mode
|
||||
|
||||
|
||||
#define DEFAULT_X_MAX_RATE 30000.0 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE 30000.0 // mm/min
|
||||
#define DEFAULT_Z_MAX_RATE 8000.0 // mm/min
|
||||
#define DEFAULT_A_MAX_RATE 30000.0 // mm/min
|
||||
#define DEFAULT_B_MAX_RATE 30000.0 // mm/min
|
||||
#define DEFAULT_C_MAX_RATE 8000.0 // mm/min
|
||||
|
||||
#define DEFAULT_X_ACCELERATION (1500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (1500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (100.0*60*60)
|
||||
#define DEFAULT_A_ACCELERATION (1500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_B_ACCELERATION (1500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_C_ACCELERATION (100.0*60*60)
|
||||
|
||||
#define DEFAULT_X_MAX_TRAVEL 250.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Y_MAX_TRAVEL 250.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Z_MAX_TRAVEL 100.0 // This is percent in servo mode
|
||||
#define DEFAULT_A_MAX_TRAVEL 250.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_B_MAX_TRAVEL 250.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_C_MAX_TRAVEL 100.0 // This is percent in servo mode
|
||||
|
84
Grbl_Esp32/Machines/lowrider_v1p2.h
Normal file
84
Grbl_Esp32/Machines/lowrider_v1p2.h
Normal file
@ -0,0 +1,84 @@
|
||||
/*
|
||||
lowrider.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the Buildlog.net MPCNC controller
|
||||
used in lowrider mode. Low rider has (2) Y and Z and one X motor
|
||||
These will not match the silkscreen or schematic descriptions...see definitions below
|
||||
https://github.com/bdring/Grbl_ESP32_MPCNC_Controller
|
||||
|
||||
2019 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "MACHINE_LOWRIDER_V1P2"
|
||||
|
||||
#define USE_GANGED_AXES // allow two motors on an axis
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_27 // use Z labeled connector
|
||||
#define X_DIRECTION_PIN GPIO_NUM_33 // use Z labeled connector
|
||||
|
||||
#define Y_STEP_PIN GPIO_NUM_14
|
||||
#define Y2_STEP_PIN GPIO_NUM_21 // ganged motor
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||
#define Y_AXIS_SQUARING
|
||||
|
||||
#define Z_STEP_PIN GPIO_NUM_12 // use X labeled connector
|
||||
#define Z2_STEP_PIN GPIO_NUM_22 // use X labeled connector
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_26 // use X labeled connector
|
||||
#define Z_AXIS_SQUARING
|
||||
|
||||
// OK to comment out to use pin for other features
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
// Note: if you use PWM rather than relay, you could map GPIO_NUM_2 to mist or flood
|
||||
//#define USE_SPINDLE_RELAY
|
||||
|
||||
#ifdef USE_SPINDLE_RELAY
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_2
|
||||
#else
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_16
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_32
|
||||
#endif
|
||||
|
||||
// Note: Only uncomment this if USE_SPINDLE_RELAY is commented out.
|
||||
// Relay can be used for Spindle or Coolant
|
||||
//#define COOLANT_FLOOD_PIN GPIO_NUM_17
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_15
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||
#define Z_LIMIT_PIN GPIO_NUM_17
|
||||
|
||||
#define LIMIT_MASK B111
|
||||
|
||||
#ifndef ENABLE_SOFTWARE_DEBOUNCE // V1P2 does not have R/C filters
|
||||
#define ENABLE_SOFTWARE_DEBOUNCE
|
||||
#endif
|
||||
|
||||
|
||||
// The default value in config.h is wrong for this controller
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef INVERT_CONTROL_PIN_MASK
|
||||
#endif
|
||||
|
||||
#define INVERT_CONTROL_PIN_MASK B1110
|
||||
|
||||
// Note: check the #define IGNORE_CONTROL_PINS is the way you want in config.h
|
||||
#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup
|
123
Grbl_Esp32/Machines/midtbot.h
Normal file
123
Grbl_Esp32/Machines/midtbot.h
Normal file
@ -0,0 +1,123 @@
|
||||
/*
|
||||
midtbot.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the Buildlog.net midtbot
|
||||
https://github.com/bdring/midTbot_esp32
|
||||
|
||||
2018 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "MACHINE_MIDTBOT"
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define Y_STEP_PIN GPIO_NUM_14
|
||||
|
||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||
|
||||
#ifndef COREXY // maybe set in config.h
|
||||
#define COREXY
|
||||
#endif
|
||||
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_2
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||
#define LIMIT_MASK B11
|
||||
|
||||
#ifndef USE_SERVO_AXES // maybe set in config.h
|
||||
#define USE_SERVO_AXES
|
||||
#endif
|
||||
|
||||
#define SERVO_Z_PIN GPIO_NUM_27
|
||||
#define SERVO_Z_CHANNEL_NUM 5
|
||||
#define SERVO_Z_RANGE_MIN 0.0
|
||||
#define SERVO_Z_RANGE_MAX 5.0
|
||||
#define SERVO_Z_HOMING_TYPE SERVO_HOMING_TARGET // during homing it will instantly move to a target value
|
||||
#define SERVO_Z_HOME_POS SERVO_Z_RANGE_MAX // move to max during homing
|
||||
#define SERVO_Z_MPOS false // will not use mpos, uses work coordinates
|
||||
|
||||
#ifndef IGNORE_CONTROL_PINS // maybe set in config.h
|
||||
#define IGNORE_CONTROL_PINS
|
||||
#endif
|
||||
|
||||
// redefine some stuff from config.h
|
||||
#ifdef HOMING_CYCLE_0
|
||||
#undef HOMING_CYCLE_0
|
||||
#endif
|
||||
|
||||
#define HOMING_CYCLE_0 (1<<Y_AXIS)
|
||||
|
||||
#ifdef HOMING_CYCLE_1
|
||||
#undef HOMING_CYCLE_1
|
||||
#endif
|
||||
|
||||
#define HOMING_CYCLE_1 (1<<X_AXIS)
|
||||
|
||||
#ifdef HOMING_CYCLE_2
|
||||
#undef HOMING_CYCLE_2
|
||||
#endif
|
||||
|
||||
#define SERVO_PEN_PIN GPIO_NUM_27
|
||||
|
||||
// defaults
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // stay on
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 2 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||
#define DEFAULT_REPORT_INCHES 0 // false
|
||||
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||
|
||||
#define DEFAULT_HOMING_ENABLE 1
|
||||
#define DEFAULT_HOMING_DIR_MASK 1
|
||||
#define DEFAULT_HOMING_FEED_RATE 200.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 1000.0 // mm/min
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||
#define DEFAULT_HOMING_PULLOFF 3.0 // mm
|
||||
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
|
||||
#define DEFAULT_LASER_MODE 0 // false
|
||||
|
||||
#define DEFAULT_X_STEPS_PER_MM 200.0
|
||||
#define DEFAULT_Y_STEPS_PER_MM 100.0
|
||||
#define DEFAULT_Z_STEPS_PER_MM 100.0 // This is percent in servo mode
|
||||
|
||||
#define DEFAULT_X_MAX_RATE 8000.0 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE 8000.0 // mm/min
|
||||
#define DEFAULT_Z_MAX_RATE 5000.0 // mm/min
|
||||
|
||||
#define DEFAULT_X_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (100.0*60*60)
|
||||
|
||||
#define DEFAULT_X_MAX_TRAVEL 100.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Y_MAX_TRAVEL 100.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Z_MAX_TRAVEL 100.0 // This is percent in servo mode
|
141
Grbl_Esp32/Machines/mpcnc_v1p1.h
Normal file
141
Grbl_Esp32/Machines/mpcnc_v1p1.h
Normal file
@ -0,0 +1,141 @@
|
||||
/*
|
||||
mpcnc.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the Buildlog.net MPCNC controller
|
||||
https://github.com/bdring/Grbl_ESP32_MPCNC_Controller
|
||||
|
||||
2019 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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/>.
|
||||
*/
|
||||
|
||||
// // Pin assignments for the Buildlog.net MPCNC controller
|
||||
|
||||
|
||||
#define MACHINE_NAME "MACHINE_MPCNC_V1P1"
|
||||
|
||||
#define USE_GANGED_AXES // allow two motors on an axis
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X2_STEP_PIN GPIO_NUM_22 // ganged motor
|
||||
#define X_AXIS_SQUARING
|
||||
|
||||
#define Y_STEP_PIN GPIO_NUM_14
|
||||
#define Y2_STEP_PIN GPIO_NUM_21 // ganged motor
|
||||
#define Y_AXIS_SQUARING
|
||||
|
||||
#define Z_STEP_PIN GPIO_NUM_27
|
||||
|
||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_33
|
||||
|
||||
// OK to comment out to use pin for other features
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
// Note: if you use PWM rather than relay, you could map GPIO_NUM_2 to mist or flood
|
||||
//#define USE_SPINDLE_RELAY
|
||||
|
||||
#ifdef USE_SPINDLE_RELAY
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_17
|
||||
#else
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_16
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_32
|
||||
#endif
|
||||
|
||||
// Note: Only uncomment this if USE_SPINDLE_RELAY is commented out.
|
||||
// Relay can be used for spindle or either coolant
|
||||
//#define COOLANT_FLOOD_PIN GPIO_NUM_2
|
||||
//#define COOLANT_MIST_PIN GPIO_NUM_2
|
||||
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_2
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||
#define Z_LIMIT_PIN GPIO_NUM_15
|
||||
#define LIMIT_MASK B111
|
||||
|
||||
#define PROBE_PIN GPIO_NUM_35
|
||||
|
||||
// The default value in config.h is wrong for this controller
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef INVERT_CONTROL_PIN_MASK
|
||||
#endif
|
||||
|
||||
#define INVERT_CONTROL_PIN_MASK B1110
|
||||
|
||||
// Note: default is #define IGNORE_CONTROL_PINS in config.h
|
||||
// uncomment to these lines to use them
|
||||
|
||||
/*
|
||||
#ifdef IGNORE_CONTROL_PINS
|
||||
#undef IGNORE_CONTROL_PINS
|
||||
#endif
|
||||
*/
|
||||
|
||||
#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup
|
||||
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // 255 = Keep steppers on
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||
#define DEFAULT_REPORT_INCHES 0 // false
|
||||
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||
|
||||
#define DEFAULT_HOMING_ENABLE 1 // false
|
||||
#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir Z,negative X,Y
|
||||
#define DEFAULT_HOMING_FEED_RATE 100.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 200.0 // mm/min
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||
#define DEFAULT_HOMING_PULLOFF 2.0 // mm
|
||||
|
||||
#ifdef USE_SPINDLE_RELAY
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1.0 // must be 1 so PWM duty is alway 100% to prevent relay damage
|
||||
#else
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // can be change to your spindle max
|
||||
#endif
|
||||
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
|
||||
#define DEFAULT_LASER_MODE 0 // false
|
||||
|
||||
#define DEFAULT_X_STEPS_PER_MM 200.0
|
||||
#define DEFAULT_Y_STEPS_PER_MM 200.0
|
||||
#define DEFAULT_Z_STEPS_PER_MM 800.0
|
||||
|
||||
#define DEFAULT_X_MAX_RATE 8000.0 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE 8000.0 // mm/min
|
||||
#define DEFAULT_Z_MAX_RATE 3000.0 // mm/min
|
||||
|
||||
#define DEFAULT_X_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (100.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
|
||||
#define DEFAULT_X_MAX_TRAVEL 500.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Y_MAX_TRAVEL 500.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Z_MAX_TRAVEL 80.0 // mm NOTE: Must be a positive value.
|
148
Grbl_Esp32/Machines/mpcnc_v1p2.h
Normal file
148
Grbl_Esp32/Machines/mpcnc_v1p2.h
Normal file
@ -0,0 +1,148 @@
|
||||
/*
|
||||
mpcnc.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the Buildlog.net MPCNC controller
|
||||
https://github.com/bdring/Grbl_ESP32_MPCNC_Controller
|
||||
|
||||
2019 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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/>.
|
||||
*/
|
||||
|
||||
// // Pin assignments for the Buildlog.net MPCNC controller
|
||||
|
||||
|
||||
|
||||
#define MACHINE_NAME "MACHINE_MPCNC_V1P2"
|
||||
|
||||
#define USE_GANGED_AXES // allow two motors on an axis
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X2_STEP_PIN GPIO_NUM_22 // ganged motor
|
||||
#define X_AXIS_SQUARING
|
||||
|
||||
#define Y_STEP_PIN GPIO_NUM_14
|
||||
#define Y2_STEP_PIN GPIO_NUM_21 // ganged motor
|
||||
#define Y_AXIS_SQUARING
|
||||
|
||||
#define Z_STEP_PIN GPIO_NUM_27
|
||||
|
||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_33
|
||||
|
||||
// OK to comment out to use pin for other features
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
// Note: if you use PWM rather than relay, you could map GPIO_NUM_2 to mist or flood
|
||||
//#define USE_SPINDLE_RELAY
|
||||
|
||||
#ifdef USE_SPINDLE_RELAY
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_2
|
||||
#else
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_16
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_32
|
||||
#endif
|
||||
|
||||
// Note: Only uncomment this if USE_SPINDLE_RELAY is commented out.
|
||||
// Relay can be used for spindle or either coolant
|
||||
//#define COOLANT_FLOOD_PIN GPIO_NUM_2
|
||||
//#define COOLANT_MIST_PIN GPIO_NUM_2
|
||||
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_17
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||
#define Z_LIMIT_PIN GPIO_NUM_15
|
||||
#define LIMIT_MASK B111
|
||||
|
||||
|
||||
#ifndef ENABLE_SOFTWARE_DEBOUNCE // V1P2 does not have R/C filters
|
||||
#define ENABLE_SOFTWARE_DEBOUNCE
|
||||
#endif
|
||||
|
||||
|
||||
#define PROBE_PIN GPIO_NUM_35
|
||||
|
||||
// The default value in config.h is wrong for this controller
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef INVERT_CONTROL_PIN_MASK
|
||||
#endif
|
||||
|
||||
#define INVERT_CONTROL_PIN_MASK B1110
|
||||
|
||||
// Note: default is #define IGNORE_CONTROL_PINS in config.h
|
||||
// uncomment to these lines to use them
|
||||
|
||||
/*
|
||||
#ifdef IGNORE_CONTROL_PINS
|
||||
#undef IGNORE_CONTROL_PINS
|
||||
#endif
|
||||
*/
|
||||
|
||||
#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup
|
||||
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // 255 = Keep steppers on
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||
#define DEFAULT_REPORT_INCHES 0 // false
|
||||
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||
|
||||
#define DEFAULT_HOMING_ENABLE 1 // false
|
||||
#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir Z,negative X,Y
|
||||
#define DEFAULT_HOMING_FEED_RATE 100.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 200.0 // mm/min
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||
#define DEFAULT_HOMING_PULLOFF 2.0 // mm
|
||||
|
||||
#ifdef USE_SPINDLE_RELAY
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1.0 // must be 1 so PWM duty is alway 100% to prevent relay damage
|
||||
#else
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // can be change to your spindle max
|
||||
#endif
|
||||
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
|
||||
#define DEFAULT_LASER_MODE 0 // false
|
||||
|
||||
#define DEFAULT_X_STEPS_PER_MM 200.0
|
||||
#define DEFAULT_Y_STEPS_PER_MM 200.0
|
||||
#define DEFAULT_Z_STEPS_PER_MM 800.0
|
||||
|
||||
#define DEFAULT_X_MAX_RATE 8000.0 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE 8000.0 // mm/min
|
||||
#define DEFAULT_Z_MAX_RATE 3000.0 // mm/min
|
||||
|
||||
#define DEFAULT_X_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (100.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
|
||||
#define DEFAULT_X_MAX_TRAVEL 500.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Y_MAX_TRAVEL 500.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Z_MAX_TRAVEL 80.0 // mm NOTE: Must be a positive value.
|
118
Grbl_Esp32/Machines/pen_laser.h
Normal file
118
Grbl_Esp32/Machines/pen_laser.h
Normal file
@ -0,0 +1,118 @@
|
||||
/*
|
||||
pen_laser.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pen assignments for the Buildlog.net pen laser controller V1 & V2
|
||||
|
||||
For pen mode be sure to uncomment #define USE_PEN_SERVO in config.h
|
||||
For solenoid mode be sure to uncomment #define USE_PEN_SERVO in config.h
|
||||
For laser mode, you do not need to change anything
|
||||
Note: You can use all 3 modes at the same time if you want
|
||||
|
||||
2019 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "MACHINE_PEN_LASER"
|
||||
|
||||
// Pick a board version
|
||||
//#define PEN_LASER_V1
|
||||
#define PEN_LASER_V2
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||
|
||||
#define Y_STEP_PIN GPIO_NUM_14
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
#ifdef PEN_LASER_V1
|
||||
#define X_LIMIT_PIN GPIO_NUM_2
|
||||
#endif
|
||||
#ifdef PEN_LASER_V2
|
||||
#define X_LIMIT_PIN GPIO_NUM_15
|
||||
#endif
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||
#define LIMIT_MASK B11
|
||||
|
||||
// If SPINDLE_PWM_PIN is commented out, this frees up the pin, but Grbl will still
|
||||
// use a virtual spindle. Do not comment out the other parameters for the spindle.
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_17 // Laser PWM
|
||||
|
||||
#define USING_SERVO // uncomment to use this feature
|
||||
//#define USING_SOLENOID // uncomment to use this feature
|
||||
|
||||
#ifdef USING_SERVO
|
||||
#define USE_SERVO_AXES
|
||||
#define SERVO_Z_PIN GPIO_NUM_27
|
||||
#define SERVO_Z_CHANNEL_NUM 3
|
||||
#define SERVO_Z_RANGE_MIN 0
|
||||
#define SERVO_Z_RANGE_MAX 10
|
||||
#endif
|
||||
|
||||
#ifdef USING_SOLENOID
|
||||
#define USE_PEN_SOLENOID
|
||||
#define SOLENOID_PEN_PIN GPIO_NUM_16
|
||||
#define SOLENOID_CHANNEL_NUM 6
|
||||
#endif
|
||||
|
||||
// defaults
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // stay on
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||
#define DEFAULT_REPORT_INCHES 0 // false
|
||||
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||
|
||||
#define DEFAULT_HOMING_ENABLE 0
|
||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir Z, negative X,Y
|
||||
#define DEFAULT_HOMING_FEED_RATE 200.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 1000.0 // mm/min
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||
#define DEFAULT_HOMING_PULLOFF 3.0 // mm
|
||||
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
|
||||
#define DEFAULT_LASER_MODE 0 // false
|
||||
|
||||
#define DEFAULT_X_STEPS_PER_MM 80
|
||||
#define DEFAULT_Y_STEPS_PER_MM 80
|
||||
#define DEFAULT_Z_STEPS_PER_MM 100.0 // This is percent in servo mode...used for calibration
|
||||
|
||||
#define DEFAULT_X_MAX_RATE 5000.0 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE 5000.0 // mm/min
|
||||
#define DEFAULT_Z_MAX_RATE 5000.0 // mm/min
|
||||
|
||||
#define DEFAULT_X_ACCELERATION (50.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (50.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (50.0*60*60)
|
||||
|
||||
#define DEFAULT_X_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Y_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Z_MAX_TRAVEL 100.0 // This is percent in servo mode...used for calibration
|
@ -1,58 +1,62 @@
|
||||
/*
|
||||
kinematics_polar_coaster.h - Implements simple kinematics for Grbl_ESP32
|
||||
Part of Grbl_ESP32
|
||||
polar_coaster.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Copyright (c) 2019 Barton Dring @buildlog
|
||||
|
||||
|
||||
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.
|
||||
Pin assignments and other configuration for the buildlog.net Polar Coaster.
|
||||
https://github.com/bdring/Polar-Coaster
|
||||
|
||||
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.
|
||||
2018 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
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 "MACHINE_POLAR_COASTER"
|
||||
|
||||
// This causes the custom code file to be included in the build
|
||||
// via ../custom_code.cpp
|
||||
#define CUSTOM_CODE_FILENAME "Custom/polar_coaster.cpp"
|
||||
|
||||
#define RADIUS_AXIS 0
|
||||
#define POLAR_AXIS 1
|
||||
|
||||
#define SEGMENT_LENGTH 0.5 // segment length in mm
|
||||
#define USE_KINEMATICS
|
||||
#define USE_FWD_KINEMATIC // report in cartesian
|
||||
#define USE_FWD_KINEMATIC // report in cartesian
|
||||
#define USE_M30
|
||||
|
||||
// ============= Begin CPU MAP ================
|
||||
#define CPU_MAP_NAME "CPU_MAP_POLAR_COASTER"
|
||||
#define X_STEP_PIN GPIO_NUM_15
|
||||
#define Y_STEP_PIN GPIO_NUM_2
|
||||
#define X_DIRECTION_PIN GPIO_NUM_25
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_26
|
||||
|
||||
#define USE_RMT_STEPS
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_15
|
||||
#define Y_STEP_PIN GPIO_NUM_2
|
||||
#define X_DIRECTION_PIN GPIO_NUM_25
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_26
|
||||
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_17
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_17
|
||||
|
||||
#ifndef USE_SERVO_AXES // maybe set in config.h
|
||||
#define USE_SERVO_AXES
|
||||
#endif
|
||||
|
||||
#define SERVO_Z_PIN GPIO_NUM_16
|
||||
#define SERVO_Z_CHANNEL_NUM 5
|
||||
#define SERVO_Z_RANGE_MIN 0.0
|
||||
#define SERVO_Z_RANGE_MAX 5.0
|
||||
#define SERVO_Z_HOMING_TYPE SERVO_HOMING_TARGET // during homing it will instantly move to a target value
|
||||
#define SERVO_Z_HOME_POS SERVO_Z_RANGE_MAX // move to max during homing
|
||||
#define SERVO_Z_MPOS false // will not use mpos, uses work coordinates
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_4
|
||||
#define LIMIT_MASK B1
|
||||
#define SERVO_Z_PIN GPIO_NUM_16
|
||||
#define SERVO_Z_CHANNEL_NUM 5
|
||||
#define SERVO_Z_RANGE_MIN 0.0
|
||||
#define SERVO_Z_RANGE_MAX 5.0
|
||||
#define SERVO_Z_HOMING_TYPE SERVO_HOMING_TARGET // during homing it will instantly move to a target value
|
||||
#define SERVO_Z_HOME_POS SERVO_Z_RANGE_MAX // move to max during homing
|
||||
#define SERVO_Z_MPOS false // will not use mpos, uses work coordinates
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_4
|
||||
#define LIMIT_MASK B1
|
||||
|
||||
#ifdef IGNORE_CONTROL_PINS // maybe set in config.h
|
||||
#undef IGNORE_CONTROL_PINS
|
||||
@ -70,12 +74,12 @@
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef INVERT_CONTROL_PIN_MASK
|
||||
#endif
|
||||
#define INVERT_CONTROL_PIN_MASK B11111111
|
||||
#define INVERT_CONTROL_PIN_MASK B11111111
|
||||
|
||||
#define MACRO_BUTTON_0_PIN GPIO_NUM_13
|
||||
#define MACRO_BUTTON_1_PIN GPIO_NUM_12
|
||||
#define MACRO_BUTTON_2_PIN GPIO_NUM_14
|
||||
|
||||
#define MACRO_BUTTON_0_PIN GPIO_NUM_13
|
||||
#define MACRO_BUTTON_1_PIN GPIO_NUM_12
|
||||
#define MACRO_BUTTON_2_PIN GPIO_NUM_14
|
||||
|
||||
// redefine some stuff from config.h
|
||||
#ifdef HOMING_CYCLE_0
|
||||
#undef HOMING_CYCLE_0
|
||||
@ -86,19 +90,19 @@
|
||||
#endif
|
||||
#ifdef HOMING_CYCLE_2
|
||||
#undef HOMING_CYCLE_2
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// ============= End CPU MAP ==================
|
||||
|
||||
// ============= Begin Default Settings ================
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // stay on
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 2 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 2 // MPos enabled
|
||||
|
||||
@ -109,7 +113,7 @@
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||
|
||||
#define DEFAULT_HOMING_ENABLE 1
|
||||
#define DEFAULT_HOMING_ENABLE 1
|
||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir Z, negative X,Y
|
||||
#define DEFAULT_HOMING_FEED_RATE 200.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 1000.0 // mm/min
|
||||
@ -131,26 +135,8 @@
|
||||
|
||||
#define DEFAULT_X_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (50.0*60*60)
|
||||
#define DEFAULT_Z_ACCELERATION (50.0*60*60)
|
||||
|
||||
#define DEFAULT_X_MAX_TRAVEL 50.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Y_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Z_MAX_TRAVEL 100.0 // This is percent in servo mode
|
||||
// ============= End Default Settings ==================
|
||||
|
||||
#ifndef kinematics_h
|
||||
#define kinematics_h
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
bool kinematics_pre_homing(uint8_t cycle_mask);
|
||||
void kinematics_post_homing();
|
||||
void inverse_kinematics(float *target, plan_line_data_t *pl_data, float *position);
|
||||
void calc_polar(float *target_xyz, float *polar, float last_angle);
|
||||
float abs_angle(float ang);
|
||||
void user_defined_macro(uint8_t index);
|
||||
|
||||
void forward_kinematics(float *position);
|
||||
void user_m30();
|
||||
|
||||
#endif
|
122
Grbl_Esp32/Machines/servo_axis.h
Normal file
122
Grbl_Esp32/Machines/servo_axis.h
Normal file
@ -0,0 +1,122 @@
|
||||
/*
|
||||
servo_axis.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the Buildlog.net pen laser controller V1
|
||||
using servos.
|
||||
|
||||
For pen mode be sure to uncomment #define USE_PEN_SERVO in config.h
|
||||
For solenoid mode be sure to uncomment #define USE_PEN_SERVO in config.h
|
||||
For laser mode, you do not need to change anything
|
||||
Note: You can use all 3 modes at the same time if you want
|
||||
|
||||
2018 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "MACHINE_SERVO_AXIS"
|
||||
|
||||
// Pick a board version
|
||||
//#define PEN_LASER_V1
|
||||
#define PEN_LASER_V2
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
#ifdef PEN_LASER_V1
|
||||
#define X_LIMIT_PIN GPIO_NUM_2
|
||||
#endif
|
||||
|
||||
#ifdef PEN_LASER_V2
|
||||
#define X_LIMIT_PIN GPIO_NUM_15
|
||||
#endif
|
||||
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||
#define LIMIT_MASK B11
|
||||
|
||||
// If SPINDLE_PWM_PIN is commented out, this frees up the pin, but Grbl will still
|
||||
// use a virtual spindle. Do not comment out the other parameters for the spindle.
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_17 // Laser PWM
|
||||
// PWM Generator is based on 80,000,000 Hz counter
|
||||
// Therefor the freq determines the resolution
|
||||
// 80,000,000 / freq = max resolution
|
||||
// For 5000 that is 80,000,000 / 5000 = 16000
|
||||
// round down to nearest bit count for SPINDLE_PWM_MAX_VALUE
|
||||
//#define SPINDLE_PWM_BASE_FREQ 5000 // Hz
|
||||
#define SPINDLE_PWM_OFF_VALUE 0
|
||||
|
||||
#ifndef SPINDLE_PWM_MIN_VALUE
|
||||
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
|
||||
#endif
|
||||
|
||||
#define SERVO_Y_PIN GPIO_NUM_14
|
||||
#define SERVO_Y_CHANNEL_NUM 6
|
||||
#define SERVO_Y_RANGE_MIN 0.0
|
||||
#define SERVO_Y_RANGE_MAX 30.0
|
||||
|
||||
#define SERVO_Z_PIN GPIO_NUM_27
|
||||
#define SERVO_Z_CHANNEL_NUM 5
|
||||
#define SERVO_Z_RANGE_MIN 0.0
|
||||
#define SERVO_Z_RANGE_MAX 20.0
|
||||
|
||||
// defaults
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // stay on
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||
#define DEFAULT_REPORT_INCHES 0 // false
|
||||
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||
|
||||
#define DEFAULT_HOMING_ENABLE 0
|
||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir Z, negative X,Y
|
||||
#define DEFAULT_HOMING_FEED_RATE 200.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 1000.0 // mm/min
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||
#define DEFAULT_HOMING_PULLOFF 3.0 // mm
|
||||
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
|
||||
#define DEFAULT_LASER_MODE 0 // false
|
||||
|
||||
#define DEFAULT_X_STEPS_PER_MM 40 // half turn on a stepper
|
||||
#define DEFAULT_Y_STEPS_PER_MM 100.0 // default calibration value
|
||||
#define DEFAULT_Z_STEPS_PER_MM 100.0 // default calibration value
|
||||
|
||||
#define DEFAULT_X_MAX_RATE 2000.0 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE 2000.0 // mm/min
|
||||
#define DEFAULT_Z_MAX_RATE 2000.0 // mm/min
|
||||
|
||||
#define DEFAULT_X_ACCELERATION (50.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (50.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (50.0*60*60)
|
||||
|
||||
#define DEFAULT_X_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Y_MAX_TRAVEL 100.0 // default calibration value
|
||||
#define DEFAULT_Z_MAX_TRAVEL 100.0 // default calibration value
|
100
Grbl_Esp32/Machines/spi_daisy_4axis.h
Normal file
100
Grbl_Esp32/Machines/spi_daisy_4axis.h
Normal file
@ -0,0 +1,100 @@
|
||||
/*
|
||||
spi_daisy_4axis.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for a 4-axis machine using Triaminic drivers
|
||||
in daisy-chained SPI mode.
|
||||
https://github.com/bdring/4_Axis_SPI_CNC
|
||||
|
||||
2019 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "SPI_DAISY_4X"
|
||||
|
||||
#ifdef N_AXIS
|
||||
#undef N_AXIS
|
||||
#endif
|
||||
#define N_AXIS 3 // can be 3 or 4. (if 3 install bypass jumper next to the A driver)
|
||||
|
||||
#define USE_TRINAMIC
|
||||
#define TRINAMIC_DAISY_CHAIN
|
||||
|
||||
// Use SPI enable instead of the enable pin
|
||||
// The hardware enable pin is tied to ground
|
||||
#define USE_TRINAMIC_ENABLE
|
||||
|
||||
// allow two motors on an axis
|
||||
#define USE_GANGED_AXES
|
||||
|
||||
#define X_DRIVER_TMC2130 // Which Driver Type?
|
||||
#define X_RSENSE 0.11f // .11 Ohm...typical of 2130 type 0.075 typical for TMC5160
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X_DIRECTION_PIN GPIO_NUM_14
|
||||
#define X2_STEP_PIN GPIO_NUM_33
|
||||
#define X2_DIRECTION_PIN GPIO_NUM_32
|
||||
#define X_TRINAMIC // using SPI control
|
||||
#define X_CS_PIN GPIO_NUM_17 // Daisy Chain, all share same CS pin
|
||||
|
||||
#define Y_DRIVER_TMC2130 // Which Driver Type?
|
||||
#define Y_RSENSE 0.11f // .11 Ohm...typical of 2130 type 0.075 typical for TMC5160
|
||||
#define Y_STEP_PIN GPIO_NUM_27
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_26
|
||||
#define Y_TRINAMIC // using SPI control
|
||||
#define Y_CS_PIN X_CS_PIN // Daisy Chain, all share same CS pin
|
||||
|
||||
#define Z_DRIVER_TMC2130 // Which Driver Type?
|
||||
#define Z_RSENSE 0.11f // .11 Ohm...typical of 2130 type 0.075 typical for TMC5160
|
||||
#define Z_STEP_PIN GPIO_NUM_15
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_2
|
||||
#define Z_TRINAMIC // using SPI control
|
||||
#define Z_CS_PIN X_CS_PIN // Daisy Chain, all share same CS pin
|
||||
|
||||
#if (N_AXIS == 4)
|
||||
#define A_DRIVER_TMC2130 // Which Driver Type?
|
||||
#define A_RSENSE 0.11f // .11 Ohm...typical of 2130 type 0.075 typical for TMC5160
|
||||
#define A_STEP_PIN GPIO_NUM_33
|
||||
#define A_DIRECTION_PIN GPIO_NUM_32
|
||||
#define A_TRINAMIC // using SPI control
|
||||
#define A_CS_PIN X_CS_PIN // Daisy Chain, all share same CS pin
|
||||
#endif
|
||||
|
||||
// Mist is a 3.3V output
|
||||
// Turn on with M7 and off with M9
|
||||
#define COOLANT_MIST_PIN GPIO_NUM_21
|
||||
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_25
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_4
|
||||
|
||||
// Relay operation
|
||||
// Install Jumper near relay
|
||||
// For spindle Use max RPM of 1
|
||||
// For PWM remove jumper and set MAX RPM to something higher ($30 setting)
|
||||
// Interlock jumper along top edge needs to be installed for both versions
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1 // Should be 1 for relay operation
|
||||
|
||||
#define PROBE_PIN GPIO_NUM_22
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_36
|
||||
#define Y_LIMIT_PIN GPIO_NUM_39
|
||||
#define Z_LIMIT_PIN GPIO_NUM_34
|
||||
|
||||
#if (N_AXIS == 4)
|
||||
#define A_LIMIT_PIN GPIO_NUM_35
|
||||
#define LIMIT_MASK B1111
|
||||
#else
|
||||
#define LIMIT_MASK B0111
|
||||
#endif
|
262
Grbl_Esp32/Machines/template.h
Normal file
262
Grbl_Esp32/Machines/template.h
Normal file
@ -0,0 +1,262 @@
|
||||
/*
|
||||
template.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Template for a machine configuration file.
|
||||
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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/>.
|
||||
*/
|
||||
|
||||
// This contains a long list of things that might possibly be
|
||||
// configured. Most machines - especially simple cartesian machines
|
||||
// that use stepper motors - will only need to define a few of the
|
||||
// options herein, often just the pin assignments.
|
||||
|
||||
// Pin assignments depend on how the ESP32 is connected to
|
||||
// the external machine. Typically the ESP32 module plugs into
|
||||
// an adapter board that wires specific ESP32 GPIO pins to
|
||||
// other connectors on the board, such as Pololu sockets for
|
||||
// stepper drivers or connectors for external drivers, limit
|
||||
// pins, spindle control, etc. This file describes how those
|
||||
// GPIO pins are wired to those other connectors.
|
||||
|
||||
// Some machines might choose to use an adapter board in a
|
||||
// non-standard way, for example a 3-axis board might have axes
|
||||
// labeled XYZ, but the machine might have only 2 axes one of which is
|
||||
// driven by two ganged motors. In that case, you would need
|
||||
// a custom version of this file that assigns the pins differently
|
||||
// from the adapter board labels.
|
||||
|
||||
// In addition to pin assignments, many other aspects of Grbl
|
||||
// can be configured, such as spindle speeds, special motor
|
||||
// types like servos and unipolars, homing order, default values
|
||||
// for $$ settings, etc. A detailed list of such options is
|
||||
// given below.
|
||||
|
||||
// Furthermore, it is possible to implement special complex
|
||||
// behavior in custom C++ code, for non-Cartesian machines,
|
||||
// unusual homing cycles, etc. See the Special Features section
|
||||
// below for additional instructions.
|
||||
|
||||
// === Machine Name
|
||||
// Change TEMPLATE to some name of your own choosing. That name
|
||||
// will be shown in a Grbl startup message to identify your
|
||||
// configuration.
|
||||
|
||||
#define MACHINE_NAME "MACHINE_TEMPLATE"
|
||||
|
||||
// If your machine requires custom code as described below in
|
||||
// Special Features, you must copy Custom/custom_code_template.cpp
|
||||
// to a new name like Custom/my_custom_code.cpp, implement the
|
||||
// functions therein, and enable its use by defining:
|
||||
// #define CUSTOM_CODE_FILENAME "Custom/my_custom_code.cpp"
|
||||
|
||||
// === Number of axes
|
||||
|
||||
// You can set the number of axes that the machine supports
|
||||
// by defining N_AXIS. If you do not define it, 3 will be
|
||||
// used. The value must be at least 3, even if your machine
|
||||
// has fewer axes.
|
||||
// #define N_AXIS 4
|
||||
|
||||
|
||||
// == Pin Assignments
|
||||
|
||||
// Step and direction pins; these must be output-capable pins,
|
||||
// specifically ESP32 GPIO numbers 0..31
|
||||
// #define X_STEP_PIN GPIO_NUM_12
|
||||
// #define X_DIRECTION_PIN GPIO_NUM_14
|
||||
// #define Y_STEP_PIN GPIO_NUM_26
|
||||
// #define Y_DIRECTION_PIN GPIO_NUM_15
|
||||
// #define Z_STEP_PIN GPIO_NUM_27
|
||||
// #define Z_DIRECTION_PIN GPIO_NUM_33
|
||||
|
||||
// The 1 bits in LIMIT_MASK set the axes that have limit switches
|
||||
// For example, if the Y axis has no limit switches but the
|
||||
// X, Z, A and B axes do, the LIMIT_MASK value would be B11101
|
||||
// #define LIMIT_MASK B111
|
||||
|
||||
// #define X_LIMIT_PIN GPIO_NUM_17
|
||||
// #define Y_LIMIT_PIN GPIO_NUM_4
|
||||
// #define Z_LIMIT_PIN GPIO_NUM_16
|
||||
|
||||
// Common enable for all steppers. If it is okay to leave
|
||||
// your drivers enabled at all times, you can leave
|
||||
// STEPPERS_DISABLE_PIN undefined and use the pin for something else.
|
||||
// #define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
// Pins for controlling various aspects of the machine. If your
|
||||
// machine does not support one of these features, you can leave
|
||||
// the corresponding pin undefined.
|
||||
|
||||
// #define SPINDLE_PWM_PIN GPIO_NUM_2 // labeled SpinPWM
|
||||
// #define SPINDLE_ENABLE_PIN GPIO_NUM_22 // labeled SpinEnbl
|
||||
// #define COOLANT_MIST_PIN GPIO_NUM_21 // labeled Mist
|
||||
// #define COOLANT_FLOOD_PIN GPIO_NUM_25 // labeled Flood
|
||||
// #define PROBE_PIN GPIO_NUM_32 // labeled Probe
|
||||
|
||||
// Input pins for various functions. If the corresponding pin is not defined,
|
||||
// the function will not be available.
|
||||
|
||||
// CONTROL_SAFETY_DOOR_PIN shuts off the machine when a door is opened
|
||||
// or some other unsafe condition exists.
|
||||
// #define CONTROL_SAFETY_DOOR_PIN GPIO_NUM_35 // labeled Door, needs external pullup
|
||||
|
||||
// RESET, FEED_HOLD, and CYCLE_START can control GCode execution at
|
||||
// the push of a button.
|
||||
|
||||
// #define CONTROL_RESET_PIN GPIO_NUM_34 // labeled Reset, needs external pullup
|
||||
// #define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // labeled Hold, needs external pullup
|
||||
// #define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // labeled Start, needs external pullup
|
||||
|
||||
// === Ganging
|
||||
// If you need to use two motors on one axis, you can "gang" the motors by
|
||||
// defining a second pin to control the other motor on the axis. For example:
|
||||
|
||||
// #define Y2_STEP_PIN GPIO_NUM_27 /* labeled Z */
|
||||
// #define Y2_DIRECTION_PIN GPIO_NUM_33 /* labeled Z */
|
||||
|
||||
// === Servos
|
||||
// To use a servo motor on an axis, do not define step and direction
|
||||
// pins for that axis, but instead include a block like this:
|
||||
// #define USE_SERVO_AXES
|
||||
|
||||
// #define SERVO_Z_PIN GPIO_NUM_22
|
||||
// #define SERVO_Z_CHANNEL_NUM 6
|
||||
// #define SERVO_Z_RANGE_MIN 0.0
|
||||
// #define SERVO_Z_RANGE_MAX 5.0
|
||||
// #define SERVO_Z_HOMING_TYPE SERVO_HOMING_TARGET // during homing it will instantly move to a target value
|
||||
// #define SERVO_Z_HOME_POS SERVO_Z_RANGE_MAX // move to max during homing
|
||||
// #define SERVO_Z_MPOS false // will not use mpos, uses work coordinates
|
||||
|
||||
// === Homing cycles
|
||||
// The default homing order is Z first (HOMING_CYCLE_0),
|
||||
// then X (HOMING_CYCLE_1), and finally Y (HOMING_CYCLE_2)
|
||||
// For machines that need different homing order, you can
|
||||
// undefine HOMING_CYCLE_n and redefine it accordingly.
|
||||
// For example, the following would first home X and Y
|
||||
// simultaneously, then A and B simultaneously, and Z
|
||||
// not at all.
|
||||
|
||||
// #undef HOMING_CYCLE_0
|
||||
// #define HOMING_CYCLE_0 ((1<<X_AXIS)|(1<<Y_AXIS))
|
||||
|
||||
// #undef HOMING_CYCLE_1
|
||||
// #define HOMING_CYCLE_1 ((1<<A_AXIS)|(1<<B_AXIS))
|
||||
|
||||
// #undef HOMING_CYCLE_2
|
||||
// #endif
|
||||
|
||||
// === Default settings
|
||||
// Grbl has many run-time settings that the user can changed by
|
||||
// commands like $110=2000 . Their values are stored in EEPROM
|
||||
// so they persist after the controller has been powered down.
|
||||
// Those settings have default values that are used if the user
|
||||
// has not altered them, or if the settings are explicitly reset
|
||||
// to the default values wth $RST=$.
|
||||
//
|
||||
// The default values are established in defaults.h, but you
|
||||
// can override any one of them by definining it here, for example:
|
||||
|
||||
//#define DEFAULT_INVERT_LIMIT_PINS 1
|
||||
//#define DEFAULT_REPORT_INCHES 1
|
||||
|
||||
// === Control Pins
|
||||
|
||||
// The control pins with names that begin with CONTROL_ are
|
||||
// ignored by default, to avoid noise problems. To make them
|
||||
// work, you must undefine IGNORE_CONTROL_PINS
|
||||
// #undef IGNORE_CONTROL_PINS
|
||||
|
||||
// If some of the control pin switches are normally closed
|
||||
// (the default is normally open), you can invert some of them
|
||||
// with INVERT_CONTROL_PIN_MASK. The bits in the mask are
|
||||
// Cycle Start, Feed Hold, Reset, Safety Door. To use a
|
||||
// normally open switch on Reset, you would say
|
||||
// #define INVERT_CONTROL_PIN_MASK B1101
|
||||
|
||||
// If your control pins do not have adequate hardware signal
|
||||
// conditioning, you can define these to use software to
|
||||
// reduce false triggering.
|
||||
// #define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
|
||||
// #define CONTROL_SW_DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
|
||||
|
||||
|
||||
// Grbl_ESP32 use the ESP32's special RMT (IR remote control) hardware
|
||||
// engine to achieve more precise high step rates than can be done
|
||||
// in software. That feature is enabled by default, but there are
|
||||
// some machines that might not want to use it, such as machines that
|
||||
// do not use ordinary stepper motors. To turn it off, do this:
|
||||
// #undef USE_RMT_STEPS
|
||||
|
||||
// === Special Features
|
||||
// Grbl_ESP32 can support non-Cartesian machines and some other
|
||||
// scenarios that cannot be handled by choosing from a set of
|
||||
// predefined selections. Instead they require machine-specific
|
||||
// C++ code functions. There are callouts in the core code for
|
||||
// such code, guarded by ifdefs that enable calling the individual
|
||||
// functions. custom_code_template.cpp describes the functions
|
||||
// that you can implement. The ifdef guards are described below:
|
||||
//
|
||||
// USE_CUSTOM_HOMING enables the user_defined_homing() function
|
||||
// that can implement an arbitrary homing sequence.
|
||||
// #define USE_CUSTOM_HOMING
|
||||
|
||||
// USE_KINEMATICS enables the functions inverse_kinematics(),
|
||||
// kinematics_pre_homing(), and kinematics_post_homing(),
|
||||
// so non-Cartesian machines can be implemented.
|
||||
// #define USE_KINEMATICS
|
||||
|
||||
// USE_FWD_KINEMATIC enables the forward_kinematics() function
|
||||
// that converts motor positions in non-Cartesian coordinate
|
||||
// systems back to Cartesian form, for status reports.
|
||||
//#define USE_FWD_KINEMATIC
|
||||
|
||||
// USE_TOOL_CHANGE enables the user_tool_change() function
|
||||
// that implements custom tool change procedures.
|
||||
// #define USE_TOOL_CHANGE
|
||||
|
||||
// Any one of MACRO_BUTTON_0_PIN, MACRO_BUTTON_1_PIN, and MACRO_BUTTON_2_PIN
|
||||
// enables the user_defined_macro(number) function which
|
||||
// implements custom behavior at the press of a button
|
||||
// #define MACRO_BUTTON_0_PIN
|
||||
|
||||
// USE_M30 enables the user_m30() function which implements
|
||||
// custom behavior when a GCode programs stops at the end
|
||||
// #define USE_M30
|
||||
|
||||
// USE_TRIAMINIC enables a suite of functions that are defined
|
||||
// in grbl_triaminic.cpp, allowing the use of Triaminic stepper
|
||||
// drivers that require software configuration at startup.
|
||||
// There are several options that control the details of such
|
||||
// drivers; inspect the code in grbl_triaminic.cpp to see them.
|
||||
// #define USE_TRIAMINIC
|
||||
// #define X_TRIAMINIC
|
||||
// #define X_DRIVER_TMC2209
|
||||
// #define TRIAMINIC_DAISY_CHAIN
|
||||
|
||||
// USE_MACHINE_TRINAMIC_INIT enables the machine_triaminic_setup()
|
||||
// function that replaces the normal setup of Triaminic drivers.
|
||||
// It could, for, example, setup StallGuard or other special modes.
|
||||
// #define USE_MACHINE_TRINAMIC_INIT
|
||||
|
||||
|
||||
// === Grbl behavior options
|
||||
// There are quite a few options that control aspects of Grbl that
|
||||
// are not specific to particular machines. They are listed and
|
||||
// described in config.h after it includes the file machine.h.
|
||||
// Normally you would not need to change them, but if you do,
|
||||
// it will be necessary to make the change in config.h
|
41
Grbl_Esp32/Machines/test_drive.h
Normal file
41
Grbl_Esp32/Machines/test_drive.h
Normal file
@ -0,0 +1,41 @@
|
||||
/*
|
||||
test_drive.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments (or lack thereof) for testing Grbl_ESP32.
|
||||
|
||||
It creates a basic 3 axis machine without actually driving
|
||||
I/O pins. Grbl will report that axes are moving, but no physical
|
||||
motor motion will occur.
|
||||
|
||||
This can be uploaded to an unattached ESP32 or attached to
|
||||
unknown hardware with no risk of pins trying to output signals
|
||||
into a short, etc that could dmamge the ESP32
|
||||
|
||||
It can also be used to get the basic program running so OTA
|
||||
(over the air) firmware loading can be done.
|
||||
|
||||
2018 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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 "MACHINE_DEFAULT - Demo Only No I/O!"
|
||||
|
||||
#define LIMIT_MASK 0 // no limit pins
|
||||
|
||||
#ifdef USE_RMT_STEPS
|
||||
#undef USE_RMT_STEPS // Suppress unused variable warning
|
||||
#endif
|
81
Grbl_Esp32/Machines/tmc2130_pen.h
Normal file
81
Grbl_Esp32/Machines/tmc2130_pen.h
Normal file
@ -0,0 +1,81 @@
|
||||
/*
|
||||
tmc21340_pen.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Pin assignments for the TMC2130 Pen/Laser controller
|
||||
https://github.com/bdring/Grbl_ESP32_TMC2130_Plotter_Controller
|
||||
|
||||
2018 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
|
||||
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/>.
|
||||
*/
|
||||
|
||||
|
||||
// Select a version to match your PCB
|
||||
//#define MACHINE_V1 // version 1 PCB
|
||||
#define MACHINE_V2 // version 2 PCB
|
||||
|
||||
#ifdef MACHINE_V1
|
||||
#define MACHINE_NAME "ESP32_TMC2130_PEN V1"
|
||||
#define X_LIMIT_PIN GPIO_NUM_2
|
||||
#else
|
||||
#define MACHINE_NAME "ESP32_TMC2130_PEN V2"
|
||||
#define X_LIMIT_PIN GPIO_NUM_32
|
||||
#endif
|
||||
|
||||
#define USE_TRINAMIC // Using at least 1 trinamic driver
|
||||
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||
#define X_TRINAMIC // using SPI control
|
||||
#define X_DRIVER_TMC2130 // Which Driver Type?
|
||||
#define X_CS_PIN GPIO_NUM_17 //chip select
|
||||
#define X_RSENSE 0.11f // .11 Ohm
|
||||
|
||||
#define Y_STEP_PIN GPIO_NUM_14
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||
#define Y_TRINAMIC // using SPI control
|
||||
#define Y_DRIVER_TMC2130 // Which Driver Type?
|
||||
#define Y_CS_PIN GPIO_NUM_16 //chip select
|
||||
#define Y_RSENSE 0.11f // .11 Ohm
|
||||
|
||||
// OK to comment out to use pin for other features
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
#ifndef USE_SERVO_AXES // may be set in config.h
|
||||
#define USE_SERVO_AXES
|
||||
#endif
|
||||
|
||||
#define SERVO_Z_PIN GPIO_NUM_27 // comment this out if PWM spindle/laser control.
|
||||
#define SERVO_Z_CHANNEL_NUM 5
|
||||
#define SERVO_Z_RANGE_MIN 0.0
|
||||
#define SERVO_Z_RANGE_MAX 5.0
|
||||
#define SERVO_Z_HOMING_TYPE SERVO_HOMING_TARGET // during homing it will instantly move to a target value
|
||||
#define SERVO_Z_HOME_POS SERVO_Z_RANGE_MAX // move to max during homing
|
||||
#define SERVO_Z_MPOS false // will not use mpos, uses work coordinates
|
||||
|
||||
|
||||
// Comment out servo pin and uncomment spindle pwm pin to use the servo PWM to control a spindle
|
||||
/*
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_27
|
||||
*/
|
||||
|
||||
// #define X_LIMIT_PIN See version section
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||
#define LIMIT_MASK B11
|
||||
|
||||
// defaults
|
||||
#define DEFAULT_Z_STEPS_PER_MM 100.0 // This is used as the servo calibration
|
||||
#define DEFAULT_Z_MAX_TRAVEL 300.0 // This is used as the servo calibration
|
@ -1,324 +0,0 @@
|
||||
/*
|
||||
atari_1020.cpp
|
||||
Part of Grbl_ESP32
|
||||
|
||||
copyright (c) 2018 - Bart Dring This file was modified for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
--------------------------------------------------------------
|
||||
|
||||
This contains all the special features required to control an
|
||||
Atari 1010 Pen Plotter
|
||||
*/
|
||||
#include "grbl.h"
|
||||
|
||||
#ifdef ATARI_1020
|
||||
|
||||
#define HOMING_PHASE_FULL_APPROACH 0 // move to right end
|
||||
#define HOMING_PHASE_CHECK 1 // check reed switch
|
||||
#define HOMING_PHASE_RETRACT 2 // retract
|
||||
#define HOMING_PHASE_SHORT_APPROACH 3 // retract
|
||||
|
||||
static TaskHandle_t solenoidSyncTaskHandle = 0;
|
||||
static TaskHandle_t atariHomingTaskHandle = 0;
|
||||
uint16_t solenoid_pull_count;
|
||||
bool atari_homing = false;
|
||||
uint8_t homing_phase = HOMING_PHASE_FULL_APPROACH;
|
||||
uint8_t current_tool;
|
||||
|
||||
void machine_init()
|
||||
{
|
||||
solenoid_pull_count = 0; // initialize
|
||||
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Atari 1020 Solenoid");
|
||||
|
||||
// setup PWM channel
|
||||
ledcSetup(SOLENOID_CHANNEL_NUM, SOLENOID_PWM_FREQ, SOLENOID_PWM_RES_BITS);
|
||||
ledcAttachPin(SOLENOID_PEN_PIN, SOLENOID_CHANNEL_NUM);
|
||||
|
||||
pinMode(SOLENOID_DIRECTION_PIN, OUTPUT); // this sets the direction of the solenoid current
|
||||
pinMode(REED_SW_PIN, INPUT_PULLUP); // external pullup required
|
||||
|
||||
// setup a task that will calculate solenoid position
|
||||
xTaskCreatePinnedToCore( solenoidSyncTask, // task
|
||||
"solenoidSyncTask", // name for task
|
||||
4096, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&solenoidSyncTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
// setup a task that will do the custom homing sequence
|
||||
xTaskCreatePinnedToCore( atari_home_task, // task
|
||||
"atari_home_task", // name for task
|
||||
4096, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&atariHomingTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
}
|
||||
|
||||
// this task tracks the Z position and sets the solenoid
|
||||
void solenoidSyncTask(void *pvParameters)
|
||||
{
|
||||
int32_t current_position[N_AXIS]; // copy of current location
|
||||
float m_pos[N_AXIS]; // machine position in mm
|
||||
TickType_t xLastWakeTime;
|
||||
const TickType_t xSolenoidFrequency = SOLENOID_TASK_FREQ; // in ticks (typically ms)
|
||||
|
||||
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
|
||||
while(true) { // don't ever return from this or the task dies
|
||||
|
||||
memcpy(current_position,sys_position,sizeof(sys_position)); // get current position in step
|
||||
system_convert_array_steps_to_mpos(m_pos,current_position); // convert to millimeters
|
||||
calc_solenoid(m_pos[Z_AXIS]); // calculate kinematics and move the servos
|
||||
|
||||
vTaskDelayUntil(&xLastWakeTime, xSolenoidFrequency);
|
||||
}
|
||||
}
|
||||
|
||||
// to do...have this return a true or false. This could be used by the normal homing feature to
|
||||
// continue with regular homing after setup
|
||||
// return true if this completes homing
|
||||
|
||||
bool user_defined_homing() {
|
||||
// create and start a task to do the special homing
|
||||
homing_phase = HOMING_PHASE_FULL_APPROACH;
|
||||
atari_homing = true;
|
||||
return true; // this does it...skip the rest of mc_homing_cycle(...)
|
||||
}
|
||||
|
||||
/*
|
||||
Do a custom homing routine.
|
||||
|
||||
A task is used because it needs to wait until until idle after each move.
|
||||
|
||||
1) Do a full travel move to the right. OK to stall if the pen started closer
|
||||
2) Check for pen 1
|
||||
3) If fail Retract
|
||||
4) move to right end
|
||||
5) Check...
|
||||
....repeat up to 12 times to try to find pen one
|
||||
|
||||
TODO can the retract, move back be 1 phase rather than 2?
|
||||
|
||||
*/
|
||||
void atari_home_task(void *pvParameters) {
|
||||
uint8_t homing_attempt = 0; // how many times have we tried to home
|
||||
TickType_t xLastWakeTime;
|
||||
const TickType_t xHomingTaskFrequency = 100; // in ticks (typically ms) .... need to make sure there is enough time to get out of idle
|
||||
char gcode_line[20];
|
||||
|
||||
while(true) { // this task will only last as long as it is homing
|
||||
|
||||
if (atari_homing) {
|
||||
// must be in idle or alarm state
|
||||
if (sys.state == STATE_IDLE) {
|
||||
switch(homing_phase) {
|
||||
case HOMING_PHASE_FULL_APPROACH: // a full width move to insure it hits left end
|
||||
inputBuffer.push("G90G0Z1\r"); // lift the pen
|
||||
sprintf(gcode_line, "G91G0X%3.2f\r", -ATARI_PAPER_WIDTH + ATARI_HOME_POS - 3.0); // plus a little extra
|
||||
inputBuffer.push(gcode_line);
|
||||
homing_attempt = 1;
|
||||
homing_phase = HOMING_PHASE_CHECK;
|
||||
break;
|
||||
case HOMING_PHASE_CHECK: // check the limits switch
|
||||
if (digitalRead(REED_SW_PIN) == 0) { // see if reed switch is grounded
|
||||
inputBuffer.push("G4P0.1\n"); // dramtic pause
|
||||
|
||||
sys_position[X_AXIS] = ATARI_HOME_POS * settings.steps_per_mm[X_AXIS];
|
||||
sys_position[Y_AXIS] = 0.0;
|
||||
sys_position[Z_AXIS] = 1.0 * settings.steps_per_mm[Y_AXIS];
|
||||
|
||||
gc_sync_position();
|
||||
plan_sync_position();
|
||||
|
||||
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls
|
||||
inputBuffer.push(gcode_line);
|
||||
|
||||
current_tool = 1; // local copy for reference...until actual M6 change
|
||||
gc_state.tool = current_tool;
|
||||
atari_homing = false; // done with homing sequence
|
||||
}
|
||||
else {
|
||||
homing_phase = HOMING_PHASE_RETRACT;
|
||||
homing_attempt++;
|
||||
}
|
||||
break;
|
||||
case HOMING_PHASE_RETRACT:
|
||||
sprintf(gcode_line, "G0X%3.2f\r", -ATARI_HOME_POS);
|
||||
inputBuffer.push(gcode_line);
|
||||
sprintf(gcode_line, "G0X%3.2f\r", ATARI_HOME_POS);
|
||||
inputBuffer.push(gcode_line);
|
||||
homing_phase = HOMING_PHASE_CHECK;
|
||||
break;
|
||||
default:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Homing phase error %d", homing_phase);
|
||||
atari_homing = false;; // kills task
|
||||
break;
|
||||
}
|
||||
|
||||
if (homing_attempt > ATARI_HOMING_ATTEMPTS) { // try all positions plus 1
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Atari homing failed");
|
||||
inputBuffer.push("G90\r");
|
||||
atari_homing = false;;
|
||||
}
|
||||
}
|
||||
}
|
||||
vTaskDelayUntil(&xLastWakeTime, xHomingTaskFrequency);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// calculate and set the PWM value for the servo
|
||||
void calc_solenoid(float penZ)
|
||||
{
|
||||
bool isPenUp;
|
||||
static bool previousPenState = false;
|
||||
uint32_t solenoid_pen_pulse_len; // duty cycle of solenoid
|
||||
|
||||
isPenUp = ( (penZ > 0) || (sys.state == STATE_ALARM) ); // is pen above Z0 or is there an alarm
|
||||
|
||||
// if the state has not change, we only count down to the pull time
|
||||
if (previousPenState == isPenUp) { // if state is unchanged
|
||||
if (solenoid_pull_count > 0) {
|
||||
solenoid_pull_count--;
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_PULL; // stay at full power while counting down
|
||||
}
|
||||
else {
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_HOLD; // pull in delay has expired so lower duty cycle
|
||||
}
|
||||
}
|
||||
else { // pen direction has changed
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_PULL; // go to full power
|
||||
solenoid_pull_count = SOLENOID_PULL_DURATION; // set the time to count down
|
||||
}
|
||||
|
||||
previousPenState = isPenUp; // save the prev state
|
||||
|
||||
digitalWrite(SOLENOID_DIRECTION_PIN, isPenUp);
|
||||
|
||||
// skip setting value if it is unchanged
|
||||
if (ledcRead(SOLENOID_CHANNEL_NUM) == solenoid_pen_pulse_len)
|
||||
return;
|
||||
|
||||
// update the PWM value
|
||||
// ledcWrite appears to have issues with interrupts, so make this a critical section
|
||||
portMUX_TYPE myMutex = portMUX_INITIALIZER_UNLOCKED;
|
||||
portENTER_CRITICAL(&myMutex);
|
||||
ledcWrite(SOLENOID_CHANNEL_NUM, solenoid_pen_pulse_len);
|
||||
portEXIT_CRITICAL(&myMutex);
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
A tool (pen) change is done by bumping the carriage against the right edge 3 times per
|
||||
position change. Pen 1-4 is valid range.
|
||||
*/
|
||||
void user_tool_change(uint8_t new_tool) {
|
||||
uint8_t move_count;
|
||||
char gcode_line[20];
|
||||
|
||||
protocol_buffer_synchronize(); // wait for all previous moves to complete
|
||||
|
||||
if ((new_tool < 1) || (new_tool > MAX_PEN_NUMBER)) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Requested Pen#%d is out of 1-4 range", new_tool);
|
||||
return;
|
||||
}
|
||||
|
||||
if (new_tool == current_tool)
|
||||
return;
|
||||
|
||||
if (new_tool > current_tool) {
|
||||
move_count = BUMPS_PER_PEN_CHANGE * (new_tool - current_tool);
|
||||
}
|
||||
else {
|
||||
move_count = BUMPS_PER_PEN_CHANGE * ((MAX_PEN_NUMBER - current_tool) + new_tool);
|
||||
}
|
||||
sprintf(gcode_line, "G0Z%3.2f\r", ATARI_TOOL_CHANGE_Z); // go to tool change height
|
||||
inputBuffer.push(gcode_line);
|
||||
for (uint8_t i = 0; i < move_count; i++) {
|
||||
sprintf(gcode_line, "G0X%3.2f\r", ATARI_HOME_POS); //
|
||||
inputBuffer.push(gcode_line);
|
||||
inputBuffer.push("G0X0\r");
|
||||
}
|
||||
|
||||
current_tool = new_tool;
|
||||
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Change to Pen#%d", current_tool);
|
||||
|
||||
}
|
||||
|
||||
// move from current tool to next tool....
|
||||
void atari_next_pen() {
|
||||
if (current_tool < MAX_PEN_NUMBER) {
|
||||
gc_state.tool = current_tool + 1;
|
||||
}
|
||||
else {
|
||||
gc_state.tool = 1;
|
||||
}
|
||||
user_tool_change(gc_state.tool);
|
||||
}
|
||||
|
||||
// Polar coaster has macro buttons, this handles those button pushes.
|
||||
void user_defined_macro(uint8_t index)
|
||||
{
|
||||
char gcode_line[20];
|
||||
|
||||
switch (index) {
|
||||
#ifdef MACRO_BUTTON_0_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_0:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Pen switch");
|
||||
inputBuffer.push("$H\r");
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef MACRO_BUTTON_1_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_1:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Color switch");
|
||||
atari_next_pen();
|
||||
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls
|
||||
inputBuffer.push(gcode_line);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef MACRO_BUTTON_2_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_2:
|
||||
// feed out some paper and reset the Y 0
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Paper switch");
|
||||
inputBuffer.push("G0Y-25\r");
|
||||
inputBuffer.push("G4P0.1\r"); // sync...forces wait for planner to clear
|
||||
sys_position[Y_AXIS] = 0.0; // reset the Y position
|
||||
gc_sync_position();
|
||||
plan_sync_position();
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Unknown Switch %d", index);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void user_m30() {
|
||||
char gcode_line[20];
|
||||
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); //
|
||||
inputBuffer.push(gcode_line);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -1,173 +0,0 @@
|
||||
/*
|
||||
atari_1020.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
copyright (c) 2018 - Bart Dring This file was modified for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This contains all the special features required to control an
|
||||
Atari 1010 Pen Plotter
|
||||
*/
|
||||
|
||||
#define CPU_MAP_NAME "CPU_MAP_ATARI_1020"
|
||||
|
||||
// ================== CPU MAP ======================
|
||||
#define USE_UNIPOLAR
|
||||
|
||||
#define X_UNIPOLAR
|
||||
#define X_PIN_PHASE_0 GPIO_NUM_13
|
||||
#define X_PIN_PHASE_1 GPIO_NUM_21
|
||||
#define X_PIN_PHASE_2 GPIO_NUM_16
|
||||
#define X_PIN_PHASE_3 GPIO_NUM_22
|
||||
|
||||
#define Y_UNIPOLAR
|
||||
#define Y_PIN_PHASE_0 GPIO_NUM_25
|
||||
#define Y_PIN_PHASE_1 GPIO_NUM_27
|
||||
#define Y_PIN_PHASE_2 GPIO_NUM_26
|
||||
#define Y_PIN_PHASE_3 GPIO_NUM_32
|
||||
|
||||
|
||||
#define SOLENOID_DIRECTION_PIN GPIO_NUM_4
|
||||
#define SOLENOID_PEN_PIN GPIO_NUM_2
|
||||
#define SOLENOID_CHANNEL_NUM 6
|
||||
|
||||
#ifdef HOMING_CYCLE_0
|
||||
#undef HOMING_CYCLE_0
|
||||
#endif
|
||||
#define HOMING_CYCLE_0 (1<<X_AXIS) // this 'bot only homes the X axis
|
||||
#ifdef HOMING_CYCLE_1
|
||||
#undef HOMING_CYCLE_1
|
||||
#endif
|
||||
#ifdef HOMING_CYCLE_2
|
||||
#undef HOMING_CYCLE_2
|
||||
#endif
|
||||
|
||||
#define REED_SW_PIN GPIO_NUM_17
|
||||
#define LIMIT_MASK 0
|
||||
|
||||
|
||||
#ifdef IGNORE_CONTROL_PINS // maybe set in config.h
|
||||
#undef IGNORE_CONTROL_PINS
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef ENABLE_CONTROL_SW_DEBOUNCE
|
||||
#define ENABLE_CONTROL_SW_DEBOUNCE
|
||||
#endif
|
||||
|
||||
#ifdef INVERT_CONTROL_PIN_MASK
|
||||
#undef IGNORE_CONTROL_PINS
|
||||
#endif
|
||||
#define INVERT_CONTROL_PIN_MASK B01110000
|
||||
|
||||
#define MACRO_BUTTON_0_PIN GPIO_NUM_34 // Pen Switch
|
||||
#define MACRO_BUTTON_1_PIN GPIO_NUM_35 // Color Switch
|
||||
#define MACRO_BUTTON_2_PIN GPIO_NUM_36 // Paper Switch
|
||||
|
||||
#ifdef DEFAULTS_GENERIC
|
||||
#undef DEFAULTS_GENERIC // undefine generic then define each default below
|
||||
#endif
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 200 // 200ms
|
||||
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
|
||||
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1
|
||||
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||
#define DEFAULT_REPORT_INCHES 0 // false
|
||||
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||
|
||||
#define DEFAULT_HOMING_ENABLE 1
|
||||
#define DEFAULT_HOMING_DIR_MASK 0
|
||||
#define DEFAULT_HOMING_FEED_RATE 3000.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 3000.0 // mm/min
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||
#define DEFAULT_HOMING_PULLOFF 2.0 // mm
|
||||
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
|
||||
#define DEFAULT_LASER_MODE 0 // false
|
||||
|
||||
#define DEFAULT_X_STEPS_PER_MM 10
|
||||
#define DEFAULT_Y_STEPS_PER_MM 10
|
||||
#define DEFAULT_Z_STEPS_PER_MM 100.0 // This is percent in servo mode
|
||||
|
||||
|
||||
#define DEFAULT_X_MAX_RATE 5000.0 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE 5000.0 // mm/min
|
||||
#define DEFAULT_Z_MAX_RATE 200000.0 // mm/min
|
||||
|
||||
#define DEFAULT_X_ACCELERATION (500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (500.0*60*60)
|
||||
|
||||
#define DEFAULT_X_MAX_TRAVEL 120.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Y_MAX_TRAVEL 20000.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Z_MAX_TRAVEL 10.0 // This is percent in servo mode
|
||||
|
||||
// ================== CPU MAP ======================
|
||||
|
||||
#define ATARI_1020
|
||||
|
||||
|
||||
#define SOLENOID_PWM_FREQ 5000
|
||||
#define SOLENOID_PWM_RES_BITS 8
|
||||
|
||||
#define SOLENOID_PULSE_LEN_PULL 255
|
||||
#define SOLENOID_PULL_DURATION 50 // in task counts...after this delay power will change to hold level see SOLENOID_TASK_FREQ
|
||||
#define SOLENOID_PULSE_LEN_HOLD 40 // solenoid hold level ... typically a lower value to prevent overheating
|
||||
|
||||
#define SOLENOID_TASK_FREQ 50 // this is milliseconds
|
||||
|
||||
#define MAX_PEN_NUMBER 4
|
||||
#define BUMPS_PER_PEN_CHANGE 3
|
||||
|
||||
|
||||
#define ATARI_HOME_POS -10.0f // this amound to the left of the paper 0
|
||||
#define ATARI_PAPER_WIDTH 100.0f //
|
||||
#define ATARI_HOMING_ATTEMPTS 13
|
||||
|
||||
// tells grbl we have some special functions to call
|
||||
#define USE_MACHINE_INIT
|
||||
#define USE_CUSTOM_HOMING
|
||||
#define USE_TOOL_CHANGE
|
||||
#define ATARI_TOOL_CHANGE_Z 5.0
|
||||
#define USE_M30 // use the user defined end of program
|
||||
|
||||
#ifndef atari_h
|
||||
#define atari_h
|
||||
|
||||
void machine_init();
|
||||
void solenoid_disable();
|
||||
void solenoidSyncTask(void *pvParameters);
|
||||
void calc_solenoid(float penZ);
|
||||
bool user_defined_homing();
|
||||
void atari_home_task(void *pvParameters);
|
||||
void user_tool_change(uint8_t new_tool);
|
||||
void user_defined_macro(uint8_t index);
|
||||
void user_m30();
|
||||
void atari_next_pen();
|
||||
|
||||
#endif
|
File diff suppressed because it is too large
Load Diff
@ -37,21 +37,20 @@ typedef enum {
|
||||
class ESPResponseStream;
|
||||
|
||||
|
||||
class COMMANDS
|
||||
{
|
||||
public:
|
||||
static bool check_command (const char *, int * cmd, String & cmd_params);
|
||||
static String get_param (String & cmd_params, const char * id, bool withspace);
|
||||
static bool execute_internal_command (int cmd, String cmd_params, level_authenticate_type auth_level = LEVEL_GUEST , ESPResponseStream *espresponse= NULL);
|
||||
class COMMANDS {
|
||||
public:
|
||||
static bool check_command(const char*, int* cmd, String& cmd_params);
|
||||
static String get_param(String& cmd_params, const char* id, bool withspace);
|
||||
static bool execute_internal_command(int cmd, String cmd_params, level_authenticate_type auth_level = LEVEL_GUEST, ESPResponseStream* espresponse = NULL);
|
||||
static void wait(uint32_t milliseconds);
|
||||
static void handle();
|
||||
static void restart_ESP();
|
||||
#ifdef ENABLE_AUTHENTICATION
|
||||
static bool isadmin (String & cmd_params);
|
||||
static bool isuser (String & cmd_params);
|
||||
static bool isLocalPasswordValid (const char * password);
|
||||
static bool isadmin(String& cmd_params);
|
||||
static bool isuser(String& cmd_params);
|
||||
static bool isLocalPasswordValid(const char* password);
|
||||
#endif
|
||||
private :
|
||||
private :
|
||||
static bool restart_ESP_module;
|
||||
};
|
||||
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
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
|
||||
@ -39,16 +39,69 @@ Some features should not be changed. See notes below.
|
||||
#define config_h
|
||||
#include <Arduino.h>
|
||||
|
||||
// !!!! Most Important Configuration Item !!!!
|
||||
// #define the CPU map you want to use
|
||||
// The CPU map is the main definition of the machine/controller you want to use
|
||||
// These are typically found in the cpu_map.h file.
|
||||
// See Github repo wiki for more details
|
||||
#define CPU_MAP_TEST_DRIVE // these are defined in cpu_map.h
|
||||
// It is no longer necessary to edit this file to choose
|
||||
// a machine configuration; edit machine.h instead
|
||||
// machine.h is #included below, after some definitions
|
||||
// that the machine file might choose to undefine.
|
||||
|
||||
// Define the homing cycle patterns with bitmasks. The homing cycle first performs a search mode
|
||||
// to quickly engage the limit switches, followed by a slower locate mode, and finished by a short
|
||||
// pull-off motion to disengage the limit switches. The following HOMING_CYCLE_x defines are executed
|
||||
// in order starting with suffix 0 and completes the homing routine for the specified-axes only. If
|
||||
// an axis is omitted from the defines, it will not home, nor will the system update its position.
|
||||
// Meaning that this allows for users with non-standard Cartesian machines, such as a lathe (x then z,
|
||||
// with no y), to configure the homing cycle behavior to their needs.
|
||||
// NOTE: The homing cycle is designed to allow sharing of limit pins, if the axes are not in the same
|
||||
// cycle, but this requires some pin settings changes in the machine definition file. For example, the default homing
|
||||
// cycle can share the Z limit pin with either X or Y limit pins, since they are on different cycles.
|
||||
// By sharing a pin, this frees up a precious IO pin for other purposes. In theory, all axes limit pins
|
||||
// may be reduced to one pin, if all axes are homed with separate cycles, or vice versa, all three axes
|
||||
// on separate pin, but homed in one cycle. Also, it should be noted that the function of hard limits
|
||||
// will not be affected by pin sharing.
|
||||
|
||||
// NOTE: Defaults are set for a traditional 3-axis CNC machine. Z-axis first to clear, followed by X & Y.
|
||||
// These homing cycle definitions precede the machine.h file so that the machine
|
||||
// definition can undefine them if necessary.
|
||||
#define HOMING_CYCLE_0 (1<<Z_AXIS) // TYPICALLY REQUIRED: First move Z to clear workspace.
|
||||
#define HOMING_CYCLE_1 (1<<X_AXIS)
|
||||
#define HOMING_CYCLE_2 (1<<Y_AXIS)
|
||||
|
||||
// NOTE: The following is for for homing X and Y at the same time
|
||||
// #define HOMING_CYCLE_0 (1<<Z_AXIS) // first home z by itself
|
||||
// #define HOMING_CYCLE_1 ((1<<X_AXIS)|(1<<Y_AXIS)) // Homes both X-Y in one cycle. NOT COMPATIBLE WITH COREXY!!!
|
||||
|
||||
// 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
|
||||
// For example B1101 will invert the function of the Reset pin.
|
||||
#define INVERT_CONTROL_PIN_MASK B1111
|
||||
|
||||
// This allows control pins to be ignored.
|
||||
// Since these are typically used on the pins that don't have pullups, they will float and cause
|
||||
// problems if not externally pulled up. Ignoring will always return not activated when read.
|
||||
#define IGNORE_CONTROL_PINS
|
||||
|
||||
#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
|
||||
|
||||
// Include the file that loads the machine-specific config file.
|
||||
// machine.h must be edited to choose the desired file.
|
||||
#include "machine.h"
|
||||
|
||||
// machine_common.h contains settings that do not change
|
||||
#include "machine_common.h"
|
||||
|
||||
// Number of axes defined (steppers, servos, etc) (valid range: 3 to 6)
|
||||
// Even if your machine only uses less than the minimum of 3, you should select 3
|
||||
#define N_AXIS 3
|
||||
#ifndef N_AXIS
|
||||
#define N_AXIS 3
|
||||
#endif
|
||||
|
||||
#ifndef LIMIT_MASK
|
||||
#define LIMIT_MASK B0
|
||||
#endif
|
||||
|
||||
#define VERBOSE_HELP // Currently this doesn't do anything
|
||||
#define GRBL_MSG_LEVEL MSG_LEVEL_INFO // what level of [MSG:....] do you want to see 0=all off
|
||||
@ -62,7 +115,7 @@ Some features should not be changed. See notes below.
|
||||
//#define CONNECT_TO_SSID "your SSID"
|
||||
//#define SSID_PASSWORD "your SSID password"
|
||||
|
||||
#define ENABLE_BLUETOOTH // enable bluetooth
|
||||
#define ENABLE_BLUETOOTH // enable bluetooth
|
||||
|
||||
#define ENABLE_SD_CARD // enable use of SD Card to run jobs
|
||||
|
||||
@ -86,15 +139,15 @@ Some features should not be changed. See notes below.
|
||||
#define ESP_RADIO_MODE "RADIO_MODE"
|
||||
|
||||
#ifdef ENABLE_AUTHENTICATION
|
||||
#define DEFAULT_ADMIN_PWD "admin"
|
||||
#define DEFAULT_USER_PWD "user";
|
||||
#define DEFAULT_ADMIN_LOGIN "admin"
|
||||
#define DEFAULT_USER_LOGIN "user"
|
||||
#define ADMIN_PWD_ENTRY "ADMIN_PWD"
|
||||
#define USER_PWD_ENTRY "USER_PWD"
|
||||
#define AUTH_ENTRY_NB 20
|
||||
#define MAX_LOCAL_PASSWORD_LENGTH 16
|
||||
#define MIN_LOCAL_PASSWORD_LENGTH 1
|
||||
#define DEFAULT_ADMIN_PWD "admin"
|
||||
#define DEFAULT_USER_PWD "user";
|
||||
#define DEFAULT_ADMIN_LOGIN "admin"
|
||||
#define DEFAULT_USER_LOGIN "user"
|
||||
#define ADMIN_PWD_ENTRY "ADMIN_PWD"
|
||||
#define USER_PWD_ENTRY "USER_PWD"
|
||||
#define AUTH_ENTRY_NB 20
|
||||
#define MAX_LOCAL_PASSWORD_LENGTH 16
|
||||
#define MIN_LOCAL_PASSWORD_LENGTH 1
|
||||
#endif
|
||||
|
||||
//Radio Mode
|
||||
@ -103,19 +156,19 @@ Some features should not be changed. See notes below.
|
||||
#define ESP_WIFI_AP 2
|
||||
#define ESP_BT 3
|
||||
|
||||
//Default mode
|
||||
//Default mode
|
||||
#ifdef ENABLE_WIFI
|
||||
#ifdef CONNECT_TO_SSID
|
||||
#define DEFAULT_RADIO_MODE ESP_WIFI_STA
|
||||
#else
|
||||
#define DEFAULT_RADIO_MODE ESP_WIFI_AP
|
||||
#endif //CONNECT_TO_SSID
|
||||
#ifdef CONNECT_TO_SSID
|
||||
#define DEFAULT_RADIO_MODE ESP_WIFI_STA
|
||||
#else
|
||||
#define DEFAULT_RADIO_MODE ESP_WIFI_AP
|
||||
#endif //CONNECT_TO_SSID
|
||||
#else
|
||||
#undef ENABLE_NOTIFICATIONS
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
#define DEFAULT_RADIO_MODE ESP_BT
|
||||
#define DEFAULT_RADIO_MODE ESP_BT
|
||||
#else
|
||||
#define DEFAULT_RADIO_MODE ESP_RADIO_OFF
|
||||
#define DEFAULT_RADIO_MODE ESP_RADIO_OFF
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@ -165,36 +218,12 @@ Some features should not be changed. See notes below.
|
||||
// mainly a safety feature to remind the user to home, since position is unknown to Grbl.
|
||||
#define HOMING_INIT_LOCK // Comment to disable
|
||||
|
||||
// Define the homing cycle patterns with bitmasks. The homing cycle first performs a search mode
|
||||
// to quickly engage the limit switches, followed by a slower locate mode, and finished by a short
|
||||
// pull-off motion to disengage the limit switches. The following HOMING_CYCLE_x defines are executed
|
||||
// in order starting with suffix 0 and completes the homing routine for the specified-axes only. If
|
||||
// an axis is omitted from the defines, it will not home, nor will the system update its position.
|
||||
// Meaning that this allows for users with non-standard Cartesian machines, such as a lathe (x then z,
|
||||
// with no y), to configure the homing cycle behavior to their needs.
|
||||
// NOTE: The homing cycle is designed to allow sharing of limit pins, if the axes are not in the same
|
||||
// cycle, but this requires some pin settings changes in cpu_map.h file. For example, the default homing
|
||||
// cycle can share the Z limit pin with either X or Y limit pins, since they are on different cycles.
|
||||
// By sharing a pin, this frees up a precious IO pin for other purposes. In theory, all axes limit pins
|
||||
// may be reduced to one pin, if all axes are homed with separate cycles, or vice versa, all three axes
|
||||
// on separate pin, but homed in one cycle. Also, it should be noted that the function of hard limits
|
||||
// will not be affected by pin sharing.
|
||||
|
||||
// NOTE: Defaults are set for a traditional 3-axis CNC machine. Z-axis first to clear, followed by X & Y.
|
||||
#define HOMING_CYCLE_0 (1<<Z_AXIS) // TYPICALLY REQUIRED: First move Z to clear workspace.
|
||||
#define HOMING_CYCLE_1 (1<<X_AXIS)
|
||||
#define HOMING_CYCLE_2 (1<<Y_AXIS)
|
||||
|
||||
// NOTE: The following is for for homingg X and Y at the same time
|
||||
// #define HOMING_CYCLE_0 (1<<Z_AXIS) // first home z by itself
|
||||
// #define HOMING_CYCLE_1 ((1<<X_AXIS)|(1<<Y_AXIS)) // Homes both X-Y in one cycle. NOT COMPATIBLE WITH COREXY!!!
|
||||
|
||||
// Number of homing cycles performed after when the machine initially jogs to limit switches.
|
||||
// This help in preventing overshoot and should improve repeatability. This value should be one or
|
||||
// greater.
|
||||
#define N_HOMING_LOCATE_CYCLE 1 // Integer (1-128)
|
||||
|
||||
// Enables single axis homing commands. $HX, $HY, and $HZ for X, Y, and Z-axis homing. The full homing
|
||||
// Enables single axis homing commands. $HX, $HY, and $HZ for X, Y, and Z-axis homing. The full homing
|
||||
// cycle is still invoked by the $H command. This is disabled by default. It's here only to address
|
||||
// users that need to switch between a two-axis and three-axis machine. This is actually very rare.
|
||||
// If you have a two-axis machine, DON'T USE THIS. Instead, just alter the homing cycle for two-axes.
|
||||
@ -206,8 +235,8 @@ Some features should not be changed. See notes below.
|
||||
// #define HOMING_FORCE_SET_ORIGIN // Uncomment to enable.
|
||||
|
||||
// Uncomment this define to force Grbl to always set the machine origin at minimum travel positions of
|
||||
// the axes. Note: The $23 setting determines the direction of travel during homing. If an axes homes towards the
|
||||
// minimum, it will set the machine position to 0. If it homes towards the maximum it will set the
|
||||
// the axes. Note: The $23 setting determines the direction of travel during homing. If an axes homes towards the
|
||||
// minimum, it will set the machine position to 0. If it homes towards the maximum it will set the
|
||||
// machine position to the max travel ($13x), minus the switch pull off ($27).
|
||||
// #define HOMING_FORCE_POSITIVE_SPACE // Uncomment to enable.
|
||||
|
||||
@ -251,7 +280,7 @@ Some features should not be changed. See notes below.
|
||||
// analog pin 4. Only use this option if you require a second coolant control pin.
|
||||
// NOTE: The M8 flood coolant control pin on analog pin 3 will still be functional regardless.
|
||||
// ESP32 NOTE! This is here for reference only. You enable both M7 and M8 by assigning them a GPIO Pin
|
||||
// in cpu_map.h
|
||||
// in the machine definition file.
|
||||
//#define ENABLE_M7 // Don't uncomment...see above!
|
||||
|
||||
// This option causes the feed hold input to act as a safety door switch. A safety door, when triggered,
|
||||
@ -275,30 +304,15 @@ Some features should not be changed. See notes below.
|
||||
// #define COREXY // Default disabled. Uncomment to enable.
|
||||
|
||||
// Enable using a servo for the Z axis on a pen type machine.
|
||||
// You typically should not define a pin for the Z axis in cpu_map.h
|
||||
// You typically should not define a pin for the Z axis in the machine definition file
|
||||
// You should configure your settings in servo_pen.h
|
||||
// #define USE_SERVO_AXES // the new method
|
||||
// define your servo pin here or in cpu_map.h
|
||||
// define your servo pin here or in the machine definition file
|
||||
//#define SERVO_PEN_PIN GPIO_NUM_27
|
||||
|
||||
// Enable using a solenoid for the Z axis on a pen type machine
|
||||
// #define USE_PEN_SOLENOID
|
||||
|
||||
// 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
|
||||
// For example B1101 will invert the function of the Reset pin.
|
||||
#define INVERT_CONTROL_PIN_MASK B1111
|
||||
|
||||
// This allows control pins to be ignored.
|
||||
// Since these are typically used on the pins that don't have pullups, they will float and cause
|
||||
// problems if not externally pulled up. Ignoring will always return not activated when read.
|
||||
#define IGNORE_CONTROL_PINS
|
||||
|
||||
#define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
|
||||
#define CONTROL_SW_DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
|
||||
|
||||
|
||||
// Inverts select limit pin states based on the following mask. This effects all limit pin functions,
|
||||
// such as hard limits and homing. However, this is different from overall invert limits setting.
|
||||
// This build option will invert only the limit pins defined here, and then the invert limits setting
|
||||
@ -363,7 +377,7 @@ Some features should not be changed. See notes below.
|
||||
|
||||
// The status report change for Grbl v1.1 and after also removed the ability to disable/enable most data
|
||||
// fields from the report. This caused issues for GUI developers, who've had to manage several scenarios
|
||||
// and configurations. The increased efficiency of the new reporting style allows for all data fields to
|
||||
// and configurations. The increased efficiency of the new reporting style allows for all data fields to
|
||||
// be sent without potential performance issues.
|
||||
// NOTE: The options below are here only provide a way to disable certain data fields if a unique
|
||||
// situation demands it, but be aware GUIs may depend on this data. If disabled, it may not be compatible.
|
||||
@ -439,10 +453,10 @@ Some features should not be changed. See notes below.
|
||||
// The hardware PWM output on pin D11 is required for variable spindle output voltages.
|
||||
#define VARIABLE_SPINDLE // Default enabled. Comment to disable.
|
||||
|
||||
// Alters the behavior of the spindle enable pin. By default Grbl will not disable the enable pin if
|
||||
// spindle speed is zero and M3/4 is active, but still sets the PWM output to zero. This allows the users
|
||||
// Alters the behavior of the spindle enable pin. By default Grbl will not disable the enable pin if
|
||||
// spindle speed is zero and M3/4 is active, but still sets the PWM output to zero. This allows the users
|
||||
// to know if the spindle is active and use it as an additional control input.
|
||||
// However, in some use cases, user may want the enable pin to disable with a zero spindle speed and
|
||||
// However, in some use cases, user may want the enable pin to disable with a zero spindle speed and
|
||||
// re-enable when spindle speed is greater than zero. This option does that.
|
||||
#define SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED // Default enabled. Comment to disable.
|
||||
|
||||
@ -551,8 +565,8 @@ Some features should not be changed. See notes below.
|
||||
// #define RX_BUFFER_SIZE 128 // (1-254) Uncomment to override defaults in serial.h
|
||||
// #define TX_BUFFER_SIZE 100 // (1-254)
|
||||
|
||||
// A simple software debouncing feature for hard limit switches. When enabled, the limit
|
||||
// switch interrupt unblock a waiting task which will recheck the limit switch pins after
|
||||
// A simple software debouncing feature for hard limit switches. When enabled, the limit
|
||||
// switch interrupt unblock a waiting task which will recheck the limit switch pins after
|
||||
// a short delay. Default disabled
|
||||
//#define ENABLE_SOFTWARE_DEBOUNCE // Default disabled. Uncomment to enable.
|
||||
#define DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
|
||||
@ -600,7 +614,7 @@ Some features should not be changed. See notes below.
|
||||
// Additional settings have been added to the original set that you see with the $$ command
|
||||
// Some senders may not be able to parse anything different from the original set
|
||||
// You can still set these like $33=5000, but you cannot read them back.
|
||||
// Default is off to limit support issues...you can enable here or in your cpu_map
|
||||
// Default is off to limit support issues...you can enable here or in your machine definition file
|
||||
// #define SHOW_EXTENDED_SETTINGS
|
||||
|
||||
// Enable the '$I=(string)' build info write command. If disabled, any existing build info data must
|
||||
@ -634,8 +648,8 @@ Some features should not be changed. See notes below.
|
||||
#define FORCE_BUFFER_SYNC_DURING_WCO_CHANGE // Default enabled. Comment to disable.
|
||||
|
||||
// By default, Grbl disables feed rate overrides for all G38.x probe cycle commands. Although this
|
||||
// may be different than some pro-class machine control, it's arguable that it should be this way.
|
||||
// Most probe sensors produce different levels of error that is dependent on rate of speed. By
|
||||
// may be different than some pro-class machine control, it's arguable that it should be this way.
|
||||
// Most probe sensors produce different levels of error that is dependent on rate of speed. By
|
||||
// keeping probing cycles to their programmed feed rates, the probe sensor should be a lot more
|
||||
// repeatable. If needed, you can disable this behavior by uncommenting the define below.
|
||||
// #define ALLOW_FEED_OVERRIDE_DURING_PROBE_CYCLES // Default disabled. Uncomment to enable.
|
||||
@ -661,13 +675,13 @@ Some features should not be changed. See notes below.
|
||||
#define PARKING_RATE 500.0 // Parking fast rate after pull-out in mm/min.
|
||||
#define PARKING_PULLOUT_RATE 100.0 // Pull-out/plunge slow feed rate in mm/min.
|
||||
#define PARKING_PULLOUT_INCREMENT 5.0 // Spindle pull-out and plunge distance in mm. Incremental distance.
|
||||
// Must be positive value or equal to zero.
|
||||
// Must be positive value or equal to zero.
|
||||
|
||||
// Enables a special set of M-code commands that enables and disables the parking motion.
|
||||
// These are controlled by `M56`, `M56 P1`, or `M56 Px` to enable and `M56 P0` to disable.
|
||||
// The command is modal and will be set after a planner sync. Since it is g-code, it is
|
||||
// Enables a special set of M-code commands that enables and disables the parking motion.
|
||||
// These are controlled by `M56`, `M56 P1`, or `M56 Px` to enable and `M56 P0` to disable.
|
||||
// The command is modal and will be set after a planner sync. Since it is g-code, it is
|
||||
// executed in sync with g-code commands. It is not a real-time command.
|
||||
// NOTE: PARKING_ENABLE is required. By default, M56 is active upon initialization. Use
|
||||
// NOTE: PARKING_ENABLE is required. By default, M56 is active upon initialization. Use
|
||||
// DEACTIVATE_PARKING_UPON_INIT to set M56 P0 as the power-up default.
|
||||
// #define ENABLE_PARKING_OVERRIDE_CONTROL // Default disabled. Uncomment to enable
|
||||
// #define DEACTIVATE_PARKING_UPON_INIT // Default disabled. Uncomment to enable.
|
||||
@ -679,7 +693,7 @@ Some features should not be changed. See notes below.
|
||||
#define DISABLE_LASER_DURING_HOLD // Default enabled. Comment to disable.
|
||||
|
||||
// Enables a piecewise linear model of the spindle PWM/speed output. Requires a solution by the
|
||||
// 'fit_nonlinear_spindle.py' script in the /doc/script folder of the repo. See file comments
|
||||
// 'fit_nonlinear_spindle.py' script in the /doc/script folder of the repo. See file comments
|
||||
// on how to gather spindle data and run the script to generate a solution.
|
||||
// #define ENABLE_PIECEWISE_LINEAR_SPINDLE // Default disabled. Uncomment to enable.
|
||||
|
||||
@ -716,19 +730,4 @@ Some features should not be changed. See notes below.
|
||||
#define RPM_LINE_A3 9.528342e-03
|
||||
#define RPM_LINE_B3 3.306286e+01
|
||||
|
||||
|
||||
/* ---------------------------------------------------------------------------------------
|
||||
OEM Single File Configuration Option
|
||||
|
||||
Instructions: Paste the cpu_map and default setting definitions below without an enclosing
|
||||
#ifdef. Comment out the CPU_MAP_xxx and DEFAULT_xxx defines at the top of this file, and
|
||||
the compiler will ignore the contents of defaults.h and cpu_map.h and use the definitions
|
||||
below.
|
||||
*/
|
||||
|
||||
// Paste CPU_MAP definitions here.
|
||||
|
||||
// Paste default settings definitions here.
|
||||
|
||||
|
||||
#endif
|
||||
|
@ -3,7 +3,7 @@
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
@ -24,117 +24,98 @@
|
||||
#include "grbl.h"
|
||||
|
||||
|
||||
void coolant_init()
|
||||
{
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
pinMode(COOLANT_FLOOD_PIN, OUTPUT);
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
pinMode(COOLANT_MIST_PIN, OUTPUT);
|
||||
#endif
|
||||
coolant_stop();
|
||||
void coolant_init() {
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
pinMode(COOLANT_FLOOD_PIN, OUTPUT);
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
pinMode(COOLANT_MIST_PIN, OUTPUT);
|
||||
#endif
|
||||
coolant_stop();
|
||||
}
|
||||
|
||||
|
||||
// Returns current coolant output state. Overrides may alter it from programmed state.
|
||||
uint8_t coolant_get_state()
|
||||
{
|
||||
uint8_t cl_state = COOLANT_STATE_DISABLE;
|
||||
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
if (! digitalRead(COOLANT_FLOOD_PIN)) {
|
||||
#else
|
||||
if (digitalRead(COOLANT_FLOOD_PIN)) {
|
||||
#endif
|
||||
cl_state |= COOLANT_STATE_FLOOD;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
if (! digitalRead(COOLANT_MIST_PIN)) {
|
||||
#else
|
||||
if (digitalRead(COOLANT_MIST_PIN)) {
|
||||
#endif
|
||||
cl_state |= COOLANT_STATE_MIST;
|
||||
uint8_t coolant_get_state() {
|
||||
uint8_t cl_state = COOLANT_STATE_DISABLE;
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
if (! digitalRead(COOLANT_FLOOD_PIN)) {
|
||||
#else
|
||||
if (digitalRead(COOLANT_FLOOD_PIN)) {
|
||||
#endif
|
||||
cl_state |= COOLANT_STATE_FLOOD;
|
||||
}
|
||||
#endif
|
||||
|
||||
return(cl_state);
|
||||
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
if (! digitalRead(COOLANT_MIST_PIN)) {
|
||||
#else
|
||||
if (digitalRead(COOLANT_MIST_PIN)) {
|
||||
#endif
|
||||
cl_state |= COOLANT_STATE_MIST;
|
||||
}
|
||||
#endif
|
||||
return (cl_state);
|
||||
}
|
||||
|
||||
|
||||
// Directly called by coolant_init(), coolant_set_state(), and mc_reset(), which can be at
|
||||
// an interrupt-level. No report flag set, but only called by routines that don't need it.
|
||||
void coolant_stop()
|
||||
{
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 1);
|
||||
#else
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 0);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
digitalWrite(COOLANT_MIST_PIN, 1);
|
||||
#else
|
||||
digitalWrite(COOLANT_MIST_PIN, 0);
|
||||
#endif
|
||||
#endif
|
||||
void coolant_stop() {
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 1);
|
||||
#else
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 0);
|
||||
#endif
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
digitalWrite(COOLANT_MIST_PIN, 1);
|
||||
#else
|
||||
digitalWrite(COOLANT_MIST_PIN, 0);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
// Main program only. Immediately sets flood coolant running state and also mist coolant,
|
||||
// Main program only. Immediately sets flood coolant running state and also mist coolant,
|
||||
// if enabled. Also sets a flag to report an update to a coolant state.
|
||||
// Called by coolant toggle override, parking restore, parking retract, sleep mode, g-code
|
||||
// parser program end, and g-code parser coolant_sync().
|
||||
void coolant_set_state(uint8_t mode)
|
||||
{
|
||||
if (sys.abort) { return; } // Block during abort.
|
||||
|
||||
if (mode == COOLANT_DISABLE) {
|
||||
|
||||
coolant_stop();
|
||||
|
||||
} else {
|
||||
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
if (mode & COOLANT_FLOOD_ENABLE) {
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 0);
|
||||
#else
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 1);
|
||||
#endif
|
||||
void coolant_set_state(uint8_t mode) {
|
||||
if (sys.abort) return; // Block during abort.
|
||||
if (mode == COOLANT_DISABLE)
|
||||
coolant_stop();
|
||||
else {
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
if (mode & COOLANT_FLOOD_ENABLE) {
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 0);
|
||||
#else
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 1);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
if (mode & COOLANT_MIST_ENABLE) {
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
digitalWrite(COOLANT_MIST_PIN, 0);
|
||||
#else
|
||||
digitalWrite(COOLANT_MIST_PIN, 1);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
if (mode & COOLANT_MIST_ENABLE) {
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
digitalWrite(COOLANT_MIST_PIN, 0);
|
||||
#else
|
||||
digitalWrite(COOLANT_MIST_PIN, 1);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
}
|
||||
|
||||
|
||||
// G-code parser entry-point for setting coolant state. Forces a planner buffer sync and bails
|
||||
// G-code parser entry-point for setting coolant state. Forces a planner buffer sync and bails
|
||||
// if an abort or check-mode is active.
|
||||
void coolant_sync(uint8_t mode)
|
||||
{
|
||||
if (sys.state == STATE_CHECK_MODE) { return; }
|
||||
protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
|
||||
coolant_set_state(mode);
|
||||
void coolant_sync(uint8_t mode) {
|
||||
if (sys.state == STATE_CHECK_MODE) return;
|
||||
protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
|
||||
coolant_set_state(mode);
|
||||
}
|
||||
|
@ -3,7 +3,7 @@
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
|
1192
Grbl_Esp32/cpu_map.h
1192
Grbl_Esp32/cpu_map.h
File diff suppressed because it is too large
Load Diff
8
Grbl_Esp32/custom_code.cpp
Normal file
8
Grbl_Esp32/custom_code.cpp
Normal file
@ -0,0 +1,8 @@
|
||||
// This file loads custom code from the Custom/ subdirectory if
|
||||
// CUSTOM_CODE_FILENAME is defined.
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
#ifdef CUSTOM_CODE_FILENAME
|
||||
#include CUSTOM_CODE_FILENAME
|
||||
#endif
|
@ -1,171 +0,0 @@
|
||||
/*
|
||||
custom_machine_template.cpp
|
||||
Part of Grbl_ESP32
|
||||
|
||||
copyright (c) 2020 - Bart Dring. This file was intended for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
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_ESP32 is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
=======================================================================
|
||||
|
||||
This is a template of a custom machine file. All of these functions are called by
|
||||
main Grbl_ESP when enabled via #define statements. The machine designer must fill
|
||||
in the contents of the functions. Almost all of them are optional. Remove any
|
||||
unused functions. See each function for more information
|
||||
|
||||
Make copies of custom_machine_template.cpp and custom_machine_template.h
|
||||
and replace the file prefix with your machine's name
|
||||
|
||||
Example:
|
||||
my_machine.h
|
||||
my_machine.cpp
|
||||
|
||||
In cpu_map.h you need to create #include links to your new machine files. This is
|
||||
done using a CPU_MAP name so that you can switch to it in config.h like any of
|
||||
the other defined machine. See the template example at the bottom of cpu_map.h
|
||||
|
||||
Example
|
||||
#ifdef CPU_MAP_MY_MACHINE
|
||||
#include my_machine.h
|
||||
#endif
|
||||
|
||||
in config.h make sure CPU_MAP_MY_MACHINE is the only define cpu map.
|
||||
|
||||
To keep your machine organized and cpu_map.h clean, put all of the stuff normally put in
|
||||
cpu_map.h in your my_machine.h file. There are sections in that template expaining it.
|
||||
|
||||
===============================================================================
|
||||
|
||||
*/
|
||||
|
||||
#ifdef CPU_MAP_CUSTOM_MACHINE // !!! Change this name to your machine map name
|
||||
/*
|
||||
This function is called if you have #define USE_MACHINE_INIT in your my_machine.h file
|
||||
This function will be called when Grbl_ESP32 first starts. You can use it to do any
|
||||
special things your machine needs at startup.
|
||||
*/
|
||||
void machine_init() {
|
||||
|
||||
}
|
||||
|
||||
/*
|
||||
This function is called if you have #define USE_CUSTOM_HOMING in your my_machine.h file
|
||||
This function gets called at the begining of the normal Grbl_ESP32 homing sequence. You
|
||||
Can skip the rest of normal Grbl_ESP32 homing by returning false. You return true if you
|
||||
want normal homing to continue. You might do this if you just need to prep the machine
|
||||
for homing.
|
||||
*/
|
||||
bool user_defined_homing() {
|
||||
return true; // True = done with homing, false = continue with normal Grbl_ESP32 homing
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
Inverse Kinematics converts X,Y,Z cartesian coordinate to the steps on your "joint"
|
||||
motors.
|
||||
|
||||
This function allows you to look at incoming move commands and modify them before
|
||||
Grbl_ESP32 puts them in the motion planner.
|
||||
|
||||
Grbl_ESP32 processes arc by converting them into tiny little line segments.
|
||||
Kinematics in Grbl_ESP32 works the same way. Search for this function across Grbl_ESP32
|
||||
for examples. You are basically converting cartesian X,Y,Z... targets to
|
||||
|
||||
target = an N_AXIS array of target positions (where the move is supposed to go)
|
||||
pl_data = planner data (see the definition of this type to see what it is)
|
||||
position = an N_AXIS array of where the machine is starting from for this move
|
||||
*/
|
||||
void inverse_kinematics(target, pl_data, position) {
|
||||
|
||||
mc_line(target, pl_data); // this simply moves to the target Replace with your kinematics.
|
||||
}
|
||||
|
||||
/*
|
||||
Forward Kinematics converts your motor postions to X,Y,Z... cartesian information.
|
||||
This is used by the status command.
|
||||
|
||||
Convert the N_AXIS array of motor positions to cartesian in your code.
|
||||
|
||||
*/
|
||||
void forward_kinematics(float *position) {
|
||||
|
||||
// position[X_AXIS] =
|
||||
// position[Y_AXIS] =
|
||||
}
|
||||
|
||||
/*
|
||||
This function is required if you have #define USE_KINEMATIC
|
||||
This function is called before normal homing
|
||||
You can use it to do special homing or just to set stuff up
|
||||
|
||||
cycle_mask = is a bit mask of the axes being homed this time.
|
||||
|
||||
*/
|
||||
bool kinematics_pre_homing(cycle_mask)) {
|
||||
return false; // finish normal homing cycle
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
This function is required if you have #define USE_KINEMATIC
|
||||
It is called at the end of normal homing
|
||||
|
||||
*/
|
||||
void kinematics_post_homing() {
|
||||
|
||||
}
|
||||
|
||||
/*
|
||||
This function is called if #USE_TOOL_CHANGE is define and
|
||||
a gcode for a tool change is received
|
||||
|
||||
*/
|
||||
void user_tool_change(uint8_t new_tool) {
|
||||
|
||||
}
|
||||
|
||||
/*
|
||||
This will be called if any of the #define MACRO_BUTTON_0_PIN options
|
||||
are defined
|
||||
*/
|
||||
void user_defined_macro(uint8_t index)
|
||||
{
|
||||
}
|
||||
|
||||
/*
|
||||
This function is called if #define USE_M30 is defined and
|
||||
an M30 gcode is received. M30 signals the end of a gcode file.
|
||||
|
||||
|
||||
*/
|
||||
void user_m30() {
|
||||
}
|
||||
|
||||
/*
|
||||
Enable this function with #define USE_MACHINE_TRINAMIC_INIT
|
||||
This will replace the normal setup of trinamic drivers with your own
|
||||
This is where you could setup StallGaurd
|
||||
|
||||
*/
|
||||
void machine_trinamic_setup() {
|
||||
|
||||
}
|
||||
|
||||
|
||||
// feel free to add any additional functions specific to your machine
|
||||
|
||||
|
||||
#endif
|
@ -1,96 +0,0 @@
|
||||
/*
|
||||
custom_machine_template.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
copyright (c) 2020 - Bart Dring. This file was intended for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
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_ESP32 is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
====================================================================
|
||||
|
||||
See custom_machine_templete.cpp for getting started creating custom
|
||||
machines
|
||||
|
||||
*/
|
||||
|
||||
// ================ config.h overrides ========================================
|
||||
/*
|
||||
|
||||
If you want to make some changes to config.h, it might be easier to do it here
|
||||
so all your changes are in your files.
|
||||
|
||||
example to change baud rate
|
||||
#ifdef BAUD_RATE
|
||||
#undef BAUDRATE
|
||||
#endif
|
||||
#define BAUD_RATE 9600
|
||||
|
||||
example to change the number of axes
|
||||
#idef N_AXIS
|
||||
#undef N_AXIS
|
||||
#endif
|
||||
#define N_AXIS 4
|
||||
|
||||
|
||||
*/
|
||||
|
||||
|
||||
// =============== CPU MAP ========================
|
||||
// Look at cpu_map.h for all the things that can go here
|
||||
|
||||
|
||||
#define CPU_MAP_NAME "CPU_MAP_MY_MACHINE"
|
||||
|
||||
#define LIMIT_MASK B111 // you need this with as many switches you are using
|
||||
|
||||
// ============== Enable custom features =======================
|
||||
|
||||
// #define #USE_MACHINE_INIT
|
||||
// #define USE_CUSTOM_HOMING
|
||||
// #define USE_KINEMATICS
|
||||
// #define USE_FWD_KINEMATIC
|
||||
// #define USE_TOOL_CHANGE
|
||||
// #define USE_M30
|
||||
// #define USE_MACHINE_TRINAMIC_INIT
|
||||
|
||||
// ===================== $$ Defaults ==========================================
|
||||
/* These are default values for any of the $$ settings.
|
||||
This will automatically set them when you upload new firmware or if you
|
||||
reset them with $RST=$.
|
||||
All default values are set in the defaults.h file. You would only need to
|
||||
put values here that are different from those values
|
||||
Below are a few examples
|
||||
*/
|
||||
#define DEFAULT_SPINDLE_FREQ 2000.0
|
||||
#define DEFAULT_X_MAX_TRAVEL 100.0
|
||||
|
||||
#ifndef custom_machine_template_h // !!!!!!!!!!!!!!! Change this to your file !!!!!!!!!!!!!
|
||||
#define custom_machine_template_h // !!! here too !!!!
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
// ================ Function Prototypes ================
|
||||
void machine_init();
|
||||
bool user_defined_homing();
|
||||
void inverse_kinematics(float *target, plan_line_data_t *pl_data, float *position);
|
||||
void forward_kinematics(float *position);
|
||||
void kinematics_post_homing();
|
||||
void user_tool_change(uint8_t new_tool);
|
||||
void user_defined_macro(uint8_t index);
|
||||
void user_m30();
|
||||
void machine_trinamic_setup();
|
||||
|
||||
#endif
|
||||
|
@ -3,7 +3,7 @@
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
@ -30,332 +30,332 @@
|
||||
|
||||
#ifndef defaults_h
|
||||
|
||||
/*
|
||||
All of these settings check to see if they have been defined already
|
||||
before defining them. This allows to to easily set them eslewhere.
|
||||
You only need to set ones that are important or unique to your
|
||||
machine. The rest will be pulled from here.
|
||||
*/
|
||||
/*
|
||||
All of these settings check to see if they have been defined already
|
||||
before defining them. This allows to to easily set them eslewhere.
|
||||
You only need to set ones that are important or unique to your
|
||||
machine. The rest will be pulled from here.
|
||||
*/
|
||||
|
||||
// Grbl generic default settings. Should work across different machines.
|
||||
#ifndef DEFAULT_STEP_PULSE_MICROSECONDS
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3 // $0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_STEPPER_IDLE_LOCK_TIME
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // $1 msec (0-254, 255 keeps steppers enabled)
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_STEPPING_INVERT_MASK
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // $2 uint8_t
|
||||
#endif
|
||||
// Grbl generic default settings. Should work across different machines.
|
||||
#ifndef DEFAULT_STEP_PULSE_MICROSECONDS
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3 // $0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_DIRECTION_INVERT_MASK
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // $3 uint8_
|
||||
#endif
|
||||
#ifndef DEFAULT_STEPPER_IDLE_LOCK_TIME
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // $1 msec (0-254, 255 keeps steppers enabled)
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_INVERT_ST_ENABLE
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // $4 boolean
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_INVERT_LIMIT_PINS
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // $5 boolean
|
||||
#endif
|
||||
#ifndef DEFAULT_STEPPING_INVERT_MASK
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0 // $2 uint8_t
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_INVERT_PROBE_PIN
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // $6 boolean
|
||||
#endif
|
||||
#ifndef DEFAULT_DIRECTION_INVERT_MASK
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0 // $3 uint8_
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_STATUS_REPORT_MASK
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1 // $10
|
||||
#endif
|
||||
#ifndef DEFAULT_INVERT_ST_ENABLE
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // $4 boolean
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_JUNCTION_DEVIATION
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // $11 mm
|
||||
#endif
|
||||
#ifndef DEFAULT_INVERT_LIMIT_PINS
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // $5 boolean
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_ARC_TOLERANCE
|
||||
#define DEFAULT_ARC_TOLERANCE 0.002 // $12 mm
|
||||
#endif
|
||||
#ifndef DEFAULT_INVERT_PROBE_PIN
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // $6 boolean
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_REPORT_INCHES
|
||||
#define DEFAULT_REPORT_INCHES 0 // $13 false
|
||||
#endif
|
||||
#ifndef DEFAULT_STATUS_REPORT_MASK
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1 // $10
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_SOFT_LIMIT_ENABLE
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // $20 false
|
||||
#endif
|
||||
#ifndef DEFAULT_JUNCTION_DEVIATION
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // $11 mm
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HARD_LIMIT_ENABLE
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // $21 false
|
||||
#endif
|
||||
#ifndef DEFAULT_ARC_TOLERANCE
|
||||
#define DEFAULT_ARC_TOLERANCE 0.002 // $12 mm
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HOMING_ENABLE
|
||||
#define DEFAULT_HOMING_ENABLE 0 // $22 false
|
||||
#endif
|
||||
#ifndef DEFAULT_REPORT_INCHES
|
||||
#define DEFAULT_REPORT_INCHES 0 // $13 false
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HOMING_DIR_MASK
|
||||
#define DEFAULT_HOMING_DIR_MASK 3 // $23 move positive dir Z, negative X,Y
|
||||
#endif
|
||||
#ifndef DEFAULT_SOFT_LIMIT_ENABLE
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // $20 false
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HOMING_FEED_RATE
|
||||
#define DEFAULT_HOMING_FEED_RATE 200.0 // $24 mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_HARD_LIMIT_ENABLE
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // $21 false
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HOMING_SEEK_RATE
|
||||
#define DEFAULT_HOMING_SEEK_RATE 2000.0 // $25 mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_HOMING_ENABLE
|
||||
#define DEFAULT_HOMING_ENABLE 0 // $22 false
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HOMING_DEBOUNCE_DELAY
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // $26 msec (0-65k)
|
||||
#endif
|
||||
#ifndef DEFAULT_HOMING_DIR_MASK
|
||||
#define DEFAULT_HOMING_DIR_MASK 3 // $23 move positive dir Z, negative X,Y
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HOMING_PULLOFF
|
||||
#define DEFAULT_HOMING_PULLOFF 1.0 // $27 mm
|
||||
#endif
|
||||
#ifndef DEFAULT_HOMING_FEED_RATE
|
||||
#define DEFAULT_HOMING_FEED_RATE 200.0 // $24 mm/min
|
||||
#endif
|
||||
|
||||
// ======== sPINDLE STUFF ====================
|
||||
#ifndef DEFAULT_HOMING_SEEK_RATE
|
||||
#define DEFAULT_HOMING_SEEK_RATE 2000.0 // $25 mm/min
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_SPINDLE_FREQ
|
||||
#define DEFAULT_SPINDLE_FREQ 5000.0 // $33 Hz (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_HOMING_DEBOUNCE_DELAY
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // $26 msec (0-65k)
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_SPINDLE_OFF_VALUE
|
||||
#define DEFAULT_SPINDLE_OFF_VALUE 0.0 // $34 Percent (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_HOMING_PULLOFF
|
||||
#define DEFAULT_HOMING_PULLOFF 1.0 // $27 mm
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_SPINDLE_MIN_VALUE
|
||||
#define DEFAULT_SPINDLE_MIN_VALUE 0.0 // $35 Percent (extended set)
|
||||
#endif
|
||||
// ======== sPINDLE STUFF ====================
|
||||
|
||||
#ifndef DEFAULT_SPINDLE_MAX_VALUE
|
||||
#define DEFAULT_SPINDLE_MAX_VALUE 100.0 // $36 Percent (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_SPINDLE_FREQ
|
||||
#define DEFAULT_SPINDLE_FREQ 5000.0 // $33 Hz (extended set)
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_SPINDLE_RPM_MAX
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
||||
#endif
|
||||
#ifndef DEFAULT_SPINDLE_OFF_VALUE
|
||||
#define DEFAULT_SPINDLE_OFF_VALUE 0.0 // $34 Percent (extended set)
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_SPINDLE_MIN_VALUE
|
||||
#define DEFAULT_SPINDLE_MIN_VALUE 0.0 // $35 Percent (extended set)
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_SPINDLE_MAX_VALUE
|
||||
#define DEFAULT_SPINDLE_MAX_VALUE 100.0 // $36 Percent (extended set)
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_SPINDLE_RPM_MAX
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef DEFAULT_SPINDLE_RPM_MIN
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
#endif
|
||||
#ifndef DEFAULT_SPINDLE_RPM_MIN
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_LASER_MODE
|
||||
#define DEFAULT_LASER_MODE 0 // false
|
||||
#endif
|
||||
#ifndef DEFAULT_LASER_MODE
|
||||
#define DEFAULT_LASER_MODE 0 // false
|
||||
#endif
|
||||
|
||||
// user settings
|
||||
#ifndef DEFAULT_USER_INT_80
|
||||
#define DEFAULT_USER_INT_80 0 // $80 User integer setting
|
||||
#endif
|
||||
// user settings
|
||||
#ifndef DEFAULT_USER_INT_80
|
||||
#define DEFAULT_USER_INT_80 0 // $80 User integer setting
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_USER_INT_81
|
||||
#define DEFAULT_USER_INT_81 0 // $81 User integer setting
|
||||
#endif
|
||||
#ifndef DEFAULT_USER_INT_81
|
||||
#define DEFAULT_USER_INT_81 0 // $81 User integer setting
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_USER_INT_82
|
||||
#define DEFAULT_USER_INT_82 0 // $82 User integer setting
|
||||
#endif
|
||||
#ifndef DEFAULT_USER_INT_82
|
||||
#define DEFAULT_USER_INT_82 0 // $82 User integer setting
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_USER_INT_83
|
||||
#define DEFAULT_USER_INT_83 0 // $83 User integer setting
|
||||
#endif
|
||||
#ifndef DEFAULT_USER_INT_83
|
||||
#define DEFAULT_USER_INT_83 0 // $83 User integer setting
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_USER_INT_84
|
||||
#define DEFAULT_USER_INT_84 0 // $84 User integer setting
|
||||
#endif
|
||||
#ifndef DEFAULT_USER_INT_84
|
||||
#define DEFAULT_USER_INT_84 0 // $84 User integer setting
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_USER_FLOAT_90
|
||||
#define DEFAULT_USER_FLOAT_90 0.0 // $90 User integer setting
|
||||
#endif
|
||||
#ifndef DEFAULT_USER_FLOAT_90
|
||||
#define DEFAULT_USER_FLOAT_90 0.0 // $90 User integer setting
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_USER_FLOAT_91
|
||||
#define DEFAULT_USER_FLOAT_91 0.0 // $92 User integer setting
|
||||
#endif
|
||||
#ifndef DEFAULT_USER_FLOAT_91
|
||||
#define DEFAULT_USER_FLOAT_91 0.0 // $92 User integer setting
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_USER_FLOAT_92
|
||||
#define DEFAULT_USER_FLOAT_92 0.0 // $92 User integer setting
|
||||
#endif
|
||||
#ifndef DEFAULT_USER_FLOAT_92
|
||||
#define DEFAULT_USER_FLOAT_92 0.0 // $92 User integer setting
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_USER_FLOAT_93
|
||||
#define DEFAULT_USER_FLOAT_93 0.0 // $93 User integer setting
|
||||
#endif
|
||||
#ifndef DEFAULT_USER_FLOAT_93
|
||||
#define DEFAULT_USER_FLOAT_93 0.0 // $93 User integer setting
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_USER_FLOAT_94
|
||||
#define DEFAULT_USER_FLOAT_94 0.0 // $94 User integer setting
|
||||
#endif
|
||||
#ifndef DEFAULT_USER_FLOAT_94
|
||||
#define DEFAULT_USER_FLOAT_94 0.0 // $94 User integer setting
|
||||
#endif
|
||||
|
||||
|
||||
// =========== AXIS RESOLUTION ======
|
||||
// =========== AXIS RESOLUTION ======
|
||||
|
||||
#ifndef DEFAULT_X_STEPS_PER_MM
|
||||
#define DEFAULT_X_STEPS_PER_MM 100.0
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_STEPS_PER_MM
|
||||
#define DEFAULT_Y_STEPS_PER_MM 100.0
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_STEPS_PER_MM
|
||||
#define DEFAULT_Z_STEPS_PER_MM 100.0
|
||||
#endif
|
||||
#ifndef DEFAULT_A_STEPS_PER_MM
|
||||
#define DEFAULT_A_STEPS_PER_MM 100.0
|
||||
#endif
|
||||
#ifndef DEFAULT_B_STEPS_PER_MM
|
||||
#define DEFAULT_B_STEPS_PER_MM 100.0
|
||||
#endif
|
||||
#ifndef DEFAULT_C_STEPS_PER_MM
|
||||
#define DEFAULT_C_STEPS_PER_MM 100.0
|
||||
#endif
|
||||
#ifndef DEFAULT_X_STEPS_PER_MM
|
||||
#define DEFAULT_X_STEPS_PER_MM 100.0
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_STEPS_PER_MM
|
||||
#define DEFAULT_Y_STEPS_PER_MM 100.0
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_STEPS_PER_MM
|
||||
#define DEFAULT_Z_STEPS_PER_MM 100.0
|
||||
#endif
|
||||
#ifndef DEFAULT_A_STEPS_PER_MM
|
||||
#define DEFAULT_A_STEPS_PER_MM 100.0
|
||||
#endif
|
||||
#ifndef DEFAULT_B_STEPS_PER_MM
|
||||
#define DEFAULT_B_STEPS_PER_MM 100.0
|
||||
#endif
|
||||
#ifndef DEFAULT_C_STEPS_PER_MM
|
||||
#define DEFAULT_C_STEPS_PER_MM 100.0
|
||||
#endif
|
||||
|
||||
// ============ AXIS MAX SPPED =========
|
||||
// ============ AXIS MAX SPPED =========
|
||||
|
||||
#ifndef DEFAULT_X_MAX_RATE
|
||||
#define DEFAULT_X_MAX_RATE 1000.0 // mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_MAX_RATE
|
||||
#define DEFAULT_Y_MAX_RATE 1000.0 // mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_MAX_RATE
|
||||
#define DEFAULT_Z_MAX_RATE 1000.0 // mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_A_MAX_RATE
|
||||
#define DEFAULT_A_MAX_RATE 1000.0 // mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_B_MAX_RATE
|
||||
#define DEFAULT_B_MAX_RATE 1000.0 // mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_C_MAX_RATE
|
||||
#define DEFAULT_C_MAX_RATE 1000.0 // mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_X_MAX_RATE
|
||||
#define DEFAULT_X_MAX_RATE 1000.0 // mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_MAX_RATE
|
||||
#define DEFAULT_Y_MAX_RATE 1000.0 // mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_MAX_RATE
|
||||
#define DEFAULT_Z_MAX_RATE 1000.0 // mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_A_MAX_RATE
|
||||
#define DEFAULT_A_MAX_RATE 1000.0 // mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_B_MAX_RATE
|
||||
#define DEFAULT_B_MAX_RATE 1000.0 // mm/min
|
||||
#endif
|
||||
#ifndef DEFAULT_C_MAX_RATE
|
||||
#define DEFAULT_C_MAX_RATE 1000.0 // mm/min
|
||||
#endif
|
||||
|
||||
// ============== Axis Acceleration =========
|
||||
// ============== Axis Acceleration =========
|
||||
|
||||
#ifndef DEFAULT_X_ACCELERATION
|
||||
#define DEFAULT_X_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_ACCELERATION
|
||||
#define DEFAULT_Y_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_ACCELERATION
|
||||
#define DEFAULT_Z_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#endif
|
||||
#ifndef DEFAULT_A_ACCELERATION
|
||||
#define DEFAULT_A_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#endif
|
||||
#ifndef DEFAULT_B_ACCELERATION
|
||||
#define DEFAULT_B_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#endif
|
||||
#ifndef DEFAULT_C_ACCELERATION
|
||||
#define DEFAULT_C_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#endif
|
||||
#ifndef DEFAULT_X_ACCELERATION
|
||||
#define DEFAULT_X_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_ACCELERATION
|
||||
#define DEFAULT_Y_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_ACCELERATION
|
||||
#define DEFAULT_Z_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#endif
|
||||
#ifndef DEFAULT_A_ACCELERATION
|
||||
#define DEFAULT_A_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#endif
|
||||
#ifndef DEFAULT_B_ACCELERATION
|
||||
#define DEFAULT_B_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#endif
|
||||
#ifndef DEFAULT_C_ACCELERATION
|
||||
#define DEFAULT_C_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#endif
|
||||
|
||||
// ========= AXIS MAX TRAVEL ============
|
||||
// ========= AXIS MAX TRAVEL ============
|
||||
|
||||
#ifndef DEFAULT_X_MAX_TRAVEL
|
||||
#define DEFAULT_X_MAX_TRAVEL 300.0 // $130 mm NOTE: Must be a positive value.
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_MAX_TRAVEL
|
||||
#define DEFAULT_Y_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_MAX_TRAVEL
|
||||
#define DEFAULT_Z_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#endif
|
||||
#ifndef DEFAULT_A_TRAVEL
|
||||
#define DEFAULT_A_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#endif
|
||||
#ifndef DEFAULT_B_MAX_TRAVEL
|
||||
#define DEFAULT_B_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#endif
|
||||
#ifndef DEFAULT_C_MAX_TRAVEL
|
||||
#define DEFAULT_C_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#endif
|
||||
#ifndef DEFAULT_X_MAX_TRAVEL
|
||||
#define DEFAULT_X_MAX_TRAVEL 300.0 // $130 mm NOTE: Must be a positive value.
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_MAX_TRAVEL
|
||||
#define DEFAULT_Y_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_MAX_TRAVEL
|
||||
#define DEFAULT_Z_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#endif
|
||||
#ifndef DEFAULT_A_MAX_TRAVEL
|
||||
#define DEFAULT_A_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#endif
|
||||
#ifndef DEFAULT_B_MAX_TRAVEL
|
||||
#define DEFAULT_B_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#endif
|
||||
#ifndef DEFAULT_C_MAX_TRAVEL
|
||||
#define DEFAULT_C_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#endif
|
||||
|
||||
// ========== Motor current (SPI Drivers ) =============
|
||||
#ifndef DEFAULT_X_CURRENT
|
||||
#define DEFAULT_X_CURRENT 0.25 // $140 current in amps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_CURRENT
|
||||
#define DEFAULT_Y_CURRENT 0.25 // $141 current in amps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_CURRENT
|
||||
#define DEFAULT_Z_CURRENT 0.25 // $142 current in amps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_A_CURRENT
|
||||
#define DEFAULT_A_CURRENT 0.25 // $143 current in amps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_B_CURRENT
|
||||
#define DEFAULT_B_CURRENT 0.25 // $144 current in amps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_C_CURRENT
|
||||
#define DEFAULT_C_CURRENT 0.25 // $145 current in amps (extended set)
|
||||
#endif
|
||||
// ========== Motor current (SPI Drivers ) =============
|
||||
#ifndef DEFAULT_X_CURRENT
|
||||
#define DEFAULT_X_CURRENT 0.25 // $140 current in amps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_CURRENT
|
||||
#define DEFAULT_Y_CURRENT 0.25 // $141 current in amps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_CURRENT
|
||||
#define DEFAULT_Z_CURRENT 0.25 // $142 current in amps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_A_CURRENT
|
||||
#define DEFAULT_A_CURRENT 0.25 // $143 current in amps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_B_CURRENT
|
||||
#define DEFAULT_B_CURRENT 0.25 // $144 current in amps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_C_CURRENT
|
||||
#define DEFAULT_C_CURRENT 0.25 // $145 current in amps (extended set)
|
||||
#endif
|
||||
|
||||
// ========== Motor hold current (SPI Drivers ) =============
|
||||
// ========== Motor hold current (SPI Drivers ) =============
|
||||
|
||||
#ifndef DEFAULT_X_HOLD_CURRENT
|
||||
#define DEFAULT_X_HOLD_CURRENT 50 // $150 percent of run current (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_HOLD_CURRENT
|
||||
#define DEFAULT_Y_HOLD_CURRENT 50 // $151 percent of run current (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_HOLD_CURRENT
|
||||
#define DEFAULT_Z_HOLD_CURRENT 50 // $152 percent of run current (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_A_HOLD_CURRENT
|
||||
#define DEFAULT_A_HOLD_CURRENT 50 // $153 percent of run current (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_B_HOLD_CURRENT
|
||||
#define DEFAULT_B_HOLD_CURRENT 50 // $154 percent of run current (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_C_HOLD_CURRENT
|
||||
#define DEFAULT_C_HOLD_CURRENT 50 // $154 percent of run current (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_X_HOLD_CURRENT
|
||||
#define DEFAULT_X_HOLD_CURRENT 50 // $150 percent of run current (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_HOLD_CURRENT
|
||||
#define DEFAULT_Y_HOLD_CURRENT 50 // $151 percent of run current (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_HOLD_CURRENT
|
||||
#define DEFAULT_Z_HOLD_CURRENT 50 // $152 percent of run current (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_A_HOLD_CURRENT
|
||||
#define DEFAULT_A_HOLD_CURRENT 50 // $153 percent of run current (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_B_HOLD_CURRENT
|
||||
#define DEFAULT_B_HOLD_CURRENT 50 // $154 percent of run current (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_C_HOLD_CURRENT
|
||||
#define DEFAULT_C_HOLD_CURRENT 50 // $154 percent of run current (extended set)
|
||||
#endif
|
||||
|
||||
// ========== Microsteps (SPI Drivers ) ================
|
||||
// ========== Microsteps (SPI Drivers ) ================
|
||||
|
||||
#ifndef DEFAULT_X_MICROSTEPS
|
||||
#define DEFAULT_X_MICROSTEPS 16 // $160 micro steps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_MICROSTEPS
|
||||
#define DEFAULT_Y_MICROSTEPS 16 // $161 micro steps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_MICROSTEPS
|
||||
#define DEFAULT_Z_MICROSTEPS 16 // $162 micro steps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_A_MICROSTEPS
|
||||
#define DEFAULT_A_MICROSTEPS 16 // $163 micro steps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_B_MICROSTEPS
|
||||
#define DEFAULT_B_MICROSTEPS 16 // $164 micro steps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_C_MICROSTEPS
|
||||
#define DEFAULT_C_MICROSTEPS 16 // $165 micro steps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_X_MICROSTEPS
|
||||
#define DEFAULT_X_MICROSTEPS 16 // $160 micro steps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_MICROSTEPS
|
||||
#define DEFAULT_Y_MICROSTEPS 16 // $161 micro steps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_MICROSTEPS
|
||||
#define DEFAULT_Z_MICROSTEPS 16 // $162 micro steps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_A_MICROSTEPS
|
||||
#define DEFAULT_A_MICROSTEPS 16 // $163 micro steps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_B_MICROSTEPS
|
||||
#define DEFAULT_B_MICROSTEPS 16 // $164 micro steps (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_C_MICROSTEPS
|
||||
#define DEFAULT_C_MICROSTEPS 16 // $165 micro steps (extended set)
|
||||
#endif
|
||||
|
||||
// ========== Stallguard (SPI Drivers ) ================
|
||||
// ========== Stallguard (SPI Drivers ) ================
|
||||
|
||||
#ifndef DEFAULT_X_STALLGUARD
|
||||
#define DEFAULT_X_STALLGUARD 16 // $170 stallguard (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_STALLGUARD
|
||||
#define DEFAULT_Y_STALLGUARD 16 // $171 stallguard (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_STALLGUARD
|
||||
#define DEFAULT_Z_STALLGUARD 16 // $172 stallguard (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_A_STALLGUARD
|
||||
#define DEFAULT_A_STALLGUARD 16 // $173 stallguard (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_B_STALLGUARD
|
||||
#define DEFAULT_B_STALLGUARD 16 // $174 stallguard (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_C_STALLGUARD
|
||||
#define DEFAULT_C_STALLGUARD 16 // $175 stallguard (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_X_STALLGUARD
|
||||
#define DEFAULT_X_STALLGUARD 16 // $170 stallguard (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Y_STALLGUARD
|
||||
#define DEFAULT_Y_STALLGUARD 16 // $171 stallguard (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_Z_STALLGUARD
|
||||
#define DEFAULT_Z_STALLGUARD 16 // $172 stallguard (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_A_STALLGUARD
|
||||
#define DEFAULT_A_STALLGUARD 16 // $173 stallguard (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_B_STALLGUARD
|
||||
#define DEFAULT_B_STALLGUARD 16 // $174 stallguard (extended set)
|
||||
#endif
|
||||
#ifndef DEFAULT_C_STALLGUARD
|
||||
#define DEFAULT_C_STALLGUARD 16 // $175 stallguard (extended set)
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
@ -20,69 +20,67 @@
|
||||
#include "config.h"
|
||||
#include "espresponse.h"
|
||||
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
|
||||
#include "web_server.h"
|
||||
#include <WebServer.h>
|
||||
#include "web_server.h"
|
||||
#include <WebServer.h>
|
||||
#endif
|
||||
|
||||
#include "report.h"
|
||||
|
||||
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
|
||||
ESPResponseStream::ESPResponseStream(WebServer * webserver){
|
||||
_header_sent=false;
|
||||
ESPResponseStream::ESPResponseStream(WebServer* webserver) {
|
||||
_header_sent = false;
|
||||
_webserver = webserver;
|
||||
_client = CLIENT_WEBUI;
|
||||
}
|
||||
#endif
|
||||
|
||||
ESPResponseStream::ESPResponseStream(){
|
||||
ESPResponseStream::ESPResponseStream() {
|
||||
_client = CLIENT_INPUT;
|
||||
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
|
||||
_header_sent=false;
|
||||
_header_sent = false;
|
||||
_webserver = NULL;
|
||||
#endif
|
||||
}
|
||||
|
||||
ESPResponseStream::ESPResponseStream(uint8_t client, bool byid){
|
||||
ESPResponseStream::ESPResponseStream(uint8_t client, bool byid) {
|
||||
(void)byid; //fake parameter to avoid confusion with pointer one (NULL == 0)
|
||||
_client = client;
|
||||
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
|
||||
_header_sent=false;
|
||||
_header_sent = false;
|
||||
_webserver = NULL;
|
||||
#endif
|
||||
}
|
||||
|
||||
void ESPResponseStream::println(const char *data){
|
||||
void ESPResponseStream::println(const char* data) {
|
||||
print(data);
|
||||
if (_client == CLIENT_TELNET) print("\r\n");
|
||||
else print("\n");
|
||||
}
|
||||
|
||||
//helper to format size to readable string
|
||||
String ESPResponseStream::formatBytes (uint64_t bytes)
|
||||
{
|
||||
if (bytes < 1024) {
|
||||
return String ((uint16_t)bytes) + " B";
|
||||
} else if (bytes < (1024 * 1024) ) {
|
||||
return String ((float)(bytes / 1024.0),2) + " KB";
|
||||
} else if (bytes < (1024 * 1024 * 1024) ) {
|
||||
return String ((float)(bytes / 1024.0 / 1024.0),2) + " MB";
|
||||
} else {
|
||||
return String ((float)(bytes / 1024.0 / 1024.0 / 1024.0),2) + " GB";
|
||||
}
|
||||
String ESPResponseStream::formatBytes(uint64_t bytes) {
|
||||
if (bytes < 1024)
|
||||
return String((uint16_t)bytes) + " B";
|
||||
else if (bytes < (1024 * 1024))
|
||||
return String((float)(bytes / 1024.0), 2) + " KB";
|
||||
else if (bytes < (1024 * 1024 * 1024))
|
||||
return String((float)(bytes / 1024.0 / 1024.0), 2) + " MB";
|
||||
else
|
||||
return String((float)(bytes / 1024.0 / 1024.0 / 1024.0), 2) + " GB";
|
||||
}
|
||||
|
||||
void ESPResponseStream::print(const char *data){
|
||||
void ESPResponseStream::print(const char* data) {
|
||||
if (_client == CLIENT_INPUT) return;
|
||||
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
|
||||
if (_webserver) {
|
||||
if (!_header_sent) {
|
||||
_webserver->setContentLength(CONTENT_LENGTH_UNKNOWN);
|
||||
_webserver->sendHeader("Content-Type","text/html");
|
||||
_webserver->sendHeader("Cache-Control","no-cache");
|
||||
_webserver->send(200);
|
||||
_header_sent = true;
|
||||
}
|
||||
_buffer+=data;
|
||||
_webserver->setContentLength(CONTENT_LENGTH_UNKNOWN);
|
||||
_webserver->sendHeader("Content-Type", "text/html");
|
||||
_webserver->sendHeader("Cache-Control", "no-cache");
|
||||
_webserver->send(200);
|
||||
_header_sent = true;
|
||||
}
|
||||
_buffer += data;
|
||||
if (_buffer.length() > 1200) {
|
||||
//send data
|
||||
_webserver->sendContent(_buffer);
|
||||
@ -96,15 +94,15 @@ void ESPResponseStream::print(const char *data){
|
||||
grbl_send(_client, data);
|
||||
}
|
||||
|
||||
void ESPResponseStream::flush(){
|
||||
void ESPResponseStream::flush() {
|
||||
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
|
||||
if (_webserver) {
|
||||
if(_header_sent) {
|
||||
if (_header_sent) {
|
||||
//send data
|
||||
if(_buffer.length() > 0)_webserver->sendContent(_buffer);
|
||||
if (_buffer.length() > 0)_webserver->sendContent(_buffer);
|
||||
//close connection
|
||||
_webserver->sendContent("");
|
||||
}
|
||||
}
|
||||
_header_sent = false;
|
||||
_buffer = "";
|
||||
}
|
||||
|
@ -23,26 +23,26 @@
|
||||
#include "config.h"
|
||||
|
||||
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
|
||||
class WebServer;
|
||||
class WebServer;
|
||||
#endif
|
||||
|
||||
class ESPResponseStream{
|
||||
public:
|
||||
void print(const char *data);
|
||||
void println(const char *data);
|
||||
class ESPResponseStream {
|
||||
public:
|
||||
void print(const char* data);
|
||||
void println(const char* data);
|
||||
void flush();
|
||||
static String formatBytes (uint64_t bytes);
|
||||
static String formatBytes(uint64_t bytes);
|
||||
uint8_t client() {return _client;}
|
||||
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
|
||||
ESPResponseStream(WebServer * webserver);
|
||||
ESPResponseStream(WebServer* webserver);
|
||||
#endif
|
||||
ESPResponseStream(uint8_t client, bool byid = true);
|
||||
ESPResponseStream();
|
||||
private:
|
||||
private:
|
||||
uint8_t _client;
|
||||
#if defined (ENABLE_HTTP) && defined(ENABLE_WIFI)
|
||||
bool _header_sent;
|
||||
WebServer * _webserver;
|
||||
WebServer* _webserver;
|
||||
String _buffer;
|
||||
#endif
|
||||
};
|
||||
|
2555
Grbl_Esp32/gcode.cpp
2555
Grbl_Esp32/gcode.cpp
File diff suppressed because it is too large
Load Diff
@ -4,10 +4,10 @@
|
||||
|
||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
@ -22,9 +22,9 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#ifndef gcode_h
|
||||
#define gcode_h
|
||||
#define gcode_h
|
||||
|
||||
|
||||
|
||||
// Define modal group internal numbers for checking multiple command violations and tracking the
|
||||
// type of command that is called in the block. A modal group is a group of g-code commands that are
|
||||
// mutually exclusive, or cannot exist on the same line, because they each toggle a state or execute
|
||||
@ -55,22 +55,22 @@
|
||||
|
||||
// Define command actions for within execution-type modal groups (motion, stopping, non-modal). Used
|
||||
// internally by the parser to know which command to execute.
|
||||
// NOTE: Some macro values are assigned specific values to make g-code state reporting and parsing
|
||||
// NOTE: Some macro values are assigned specific values to make g-code state reporting and parsing
|
||||
// compile a litte smaller. Necessary due to being completely out of flash on the 328p. Although not
|
||||
// ideal, just be careful with values that state 'do not alter' and check both report.c and gcode.c
|
||||
// ideal, just be careful with values that state 'do not alter' and check both report.c and gcode.c
|
||||
// to see how they are used, if you need to alter them.
|
||||
|
||||
// Modal Group G0: Non-modal actions
|
||||
#define NON_MODAL_NO_ACTION 0 // (Default: Must be zero)
|
||||
#define NON_MODAL_DWELL 4 // G4 (Do not alter value)
|
||||
#define NON_MODAL_SET_COORDINATE_DATA 10 // G10 (Do not alter value)
|
||||
#define NON_MODAL_GO_HOME_0 28 // G28 (Do not alter value)
|
||||
#define NON_MODAL_SET_HOME_0 38 // G28.1 (Do not alter value)
|
||||
#define NON_MODAL_GO_HOME_1 30 // G30 (Do not alter value)
|
||||
#define NON_MODAL_SET_HOME_1 40 // G30.1 (Do not alter value)
|
||||
#define NON_MODAL_ABSOLUTE_OVERRIDE 53 // G53 (Do not alter value)
|
||||
#define NON_MODAL_SET_COORDINATE_OFFSET 92 // G92 (Do not alter value)
|
||||
#define NON_MODAL_RESET_COORDINATE_OFFSET 102 //G92.1 (Do not alter value)
|
||||
#define NON_MODAL_NO_ACTION 0 // (Default: Must be zero)
|
||||
#define NON_MODAL_DWELL 4 // G4 (Do not alter value)
|
||||
#define NON_MODAL_SET_COORDINATE_DATA 10 // G10 (Do not alter value)
|
||||
#define NON_MODAL_GO_HOME_0 28 // G28 (Do not alter value)
|
||||
#define NON_MODAL_SET_HOME_0 38 // G28.1 (Do not alter value)
|
||||
#define NON_MODAL_GO_HOME_1 30 // G30 (Do not alter value)
|
||||
#define NON_MODAL_SET_HOME_1 40 // G30.1 (Do not alter value)
|
||||
#define NON_MODAL_ABSOLUTE_OVERRIDE 53 // G53 (Do not alter value)
|
||||
#define NON_MODAL_SET_COORDINATE_OFFSET 92 // G92 (Do not alter value)
|
||||
#define NON_MODAL_RESET_COORDINATE_OFFSET 102 //G92.1 (Do not alter value)
|
||||
|
||||
// Modal Group G1: Motion modes
|
||||
#define MOTION_MODE_SEEK 0 // G0 (Default: Must be zero)
|
||||
@ -169,9 +169,9 @@
|
||||
#define GC_PROBE_FAIL_INIT GC_UPDATE_POS_NONE
|
||||
#define GC_PROBE_FAIL_END GC_UPDATE_POS_TARGET
|
||||
#ifdef SET_CHECK_MODE_PROBE_TO_START
|
||||
#define GC_PROBE_CHECK_MODE GC_UPDATE_POS_NONE
|
||||
#define GC_PROBE_CHECK_MODE GC_UPDATE_POS_NONE
|
||||
#else
|
||||
#define GC_PROBE_CHECK_MODE GC_UPDATE_POS_TARGET
|
||||
#define GC_PROBE_CHECK_MODE GC_UPDATE_POS_TARGET
|
||||
#endif
|
||||
|
||||
// Define gcode parser flags for handling special cases.
|
||||
@ -188,60 +188,60 @@
|
||||
|
||||
// NOTE: When this struct is zeroed, the above defines set the defaults for the system.
|
||||
typedef struct {
|
||||
uint8_t motion; // {G0,G1,G2,G3,G38.2,G80}
|
||||
uint8_t feed_rate; // {G93,G94}
|
||||
uint8_t units; // {G20,G21}
|
||||
uint8_t distance; // {G90,G91}
|
||||
// uint8_t distance_arc; // {G91.1} NOTE: Don't track. Only default supported.
|
||||
uint8_t plane_select; // {G17,G18,G19}
|
||||
// uint8_t cutter_comp; // {G40} NOTE: Don't track. Only default supported.
|
||||
uint8_t tool_length; // {G43.1,G49}
|
||||
uint8_t coord_select; // {G54,G55,G56,G57,G58,G59}
|
||||
// uint8_t control; // {G61} NOTE: Don't track. Only default supported.
|
||||
uint8_t program_flow; // {M0,M1,M2,M30}
|
||||
uint8_t coolant; // {M7,M8,M9}
|
||||
uint8_t spindle; // {M3,M4,M5}
|
||||
uint8_t tool_change; // {M6}
|
||||
uint8_t io_control; // {M62, M63}
|
||||
uint8_t motion; // {G0,G1,G2,G3,G38.2,G80}
|
||||
uint8_t feed_rate; // {G93,G94}
|
||||
uint8_t units; // {G20,G21}
|
||||
uint8_t distance; // {G90,G91}
|
||||
// uint8_t distance_arc; // {G91.1} NOTE: Don't track. Only default supported.
|
||||
uint8_t plane_select; // {G17,G18,G19}
|
||||
// uint8_t cutter_comp; // {G40} NOTE: Don't track. Only default supported.
|
||||
uint8_t tool_length; // {G43.1,G49}
|
||||
uint8_t coord_select; // {G54,G55,G56,G57,G58,G59}
|
||||
// uint8_t control; // {G61} NOTE: Don't track. Only default supported.
|
||||
uint8_t program_flow; // {M0,M1,M2,M30}
|
||||
uint8_t coolant; // {M7,M8,M9}
|
||||
uint8_t spindle; // {M3,M4,M5}
|
||||
uint8_t tool_change; // {M6}
|
||||
uint8_t io_control; // {M62, M63}
|
||||
} gc_modal_t;
|
||||
|
||||
typedef struct {
|
||||
float f; // Feed
|
||||
float ijk[N_AXIS]; // I,J,K Axis arc offsets
|
||||
uint8_t l; // G10 or canned cycles parameters
|
||||
int32_t n; // Line number
|
||||
float p; // G10 or dwell parameters
|
||||
// float q; // G82 peck drilling
|
||||
float r; // Arc radius
|
||||
float s; // Spindle speed
|
||||
uint8_t t; // Tool selection
|
||||
float xyz[N_AXIS]; // X,Y,Z Translational axes
|
||||
float f; // Feed
|
||||
float ijk[N_AXIS]; // I,J,K Axis arc offsets
|
||||
uint8_t l; // G10 or canned cycles parameters
|
||||
int32_t n; // Line number
|
||||
float p; // G10 or dwell parameters
|
||||
// float q; // G82 peck drilling
|
||||
float r; // Arc radius
|
||||
float s; // Spindle speed
|
||||
uint8_t t; // Tool selection
|
||||
float xyz[N_AXIS]; // X,Y,Z Translational axes
|
||||
} gc_values_t;
|
||||
|
||||
|
||||
typedef struct {
|
||||
gc_modal_t modal;
|
||||
gc_modal_t modal;
|
||||
|
||||
float spindle_speed; // RPM
|
||||
float feed_rate; // Millimeters/min
|
||||
uint8_t tool; // Tracks tool number. NOT USED.
|
||||
int32_t line_number; // Last line number sent
|
||||
float spindle_speed; // RPM
|
||||
float feed_rate; // Millimeters/min
|
||||
uint8_t tool; // Tracks tool number. NOT USED.
|
||||
int32_t line_number; // Last line number sent
|
||||
|
||||
float position[N_AXIS]; // Where the interpreter considers the tool to be at this point in the code
|
||||
float position[N_AXIS]; // Where the interpreter considers the tool to be at this point in the code
|
||||
|
||||
float coord_system[N_AXIS]; // Current work coordinate system (G54+). Stores offset from absolute machine
|
||||
// position in mm. Loaded from EEPROM when called.
|
||||
float coord_offset[N_AXIS]; // Retains the G92 coordinate offset (work coordinates) relative to
|
||||
// machine zero in mm. Non-persistent. Cleared upon reset and boot.
|
||||
float tool_length_offset; // Tracks tool length offset value when enabled.
|
||||
float coord_system[N_AXIS]; // Current work coordinate system (G54+). Stores offset from absolute machine
|
||||
// position in mm. Loaded from EEPROM when called.
|
||||
float coord_offset[N_AXIS]; // Retains the G92 coordinate offset (work coordinates) relative to
|
||||
// machine zero in mm. Non-persistent. Cleared upon reset and boot.
|
||||
float tool_length_offset; // Tracks tool length offset value when enabled.
|
||||
} parser_state_t;
|
||||
extern parser_state_t gc_state;
|
||||
|
||||
|
||||
typedef struct {
|
||||
uint8_t non_modal_command;
|
||||
gc_modal_t modal;
|
||||
gc_values_t values;
|
||||
uint8_t non_modal_command;
|
||||
gc_modal_t modal;
|
||||
gc_values_t values;
|
||||
} parser_block_t;
|
||||
|
||||
|
||||
@ -249,7 +249,7 @@ typedef struct {
|
||||
void gc_init();
|
||||
|
||||
// Execute one block of rs275/ngc/g-code
|
||||
uint8_t gc_execute_line(char *line, uint8_t client);
|
||||
uint8_t gc_execute_line(char* line, uint8_t client);
|
||||
|
||||
// Set g-code parser position. Input in steps.
|
||||
void gc_sync_position();
|
||||
|
@ -2,10 +2,10 @@
|
||||
grbl.h - Header for system level commands and real-time processes
|
||||
Part of Grbl
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
|
||||
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
|
||||
@ -20,7 +20,7 @@
|
||||
|
||||
// Grbl versioning system
|
||||
#define GRBL_VERSION "1.1f"
|
||||
#define GRBL_VERSION_BUILD "20200225"
|
||||
#define GRBL_VERSION_BUILD "20200319"
|
||||
|
||||
//#include <sdkconfig.h>
|
||||
#include <Arduino.h>
|
||||
@ -34,7 +34,6 @@
|
||||
// Define the Grbl system include files. NOTE: Do not alter organization.
|
||||
#include "config.h"
|
||||
#include "nuts_bolts.h"
|
||||
#include "cpu_map.h"
|
||||
#include "tdef.h"
|
||||
|
||||
#include "defaults.h"
|
||||
@ -58,37 +57,59 @@
|
||||
#include "inputbuffer.h"
|
||||
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
#include "BTconfig.h"
|
||||
#include "BTconfig.h"
|
||||
#endif
|
||||
|
||||
#ifdef ENABLE_SD_CARD
|
||||
#include "grbl_sd.h"
|
||||
#ifdef ENABLE_SD_CARD
|
||||
#include "grbl_sd.h"
|
||||
#endif
|
||||
|
||||
#ifdef ENABLE_WIFI
|
||||
#ifdef ENABLE_WIFI
|
||||
#include "wificonfig.h"
|
||||
#ifdef ENABLE_HTTP
|
||||
#include "serial2socket.h"
|
||||
#include "serial2socket.h"
|
||||
#endif
|
||||
#ifdef ENABLE_TELNET
|
||||
#include "telnet_server.h"
|
||||
#include "telnet_server.h"
|
||||
#endif
|
||||
#ifdef ENABLE_NOTIFICATIONS
|
||||
#include "notifications_service.h"
|
||||
#include "notifications_service.h"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#include "solenoid_pen.h"
|
||||
|
||||
#ifdef USE_SERVO_AXES
|
||||
#include "servo_axis.h"
|
||||
#include "servo_axis.h"
|
||||
#endif
|
||||
|
||||
#ifdef USE_TRINAMIC
|
||||
#include "grbl_trinamic.h"
|
||||
#include "grbl_trinamic.h"
|
||||
#endif
|
||||
|
||||
#ifdef USE_UNIPOLAR
|
||||
#include "grbl_unipolar.h"
|
||||
#include "grbl_unipolar.h"
|
||||
#endif
|
||||
|
||||
// Called if USE_MACHINE_INIT is defined
|
||||
void machine_init();
|
||||
|
||||
// Called if USE_CUSTOM_HOMING is defined
|
||||
bool user_defined_homing();
|
||||
|
||||
// Called if USE_KINEMATICS is defined
|
||||
void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position);
|
||||
bool kinematics_pre_homing(uint8_t cycle_mask);
|
||||
void kinematics_post_homing();
|
||||
|
||||
// Called if USE_FWD_KINEMATIC is defined
|
||||
void forward_kinematics(float* position);
|
||||
|
||||
// Called if MACRO_BUTTON_0_PIN or MACRO_BUTTON_1_PIN or MACRO_BUTTON_2_PIN is defined
|
||||
void user_defined_macro(uint8_t index);
|
||||
|
||||
// Called if USE_M30 is defined
|
||||
void user_m30();
|
||||
|
||||
// Called if USE_TOOL_CHANGE is defined
|
||||
void user_tool_change(uint8_t new_tool);
|
||||
|
@ -2,10 +2,10 @@
|
||||
eeprom.cpp - Header for system level commands and real-time processes
|
||||
Part of Grbl
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
|
||||
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
|
||||
@ -20,24 +20,24 @@
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
void memcpy_to_eeprom_with_checksum(unsigned int destination, char *source, unsigned int size) {
|
||||
unsigned char checksum = 0;
|
||||
for(; size > 0; size--) {
|
||||
checksum = (checksum << 1) || (checksum >> 7);
|
||||
checksum += *source;
|
||||
EEPROM.write(destination++, *(source++));
|
||||
}
|
||||
EEPROM.write(destination, checksum);
|
||||
EEPROM.commit();
|
||||
void memcpy_to_eeprom_with_checksum(unsigned int destination, char* source, unsigned int size) {
|
||||
unsigned char checksum = 0;
|
||||
for (; size > 0; size--) {
|
||||
checksum = (checksum << 1) || (checksum >> 7);
|
||||
checksum += *source;
|
||||
EEPROM.write(destination++, *(source++));
|
||||
}
|
||||
EEPROM.write(destination, checksum);
|
||||
EEPROM.commit();
|
||||
}
|
||||
|
||||
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));
|
||||
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));
|
||||
}
|
||||
|
@ -2,10 +2,10 @@
|
||||
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
|
||||
@ -25,7 +25,7 @@
|
||||
|
||||
//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, char *source, unsigned int size);
|
||||
int memcpy_from_eeprom_with_checksum(char *destination, unsigned int source, unsigned int size);
|
||||
void memcpy_to_eeprom_with_checksum(unsigned int destination, char* source, unsigned int size);
|
||||
int memcpy_from_eeprom_with_checksum(char* destination, unsigned int source, unsigned int size);
|
||||
|
||||
#endif
|
||||
|
@ -4,11 +4,11 @@
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
2018-12-29 - Wolfgang Lienbacher renamed file from limits.h to grbl_limits.h
|
||||
fixing ambiguation issues with limit.h in the esp32 Arduino Framework
|
||||
2018-12-29 - Wolfgang Lienbacher renamed file from limits.h to grbl_limits.h
|
||||
fixing ambiguation issues with limit.h in the esp32 Arduino Framework
|
||||
when compiling with VS-Code/PlatformIO.
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
@ -33,40 +33,37 @@ xQueueHandle limit_sw_queue; // used by limit switch debouncing
|
||||
|
||||
// Homing axis search distance multiplier. Computed by this value times the cycle travel.
|
||||
#ifndef HOMING_AXIS_SEARCH_SCALAR
|
||||
#define HOMING_AXIS_SEARCH_SCALAR 1.1 // Must be > 1 to ensure limit switch will be engaged.
|
||||
#define HOMING_AXIS_SEARCH_SCALAR 1.1 // Must be > 1 to ensure limit switch will be engaged.
|
||||
#endif
|
||||
#ifndef HOMING_AXIS_LOCATE_SCALAR
|
||||
#define HOMING_AXIS_LOCATE_SCALAR 5.0 // Must be > 1 to ensure limit switch is cleared.
|
||||
#define HOMING_AXIS_LOCATE_SCALAR 5.0 // Must be > 1 to ensure limit switch is cleared.
|
||||
#endif
|
||||
|
||||
void IRAM_ATTR isr_limit_switches()
|
||||
{
|
||||
// Ignore limit switches if already in an alarm state or in-process of executing an alarm.
|
||||
void IRAM_ATTR isr_limit_switches() {
|
||||
// Ignore limit switches if already in an alarm state or in-process of executing an alarm.
|
||||
// When in the alarm state, Grbl should have been reset or will force a reset, so any pending
|
||||
// moves in the planner and serial buffers are all cleared and newly sent blocks will be
|
||||
// locked out until a homing cycle or a kill lock command. Allows the user to disable the hard
|
||||
// limit setting if their limits are constantly triggering after a reset and move their axes.
|
||||
|
||||
if ( ( sys.state != STATE_ALARM) & (bit_isfalse(sys.state, STATE_HOMING)) ) {
|
||||
if (!(sys_rt_exec_alarm)) {
|
||||
|
||||
#ifdef ENABLE_SOFTWARE_DEBOUNCE
|
||||
// we will start a task that will recheck the switches after a small delay
|
||||
int evt;
|
||||
xQueueSendFromISR(limit_sw_queue, &evt, NULL);
|
||||
#else
|
||||
#ifdef HARD_LIMIT_FORCE_STATE_CHECK
|
||||
// Check limit pin state.
|
||||
if (limits_get_state()) {
|
||||
mc_reset(); // Initiate system kill.
|
||||
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
|
||||
}
|
||||
#else
|
||||
mc_reset(); // Initiate system kill.
|
||||
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
if ((sys.state != STATE_ALARM) & (bit_isfalse(sys.state, STATE_HOMING))) {
|
||||
if (!(sys_rt_exec_alarm)) {
|
||||
#ifdef ENABLE_SOFTWARE_DEBOUNCE
|
||||
// we will start a task that will recheck the switches after a small delay
|
||||
int evt;
|
||||
xQueueSendFromISR(limit_sw_queue, &evt, NULL);
|
||||
#else
|
||||
#ifdef HARD_LIMIT_FORCE_STATE_CHECK
|
||||
// Check limit pin state.
|
||||
if (limits_get_state()) {
|
||||
mc_reset(); // Initiate system kill.
|
||||
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
|
||||
}
|
||||
#else
|
||||
mc_reset(); // Initiate system kill.
|
||||
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -77,421 +74,364 @@ void IRAM_ATTR isr_limit_switches()
|
||||
// circumvent the processes for executing motions in normal operation.
|
||||
// NOTE: Only the abort realtime command can interrupt this process.
|
||||
// TODO: Move limit pin-specific calls to a general function for portability.
|
||||
void limits_go_home(uint8_t cycle_mask)
|
||||
{
|
||||
if (sys.abort) { return; } // Block if system reset has been issued.
|
||||
|
||||
// Initialize plan data struct for homing motion. Spindle and coolant are disabled.
|
||||
plan_line_data_t plan_data;
|
||||
plan_line_data_t *pl_data = &plan_data;
|
||||
memset(pl_data,0,sizeof(plan_line_data_t));
|
||||
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION|PL_COND_FLAG_NO_FEED_OVERRIDE);
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
void limits_go_home(uint8_t cycle_mask) {
|
||||
if (sys.abort) return; // Block if system reset has been issued.
|
||||
// Initialize plan data struct for homing motion. Spindle and coolant are disabled.
|
||||
plan_line_data_t plan_data;
|
||||
plan_line_data_t* pl_data = &plan_data;
|
||||
memset(pl_data, 0, sizeof(plan_line_data_t));
|
||||
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION | PL_COND_FLAG_NO_FEED_OVERRIDE);
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
pl_data->line_number = HOMING_CYCLE_LINE_NUMBER;
|
||||
#endif
|
||||
|
||||
// Initialize variables used for homing computations.
|
||||
uint8_t n_cycle = (2*n_homing_locate_cycle+1);
|
||||
uint8_t step_pin[N_AXIS];
|
||||
float target[N_AXIS];
|
||||
float max_travel = 0.0;
|
||||
uint8_t idx;
|
||||
for (idx=0; idx<N_AXIS; idx++) {
|
||||
// Initialize step pin masks
|
||||
step_pin[idx] = get_step_pin_mask(idx);
|
||||
#ifdef COREXY
|
||||
if ((idx==A_MOTOR)||(idx==B_MOTOR)) { step_pin[idx] = (get_step_pin_mask(X_AXIS)|get_step_pin_mask(Y_AXIS)); }
|
||||
#endif
|
||||
|
||||
if (bit_istrue(cycle_mask,bit(idx))) {
|
||||
// Set target based on max_travel setting. Ensure homing switches engaged with search scalar.
|
||||
// NOTE: settings.max_travel[] is stored as a negative value.
|
||||
max_travel = MAX(max_travel,(-HOMING_AXIS_SEARCH_SCALAR)*settings.max_travel[idx]);
|
||||
}
|
||||
}
|
||||
|
||||
// Set search mode with approach at seek rate to quickly engage the specified cycle_mask limit switches.
|
||||
bool approach = true;
|
||||
float homing_rate = settings.homing_seek_rate;
|
||||
|
||||
uint8_t limit_state, axislock, n_active_axis;
|
||||
do {
|
||||
|
||||
system_convert_array_steps_to_mpos(target,sys_position);
|
||||
|
||||
// Initialize and declare variables needed for homing routine.
|
||||
axislock = 0;
|
||||
n_active_axis = 0;
|
||||
for (idx=0; idx<N_AXIS; idx++) {
|
||||
// Set target location for active axes and setup computation for homing rate.
|
||||
if (bit_istrue(cycle_mask,bit(idx))) {
|
||||
n_active_axis++;
|
||||
#ifdef COREXY
|
||||
if (idx == X_AXIS) {
|
||||
int32_t axis_position = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||
sys_position[A_MOTOR] = axis_position;
|
||||
sys_position[B_MOTOR] = -axis_position;
|
||||
} else if (idx == Y_AXIS) {
|
||||
int32_t axis_position = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||
sys_position[A_MOTOR] = sys_position[B_MOTOR] = axis_position;
|
||||
} else {
|
||||
sys_position[Z_AXIS] = 0;
|
||||
}
|
||||
#else
|
||||
sys_position[idx] = 0;
|
||||
#endif
|
||||
// Set target direction based on cycle mask and homing cycle approach state.
|
||||
// NOTE: This happens to compile smaller than any other implementation tried.
|
||||
if (bit_istrue(settings.homing_dir_mask,bit(idx))) {
|
||||
if (approach) { target[idx] = -max_travel; }
|
||||
else { target[idx] = max_travel; }
|
||||
} else {
|
||||
if (approach) { target[idx] = max_travel; }
|
||||
else { target[idx] = -max_travel; }
|
||||
#endif
|
||||
// Initialize variables used for homing computations.
|
||||
uint8_t n_cycle = (2 * n_homing_locate_cycle + 1);
|
||||
uint8_t step_pin[N_AXIS];
|
||||
float target[N_AXIS];
|
||||
float max_travel = 0.0;
|
||||
uint8_t idx;
|
||||
for (idx = 0; idx < N_AXIS; idx++) {
|
||||
// Initialize step pin masks
|
||||
step_pin[idx] = get_step_pin_mask(idx);
|
||||
#ifdef COREXY
|
||||
if ((idx == A_MOTOR) || (idx == B_MOTOR)) step_pin[idx] = (get_step_pin_mask(X_AXIS) | get_step_pin_mask(Y_AXIS));
|
||||
#endif
|
||||
if (bit_istrue(cycle_mask, bit(idx))) {
|
||||
// Set target based on max_travel setting. Ensure homing switches engaged with search scalar.
|
||||
// NOTE: settings.max_travel[] is stored as a negative value.
|
||||
max_travel = MAX(max_travel, (-HOMING_AXIS_SEARCH_SCALAR) * settings.max_travel[idx]);
|
||||
}
|
||||
// Apply axislock to the step port pins active in this cycle.
|
||||
axislock |= step_pin[idx];
|
||||
}
|
||||
|
||||
}
|
||||
homing_rate *= sqrt(n_active_axis); // [sqrt(N_AXIS)] Adjust so individual axes all move at homing rate.
|
||||
sys.homing_axis_lock = axislock;
|
||||
|
||||
// Perform homing cycle. Planner buffer should be empty, as required to initiate the homing cycle.
|
||||
pl_data->feed_rate = homing_rate; // Set current homing rate.
|
||||
plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
|
||||
|
||||
sys.step_control = STEP_CONTROL_EXECUTE_SYS_MOTION; // Set to execute homing motion and clear existing flags.
|
||||
st_prep_buffer(); // Prep and fill segment buffer from newly planned block.
|
||||
st_wake_up(); // Initiate motion
|
||||
// Set search mode with approach at seek rate to quickly engage the specified cycle_mask limit switches.
|
||||
bool approach = true;
|
||||
float homing_rate = settings.homing_seek_rate;
|
||||
uint8_t limit_state, axislock, n_active_axis;
|
||||
do {
|
||||
if (approach) {
|
||||
// Check limit state. Lock out cycle axes when they change.
|
||||
limit_state = limits_get_state();
|
||||
for (idx=0; idx<N_AXIS; idx++) {
|
||||
if (axislock & step_pin[idx]) {
|
||||
if (limit_state & (1 << idx)) {
|
||||
#ifdef COREXY
|
||||
if (idx==Z_AXIS) { axislock &= ~(step_pin[Z_AXIS]); }
|
||||
else { axislock &= ~(step_pin[A_MOTOR]|step_pin[B_MOTOR]); }
|
||||
#else
|
||||
axislock &= ~(step_pin[idx]);
|
||||
#endif
|
||||
system_convert_array_steps_to_mpos(target, sys_position);
|
||||
// Initialize and declare variables needed for homing routine.
|
||||
axislock = 0;
|
||||
n_active_axis = 0;
|
||||
for (idx = 0; idx < N_AXIS; idx++) {
|
||||
// Set target location for active axes and setup computation for homing rate.
|
||||
if (bit_istrue(cycle_mask, bit(idx))) {
|
||||
n_active_axis++;
|
||||
#ifdef COREXY
|
||||
if (idx == X_AXIS) {
|
||||
int32_t axis_position = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||
sys_position[A_MOTOR] = axis_position;
|
||||
sys_position[B_MOTOR] = -axis_position;
|
||||
} else if (idx == Y_AXIS) {
|
||||
int32_t axis_position = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||
sys_position[A_MOTOR] = sys_position[B_MOTOR] = axis_position;
|
||||
} else
|
||||
sys_position[Z_AXIS] = 0;
|
||||
#else
|
||||
sys_position[idx] = 0;
|
||||
#endif
|
||||
// Set target direction based on cycle mask and homing cycle approach state.
|
||||
// NOTE: This happens to compile smaller than any other implementation tried.
|
||||
if (bit_istrue(settings.homing_dir_mask, bit(idx))) {
|
||||
if (approach) target[idx] = -max_travel;
|
||||
else target[idx] = max_travel;
|
||||
} else {
|
||||
if (approach) target[idx] = max_travel;
|
||||
else target[idx] = -max_travel;
|
||||
}
|
||||
// Apply axislock to the step port pins active in this cycle.
|
||||
axislock |= step_pin[idx];
|
||||
}
|
||||
}
|
||||
}
|
||||
homing_rate *= sqrt(n_active_axis); // [sqrt(N_AXIS)] Adjust so individual axes all move at homing rate.
|
||||
sys.homing_axis_lock = axislock;
|
||||
}
|
||||
|
||||
st_prep_buffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us.
|
||||
|
||||
// Exit routines: No time to run protocol_execute_realtime() in this loop.
|
||||
if (sys_rt_exec_state & (EXEC_SAFETY_DOOR | EXEC_RESET | EXEC_CYCLE_STOP)) {
|
||||
uint8_t rt_exec = sys_rt_exec_state;
|
||||
// Homing failure condition: Reset issued during cycle.
|
||||
if (rt_exec & EXEC_RESET) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_RESET); }
|
||||
// Homing failure condition: Safety door was opened.
|
||||
if (rt_exec & EXEC_SAFETY_DOOR) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_DOOR); }
|
||||
// Homing failure condition: Limit switch still engaged after pull-off motion
|
||||
if (!approach && (limits_get_state() & cycle_mask)) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_PULLOFF); }
|
||||
// Homing failure condition: Limit switch not found during approach.
|
||||
if (approach && (rt_exec & EXEC_CYCLE_STOP)) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_APPROACH); }
|
||||
if (sys_rt_exec_alarm) {
|
||||
mc_reset(); // Stop motors, if they are running.
|
||||
protocol_execute_realtime();
|
||||
return;
|
||||
// Perform homing cycle. Planner buffer should be empty, as required to initiate the homing cycle.
|
||||
pl_data->feed_rate = homing_rate; // Set current homing rate.
|
||||
plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
|
||||
sys.step_control = STEP_CONTROL_EXECUTE_SYS_MOTION; // Set to execute homing motion and clear existing flags.
|
||||
st_prep_buffer(); // Prep and fill segment buffer from newly planned block.
|
||||
st_wake_up(); // Initiate motion
|
||||
do {
|
||||
if (approach) {
|
||||
// Check limit state. Lock out cycle axes when they change.
|
||||
limit_state = limits_get_state();
|
||||
for (idx = 0; idx < N_AXIS; idx++) {
|
||||
if (axislock & step_pin[idx]) {
|
||||
if (limit_state & (1 << idx)) {
|
||||
#ifdef COREXY
|
||||
if (idx == Z_AXIS) axislock &= ~(step_pin[Z_AXIS]);
|
||||
else axislock &= ~(step_pin[A_MOTOR] | step_pin[B_MOTOR]);
|
||||
#else
|
||||
axislock &= ~(step_pin[idx]);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
sys.homing_axis_lock = axislock;
|
||||
}
|
||||
st_prep_buffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us.
|
||||
// Exit routines: No time to run protocol_execute_realtime() in this loop.
|
||||
if (sys_rt_exec_state & (EXEC_SAFETY_DOOR | EXEC_RESET | EXEC_CYCLE_STOP)) {
|
||||
uint8_t rt_exec = sys_rt_exec_state;
|
||||
// Homing failure condition: Reset issued during cycle.
|
||||
if (rt_exec & EXEC_RESET) system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_RESET);
|
||||
// Homing failure condition: Safety door was opened.
|
||||
if (rt_exec & EXEC_SAFETY_DOOR) system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_DOOR);
|
||||
// Homing failure condition: Limit switch still engaged after pull-off motion
|
||||
if (!approach && (limits_get_state() & cycle_mask)) system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_PULLOFF);
|
||||
// Homing failure condition: Limit switch not found during approach.
|
||||
if (approach && (rt_exec & EXEC_CYCLE_STOP)) system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_APPROACH);
|
||||
if (sys_rt_exec_alarm) {
|
||||
mc_reset(); // Stop motors, if they are running.
|
||||
protocol_execute_realtime();
|
||||
return;
|
||||
} else {
|
||||
// Pull-off motion complete. Disable CYCLE_STOP from executing.
|
||||
system_clear_exec_state_flag(EXEC_CYCLE_STOP);
|
||||
break;
|
||||
}
|
||||
}
|
||||
} while (STEP_MASK & axislock);
|
||||
st_reset(); // Immediately force kill steppers and reset step segment buffer.
|
||||
delay_ms(settings.homing_debounce_delay); // Delay to allow transient dynamics to dissipate.
|
||||
// Reverse direction and reset homing rate for locate cycle(s).
|
||||
approach = !approach;
|
||||
// After first cycle, homing enters locating phase. Shorten search to pull-off distance.
|
||||
if (approach) {
|
||||
max_travel = settings.homing_pulloff * HOMING_AXIS_LOCATE_SCALAR;
|
||||
homing_rate = settings.homing_feed_rate;
|
||||
} else {
|
||||
// Pull-off motion complete. Disable CYCLE_STOP from executing.
|
||||
system_clear_exec_state_flag(EXEC_CYCLE_STOP);
|
||||
break;
|
||||
max_travel = settings.homing_pulloff;
|
||||
homing_rate = settings.homing_seek_rate;
|
||||
}
|
||||
} while (n_cycle-- > 0);
|
||||
// The active cycle axes should now be homed and machine limits have been located. By
|
||||
// default, Grbl defines machine space as all negative, as do most CNCs. Since limit switches
|
||||
// can be on either side of an axes, check and set axes machine zero appropriately. Also,
|
||||
// set up pull-off maneuver from axes limit switches that have been homed. This provides
|
||||
// some initial clearance off the switches and should also help prevent them from falsely
|
||||
// triggering when hard limits are enabled or when more than one axes shares a limit pin.
|
||||
int32_t set_axis_position;
|
||||
// Set machine positions for homed limit switches. Don't update non-homed axes.
|
||||
for (idx = 0; idx < N_AXIS; idx++) {
|
||||
// NOTE: settings.max_travel[] is stored as a negative value.
|
||||
if (cycle_mask & bit(idx)) {
|
||||
#ifdef HOMING_FORCE_SET_ORIGIN
|
||||
set_axis_position = 0;
|
||||
#else
|
||||
if (bit_istrue(settings.homing_dir_mask, bit(idx))) {
|
||||
#ifdef HOMING_FORCE_POSITIVE_SPACE
|
||||
set_axis_position = 0; //lround(settings.homing_pulloff*settings.steps_per_mm[idx]);
|
||||
#else
|
||||
set_axis_position = lround((settings.max_travel[idx] + settings.homing_pulloff) * settings.steps_per_mm[idx]);
|
||||
#endif
|
||||
} else {
|
||||
#ifdef HOMING_FORCE_POSITIVE_SPACE
|
||||
set_axis_position = lround((-settings.max_travel[idx] - settings.homing_pulloff) * settings.steps_per_mm[idx]);
|
||||
#else
|
||||
set_axis_position = lround(-settings.homing_pulloff * settings.steps_per_mm[idx]);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
#ifdef COREXY
|
||||
if (idx == X_AXIS) {
|
||||
int32_t off_axis_position = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||
sys_position[A_MOTOR] = set_axis_position + off_axis_position;
|
||||
sys_position[B_MOTOR] = set_axis_position - off_axis_position;
|
||||
} else if (idx == Y_AXIS) {
|
||||
int32_t off_axis_position = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||
sys_position[A_MOTOR] = off_axis_position + set_axis_position;
|
||||
sys_position[B_MOTOR] = off_axis_position - set_axis_position;
|
||||
} else
|
||||
sys_position[idx] = set_axis_position;
|
||||
#else
|
||||
sys_position[idx] = set_axis_position;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
} while (STEP_MASK & axislock);
|
||||
|
||||
st_reset(); // Immediately force kill steppers and reset step segment buffer.
|
||||
delay_ms(settings.homing_debounce_delay); // Delay to allow transient dynamics to dissipate.
|
||||
|
||||
// Reverse direction and reset homing rate for locate cycle(s).
|
||||
approach = !approach;
|
||||
|
||||
// After first cycle, homing enters locating phase. Shorten search to pull-off distance.
|
||||
if (approach) {
|
||||
max_travel = settings.homing_pulloff*HOMING_AXIS_LOCATE_SCALAR;
|
||||
homing_rate = settings.homing_feed_rate;
|
||||
} else {
|
||||
max_travel = settings.homing_pulloff;
|
||||
homing_rate = settings.homing_seek_rate;
|
||||
}
|
||||
|
||||
} while (n_cycle-- > 0);
|
||||
|
||||
// The active cycle axes should now be homed and machine limits have been located. By
|
||||
// default, Grbl defines machine space as all negative, as do most CNCs. Since limit switches
|
||||
// can be on either side of an axes, check and set axes machine zero appropriately. Also,
|
||||
// set up pull-off maneuver from axes limit switches that have been homed. This provides
|
||||
// some initial clearance off the switches and should also help prevent them from falsely
|
||||
// triggering when hard limits are enabled or when more than one axes shares a limit pin.
|
||||
int32_t set_axis_position;
|
||||
// Set machine positions for homed limit switches. Don't update non-homed axes.
|
||||
for (idx=0; idx<N_AXIS; idx++) {
|
||||
// NOTE: settings.max_travel[] is stored as a negative value.
|
||||
if (cycle_mask & bit(idx)) {
|
||||
#ifdef HOMING_FORCE_SET_ORIGIN
|
||||
set_axis_position = 0;
|
||||
#else
|
||||
if ( bit_istrue(settings.homing_dir_mask,bit(idx)) ) {
|
||||
#ifdef HOMING_FORCE_POSITIVE_SPACE
|
||||
set_axis_position = 0; //lround(settings.homing_pulloff*settings.steps_per_mm[idx]);
|
||||
#else
|
||||
set_axis_position = lround((settings.max_travel[idx]+settings.homing_pulloff)*settings.steps_per_mm[idx]);
|
||||
#endif
|
||||
} else {
|
||||
#ifdef HOMING_FORCE_POSITIVE_SPACE
|
||||
set_axis_position = lround((-settings.max_travel[idx]-settings.homing_pulloff)*settings.steps_per_mm[idx]);
|
||||
#else
|
||||
set_axis_position = lround(-settings.homing_pulloff*settings.steps_per_mm[idx]);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef COREXY
|
||||
if (idx==X_AXIS) {
|
||||
int32_t off_axis_position = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||
sys_position[A_MOTOR] = set_axis_position + off_axis_position;
|
||||
sys_position[B_MOTOR] = set_axis_position - off_axis_position;
|
||||
} else if (idx==Y_AXIS) {
|
||||
int32_t off_axis_position = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||
sys_position[A_MOTOR] = off_axis_position + set_axis_position;
|
||||
sys_position[B_MOTOR] = off_axis_position - set_axis_position;
|
||||
} else {
|
||||
sys_position[idx] = set_axis_position;
|
||||
}
|
||||
#else
|
||||
sys_position[idx] = set_axis_position;
|
||||
#endif
|
||||
|
||||
}
|
||||
}
|
||||
sys.step_control = STEP_CONTROL_NORMAL_OP; // Return step control to normal operation.
|
||||
sys.step_control = STEP_CONTROL_NORMAL_OP; // Return step control to normal operation.
|
||||
}
|
||||
|
||||
|
||||
void limits_init()
|
||||
{
|
||||
|
||||
#ifndef DISABLE_LIMIT_PIN_PULL_UP
|
||||
#ifdef X_LIMIT_PIN
|
||||
pinMode(X_LIMIT_PIN, INPUT_PULLUP); // input with pullup
|
||||
#endif
|
||||
#ifdef Y_LIMIT_PIN
|
||||
pinMode(Y_LIMIT_PIN, INPUT_PULLUP);
|
||||
#endif
|
||||
#ifdef Z_LIMIT_PIN
|
||||
pinMode(Z_LIMIT_PIN, INPUT_PULLUP);
|
||||
#endif
|
||||
#ifdef A_LIMIT_PIN
|
||||
pinMode(A_LIMIT_PIN, INPUT_PULLUP);
|
||||
#endif
|
||||
#ifdef B_LIMIT_PIN
|
||||
pinMode(B_LIMIT_PIN, INPUT_PULLUP);
|
||||
#endif
|
||||
#ifdef C_LIMIT_PIN
|
||||
pinMode(C_LIMIT_PIN, INPUT_PULLUP);
|
||||
#endif
|
||||
#else
|
||||
#ifdef X_LIMIT_PIN
|
||||
pinMode(X_LIMIT_PIN, INPUT); // input no pullup
|
||||
#endif
|
||||
#ifdef Y_LIMIT_PIN
|
||||
pinMode(Y_LIMIT_PIN, INPUT);
|
||||
#endif
|
||||
#ifdef Z_LIMIT_PIN
|
||||
pinMode(Z_LIMIT_PIN, INPUT);
|
||||
#endif
|
||||
#ifdef A_LIMIT_PIN
|
||||
pinMode(A_LIMIT_PIN, INPUT); // input no pullup
|
||||
#endif
|
||||
#ifdef B_LIMIT_PIN
|
||||
pinMode(B_LIMIT_PIN, INPUT);
|
||||
#endif
|
||||
#ifdef C_LIMIT_PIN
|
||||
pinMode(C_LIMIT_PIN, INPUT);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
if (bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE)) {
|
||||
// attach interrupt to them
|
||||
#ifdef X_LIMIT_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(X_LIMIT_PIN), isr_limit_switches, CHANGE);
|
||||
#endif
|
||||
#ifdef Y_LIMIT_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(Y_LIMIT_PIN), isr_limit_switches, CHANGE);
|
||||
#endif
|
||||
#ifdef Z_LIMIT_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(Z_LIMIT_PIN), isr_limit_switches, CHANGE);
|
||||
#endif
|
||||
#ifdef A_LIMIT_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(A_LIMIT_PIN), isr_limit_switches, CHANGE);
|
||||
#endif
|
||||
#ifdef B_LIMIT_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(B_LIMIT_PIN), isr_limit_switches, CHANGE);
|
||||
#endif
|
||||
#ifdef C_LIMIT_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(C_LIMIT_PIN), isr_limit_switches, CHANGE);
|
||||
#endif
|
||||
} else {
|
||||
limits_disable();
|
||||
}
|
||||
|
||||
// setup task used for debouncing
|
||||
limit_sw_queue = xQueueCreate(10, sizeof( int ));
|
||||
|
||||
xTaskCreate(limitCheckTask,
|
||||
"limitCheckTask",
|
||||
2048,
|
||||
NULL,
|
||||
5, // priority
|
||||
NULL);
|
||||
|
||||
|
||||
void limits_init() {
|
||||
#ifndef DISABLE_LIMIT_PIN_PULL_UP
|
||||
#ifdef X_LIMIT_PIN
|
||||
pinMode(X_LIMIT_PIN, INPUT_PULLUP); // input with pullup
|
||||
#endif
|
||||
#ifdef Y_LIMIT_PIN
|
||||
pinMode(Y_LIMIT_PIN, INPUT_PULLUP);
|
||||
#endif
|
||||
#ifdef Z_LIMIT_PIN
|
||||
pinMode(Z_LIMIT_PIN, INPUT_PULLUP);
|
||||
#endif
|
||||
#ifdef A_LIMIT_PIN
|
||||
pinMode(A_LIMIT_PIN, INPUT_PULLUP);
|
||||
#endif
|
||||
#ifdef B_LIMIT_PIN
|
||||
pinMode(B_LIMIT_PIN, INPUT_PULLUP);
|
||||
#endif
|
||||
#ifdef C_LIMIT_PIN
|
||||
pinMode(C_LIMIT_PIN, INPUT_PULLUP);
|
||||
#endif
|
||||
#else
|
||||
#ifdef X_LIMIT_PIN
|
||||
pinMode(X_LIMIT_PIN, INPUT); // input no pullup
|
||||
#endif
|
||||
#ifdef Y_LIMIT_PIN
|
||||
pinMode(Y_LIMIT_PIN, INPUT);
|
||||
#endif
|
||||
#ifdef Z_LIMIT_PIN
|
||||
pinMode(Z_LIMIT_PIN, INPUT);
|
||||
#endif
|
||||
#ifdef A_LIMIT_PIN
|
||||
pinMode(A_LIMIT_PIN, INPUT); // input no pullup
|
||||
#endif
|
||||
#ifdef B_LIMIT_PIN
|
||||
pinMode(B_LIMIT_PIN, INPUT);
|
||||
#endif
|
||||
#ifdef C_LIMIT_PIN
|
||||
pinMode(C_LIMIT_PIN, INPUT);
|
||||
#endif
|
||||
#endif
|
||||
if (bit_istrue(settings.flags, BITFLAG_HARD_LIMIT_ENABLE)) {
|
||||
// attach interrupt to them
|
||||
#ifdef X_LIMIT_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(X_LIMIT_PIN), isr_limit_switches, CHANGE);
|
||||
#endif
|
||||
#ifdef Y_LIMIT_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(Y_LIMIT_PIN), isr_limit_switches, CHANGE);
|
||||
#endif
|
||||
#ifdef Z_LIMIT_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(Z_LIMIT_PIN), isr_limit_switches, CHANGE);
|
||||
#endif
|
||||
#ifdef A_LIMIT_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(A_LIMIT_PIN), isr_limit_switches, CHANGE);
|
||||
#endif
|
||||
#ifdef B_LIMIT_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(B_LIMIT_PIN), isr_limit_switches, CHANGE);
|
||||
#endif
|
||||
#ifdef C_LIMIT_PIN
|
||||
attachInterrupt(digitalPinToInterrupt(C_LIMIT_PIN), isr_limit_switches, CHANGE);
|
||||
#endif
|
||||
} else
|
||||
limits_disable();
|
||||
// setup task used for debouncing
|
||||
limit_sw_queue = xQueueCreate(10, sizeof(int));
|
||||
xTaskCreate(limitCheckTask,
|
||||
"limitCheckTask",
|
||||
2048,
|
||||
NULL,
|
||||
5, // priority
|
||||
NULL);
|
||||
}
|
||||
|
||||
|
||||
// Disables hard limits.
|
||||
void limits_disable()
|
||||
{
|
||||
detachInterrupt(X_LIMIT_BIT);
|
||||
detachInterrupt(Y_LIMIT_BIT);
|
||||
detachInterrupt(Z_LIMIT_BIT);
|
||||
detachInterrupt(A_LIMIT_BIT);
|
||||
detachInterrupt(B_LIMIT_BIT);
|
||||
detachInterrupt(C_LIMIT_BIT);
|
||||
void limits_disable() {
|
||||
detachInterrupt(X_LIMIT_BIT);
|
||||
detachInterrupt(Y_LIMIT_BIT);
|
||||
detachInterrupt(Z_LIMIT_BIT);
|
||||
detachInterrupt(A_LIMIT_BIT);
|
||||
detachInterrupt(B_LIMIT_BIT);
|
||||
detachInterrupt(C_LIMIT_BIT);
|
||||
}
|
||||
|
||||
|
||||
// Returns limit state as a bit-wise uint8 variable. Each bit indicates an axis limit, where
|
||||
// triggered is 1 and not triggered is 0. Invert mask is applied. Axes are defined by their
|
||||
// number in bit position, i.e. Z_AXIS is (1<<2) or bit 2, and Y_AXIS is (1<<1) or bit 1.
|
||||
uint8_t limits_get_state()
|
||||
{
|
||||
uint8_t limit_state = 0;
|
||||
uint8_t pin = 0;
|
||||
|
||||
#ifdef X_LIMIT_PIN
|
||||
pin += digitalRead(X_LIMIT_PIN);
|
||||
#endif
|
||||
|
||||
#ifdef Y_LIMIT_PIN
|
||||
pin += (digitalRead(Y_LIMIT_PIN) << Y_AXIS);
|
||||
#endif
|
||||
|
||||
#ifdef Z_LIMIT_PIN
|
||||
pin += (digitalRead(Z_LIMIT_PIN) << Z_AXIS);
|
||||
#endif
|
||||
|
||||
#ifdef A_LIMIT_PIN
|
||||
pin += (digitalRead(A_LIMIT_PIN) << A_AXIS);
|
||||
#endif
|
||||
|
||||
#ifdef B_LIMIT_PIN
|
||||
pin += (digitalRead(B_LIMIT_PIN) << B_AXIS);
|
||||
#endif
|
||||
|
||||
#ifdef C_LIMIT_PIN
|
||||
pin += (digitalRead(C_LIMIT_PIN) << C_AXIS);
|
||||
#endif
|
||||
|
||||
#ifdef INVERT_LIMIT_PIN_MASK // not normally used..unless you have both normal and inverted switches
|
||||
pin ^= INVERT_LIMIT_PIN_MASK;
|
||||
#endif
|
||||
|
||||
if (bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) {
|
||||
pin ^= LIMIT_MASK;
|
||||
}
|
||||
|
||||
if (pin) {
|
||||
uint8_t idx;
|
||||
for (idx=0; idx<N_AXIS; idx++) {
|
||||
if (pin & get_limit_pin_mask(idx)) {
|
||||
limit_state |= (1 << idx);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return(limit_state);
|
||||
uint8_t limits_get_state() {
|
||||
uint8_t limit_state = 0;
|
||||
uint8_t pin = 0;
|
||||
#ifdef X_LIMIT_PIN
|
||||
pin += digitalRead(X_LIMIT_PIN);
|
||||
#endif
|
||||
#ifdef Y_LIMIT_PIN
|
||||
pin += (digitalRead(Y_LIMIT_PIN) << Y_AXIS);
|
||||
#endif
|
||||
#ifdef Z_LIMIT_PIN
|
||||
pin += (digitalRead(Z_LIMIT_PIN) << Z_AXIS);
|
||||
#endif
|
||||
#ifdef A_LIMIT_PIN
|
||||
pin += (digitalRead(A_LIMIT_PIN) << A_AXIS);
|
||||
#endif
|
||||
#ifdef B_LIMIT_PIN
|
||||
pin += (digitalRead(B_LIMIT_PIN) << B_AXIS);
|
||||
#endif
|
||||
#ifdef C_LIMIT_PIN
|
||||
pin += (digitalRead(C_LIMIT_PIN) << C_AXIS);
|
||||
#endif
|
||||
#ifdef INVERT_LIMIT_PIN_MASK // not normally used..unless you have both normal and inverted switches
|
||||
pin ^= INVERT_LIMIT_PIN_MASK;
|
||||
#endif
|
||||
if (bit_istrue(settings.flags, BITFLAG_INVERT_LIMIT_PINS))
|
||||
pin ^= LIMIT_MASK;
|
||||
if (pin) {
|
||||
uint8_t idx;
|
||||
for (idx = 0; idx < N_AXIS; idx++) {
|
||||
if (pin & get_limit_pin_mask(idx))
|
||||
limit_state |= (1 << idx);
|
||||
}
|
||||
}
|
||||
return (limit_state);
|
||||
}
|
||||
|
||||
// Performs a soft limit check. Called from mc_line() only. Assumes the machine has been homed,
|
||||
// the workspace volume is in all negative space, and the system is in normal operation.
|
||||
// NOTE: Used by jogging to limit travel within soft-limit volume.
|
||||
void limits_soft_check(float *target)
|
||||
{
|
||||
if (system_check_travel_limits(target)) {
|
||||
sys.soft_limit = true;
|
||||
// Force feed hold if cycle is active. All buffered blocks are guaranteed to be within
|
||||
// workspace volume so just come to a controlled stop so position is not lost. When complete
|
||||
// enter alarm mode.
|
||||
if (sys.state == STATE_CYCLE) {
|
||||
system_set_exec_state_flag(EXEC_FEED_HOLD);
|
||||
do {
|
||||
protocol_execute_realtime();
|
||||
if (sys.abort) { return; }
|
||||
} while ( sys.state != STATE_IDLE );
|
||||
void limits_soft_check(float* target) {
|
||||
if (system_check_travel_limits(target)) {
|
||||
sys.soft_limit = true;
|
||||
// Force feed hold if cycle is active. All buffered blocks are guaranteed to be within
|
||||
// workspace volume so just come to a controlled stop so position is not lost. When complete
|
||||
// enter alarm mode.
|
||||
if (sys.state == STATE_CYCLE) {
|
||||
system_set_exec_state_flag(EXEC_FEED_HOLD);
|
||||
do {
|
||||
protocol_execute_realtime();
|
||||
if (sys.abort) return;
|
||||
} while (sys.state != STATE_IDLE);
|
||||
}
|
||||
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
|
||||
system_set_exec_alarm(EXEC_ALARM_SOFT_LIMIT); // Indicate soft limit critical event
|
||||
protocol_execute_realtime(); // Execute to enter critical event loop and system abort
|
||||
return;
|
||||
}
|
||||
|
||||
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
|
||||
system_set_exec_alarm(EXEC_ALARM_SOFT_LIMIT); // Indicate soft limit critical event
|
||||
protocol_execute_realtime(); // Execute to enter critical event loop and system abort
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// this is the task
|
||||
void limitCheckTask(void *pvParameters)
|
||||
{
|
||||
while(true) {
|
||||
int evt;
|
||||
xQueueReceive(limit_sw_queue, &evt, portMAX_DELAY); // block until receive queue
|
||||
vTaskDelay( DEBOUNCE_PERIOD / portTICK_PERIOD_MS ); // delay a while
|
||||
|
||||
uint8_t switch_state;
|
||||
|
||||
switch_state = limits_get_state();
|
||||
|
||||
if (switch_state) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Limit Switch State %08d", switch_state);
|
||||
mc_reset(); // Initiate system kill.
|
||||
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
|
||||
}
|
||||
}
|
||||
void limitCheckTask(void* pvParameters) {
|
||||
while (true) {
|
||||
int evt;
|
||||
xQueueReceive(limit_sw_queue, &evt, portMAX_DELAY); // block until receive queue
|
||||
vTaskDelay(DEBOUNCE_PERIOD / portTICK_PERIOD_MS); // delay a while
|
||||
uint8_t switch_state;
|
||||
switch_state = limits_get_state();
|
||||
if (switch_state) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Limit Switch State %08d", switch_state);
|
||||
mc_reset(); // Initiate system kill.
|
||||
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// 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
|
||||
bool axis_is_squared(uint8_t axis_mask)
|
||||
{
|
||||
// Note: multi-axis homing returns false because it will not match any of the following
|
||||
|
||||
if (axis_mask == (1<<X_AXIS)) {
|
||||
#ifdef X_AXIS_SQUARING
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
|
||||
if (axis_mask == (1<<Y_AXIS)) {
|
||||
#ifdef Y_AXIS_SQUARING
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
|
||||
if (axis_mask == (1<<Z_AXIS)) {
|
||||
#ifdef Z_AXIS_SQUARING
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
|
||||
return false;
|
||||
|
||||
bool axis_is_squared(uint8_t axis_mask) {
|
||||
// Note: multi-axis homing returns false because it will not match any of the following
|
||||
if (axis_mask == (1 << X_AXIS)) {
|
||||
#ifdef X_AXIS_SQUARING
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
if (axis_mask == (1 << Y_AXIS)) {
|
||||
#ifdef Y_AXIS_SQUARING
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
if (axis_mask == (1 << Z_AXIS)) {
|
||||
#ifdef Z_AXIS_SQUARING
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
return false;
|
||||
}
|
@ -4,11 +4,11 @@
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
2018-12-29 - Wolfgang Lienbacher renamed file from limits.h to grbl_limits.h
|
||||
fixing ambiguation issues with limit.h in the esp32 Arduino Framework
|
||||
2018-12-29 - Wolfgang Lienbacher renamed file from limits.h to grbl_limits.h
|
||||
fixing ambiguation issues with limit.h in the esp32 Arduino Framework
|
||||
when compiling with VS-Code/PlatformIO.
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
@ -47,13 +47,13 @@ uint8_t limits_get_state();
|
||||
void limits_go_home(uint8_t cycle_mask);
|
||||
|
||||
// Check for soft limit violations
|
||||
void limits_soft_check(float *target);
|
||||
void limits_soft_check(float* target);
|
||||
|
||||
void isr_limit_switches();
|
||||
|
||||
bool axis_is_squared(uint8_t axis_mask);
|
||||
|
||||
// A task that runs after a limit switch interrupt.
|
||||
void limitCheckTask(void *pvParameters);
|
||||
void limitCheckTask(void* pvParameters);
|
||||
|
||||
#endif
|
@ -41,59 +41,48 @@ static char comment[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
|
||||
return true;
|
||||
}*/
|
||||
|
||||
void listDir(fs::FS &fs, const char * dirname, uint8_t levels, uint8_t client)
|
||||
{
|
||||
//char temp_filename[128]; // to help filter by extension TODO: 128 needs a definition based on something
|
||||
|
||||
File root = fs.open(dirname);
|
||||
if(!root) {
|
||||
report_status_message(STATUS_SD_FAILED_OPEN_DIR, client);
|
||||
return;
|
||||
}
|
||||
if(!root.isDirectory()) {
|
||||
report_status_message(STATUS_SD_DIR_NOT_FOUND, client);
|
||||
return;
|
||||
}
|
||||
|
||||
File file = root.openNextFile();
|
||||
while(file) {
|
||||
if(file.isDirectory()) {
|
||||
if(levels) {
|
||||
listDir(fs, file.name(), levels -1, client);
|
||||
}
|
||||
} else {
|
||||
grbl_sendf(CLIENT_ALL, "[FILE:%s|SIZE:%d]\r\n", file.name(), file.size());
|
||||
void listDir(fs::FS& fs, const char* dirname, uint8_t levels, uint8_t client) {
|
||||
//char temp_filename[128]; // to help filter by extension TODO: 128 needs a definition based on something
|
||||
File root = fs.open(dirname);
|
||||
if (!root) {
|
||||
report_status_message(STATUS_SD_FAILED_OPEN_DIR, client);
|
||||
return;
|
||||
}
|
||||
if (!root.isDirectory()) {
|
||||
report_status_message(STATUS_SD_DIR_NOT_FOUND, client);
|
||||
return;
|
||||
}
|
||||
File file = root.openNextFile();
|
||||
while (file) {
|
||||
if (file.isDirectory()) {
|
||||
if (levels)
|
||||
listDir(fs, file.name(), levels - 1, client);
|
||||
} else
|
||||
grbl_sendf(CLIENT_ALL, "[FILE:%s|SIZE:%d]\r\n", file.name(), file.size());
|
||||
file = root.openNextFile();
|
||||
}
|
||||
file = root.openNextFile();
|
||||
}
|
||||
}
|
||||
|
||||
boolean openFile(fs::FS &fs, const char * path)
|
||||
{
|
||||
myFile = fs.open(path);
|
||||
|
||||
if(!myFile) {
|
||||
//report_status_message(STATUS_SD_FAILED_READ, CLIENT_SERIAL);
|
||||
return false;
|
||||
}
|
||||
|
||||
set_sd_state(SDCARD_BUSY_PRINTING);
|
||||
SD_ready_next = false; // this will get set to true when Grbl issues "ok" message
|
||||
sd_current_line_number = 0;
|
||||
return true;
|
||||
boolean openFile(fs::FS& fs, const char* path) {
|
||||
myFile = fs.open(path);
|
||||
if (!myFile) {
|
||||
//report_status_message(STATUS_SD_FAILED_READ, CLIENT_SERIAL);
|
||||
return false;
|
||||
}
|
||||
set_sd_state(SDCARD_BUSY_PRINTING);
|
||||
SD_ready_next = false; // this will get set to true when Grbl issues "ok" message
|
||||
sd_current_line_number = 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
boolean closeFile()
|
||||
{
|
||||
if(!myFile) {
|
||||
return false;
|
||||
}
|
||||
|
||||
set_sd_state(SDCARD_IDLE);
|
||||
SD_ready_next = false;
|
||||
sd_current_line_number = 0;
|
||||
myFile.close();
|
||||
return true;
|
||||
boolean closeFile() {
|
||||
if (!myFile)
|
||||
return false;
|
||||
set_sd_state(SDCARD_IDLE);
|
||||
SD_ready_next = false;
|
||||
sd_current_line_number = 0;
|
||||
myFile.close();
|
||||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
@ -103,131 +92,110 @@ boolean closeFile()
|
||||
make uppercase
|
||||
return true if a line is
|
||||
*/
|
||||
boolean readFileLine(char *line)
|
||||
{
|
||||
char c;
|
||||
uint8_t index = 0;
|
||||
uint8_t line_flags = 0;
|
||||
uint8_t comment_char_counter = 0;
|
||||
|
||||
if (!myFile) {
|
||||
report_status_message(STATUS_SD_FAILED_READ, SD_client);
|
||||
return false;
|
||||
}
|
||||
|
||||
sd_current_line_number += 1;
|
||||
|
||||
while(myFile.available()) {
|
||||
c = myFile.read();
|
||||
|
||||
if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) { // capture all characters into a comment buffer
|
||||
comment[comment_char_counter++] = c;
|
||||
}
|
||||
|
||||
if (c == '\r' || c == ' ' ) {
|
||||
// ignore these whitespace items
|
||||
} else if (c == '(') {
|
||||
line_flags |= LINE_FLAG_COMMENT_PARENTHESES;
|
||||
} else if (c == ')') {
|
||||
// End of '()' comment. Resume line allowed.
|
||||
if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) {
|
||||
line_flags &= ~(LINE_FLAG_COMMENT_PARENTHESES);
|
||||
comment[comment_char_counter] = 0; // null terminate
|
||||
report_gcode_comment(comment);
|
||||
}
|
||||
} else if (c == ';') {
|
||||
// NOTE: ';' comment to EOL is a LinuxCNC definition. Not NIST.
|
||||
if (!(line_flags & LINE_FLAG_COMMENT_PARENTHESES)) { // semi colon inside parentheses do not mean anything
|
||||
line_flags |= LINE_FLAG_COMMENT_SEMICOLON;
|
||||
}
|
||||
} else if (c == '%') {
|
||||
// discard this character
|
||||
} else if (c == '\n') { // found the newline, so mark the end and return true
|
||||
line[index] = '\0';
|
||||
return true;
|
||||
} else { // add characters to the line
|
||||
if (!line_flags) {
|
||||
c = toupper(c); // make upper case
|
||||
line[index] = c;
|
||||
index++;
|
||||
}
|
||||
boolean readFileLine(char* line) {
|
||||
char c;
|
||||
uint8_t index = 0;
|
||||
uint8_t line_flags = 0;
|
||||
uint8_t comment_char_counter = 0;
|
||||
if (!myFile) {
|
||||
report_status_message(STATUS_SD_FAILED_READ, SD_client);
|
||||
return false;
|
||||
}
|
||||
|
||||
if (index == 255) { // name is too long so return false
|
||||
line[index] = '\0';
|
||||
report_status_message(STATUS_OVERFLOW, SD_client);
|
||||
return false;
|
||||
sd_current_line_number += 1;
|
||||
while (myFile.available()) {
|
||||
c = myFile.read();
|
||||
if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) // capture all characters into a comment buffer
|
||||
comment[comment_char_counter++] = c;
|
||||
if (c == '\r' || c == ' ') {
|
||||
// ignore these whitespace items
|
||||
} else if (c == '(')
|
||||
line_flags |= LINE_FLAG_COMMENT_PARENTHESES;
|
||||
else if (c == ')') {
|
||||
// End of '()' comment. Resume line allowed.
|
||||
if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) {
|
||||
line_flags &= ~(LINE_FLAG_COMMENT_PARENTHESES);
|
||||
comment[comment_char_counter] = 0; // null terminate
|
||||
report_gcode_comment(comment);
|
||||
}
|
||||
} else if (c == ';') {
|
||||
// NOTE: ';' comment to EOL is a LinuxCNC definition. Not NIST.
|
||||
if (!(line_flags & LINE_FLAG_COMMENT_PARENTHESES)) // semi colon inside parentheses do not mean anything
|
||||
line_flags |= LINE_FLAG_COMMENT_SEMICOLON;
|
||||
} else if (c == '%') {
|
||||
// discard this character
|
||||
} else if (c == '\n') { // found the newline, so mark the end and return true
|
||||
line[index] = '\0';
|
||||
return true;
|
||||
} else { // add characters to the line
|
||||
if (!line_flags) {
|
||||
c = toupper(c); // make upper case
|
||||
line[index] = c;
|
||||
index++;
|
||||
}
|
||||
}
|
||||
if (index == 255) { // name is too long so return false
|
||||
line[index] = '\0';
|
||||
report_status_message(STATUS_OVERFLOW, SD_client);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
// some files end without a newline
|
||||
if (index !=0) {
|
||||
line[index] = '\0';
|
||||
return true;
|
||||
} else { // empty line after new line
|
||||
return false;
|
||||
}
|
||||
// some files end without a newline
|
||||
if (index != 0) {
|
||||
line[index] = '\0';
|
||||
return true;
|
||||
} else // empty line after new line
|
||||
return false;
|
||||
}
|
||||
|
||||
// return a percentage complete 50.5 = 50.5%
|
||||
float sd_report_perc_complete()
|
||||
{
|
||||
if (!myFile) {
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
return ((float)myFile.position() / (float)myFile.size() * 100.0);
|
||||
float sd_report_perc_complete() {
|
||||
if (!myFile)
|
||||
return 0.0;
|
||||
return ((float)myFile.position() / (float)myFile.size() * 100.0);
|
||||
}
|
||||
|
||||
uint32_t sd_get_current_line_number()
|
||||
{
|
||||
return sd_current_line_number;
|
||||
uint32_t sd_get_current_line_number() {
|
||||
return sd_current_line_number;
|
||||
}
|
||||
|
||||
|
||||
uint8_t sd_state = SDCARD_IDLE;
|
||||
|
||||
uint8_t get_sd_state(bool refresh)
|
||||
{
|
||||
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)) {
|
||||
sd_state = SDCARD_NOT_PRESENT;
|
||||
return sd_state;
|
||||
}
|
||||
//no need to go further if SD detect is not correct
|
||||
if (!((digitalRead(SDCARD_DET_PIN) == SDCARD_DET_VAL) ? true : false)) {
|
||||
sd_state = SDCARD_NOT_PRESENT;
|
||||
return sd_state;
|
||||
}
|
||||
#endif
|
||||
//if busy doing something return state
|
||||
if (!((sd_state == SDCARD_NOT_PRESENT) || (sd_state == SDCARD_IDLE))) {
|
||||
return sd_state;
|
||||
}
|
||||
if (!refresh) {
|
||||
return sd_state; //to avoid refresh=true + busy to reset SD and waste time
|
||||
}
|
||||
//SD is idle or not detected, let see if still the case
|
||||
|
||||
//if busy doing something return state
|
||||
if (!((sd_state == SDCARD_NOT_PRESENT) || (sd_state == SDCARD_IDLE)))
|
||||
return sd_state;
|
||||
if (!refresh) {
|
||||
return sd_state; //to avoid refresh=true + busy to reset SD and waste time
|
||||
}
|
||||
//SD is idle or not detected, let see if still the case
|
||||
SD.end();
|
||||
sd_state = SDCARD_NOT_PRESENT;
|
||||
//using default value for speed ? should be parameter
|
||||
//refresh content if card was removed
|
||||
if (SD.begin((GRBL_SPI_SS == -1)?SS:GRBL_SPI_SS, SPI, GRBL_SPI_FREQ)) {
|
||||
if ( SD.cardSize() > 0 )sd_state = SDCARD_IDLE;
|
||||
if (SD.begin((GRBL_SPI_SS == -1) ? SS : GRBL_SPI_SS, SPI, GRBL_SPI_FREQ)) {
|
||||
if (SD.cardSize() > 0)sd_state = SDCARD_IDLE;
|
||||
}
|
||||
return sd_state;
|
||||
return sd_state;
|
||||
}
|
||||
|
||||
uint8_t set_sd_state(uint8_t flag)
|
||||
{
|
||||
sd_state = flag;
|
||||
return sd_state;
|
||||
uint8_t set_sd_state(uint8_t flag) {
|
||||
sd_state = flag;
|
||||
return sd_state;
|
||||
}
|
||||
|
||||
void sd_get_current_filename(char* name)
|
||||
{
|
||||
|
||||
if (myFile) {
|
||||
strcpy(name, myFile.name());
|
||||
} else {
|
||||
name[0] = 0;
|
||||
}
|
||||
void sd_get_current_filename(char* name) {
|
||||
if (myFile)
|
||||
strcpy(name, myFile.name());
|
||||
else
|
||||
name[0] = 0;
|
||||
}
|
||||
|
||||
|
||||
|
@ -12,15 +12,15 @@
|
||||
* D0 MISO
|
||||
* D1 -
|
||||
*/
|
||||
|
||||
|
||||
#ifndef grbl_sd_h
|
||||
#define grbl_sd_h
|
||||
|
||||
|
||||
#include "grbl.h"
|
||||
#include "FS.h"
|
||||
#include "SD.h"
|
||||
#include "SPI.h"
|
||||
#include "grbl.h"
|
||||
#include "FS.h"
|
||||
#include "SD.h"
|
||||
#include "SPI.h"
|
||||
|
||||
#define FILE_TYPE_COUNT 5 // number of acceptable gcode file types in array
|
||||
|
||||
@ -41,11 +41,11 @@ extern uint8_t SD_client;
|
||||
//bool sd_mount();
|
||||
uint8_t get_sd_state(bool refresh);
|
||||
uint8_t set_sd_state(uint8_t flag);
|
||||
void listDir(fs::FS &fs, const char * dirname, uint8_t levels, uint8_t client);
|
||||
boolean openFile(fs::FS &fs, const char * path);
|
||||
void listDir(fs::FS& fs, const char* dirname, uint8_t levels, uint8_t client);
|
||||
boolean openFile(fs::FS& fs, const char* path);
|
||||
boolean closeFile();
|
||||
boolean readFileLine(char *line);
|
||||
void readFile(fs::FS &fs, const char * path);
|
||||
boolean readFileLine(char* line);
|
||||
void readFile(fs::FS& fs, const char* path);
|
||||
float sd_report_perc_complete();
|
||||
uint32_t sd_get_current_line_number();
|
||||
void sd_get_current_filename(char* name);
|
||||
|
@ -1,10 +1,10 @@
|
||||
/*
|
||||
grbl_trinamic.cpp - Support for Trinamic Stepper Drivers SPI Mode
|
||||
using the TMCStepper library
|
||||
|
||||
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Copyright (c) 2019 Barton Dring for Buildlog.net LLC
|
||||
Copyright (c) 2019 Barton Dring for Buildlog.net LLC
|
||||
|
||||
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
|
||||
@ -21,15 +21,16 @@
|
||||
*/
|
||||
#include "grbl.h"
|
||||
|
||||
#ifdef USE_TRINAMIC
|
||||
#ifdef USE_TRINAMIC
|
||||
/*
|
||||
The drivers can use SPI daisy chaining to allow the use of only (1) CS_PIN.
|
||||
The PCB must be designed for this, with SDO pins being coonect to the
|
||||
next driver's SDI pin. The final SDO goes back to the controller.
|
||||
|
||||
This is setup in cpu_map.
|
||||
add #define TRINAMIC_DAISY_CHAIN to your map
|
||||
Make every axis CS_PIN definition be for the same pin like this...
|
||||
The drivers can use SPI daisy chaining to allow the use of a single CS_PIN.
|
||||
The PCB must be designed for this, with SDO pins connected to the
|
||||
next driver's SDI pin and the final SDO going back to the CPU.
|
||||
|
||||
To set this up, #define TRINAMIC_DAISY_CHAIN in your machine definition
|
||||
file (Machines/something.h).
|
||||
|
||||
Set the CS_PIN definition for every axis to the same pin, like this...
|
||||
#define X_CS_PIN GPIO_NUM_17
|
||||
#define Y_CS_PIN GPIO_NUM_17
|
||||
...etc.
|
||||
@ -40,266 +41,232 @@
|
||||
|
||||
*/
|
||||
#ifndef TRINAMIC_DAISY_CHAIN
|
||||
#define X_DRIVER_SPI_INDEX -1
|
||||
#define Y_DRIVER_SPI_INDEX -1
|
||||
#define Z_DRIVER_SPI_INDEX -1
|
||||
#define A_DRIVER_SPI_INDEX -1
|
||||
#define B_DRIVER_SPI_INDEX -1
|
||||
#define C_DRIVER_SPI_INDEX -1
|
||||
#define X_DRIVER_SPI_INDEX -1
|
||||
#define Y_DRIVER_SPI_INDEX -1
|
||||
#define Z_DRIVER_SPI_INDEX -1
|
||||
#define A_DRIVER_SPI_INDEX -1
|
||||
#define B_DRIVER_SPI_INDEX -1
|
||||
#define C_DRIVER_SPI_INDEX -1
|
||||
#else
|
||||
#define X_DRIVER_SPI_INDEX 1
|
||||
#define Y_DRIVER_SPI_INDEX 2
|
||||
#define Z_DRIVER_SPI_INDEX 3
|
||||
#define A_DRIVER_SPI_INDEX 4
|
||||
#define B_DRIVER_SPI_INDEX 5
|
||||
#define C_DRIVER_SPI_INDEX 6
|
||||
#define X_DRIVER_SPI_INDEX 1
|
||||
#define Y_DRIVER_SPI_INDEX 2
|
||||
#define Z_DRIVER_SPI_INDEX 3
|
||||
#define A_DRIVER_SPI_INDEX 4
|
||||
#define B_DRIVER_SPI_INDEX 5
|
||||
#define C_DRIVER_SPI_INDEX 6
|
||||
#endif
|
||||
|
||||
// TODO try to use the #define ## method to clean this up
|
||||
//#define DRIVER(driver, axis) driver##Stepper = TRINAMIC_axis## = driver##Stepper(axis##_CS_PIN, axis##_RSENSE);
|
||||
|
||||
#ifdef X_TRINAMIC
|
||||
#ifdef X_DRIVER_TMC2130
|
||||
TMC2130Stepper TRINAMIC_X = TMC2130Stepper(X_CS_PIN, X_RSENSE, X_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef X_DRIVER_TMC2209
|
||||
TMC2209Stepper TRINAMIC_X = TMC2209Stepper(X_CS_PIN, X_RSENSE, X_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef X_DRIVER_TMC5160
|
||||
TMC5160Stepper TRINAMIC_X = TMC5160Stepper(X_CS_PIN, X_RSENSE, X_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef X_DRIVER_TMC2130
|
||||
TMC2130Stepper TRINAMIC_X = TMC2130Stepper(X_CS_PIN, X_RSENSE, X_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef X_DRIVER_TMC2209
|
||||
TMC2209Stepper TRINAMIC_X = TMC2209Stepper(X_CS_PIN, X_RSENSE, X_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef X_DRIVER_TMC5160
|
||||
TMC5160Stepper TRINAMIC_X = TMC5160Stepper(X_CS_PIN, X_RSENSE, X_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef Y_TRINAMIC
|
||||
#ifdef Y_DRIVER_TMC2130
|
||||
TMC2130Stepper TRINAMIC_Y = TMC2130Stepper(Y_CS_PIN, Y_RSENSE, Y_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef Y_DRIVER_TMC2209
|
||||
TMC2209Stepper TRINAMIC_Y = TMC2209Stepper(Y_CS_PIN, Y_RSENSE, Y_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef Y_DRIVER_TMC5160
|
||||
TMC5160Stepper TRINAMIC_Y = TMC5160Stepper(Y_CS_PIN, Y_RSENSE, Y_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef Y_DRIVER_TMC2130
|
||||
TMC2130Stepper TRINAMIC_Y = TMC2130Stepper(Y_CS_PIN, Y_RSENSE, Y_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef Y_DRIVER_TMC2209
|
||||
TMC2209Stepper TRINAMIC_Y = TMC2209Stepper(Y_CS_PIN, Y_RSENSE, Y_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef Y_DRIVER_TMC5160
|
||||
TMC5160Stepper TRINAMIC_Y = TMC5160Stepper(Y_CS_PIN, Y_RSENSE, Y_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef Z_TRINAMIC
|
||||
#ifdef Z_DRIVER_TMC2130
|
||||
TMC2130Stepper TRINAMIC_Z = TMC2130Stepper(Z_CS_PIN, Z_RSENSE, Z_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef Z_DRIVER_TMC2209
|
||||
TMC2209Stepper TRINAMIC_Z = TMC2209Stepper(Z_CS_PIN, Z_RSENSE, Z_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef Z_DRIVER_TMC5160
|
||||
TMC5160Stepper TRINAMIC_Z = TMC5160Stepper(Z_CS_PIN, Z_RSENSE, Z_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef Z_DRIVER_TMC2130
|
||||
TMC2130Stepper TRINAMIC_Z = TMC2130Stepper(Z_CS_PIN, Z_RSENSE, Z_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef Z_DRIVER_TMC2209
|
||||
TMC2209Stepper TRINAMIC_Z = TMC2209Stepper(Z_CS_PIN, Z_RSENSE, Z_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef Z_DRIVER_TMC5160
|
||||
TMC5160Stepper TRINAMIC_Z = TMC5160Stepper(Z_CS_PIN, Z_RSENSE, Z_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef A_TRINAMIC
|
||||
#ifdef A_DRIVER_TMC2130
|
||||
TMC2130Stepper TRINAMIC_A = TMC2130Stepper(A_CS_PIN, A_RSENSE, A_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef A_DRIVER_TMC2209
|
||||
TMC2209Stepper TRINAMIC_A = TMC2209Stepper(A_CS_PIN, A_RSENSE, A_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef A_DRIVER_TMC5160
|
||||
TMC5160Stepper TRINAMIC_A = TMC5160Stepper(A_CS_PIN, A_RSENSE, A_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef A_DRIVER_TMC2130
|
||||
TMC2130Stepper TRINAMIC_A = TMC2130Stepper(A_CS_PIN, A_RSENSE, A_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef A_DRIVER_TMC2209
|
||||
TMC2209Stepper TRINAMIC_A = TMC2209Stepper(A_CS_PIN, A_RSENSE, A_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef A_DRIVER_TMC5160
|
||||
TMC5160Stepper TRINAMIC_A = TMC5160Stepper(A_CS_PIN, A_RSENSE, A_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef B_TRINAMIC
|
||||
#ifdef B_DRIVER_TMC2130
|
||||
TMC2130Stepper TRINAMIC_B = TMC2130Stepper(B_CS_PIN, B_RSENSE, B_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef B_DRIVER_TMC2209
|
||||
TMC2209Stepper TRINAMIC_B = TMC2209Stepper(B_CS_PIN, B_RSENSE, B_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef B_DRIVER_TMC5160
|
||||
TMC5160Stepper TRINAMIC_B = TMC5160Stepper(B_CS_PIN, B_RSENSE, B_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef B_DRIVER_TMC2130
|
||||
TMC2130Stepper TRINAMIC_B = TMC2130Stepper(B_CS_PIN, B_RSENSE, B_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef B_DRIVER_TMC2209
|
||||
TMC2209Stepper TRINAMIC_B = TMC2209Stepper(B_CS_PIN, B_RSENSE, B_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef B_DRIVER_TMC5160
|
||||
TMC5160Stepper TRINAMIC_B = TMC5160Stepper(B_CS_PIN, B_RSENSE, B_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef C_TRINAMIC
|
||||
#ifdef C_DRIVER_TMC2130
|
||||
TMC2130Stepper TRINAMIC_c = TMC2130Stepper(C_CS_PIN, C_RSENSE, C_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef C_DRIVER_TMC2209
|
||||
TMC2209Stepper TRINAMIC_C = TMC2209Stepper(C_CS_PIN, C_RSENSE, C_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef C_DRIVER_TMC5160
|
||||
TMC5160Stepper TRINAMIC_C = TMC5160Stepper(C_CS_PIN, C_RSENSE, C_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef C_DRIVER_TMC2130
|
||||
TMC2130Stepper TRINAMIC_c = TMC2130Stepper(C_CS_PIN, C_RSENSE, C_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef C_DRIVER_TMC2209
|
||||
TMC2209Stepper TRINAMIC_C = TMC2209Stepper(C_CS_PIN, C_RSENSE, C_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#ifdef C_DRIVER_TMC5160
|
||||
TMC5160Stepper TRINAMIC_C = TMC5160Stepper(C_CS_PIN, C_RSENSE, C_DRIVER_SPI_INDEX);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// TODO ABC Axes
|
||||
|
||||
void Trinamic_Init()
|
||||
{
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "TMCStepper Init using Library Ver 0x%06x", TMCSTEPPER_VERSION);
|
||||
|
||||
SPI.begin();
|
||||
|
||||
#ifdef USE_MACHINE_TRINAMIC_INIT
|
||||
machine_trinamic_setup();
|
||||
return;
|
||||
#endif
|
||||
|
||||
#ifdef X_TRINAMIC
|
||||
TRINAMIC_X.begin(); // Initiate pins and registries
|
||||
trinamic_test_response(TRINAMIC_X.test_connection(), "X");
|
||||
TRINAMIC_X.toff(TRINAMIC_DEFAULT_TOFF);
|
||||
TRINAMIC_X.microsteps(settings.microsteps[X_AXIS]);
|
||||
TRINAMIC_X.rms_current(settings.current[X_AXIS] * 1000.0, settings.hold_current[X_AXIS]/100.0);
|
||||
TRINAMIC_X.en_pwm_mode(1); // Enable extremely quiet stepping
|
||||
TRINAMIC_X.pwm_autoscale(1);
|
||||
#endif
|
||||
|
||||
#ifdef Y_TRINAMIC
|
||||
TRINAMIC_Y.begin(); // Initiate pins and registries
|
||||
trinamic_test_response(TRINAMIC_Y.test_connection(), "Y");
|
||||
TRINAMIC_Y.toff(TRINAMIC_DEFAULT_TOFF);
|
||||
TRINAMIC_Y.microsteps(settings.microsteps[Y_AXIS]);
|
||||
TRINAMIC_Y.rms_current(settings.current[Y_AXIS] * 1000.0, settings.hold_current[Y_AXIS]/100.0);
|
||||
TRINAMIC_Y.en_pwm_mode(1); // Enable extremely quiet stepping
|
||||
TRINAMIC_Y.pwm_autoscale(1);
|
||||
#endif
|
||||
|
||||
#ifdef Z_TRINAMIC
|
||||
TRINAMIC_Z.begin(); // Initiate pins and registries
|
||||
trinamic_test_response(TRINAMIC_Z.test_connection(), "Z");
|
||||
TRINAMIC_Z.toff(TRINAMIC_DEFAULT_TOFF);
|
||||
TRINAMIC_Z.microsteps(settings.microsteps[Z_AXIS]);
|
||||
TRINAMIC_Z.rms_current(settings.current[Z_AXIS] * 1000.0, settings.hold_current[Z_AXIS]/100.0);
|
||||
TRINAMIC_Z.en_pwm_mode(1); // Enable extremely quiet stepping
|
||||
TRINAMIC_Z.pwm_autoscale(1);
|
||||
#endif
|
||||
|
||||
#ifdef A_TRINAMIC
|
||||
TRINAMIC_A.begin(); // Initiate pins and registries
|
||||
trinamic_test_response(TRINAMIC_A.test_connection(), "A");
|
||||
TRINAMIC_A.toff(TRINAMIC_DEFAULT_TOFF);
|
||||
TRINAMIC_A.microsteps(settings.microsteps[A_AXIS]);
|
||||
TRINAMIC_A.rms_current(settings.current[A_AXIS] * 1000.0, settings.hold_current[A_AXIS]/100.0);
|
||||
TRINAMIC_A.en_pwm_mode(1); // Enable extremely quiet stepping
|
||||
TRINAMIC_A.pwm_autoscale(1);
|
||||
#endif
|
||||
|
||||
#ifdef B_TRINAMIC
|
||||
TRINAMIC_B.begin(); // Initiate pins and registries
|
||||
trinamic_test_response(TRINAMIC_B.test_connection(), "B");
|
||||
TRINAMIC_B.toff(TRINAMIC_DEFAULT_TOFF);
|
||||
TRINAMIC_B.microsteps(settings.microsteps[B_AXIS]);
|
||||
TRINAMIC_B.rms_current(settings.current[B_AXIS] * 1000.0, settings.hold_current[B_AXIS]/100.0);
|
||||
TRINAMIC_B.en_pwm_mode(1); // Enable extremely quiet stepping
|
||||
TRINAMIC_B.pwm_autoscale(1);
|
||||
#endif
|
||||
|
||||
#ifdef C_TRINAMIC
|
||||
TRINAMIC_C.begin(); // Initiate pins and registries
|
||||
trinamic_test_response(TRINAMIC_C.test_connection(), "C");
|
||||
TRINAMIC_C.toff(TRINAMIC_DEFAULT_TOFF);
|
||||
TRINAMIC_C.microsteps(settings.microsteps[C_AXIS]);
|
||||
TRINAMIC_C.rms_current(settings.current[C_AXIS] * 1000.0, settings.hold_current[C_AXIS]/100.0);
|
||||
TRINAMIC_C.en_pwm_mode(1); // Enable extremely quiet stepping
|
||||
TRINAMIC_C.pwm_autoscale(1);
|
||||
#endif
|
||||
|
||||
|
||||
void Trinamic_Init() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "TMCStepper Init using Library Ver 0x%06x", TMCSTEPPER_VERSION);
|
||||
SPI.begin();
|
||||
#ifdef USE_MACHINE_TRINAMIC_INIT
|
||||
machine_trinamic_setup();
|
||||
return;
|
||||
#endif
|
||||
#ifdef X_TRINAMIC
|
||||
TRINAMIC_X.begin(); // Initiate pins and registries
|
||||
trinamic_test_response(TRINAMIC_X.test_connection(), "X");
|
||||
TRINAMIC_X.toff(TRINAMIC_DEFAULT_TOFF);
|
||||
TRINAMIC_X.microsteps(settings.microsteps[X_AXIS]);
|
||||
TRINAMIC_X.rms_current(settings.current[X_AXIS] * 1000.0, settings.hold_current[X_AXIS] / 100.0);
|
||||
TRINAMIC_X.en_pwm_mode(1); // Enable extremely quiet stepping
|
||||
TRINAMIC_X.pwm_autoscale(1);
|
||||
#endif
|
||||
#ifdef Y_TRINAMIC
|
||||
TRINAMIC_Y.begin(); // Initiate pins and registries
|
||||
trinamic_test_response(TRINAMIC_Y.test_connection(), "Y");
|
||||
TRINAMIC_Y.toff(TRINAMIC_DEFAULT_TOFF);
|
||||
TRINAMIC_Y.microsteps(settings.microsteps[Y_AXIS]);
|
||||
TRINAMIC_Y.rms_current(settings.current[Y_AXIS] * 1000.0, settings.hold_current[Y_AXIS] / 100.0);
|
||||
TRINAMIC_Y.en_pwm_mode(1); // Enable extremely quiet stepping
|
||||
TRINAMIC_Y.pwm_autoscale(1);
|
||||
#endif
|
||||
#ifdef Z_TRINAMIC
|
||||
TRINAMIC_Z.begin(); // Initiate pins and registries
|
||||
trinamic_test_response(TRINAMIC_Z.test_connection(), "Z");
|
||||
TRINAMIC_Z.toff(TRINAMIC_DEFAULT_TOFF);
|
||||
TRINAMIC_Z.microsteps(settings.microsteps[Z_AXIS]);
|
||||
TRINAMIC_Z.rms_current(settings.current[Z_AXIS] * 1000.0, settings.hold_current[Z_AXIS] / 100.0);
|
||||
TRINAMIC_Z.en_pwm_mode(1); // Enable extremely quiet stepping
|
||||
TRINAMIC_Z.pwm_autoscale(1);
|
||||
#endif
|
||||
#ifdef A_TRINAMIC
|
||||
TRINAMIC_A.begin(); // Initiate pins and registries
|
||||
trinamic_test_response(TRINAMIC_A.test_connection(), "A");
|
||||
TRINAMIC_A.toff(TRINAMIC_DEFAULT_TOFF);
|
||||
TRINAMIC_A.microsteps(settings.microsteps[A_AXIS]);
|
||||
TRINAMIC_A.rms_current(settings.current[A_AXIS] * 1000.0, settings.hold_current[A_AXIS] / 100.0);
|
||||
TRINAMIC_A.en_pwm_mode(1); // Enable extremely quiet stepping
|
||||
TRINAMIC_A.pwm_autoscale(1);
|
||||
#endif
|
||||
#ifdef B_TRINAMIC
|
||||
TRINAMIC_B.begin(); // Initiate pins and registries
|
||||
trinamic_test_response(TRINAMIC_B.test_connection(), "B");
|
||||
TRINAMIC_B.toff(TRINAMIC_DEFAULT_TOFF);
|
||||
TRINAMIC_B.microsteps(settings.microsteps[B_AXIS]);
|
||||
TRINAMIC_B.rms_current(settings.current[B_AXIS] * 1000.0, settings.hold_current[B_AXIS] / 100.0);
|
||||
TRINAMIC_B.en_pwm_mode(1); // Enable extremely quiet stepping
|
||||
TRINAMIC_B.pwm_autoscale(1);
|
||||
#endif
|
||||
#ifdef C_TRINAMIC
|
||||
TRINAMIC_C.begin(); // Initiate pins and registries
|
||||
trinamic_test_response(TRINAMIC_C.test_connection(), "C");
|
||||
TRINAMIC_C.toff(TRINAMIC_DEFAULT_TOFF);
|
||||
TRINAMIC_C.microsteps(settings.microsteps[C_AXIS]);
|
||||
TRINAMIC_C.rms_current(settings.current[C_AXIS] * 1000.0, settings.hold_current[C_AXIS] / 100.0);
|
||||
TRINAMIC_C.en_pwm_mode(1); // Enable extremely quiet stepping
|
||||
TRINAMIC_C.pwm_autoscale(1);
|
||||
#endif
|
||||
}
|
||||
|
||||
void trinamic_change_settings()
|
||||
{
|
||||
#ifdef X_TRINAMIC
|
||||
TRINAMIC_X.microsteps(settings.microsteps[X_AXIS]);
|
||||
TRINAMIC_X.rms_current(settings.current[X_AXIS] * 1000.0, settings.hold_current[X_AXIS]/100.0);
|
||||
#endif
|
||||
|
||||
#ifdef Y_TRINAMIC
|
||||
TRINAMIC_Y.microsteps(settings.microsteps[Y_AXIS]);
|
||||
TRINAMIC_Y.rms_current(settings.current[Y_AXIS] * 1000.0, settings.hold_current[Y_AXIS]/100.0);
|
||||
#endif
|
||||
|
||||
#ifdef Z_TRINAMIC
|
||||
TRINAMIC_Z.microsteps(settings.microsteps[Z_AXIS]);
|
||||
TRINAMIC_Z.rms_current(settings.current[Z_AXIS] * 1000.0, settings.hold_current[Z_AXIS]/100.0);
|
||||
#endif
|
||||
|
||||
#ifdef A_TRINAMIC
|
||||
TRINAMIC_A.microsteps(settings.microsteps[A_AXIS]);
|
||||
TRINAMIC_A.rms_current(settings.current[A_AXIS] * 1000.0, settings.hold_current[A_AXIS]/100.0);
|
||||
#endif
|
||||
|
||||
#ifdef B_TRINAMIC
|
||||
TRINAMIC_B.microsteps(settings.microsteps[B_AXIS]);
|
||||
TTRINAMIC_B.rms_current(settings.current[B_AXIS] * 1000.0, settings.hold_current[B_AXIS]/100.0);
|
||||
#endif
|
||||
|
||||
#ifdef C_TRINAMIC
|
||||
TRINAMIC_C.microsteps(settings.microsteps[C_AXIS]);
|
||||
TRINAMIC_C.rms_current(settings.current[C_AXIS] * 1000.0, settings.hold_current[C_AXIS]/100.0);
|
||||
#endif
|
||||
// Call this function called whenever $$ settings that affect the drivers are changed
|
||||
void trinamic_change_settings() {
|
||||
#ifdef X_TRINAMIC
|
||||
TRINAMIC_X.microsteps(settings.microsteps[X_AXIS]);
|
||||
TRINAMIC_X.rms_current(settings.current[X_AXIS] * 1000.0, settings.hold_current[X_AXIS] / 100.0);
|
||||
#endif
|
||||
#ifdef Y_TRINAMIC
|
||||
TRINAMIC_Y.microsteps(settings.microsteps[Y_AXIS]);
|
||||
TRINAMIC_Y.rms_current(settings.current[Y_AXIS] * 1000.0, settings.hold_current[Y_AXIS] / 100.0);
|
||||
#endif
|
||||
#ifdef Z_TRINAMIC
|
||||
TRINAMIC_Z.microsteps(settings.microsteps[Z_AXIS]);
|
||||
TRINAMIC_Z.rms_current(settings.current[Z_AXIS] * 1000.0, settings.hold_current[Z_AXIS] / 100.0);
|
||||
#endif
|
||||
#ifdef A_TRINAMIC
|
||||
TRINAMIC_A.microsteps(settings.microsteps[A_AXIS]);
|
||||
TRINAMIC_A.rms_current(settings.current[A_AXIS] * 1000.0, settings.hold_current[A_AXIS] / 100.0);
|
||||
#endif
|
||||
#ifdef B_TRINAMIC
|
||||
TRINAMIC_B.microsteps(settings.microsteps[B_AXIS]);
|
||||
TTRINAMIC_B.rms_current(settings.current[B_AXIS] * 1000.0, settings.hold_current[B_AXIS] / 100.0);
|
||||
#endif
|
||||
#ifdef C_TRINAMIC
|
||||
TRINAMIC_C.microsteps(settings.microsteps[C_AXIS]);
|
||||
TRINAMIC_C.rms_current(settings.current[C_AXIS] * 1000.0, settings.hold_current[C_AXIS] / 100.0);
|
||||
#endif
|
||||
}
|
||||
|
||||
void trinamic_test_response(uint8_t result, const char *axis)
|
||||
{
|
||||
if (result) {
|
||||
grbl_sendf(CLIENT_SERIAL, "failed.");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test failed", axis);
|
||||
switch(result) {
|
||||
case 1:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test check connection", axis);
|
||||
break;
|
||||
case 2:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test check motor power", axis);
|
||||
break;
|
||||
// Display the response of the attempt to connect to a Trinamic driver
|
||||
void trinamic_test_response(uint8_t result, const char* axis) {
|
||||
if (result) {
|
||||
switch (result) {
|
||||
case 1:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test failed. Check connection", axis);
|
||||
break;
|
||||
case 2:
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test failed. Check motor power", axis);
|
||||
break;
|
||||
}
|
||||
}
|
||||
else {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test passed", axis);
|
||||
}
|
||||
} else
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test passed", axis);
|
||||
}
|
||||
|
||||
void trinamic_stepper_enable(bool enable) {
|
||||
|
||||
// Trinamic_Init() has already enabled the drivers in case #define USE_TRINAMIC_ENABLE is not used
|
||||
// so the previous_state is set accordingly
|
||||
static bool previous_state = true;
|
||||
|
||||
uint8_t toff;
|
||||
|
||||
if (enable == previous_state)
|
||||
return;
|
||||
|
||||
previous_state = enable;
|
||||
|
||||
if (enable)
|
||||
toff = TRINAMIC_DEFAULT_TOFF;
|
||||
else
|
||||
toff = 0; // diables driver
|
||||
|
||||
#ifdef X_TRINAMIC
|
||||
TRINAMIC_X.toff(toff);
|
||||
#endif
|
||||
|
||||
#ifdef Y_TRINAMIC
|
||||
TRINAMIC_Y.toff(toff);
|
||||
#endif
|
||||
|
||||
#ifdef Z_TRINAMIC
|
||||
TRINAMIC_Z.toff(toff);
|
||||
#endif
|
||||
|
||||
#ifdef A_TRINAMIC
|
||||
TRINAMIC_A.toff(toff);
|
||||
#endif
|
||||
|
||||
#ifdef B_TRINAMIC
|
||||
TRINAMIC_B.toff(toff);
|
||||
#endif
|
||||
|
||||
#ifdef C_TRINAMIC
|
||||
TRINAMIC_C.toff(toff);
|
||||
#endif
|
||||
|
||||
// Trinamic_Init() has already enabled the drivers in case #define USE_TRINAMIC_ENABLE is not used
|
||||
// so the previous_state is set accordingly
|
||||
static bool previous_state = true;
|
||||
uint8_t toff;
|
||||
if (enable == previous_state)
|
||||
return;
|
||||
previous_state = enable;
|
||||
if (enable)
|
||||
toff = TRINAMIC_DEFAULT_TOFF;
|
||||
else
|
||||
toff = 0; // diables driver
|
||||
#ifdef X_TRINAMIC
|
||||
TRINAMIC_X.toff(toff);
|
||||
#endif
|
||||
#ifdef Y_TRINAMIC
|
||||
TRINAMIC_Y.toff(toff);
|
||||
#endif
|
||||
#ifdef Z_TRINAMIC
|
||||
TRINAMIC_Z.toff(toff);
|
||||
#endif
|
||||
#ifdef A_TRINAMIC
|
||||
TRINAMIC_A.toff(toff);
|
||||
#endif
|
||||
#ifdef B_TRINAMIC
|
||||
TRINAMIC_B.toff(toff);
|
||||
#endif
|
||||
#ifdef C_TRINAMIC
|
||||
TRINAMIC_C.toff(toff);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
@ -1,8 +1,8 @@
|
||||
/*
|
||||
grbl_trinamic.h - Support for TMC2130 Stepper Drivers SPI Mode
|
||||
Part of Grbl_ESP32
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Copyright (c) 2019 Barton Dring for Buildlog.net LLC
|
||||
Copyright (c) 2019 Barton Dring for Buildlog.net LLC
|
||||
|
||||
GrblESP32 is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
@ -21,16 +21,19 @@
|
||||
|
||||
|
||||
#ifndef GRBL_TRINAMIC_h
|
||||
#define GRBL_TRINAMIC_h
|
||||
#define GRBL_TRINAMIC_h
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
#ifdef USE_TRINAMIC
|
||||
#include <TMCStepper.h> // https://github.com/teemuatlut/TMCStepper
|
||||
void Trinamic_Init();
|
||||
void trinamic_change_settings();
|
||||
void trinamic_test_response(uint8_t result, const char *axis);
|
||||
void trinamic_stepper_enable(bool enable);
|
||||
#include <TMCStepper.h> // https://github.com/teemuatlut/TMCStepper
|
||||
void Trinamic_Init();
|
||||
void trinamic_change_settings();
|
||||
void trinamic_test_response(uint8_t result, const char* axis);
|
||||
void trinamic_stepper_enable(bool enable);
|
||||
#ifdef USE_MACHINE_TRINAMIC_INIT
|
||||
void machine_trinamic_setup();
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#endif
|
||||
#endif // GRBL_TRIAMINIC_h
|
||||
|
@ -21,7 +21,7 @@
|
||||
Unipolar Class
|
||||
|
||||
This class allows you to control a unipolar motor. Unipolar motors have 5 wires. One
|
||||
is typically tied to a voltage, while the other 4 are switched to ground in a
|
||||
is typically tied to a voltage, while the other 4 are switched to ground in a
|
||||
sequence
|
||||
|
||||
To take a step simply call the step(step, direction) function.
|
||||
@ -29,206 +29,186 @@
|
||||
*/
|
||||
#include "grbl.h"
|
||||
|
||||
#ifdef USE_UNIPOLAR
|
||||
#ifdef USE_UNIPOLAR
|
||||
|
||||
// assign the I/O pins used for each coil of the motors
|
||||
#ifdef X_UNIPOLAR
|
||||
Unipolar X_Unipolar(X_PIN_PHASE_0, X_PIN_PHASE_1, X_PIN_PHASE_2, X_PIN_PHASE_3, true);
|
||||
#endif
|
||||
// assign the I/O pins used for each coil of the motors
|
||||
#ifdef X_UNIPOLAR
|
||||
Unipolar X_Unipolar(X_PIN_PHASE_0, X_PIN_PHASE_1, X_PIN_PHASE_2, X_PIN_PHASE_3, true);
|
||||
#endif
|
||||
|
||||
#ifdef Y_UNIPOLAR
|
||||
Unipolar Y_Unipolar(Y_PIN_PHASE_0, Y_PIN_PHASE_1, Y_PIN_PHASE_2, Y_PIN_PHASE_3, true);
|
||||
#endif
|
||||
#ifdef Y_UNIPOLAR
|
||||
Unipolar Y_Unipolar(Y_PIN_PHASE_0, Y_PIN_PHASE_1, Y_PIN_PHASE_2, Y_PIN_PHASE_3, true);
|
||||
#endif
|
||||
|
||||
#ifdef Z_UNIPOLAR
|
||||
Unipolar Z_Unipolar(Z_PIN_PHASE_0, Z_PIN_PHASE_1, Z_PIN_PHASE_2, Z_PIN_PHASE_3, true);
|
||||
#endif
|
||||
#ifdef Z_UNIPOLAR
|
||||
Unipolar Z_Unipolar(Z_PIN_PHASE_0, Z_PIN_PHASE_1, Z_PIN_PHASE_2, Z_PIN_PHASE_3, true);
|
||||
#endif
|
||||
|
||||
void unipolar_init(){
|
||||
#ifdef X_UNIPOLAR
|
||||
X_Unipolar.init();
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "X unipolar");
|
||||
#endif
|
||||
#ifdef Y_UNIPOLAR
|
||||
Y_Unipolar.init();
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Y unipolar");
|
||||
#endif
|
||||
#ifdef Z_UNIPOLAR
|
||||
Z_Unipolar.init();
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Z unipolar");
|
||||
#endif
|
||||
}
|
||||
void unipolar_init() {
|
||||
#ifdef X_UNIPOLAR
|
||||
X_Unipolar.init();
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "X unipolar");
|
||||
#endif
|
||||
#ifdef Y_UNIPOLAR
|
||||
Y_Unipolar.init();
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Y unipolar");
|
||||
#endif
|
||||
#ifdef Z_UNIPOLAR
|
||||
Z_Unipolar.init();
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Z unipolar");
|
||||
#endif
|
||||
}
|
||||
|
||||
void unipolar_step(uint8_t step_mask, uint8_t dir_mask)
|
||||
{
|
||||
#ifdef X_UNIPOLAR
|
||||
X_Unipolar.step(step_mask & (1<<X_AXIS), dir_mask & (1<<X_AXIS));
|
||||
#endif
|
||||
#ifdef Y_UNIPOLAR
|
||||
Y_Unipolar.step(step_mask & (1<<Y_AXIS), dir_mask & (1<<Y_AXIS));
|
||||
#endif
|
||||
#ifdef Z_UNIPOLAR
|
||||
Z_Unipolar.step(step_mask & (1<<Z_AXIS), dir_mask & (1<<ZX_AXIS));
|
||||
#endif
|
||||
}
|
||||
|
||||
void unipolar_disable(bool disable)
|
||||
{
|
||||
#ifdef X_UNIPOLAR
|
||||
X_Unipolar.set_enabled(!disable);
|
||||
#endif
|
||||
#ifdef Y_UNIPOLAR
|
||||
Y_Unipolar.set_enabled(!disable);
|
||||
#endif
|
||||
#ifdef Z_UNIPOLAR
|
||||
Z_Unipolar.set_enabled(!disable);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
Unipolar::Unipolar(uint8_t pin_phase0, uint8_t pin_phase1, uint8_t pin_phase2, uint8_t pin_phase3, bool half_step) // constructor
|
||||
{
|
||||
_pin_phase0 = pin_phase0;
|
||||
_pin_phase1 = pin_phase1;
|
||||
_pin_phase2 = pin_phase2;
|
||||
_pin_phase3 = pin_phase3;
|
||||
_half_step = half_step;
|
||||
}
|
||||
|
||||
void Unipolar::init() {
|
||||
pinMode(_pin_phase0, OUTPUT);
|
||||
pinMode(_pin_phase1, OUTPUT);
|
||||
pinMode(_pin_phase2, OUTPUT);
|
||||
pinMode(_pin_phase3, OUTPUT);
|
||||
|
||||
_current_phase = 0;
|
||||
set_enabled(false);
|
||||
}
|
||||
void unipolar_step(uint8_t step_mask, uint8_t dir_mask) {
|
||||
#ifdef X_UNIPOLAR
|
||||
X_Unipolar.step(step_mask & (1 << X_AXIS), dir_mask & (1 << X_AXIS));
|
||||
#endif
|
||||
#ifdef Y_UNIPOLAR
|
||||
Y_Unipolar.step(step_mask & (1 << Y_AXIS), dir_mask & (1 << Y_AXIS));
|
||||
#endif
|
||||
#ifdef Z_UNIPOLAR
|
||||
Z_Unipolar.step(step_mask & (1 << Z_AXIS), dir_mask & (1 << ZX_AXIS));
|
||||
#endif
|
||||
}
|
||||
|
||||
void Unipolar::set_enabled(bool enabled)
|
||||
{
|
||||
if (enabled == _enabled)
|
||||
return; // no change
|
||||
|
||||
_enabled = enabled;
|
||||
|
||||
if (!enabled) {
|
||||
digitalWrite(_pin_phase0, 0);
|
||||
digitalWrite(_pin_phase1, 0);
|
||||
digitalWrite(_pin_phase2, 0);
|
||||
digitalWrite(_pin_phase3, 0);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
To take a step set step to true and set the driection
|
||||
|
||||
step is included so that st.step_outbits can be used to determine if a
|
||||
step is required on this axis
|
||||
*/
|
||||
void Unipolar::step(bool step, bool dir_forward)
|
||||
{
|
||||
uint8_t _phase[8] = {0, 0, 0, 0, 0, 0, 0, 0}; // temporary phase values...all start as off
|
||||
uint8_t phase_max;
|
||||
|
||||
if (_half_step)
|
||||
phase_max = 7;
|
||||
else
|
||||
phase_max = 3;
|
||||
|
||||
if (!step)
|
||||
return; // a step is not required on this interrupt
|
||||
|
||||
if (!_enabled)
|
||||
return; // don't do anything, phase is not changed or lost
|
||||
|
||||
if (dir_forward) { // count up
|
||||
if (_current_phase == phase_max) {
|
||||
_current_phase = 0;
|
||||
}
|
||||
else {
|
||||
_current_phase++;
|
||||
}
|
||||
}
|
||||
else { // count down
|
||||
if (_current_phase == 0) {
|
||||
_current_phase = phase_max;
|
||||
}
|
||||
else {
|
||||
_current_phase--;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
8 Step : A – AB – B – BC – C – CD – D – DA
|
||||
4 Step : AB – BC – CD – DA (Usual application)
|
||||
|
||||
Step IN4 IN3 IN2 IN1
|
||||
A 0 0 0 1
|
||||
AB 0 0 1 1
|
||||
B 0 0 1 0
|
||||
BC 0 1 1 0
|
||||
C 0 1 0 0
|
||||
CD 1 1 0 0
|
||||
D 1 0 0 0
|
||||
DA 1 0 0 1
|
||||
*/
|
||||
if (_half_step) {
|
||||
switch (_current_phase) {
|
||||
case 0:
|
||||
_phase[0] = 1;
|
||||
break;
|
||||
case 1:
|
||||
_phase[0] = 1;
|
||||
_phase[1] = 1;
|
||||
break;
|
||||
case 2:
|
||||
_phase[1] = 1;
|
||||
break;
|
||||
case 3:
|
||||
_phase[1] = 1;
|
||||
_phase[2] = 1;
|
||||
break;
|
||||
case 4:
|
||||
_phase[2] = 1;
|
||||
break;
|
||||
case 5:
|
||||
_phase[2] = 1;
|
||||
_phase[3] = 1;
|
||||
break;
|
||||
case 6:
|
||||
_phase[3] = 1;
|
||||
break;
|
||||
case 7:
|
||||
_phase[3] = 1;
|
||||
_phase[0] = 1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
else {
|
||||
switch (_current_phase) {
|
||||
case 0:
|
||||
_phase[0] = 1;
|
||||
_phase[1] = 1;
|
||||
break;
|
||||
case 1:
|
||||
_phase[1] = 1;
|
||||
_phase[2] = 1;
|
||||
break;
|
||||
case 2:
|
||||
_phase[2] = 1;
|
||||
_phase[3] = 1;
|
||||
break;
|
||||
case 3:
|
||||
_phase[3] = 1;
|
||||
_phase[0] = 1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
digitalWrite(_pin_phase0, _phase[0]);
|
||||
digitalWrite(_pin_phase1, _phase[1]);
|
||||
digitalWrite(_pin_phase2, _phase[2]);
|
||||
digitalWrite(_pin_phase3, _phase[3]);
|
||||
}
|
||||
void unipolar_disable(bool disable) {
|
||||
#ifdef X_UNIPOLAR
|
||||
X_Unipolar.set_enabled(!disable);
|
||||
#endif
|
||||
#ifdef Y_UNIPOLAR
|
||||
Y_Unipolar.set_enabled(!disable);
|
||||
#endif
|
||||
#ifdef Z_UNIPOLAR
|
||||
Z_Unipolar.set_enabled(!disable);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
Unipolar::Unipolar(uint8_t pin_phase0, uint8_t pin_phase1, uint8_t pin_phase2, uint8_t pin_phase3, bool half_step) { // constructor
|
||||
_pin_phase0 = pin_phase0;
|
||||
_pin_phase1 = pin_phase1;
|
||||
_pin_phase2 = pin_phase2;
|
||||
_pin_phase3 = pin_phase3;
|
||||
_half_step = half_step;
|
||||
}
|
||||
|
||||
void Unipolar::init() {
|
||||
pinMode(_pin_phase0, OUTPUT);
|
||||
pinMode(_pin_phase1, OUTPUT);
|
||||
pinMode(_pin_phase2, OUTPUT);
|
||||
pinMode(_pin_phase3, OUTPUT);
|
||||
_current_phase = 0;
|
||||
set_enabled(false);
|
||||
}
|
||||
|
||||
void Unipolar::set_enabled(bool enabled) {
|
||||
if (enabled == _enabled)
|
||||
return; // no change
|
||||
_enabled = enabled;
|
||||
if (!enabled) {
|
||||
digitalWrite(_pin_phase0, 0);
|
||||
digitalWrite(_pin_phase1, 0);
|
||||
digitalWrite(_pin_phase2, 0);
|
||||
digitalWrite(_pin_phase3, 0);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
To take a step set step to true and set the driection
|
||||
|
||||
step is included so that st.step_outbits can be used to determine if a
|
||||
step is required on this axis
|
||||
*/
|
||||
void Unipolar::step(bool step, bool dir_forward) {
|
||||
uint8_t _phase[8] = {0, 0, 0, 0, 0, 0, 0, 0}; // temporary phase values...all start as off
|
||||
uint8_t phase_max;
|
||||
if (_half_step)
|
||||
phase_max = 7;
|
||||
else
|
||||
phase_max = 3;
|
||||
if (!step)
|
||||
return; // a step is not required on this interrupt
|
||||
if (!_enabled)
|
||||
return; // don't do anything, phase is not changed or lost
|
||||
if (dir_forward) { // count up
|
||||
if (_current_phase == phase_max)
|
||||
_current_phase = 0;
|
||||
else
|
||||
_current_phase++;
|
||||
} else { // count down
|
||||
if (_current_phase == 0)
|
||||
_current_phase = phase_max;
|
||||
else
|
||||
_current_phase--;
|
||||
}
|
||||
/*
|
||||
8 Step : A – AB – B – BC – C – CD – D – DA
|
||||
4 Step : AB – BC – CD – DA (Usual application)
|
||||
|
||||
Step IN4 IN3 IN2 IN1
|
||||
A 0 0 0 1
|
||||
AB 0 0 1 1
|
||||
B 0 0 1 0
|
||||
BC 0 1 1 0
|
||||
C 0 1 0 0
|
||||
CD 1 1 0 0
|
||||
D 1 0 0 0
|
||||
DA 1 0 0 1
|
||||
*/
|
||||
if (_half_step) {
|
||||
switch (_current_phase) {
|
||||
case 0:
|
||||
_phase[0] = 1;
|
||||
break;
|
||||
case 1:
|
||||
_phase[0] = 1;
|
||||
_phase[1] = 1;
|
||||
break;
|
||||
case 2:
|
||||
_phase[1] = 1;
|
||||
break;
|
||||
case 3:
|
||||
_phase[1] = 1;
|
||||
_phase[2] = 1;
|
||||
break;
|
||||
case 4:
|
||||
_phase[2] = 1;
|
||||
break;
|
||||
case 5:
|
||||
_phase[2] = 1;
|
||||
_phase[3] = 1;
|
||||
break;
|
||||
case 6:
|
||||
_phase[3] = 1;
|
||||
break;
|
||||
case 7:
|
||||
_phase[3] = 1;
|
||||
_phase[0] = 1;
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
switch (_current_phase) {
|
||||
case 0:
|
||||
_phase[0] = 1;
|
||||
_phase[1] = 1;
|
||||
break;
|
||||
case 1:
|
||||
_phase[1] = 1;
|
||||
_phase[2] = 1;
|
||||
break;
|
||||
case 2:
|
||||
_phase[2] = 1;
|
||||
_phase[3] = 1;
|
||||
break;
|
||||
case 3:
|
||||
_phase[3] = 1;
|
||||
_phase[0] = 1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
digitalWrite(_pin_phase0, _phase[0]);
|
||||
digitalWrite(_pin_phase1, _phase[1]);
|
||||
digitalWrite(_pin_phase2, _phase[2]);
|
||||
digitalWrite(_pin_phase3, _phase[3]);
|
||||
}
|
||||
#endif
|
@ -1,4 +1,4 @@
|
||||
/*
|
||||
/*
|
||||
grbl_unipolar.h
|
||||
Part of Grbl_ESP32
|
||||
|
||||
@ -21,34 +21,34 @@
|
||||
Unipolar Class
|
||||
|
||||
This class allows you to control a unipolar motor. Unipolar motors have 5 wires. One
|
||||
is typically tied to a voltage, while the other 4 are switched to ground in a
|
||||
is typically tied to a voltage, while the other 4 are switched to ground in a
|
||||
sequence
|
||||
|
||||
To take a step simply call the step(direction) function. It will take
|
||||
To take a step simply call the step(direction) function. It will take
|
||||
|
||||
*/
|
||||
#ifndef grbl_unipolar_h
|
||||
#define grbl_unipolar_h
|
||||
#define grbl_unipolar_h
|
||||
|
||||
void unipolar_init();
|
||||
void unipolar_step(uint8_t step_mask, uint8_t dir_mask);
|
||||
void unipolar_disable(bool enable);
|
||||
void unipolar_init();
|
||||
void unipolar_step(uint8_t step_mask, uint8_t dir_mask);
|
||||
void unipolar_disable(bool enable);
|
||||
|
||||
class Unipolar{
|
||||
public:
|
||||
Unipolar(uint8_t pin_phase0, uint8_t pin_phase1, uint8_t pin_phase2, uint8_t pin_phase3, bool half_step); // constructor
|
||||
void set_enabled(bool enabled);
|
||||
void step(bool step, bool dir_forward);
|
||||
void init();
|
||||
|
||||
private:
|
||||
uint8_t _current_phase = 0;
|
||||
bool _enabled = false;
|
||||
bool _half_step = true; // default is half step, full step
|
||||
uint8_t _pin_phase0;
|
||||
uint8_t _pin_phase1;
|
||||
uint8_t _pin_phase2;
|
||||
uint8_t _pin_phase3;
|
||||
|
||||
};
|
||||
class Unipolar {
|
||||
public:
|
||||
Unipolar(uint8_t pin_phase0, uint8_t pin_phase1, uint8_t pin_phase2, uint8_t pin_phase3, bool half_step); // constructor
|
||||
void set_enabled(bool enabled);
|
||||
void step(bool step, bool dir_forward);
|
||||
void init();
|
||||
|
||||
private:
|
||||
uint8_t _current_phase = 0;
|
||||
bool _enabled = false;
|
||||
bool _half_step = true; // default is half step, full step
|
||||
uint8_t _pin_phase0;
|
||||
uint8_t _pin_phase1;
|
||||
uint8_t _pin_phase2;
|
||||
uint8_t _pin_phase3;
|
||||
|
||||
};
|
||||
#endif
|
@ -27,94 +27,89 @@
|
||||
InputBuffer inputBuffer;
|
||||
|
||||
|
||||
InputBuffer::InputBuffer(){
|
||||
InputBuffer::InputBuffer() {
|
||||
_RXbufferSize = 0;
|
||||
_RXbufferpos = 0;
|
||||
}
|
||||
InputBuffer::~InputBuffer(){
|
||||
InputBuffer::~InputBuffer() {
|
||||
_RXbufferSize = 0;
|
||||
_RXbufferpos = 0;
|
||||
}
|
||||
void InputBuffer::begin(){
|
||||
void InputBuffer::begin() {
|
||||
_RXbufferSize = 0;
|
||||
_RXbufferpos = 0;
|
||||
}
|
||||
|
||||
void InputBuffer::end(){
|
||||
void InputBuffer::end() {
|
||||
_RXbufferSize = 0;
|
||||
_RXbufferpos = 0;
|
||||
}
|
||||
|
||||
InputBuffer::operator bool() const
|
||||
{
|
||||
InputBuffer::operator bool() const {
|
||||
return true;
|
||||
}
|
||||
|
||||
int InputBuffer::available(){
|
||||
int InputBuffer::available() {
|
||||
return _RXbufferSize;
|
||||
}
|
||||
|
||||
int InputBuffer::availableforwrite(){
|
||||
int InputBuffer::availableforwrite() {
|
||||
return (RXBUFFERSIZE - _RXbufferSize);
|
||||
}
|
||||
|
||||
size_t InputBuffer::write(uint8_t c)
|
||||
{
|
||||
if ((1 + _RXbufferSize) <= RXBUFFERSIZE){
|
||||
size_t InputBuffer::write(uint8_t c) {
|
||||
if ((1 + _RXbufferSize) <= RXBUFFERSIZE) {
|
||||
int current = _RXbufferpos + _RXbufferSize;
|
||||
if (current > RXBUFFERSIZE)
|
||||
if (current > RXBUFFERSIZE)
|
||||
current = current - RXBUFFERSIZE;
|
||||
|
||||
if (current > (RXBUFFERSIZE-1))
|
||||
current = 0;
|
||||
_RXbuffer[current] = c;
|
||||
current ++;
|
||||
|
||||
_RXbufferSize+=1;
|
||||
if (current > (RXBUFFERSIZE - 1))
|
||||
current = 0;
|
||||
_RXbuffer[current] = c;
|
||||
current ++;
|
||||
_RXbufferSize += 1;
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
size_t InputBuffer::write(const uint8_t *buffer, size_t size)
|
||||
{
|
||||
size_t InputBuffer::write(const uint8_t* buffer, size_t size) {
|
||||
//No need currently
|
||||
//keep for compatibility
|
||||
return size;
|
||||
}
|
||||
|
||||
int InputBuffer::peek(void){
|
||||
int InputBuffer::peek(void) {
|
||||
if (_RXbufferSize > 0)return _RXbuffer[_RXbufferpos];
|
||||
else return -1;
|
||||
}
|
||||
|
||||
bool InputBuffer::push (const char * data){
|
||||
bool InputBuffer::push(const char* data) {
|
||||
int data_size = strlen(data);
|
||||
if ((data_size + _RXbufferSize) <= RXBUFFERSIZE){
|
||||
if ((data_size + _RXbufferSize) <= RXBUFFERSIZE) {
|
||||
int current = _RXbufferpos + _RXbufferSize;
|
||||
if (current > RXBUFFERSIZE) current = current - RXBUFFERSIZE;
|
||||
for (int i = 0; i < data_size; i++){
|
||||
if (current > (RXBUFFERSIZE-1)) current = 0;
|
||||
_RXbuffer[current] = data[i];
|
||||
current ++;
|
||||
for (int i = 0; i < data_size; i++) {
|
||||
if (current > (RXBUFFERSIZE - 1)) current = 0;
|
||||
_RXbuffer[current] = data[i];
|
||||
current ++;
|
||||
}
|
||||
_RXbufferSize+=strlen(data);
|
||||
_RXbufferSize += strlen(data);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
int InputBuffer::read(void){
|
||||
int InputBuffer::read(void) {
|
||||
if (_RXbufferSize > 0) {
|
||||
int v = _RXbuffer[_RXbufferpos];
|
||||
_RXbufferpos++;
|
||||
if (_RXbufferpos > (RXBUFFERSIZE-1))_RXbufferpos = 0;
|
||||
if (_RXbufferpos > (RXBUFFERSIZE - 1))_RXbufferpos = 0;
|
||||
_RXbufferSize--;
|
||||
return v;
|
||||
} else return -1;
|
||||
}
|
||||
|
||||
void InputBuffer::flush(void){
|
||||
void InputBuffer::flush(void) {
|
||||
//No need currently
|
||||
//keep for compatibility
|
||||
}
|
||||
|
@ -24,31 +24,26 @@
|
||||
|
||||
#include "Print.h"
|
||||
#define RXBUFFERSIZE 128
|
||||
class InputBuffer: public Print{
|
||||
public:
|
||||
class InputBuffer: public Print {
|
||||
public:
|
||||
InputBuffer();
|
||||
~InputBuffer();
|
||||
size_t write(uint8_t c);
|
||||
size_t write(const uint8_t *buffer, size_t size);
|
||||
size_t write(const uint8_t* buffer, size_t size);
|
||||
|
||||
inline size_t write(const char * s)
|
||||
{
|
||||
inline size_t write(const char* s) {
|
||||
return write((uint8_t*) s, strlen(s));
|
||||
}
|
||||
inline size_t write(unsigned long n)
|
||||
{
|
||||
inline size_t write(unsigned long n) {
|
||||
return write((uint8_t) n);
|
||||
}
|
||||
inline size_t write(long n)
|
||||
{
|
||||
inline size_t write(long n) {
|
||||
return write((uint8_t) n);
|
||||
}
|
||||
inline size_t write(unsigned int n)
|
||||
{
|
||||
inline size_t write(unsigned int n) {
|
||||
return write((uint8_t) n);
|
||||
}
|
||||
inline size_t write(int n)
|
||||
{
|
||||
inline size_t write(int n) {
|
||||
return write((uint8_t) n);
|
||||
}
|
||||
void begin();
|
||||
@ -57,10 +52,10 @@ class InputBuffer: public Print{
|
||||
int availableforwrite();
|
||||
int peek(void);
|
||||
int read(void);
|
||||
bool push (const char * data);
|
||||
bool push(const char* data);
|
||||
void flush(void);
|
||||
operator bool() const;
|
||||
private:
|
||||
private:
|
||||
uint8_t _RXbuffer[RXBUFFERSIZE];
|
||||
uint16_t _RXbufferSize;
|
||||
uint16_t _RXbufferpos;
|
||||
|
@ -3,7 +3,7 @@
|
||||
Part of Grbl
|
||||
|
||||
Copyright (c) 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
|
||||
|
||||
@ -25,29 +25,25 @@
|
||||
|
||||
|
||||
// Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog.
|
||||
uint8_t jog_execute(plan_line_data_t *pl_data, parser_block_t *gc_block)
|
||||
{
|
||||
// Initialize planner data struct for jogging motions.
|
||||
// NOTE: Spindle and coolant are allowed to fully function with overrides during a jog.
|
||||
pl_data->feed_rate = gc_block->values.f;
|
||||
pl_data->condition |= PL_COND_FLAG_NO_FEED_OVERRIDE;
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
uint8_t jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block) {
|
||||
// Initialize planner data struct for jogging motions.
|
||||
// NOTE: Spindle and coolant are allowed to fully function with overrides during a jog.
|
||||
pl_data->feed_rate = gc_block->values.f;
|
||||
pl_data->condition |= PL_COND_FLAG_NO_FEED_OVERRIDE;
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
pl_data->line_number = gc_block->values.n;
|
||||
#endif
|
||||
|
||||
if (bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE)) {
|
||||
if (system_check_travel_limits(gc_block->values.xyz)) { return(STATUS_TRAVEL_EXCEEDED); }
|
||||
}
|
||||
|
||||
// Valid jog command. Plan, set state, and execute.
|
||||
mc_line(gc_block->values.xyz,pl_data);
|
||||
if (sys.state == STATE_IDLE) {
|
||||
if (plan_get_current_block() != NULL) { // Check if there is a block to execute.
|
||||
sys.state = STATE_JOG;
|
||||
st_prep_buffer();
|
||||
st_wake_up(); // NOTE: Manual start. No state machine required.
|
||||
#endif
|
||||
if (bit_istrue(settings.flags, BITFLAG_SOFT_LIMIT_ENABLE)) {
|
||||
if (system_check_travel_limits(gc_block->values.xyz)) return (STATUS_TRAVEL_EXCEEDED);
|
||||
}
|
||||
}
|
||||
|
||||
return(STATUS_OK);
|
||||
// Valid jog command. Plan, set state, and execute.
|
||||
mc_line(gc_block->values.xyz, pl_data);
|
||||
if (sys.state == STATE_IDLE) {
|
||||
if (plan_get_current_block() != NULL) { // Check if there is a block to execute.
|
||||
sys.state = STATE_JOG;
|
||||
st_prep_buffer();
|
||||
st_wake_up(); // NOTE: Manual start. No state machine required.
|
||||
}
|
||||
}
|
||||
return (STATUS_OK);
|
||||
}
|
||||
|
62
Grbl_Esp32/machine.h
Normal file
62
Grbl_Esp32/machine.h
Normal file
@ -0,0 +1,62 @@
|
||||
// This file is where you choose the machine type, by including
|
||||
// one or more machine definition files as described below.
|
||||
|
||||
#ifndef _machine_h
|
||||
#define _machine_h
|
||||
|
||||
#ifndef MACHINE_FILENAME
|
||||
|
||||
// !!! For initial testing, start with test_drive.h which disables
|
||||
// all I/O pins
|
||||
#include "Machines/test_drive.h"
|
||||
|
||||
// !!! For actual use, change the line above to select a board
|
||||
// from Machines/, for example:
|
||||
// #include "Machines/3axis_v4.h"
|
||||
|
||||
// Some configurations use two files, the first establishing a base
|
||||
// configuration and the second providing additional customization,
|
||||
// for example:
|
||||
// #include "Machines/3axis_v4.h"
|
||||
// #include "Machines/add_esc_spindle.h"
|
||||
|
||||
// === OEM Single File Configuration Option
|
||||
// OEMs that wish to publish source code that is configured for a
|
||||
// specific machine may put all of their configuration definitions
|
||||
// directly in this file, without including any other file above.
|
||||
|
||||
#else
|
||||
|
||||
// By using the external environment to define MACHINE_FILENAME,
|
||||
// a configuration can be chosen without editing this file.
|
||||
// That is useful for automated testing scripts.
|
||||
//
|
||||
// For example, when using the platformio compilation environment
|
||||
// under Linux, you could issue the following command line:
|
||||
// PLATFORMIO_BUILD_FLAGS=-DMACHINE_FILENAME=3axis_v4.h platformio run
|
||||
//
|
||||
// Under Windows, using PowerShell, the command would be:
|
||||
// $env:PLATFORMIO_BUILD_FLAGS='-DMACHINE_FILENAME=3axis_v4.h'; platformio run
|
||||
//
|
||||
// When using the Arduino IDE, there is no easy way to pass variables
|
||||
// to the compiler, so this feature is not useful for Arduino.
|
||||
//
|
||||
// MACHINE_FILENAME must not include the Machines/ path prefix; it is
|
||||
// supplied automatically.
|
||||
|
||||
// MACHINE_PATHNAME_QUOTED constructs a path that is suitable for #include
|
||||
#define MACHINE_PATHNAME_QUOTED(name) <Machines/name>
|
||||
|
||||
#include MACHINE_PATHNAME_QUOTED(MACHINE_FILENAME)
|
||||
|
||||
// You can choose two-file configurations by also defining MACHINE_FILENAME2,
|
||||
// for example:
|
||||
// $env:PLATFORMIO_BUILD_FLAGS='-DMACHINE_FILENAME=3axis_v4.h -DMACHINE_FILENAME2=add_esc_spindle.h'; platformio run
|
||||
|
||||
#ifdef MACHINE_FILENAME2
|
||||
#include MACHINE_PATHNAME_QUOTED(MACHINE_FILENAME2)
|
||||
#endif
|
||||
|
||||
#endif // MACHINE_FILENAME
|
||||
|
||||
#endif // _machine_h
|
63
Grbl_Esp32/machine_common.h
Normal file
63
Grbl_Esp32/machine_common.h
Normal file
@ -0,0 +1,63 @@
|
||||
#ifndef _machine_common_h
|
||||
#define _machine_common_h
|
||||
|
||||
#ifndef SPINDLE_PWM_BIT_PRECISION
|
||||
#define SPINDLE_PWM_BIT_PRECISION 8
|
||||
#endif
|
||||
|
||||
#define SPINDLE_PWM_MAX_VALUE ((1<<SPINDLE_PWM_BIT_PRECISION) - 1)
|
||||
#define SPINDLE_PWM_CHANNEL 0
|
||||
|
||||
// Grbl setting that are common to all machines
|
||||
// It should not be necessary to change anything herein
|
||||
|
||||
#ifndef GRBL_SPI_FREQ
|
||||
// You can override these by defining them in a board file.
|
||||
// To override, you must set all of them
|
||||
//-1 means use the default board pin
|
||||
#define GRBL_SPI_SS -1
|
||||
#define GRBL_SPI_MOSI -1
|
||||
#define GRBL_SPI_MISO -1
|
||||
#define GRBL_SPI_SCK -1
|
||||
#define GRBL_SPI_FREQ 4000000
|
||||
#endif
|
||||
|
||||
// ESP32 CPU Settings
|
||||
#define F_TIMERS 80000000 // a reference to the speed of ESP32 timers
|
||||
#define F_STEPPER_TIMER 20000000 // frequency of step pulse timer
|
||||
#define STEPPER_OFF_TIMER_PRESCALE 8 // gives a frequency of 10MHz
|
||||
#define STEPPER_OFF_PERIOD_uSEC 3 // each tick is
|
||||
|
||||
#define STEP_PULSE_MIN 2 // uSeconds
|
||||
#define STEP_PULSE_MAX 10 // uSeconds
|
||||
|
||||
// =============== Don't change or comment these out ======================
|
||||
// They are for legacy purposes and will not affect your I/O
|
||||
|
||||
#define X_STEP_BIT 0
|
||||
#define Y_STEP_BIT 1
|
||||
#define Z_STEP_BIT 2
|
||||
#define A_STEP_BIT 3
|
||||
#define B_STEP_BIT 4
|
||||
#define C_STEP_BIT 5
|
||||
#define STEP_MASK B111111
|
||||
|
||||
#define X_DIRECTION_BIT 0
|
||||
#define Y_DIRECTION_BIT 1
|
||||
#define Z_DIRECTION_BIT 2
|
||||
#define A_DIRECTION_BIT 3
|
||||
#define B_DIRECTION_BIT 4
|
||||
#define C_DIRECTION_BIT 5
|
||||
|
||||
#define X_LIMIT_BIT 0
|
||||
#define Y_LIMIT_BIT 1
|
||||
#define Z_LIMIT_BIT 2
|
||||
#define A_LIMIT_BIT 3
|
||||
#define B_LIMIT_BIT 4
|
||||
#define C_LIMIT_BIT 5
|
||||
|
||||
#define PROBE_MASK 1
|
||||
|
||||
#define CONTROL_MASK B1111
|
||||
|
||||
#endif // _machine_common_h
|
@ -4,7 +4,7 @@
|
||||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
@ -27,14 +27,13 @@
|
||||
uint8_t ganged_mode = SQUARING_MODE_DUAL;
|
||||
|
||||
|
||||
// this allows kinematics to be used.
|
||||
void mc_line_kins(float *target, plan_line_data_t *pl_data, float *position)
|
||||
{
|
||||
#ifndef USE_KINEMATICS
|
||||
mc_line(target, pl_data);
|
||||
#else // else use kinematics
|
||||
inverse_kinematics(target, pl_data, position);
|
||||
#endif
|
||||
// this allows kinematics to be used.
|
||||
void mc_line_kins(float* target, plan_line_data_t* pl_data, float* position) {
|
||||
#ifndef USE_KINEMATICS
|
||||
mc_line(target, pl_data);
|
||||
#else // else use kinematics
|
||||
inverse_kinematics(target, pl_data, position);
|
||||
#endif
|
||||
}
|
||||
|
||||
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
|
||||
@ -44,44 +43,39 @@ void mc_line_kins(float *target, plan_line_data_t *pl_data, float *position)
|
||||
// segments, must pass through this routine before being passed to the planner. The seperation of
|
||||
// mc_line and plan_buffer_line is done primarily to place non-planner-type functions from being
|
||||
// in the planner and to let backlash compensation or canned cycle integration simple and direct.
|
||||
void mc_line(float *target, plan_line_data_t *pl_data)
|
||||
{
|
||||
// If enabled, check for soft limit violations. Placed here all line motions are picked up
|
||||
// from everywhere in Grbl.
|
||||
if (bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE)) {
|
||||
// NOTE: Block jog state. Jogging is a special case and soft limits are handled independently.
|
||||
if (sys.state != STATE_JOG) { limits_soft_check(target); }
|
||||
}
|
||||
|
||||
// If in check gcode mode, prevent motion by blocking planner. Soft limits still work.
|
||||
if (sys.state == STATE_CHECK_MODE) { return; }
|
||||
|
||||
// NOTE: Backlash compensation may be installed here. It will need direction info to track when
|
||||
// to insert a backlash line motion(s) before the intended line motion and will require its own
|
||||
// plan_check_full_buffer() and check for system abort loop. Also for position reporting
|
||||
// backlash steps will need to be also tracked, which will need to be kept at a system level.
|
||||
// There are likely some other things that will need to be tracked as well. However, we feel
|
||||
// that backlash compensation should NOT be handled by Grbl itself, because there are a myriad
|
||||
// of ways to implement it and can be effective or ineffective for different CNC machines. This
|
||||
// would be better handled by the interface as a post-processor task, where the original g-code
|
||||
// is translated and inserts backlash motions that best suits the machine.
|
||||
// NOTE: Perhaps as a middle-ground, all that needs to be sent is a flag or special command that
|
||||
// indicates to Grbl what is a backlash compensation motion, so that Grbl executes the move but
|
||||
// doesn't update the machine position values. Since the position values used by the g-code
|
||||
// parser and planner are separate from the system machine positions, this is doable.
|
||||
|
||||
// If the buffer is full: good! That means we are well ahead of the robot.
|
||||
// Remain in this loop until there is room in the buffer.
|
||||
do {
|
||||
protocol_execute_realtime(); // Check for any run-time commands
|
||||
if (sys.abort) { return; } // Bail, if system abort.
|
||||
if ( plan_check_full_buffer() ) { protocol_auto_cycle_start(); } // Auto-cycle start when buffer is full.
|
||||
else { break; }
|
||||
} while (1);
|
||||
|
||||
// Plan and queue motion into planner buffer
|
||||
// uint8_t plan_status; // Not used in normal operation.
|
||||
plan_buffer_line(target, pl_data);
|
||||
void mc_line(float* target, plan_line_data_t* pl_data) {
|
||||
// If enabled, check for soft limit violations. Placed here all line motions are picked up
|
||||
// from everywhere in Grbl.
|
||||
if (bit_istrue(settings.flags, BITFLAG_SOFT_LIMIT_ENABLE)) {
|
||||
// NOTE: Block jog state. Jogging is a special case and soft limits are handled independently.
|
||||
if (sys.state != STATE_JOG) limits_soft_check(target);
|
||||
}
|
||||
// If in check gcode mode, prevent motion by blocking planner. Soft limits still work.
|
||||
if (sys.state == STATE_CHECK_MODE) return;
|
||||
// NOTE: Backlash compensation may be installed here. It will need direction info to track when
|
||||
// to insert a backlash line motion(s) before the intended line motion and will require its own
|
||||
// plan_check_full_buffer() and check for system abort loop. Also for position reporting
|
||||
// backlash steps will need to be also tracked, which will need to be kept at a system level.
|
||||
// There are likely some other things that will need to be tracked as well. However, we feel
|
||||
// that backlash compensation should NOT be handled by Grbl itself, because there are a myriad
|
||||
// of ways to implement it and can be effective or ineffective for different CNC machines. This
|
||||
// would be better handled by the interface as a post-processor task, where the original g-code
|
||||
// is translated and inserts backlash motions that best suits the machine.
|
||||
// NOTE: Perhaps as a middle-ground, all that needs to be sent is a flag or special command that
|
||||
// indicates to Grbl what is a backlash compensation motion, so that Grbl executes the move but
|
||||
// doesn't update the machine position values. Since the position values used by the g-code
|
||||
// parser and planner are separate from the system machine positions, this is doable.
|
||||
// If the buffer is full: good! That means we are well ahead of the robot.
|
||||
// Remain in this loop until there is room in the buffer.
|
||||
do {
|
||||
protocol_execute_realtime(); // Check for any run-time commands
|
||||
if (sys.abort) return; // Bail, if system abort.
|
||||
if (plan_check_full_buffer()) protocol_auto_cycle_start(); // Auto-cycle start when buffer is full.
|
||||
else break;
|
||||
} while (1);
|
||||
// Plan and queue motion into planner buffer
|
||||
// uint8_t plan_status; // Not used in normal operation.
|
||||
plan_buffer_line(target, pl_data);
|
||||
}
|
||||
|
||||
|
||||
@ -92,373 +86,322 @@ void mc_line(float *target, plan_line_data_t *pl_data)
|
||||
// The arc is approximated by generating a huge number of tiny, linear segments. The chordal tolerance
|
||||
// of each segment is configured in settings.arc_tolerance, which is defined to be the maximum normal
|
||||
// distance from segment to the circle when the end points both lie on the circle.
|
||||
void mc_arc(float *target, plan_line_data_t *pl_data, float *position, float *offset, float radius,
|
||||
uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc)
|
||||
{
|
||||
float center_axis0 = position[axis_0] + offset[axis_0];
|
||||
float center_axis1 = position[axis_1] + offset[axis_1];
|
||||
float r_axis0 = -offset[axis_0]; // Radius vector from center to current location
|
||||
float r_axis1 = -offset[axis_1];
|
||||
float rt_axis0 = target[axis_0] - center_axis0;
|
||||
float rt_axis1 = target[axis_1] - center_axis1;
|
||||
|
||||
void mc_arc(float* target, plan_line_data_t* pl_data, float* position, float* offset, float radius,
|
||||
uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc) {
|
||||
float center_axis0 = position[axis_0] + offset[axis_0];
|
||||
float center_axis1 = position[axis_1] + offset[axis_1];
|
||||
float r_axis0 = -offset[axis_0]; // Radius vector from center to current location
|
||||
float r_axis1 = -offset[axis_1];
|
||||
float rt_axis0 = target[axis_0] - center_axis0;
|
||||
float rt_axis1 = target[axis_1] - center_axis1;
|
||||
#ifdef USE_KINEMATICS
|
||||
float previous_position[N_AXIS];
|
||||
uint16_t n;
|
||||
for (n = 0; n < N_AXIS; n++) {
|
||||
previous_position[n] = position[n];
|
||||
}
|
||||
float previous_position[N_AXIS];
|
||||
uint16_t n;
|
||||
for (n = 0; n < N_AXIS; n++)
|
||||
previous_position[n] = position[n];
|
||||
#endif
|
||||
|
||||
// CCW angle between position and target from circle center. Only one atan2() trig computation required.
|
||||
float angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1);
|
||||
if (is_clockwise_arc) { // Correct atan2 output per direction
|
||||
if (angular_travel >= -ARC_ANGULAR_TRAVEL_EPSILON) { angular_travel -= 2*M_PI; }
|
||||
} else {
|
||||
if (angular_travel <= ARC_ANGULAR_TRAVEL_EPSILON) { angular_travel += 2*M_PI; }
|
||||
}
|
||||
|
||||
// NOTE: Segment end points are on the arc, which can lead to the arc diameter being smaller by up to
|
||||
// (2x) settings.arc_tolerance. For 99% of users, this is just fine. If a different arc segment fit
|
||||
// is desired, i.e. least-squares, midpoint on arc, just change the mm_per_arc_segment calculation.
|
||||
// For the intended uses of Grbl, this value shouldn't exceed 2000 for the strictest of cases.
|
||||
uint16_t segments = floor(fabs(0.5*angular_travel*radius)/
|
||||
sqrt(settings.arc_tolerance*(2*radius - settings.arc_tolerance)) );
|
||||
|
||||
if (segments) {
|
||||
// Multiply inverse feed_rate to compensate for the fact that this movement is approximated
|
||||
// by a number of discrete segments. The inverse feed_rate should be correct for the sum of
|
||||
// all segments.
|
||||
if (pl_data->condition & PL_COND_FLAG_INVERSE_TIME) {
|
||||
pl_data->feed_rate *= segments;
|
||||
bit_false(pl_data->condition,PL_COND_FLAG_INVERSE_TIME); // Force as feed absolute mode over arc segments.
|
||||
// CCW angle between position and target from circle center. Only one atan2() trig computation required.
|
||||
float angular_travel = atan2(r_axis0 * rt_axis1 - r_axis1 * rt_axis0, r_axis0 * rt_axis0 + r_axis1 * rt_axis1);
|
||||
if (is_clockwise_arc) { // Correct atan2 output per direction
|
||||
if (angular_travel >= -ARC_ANGULAR_TRAVEL_EPSILON) angular_travel -= 2 * M_PI;
|
||||
} else {
|
||||
if (angular_travel <= ARC_ANGULAR_TRAVEL_EPSILON) angular_travel += 2 * M_PI;
|
||||
}
|
||||
|
||||
float theta_per_segment = angular_travel/segments;
|
||||
float linear_per_segment = (target[axis_linear] - position[axis_linear])/segments;
|
||||
// NOTE: Segment end points are on the arc, which can lead to the arc diameter being smaller by up to
|
||||
// (2x) settings.arc_tolerance. For 99% of users, this is just fine. If a different arc segment fit
|
||||
// is desired, i.e. least-squares, midpoint on arc, just change the mm_per_arc_segment calculation.
|
||||
// For the intended uses of Grbl, this value shouldn't exceed 2000 for the strictest of cases.
|
||||
uint16_t segments = floor(fabs(0.5 * angular_travel * radius) /
|
||||
sqrt(settings.arc_tolerance * (2 * radius - settings.arc_tolerance)));
|
||||
if (segments) {
|
||||
// Multiply inverse feed_rate to compensate for the fact that this movement is approximated
|
||||
// by a number of discrete segments. The inverse feed_rate should be correct for the sum of
|
||||
// all segments.
|
||||
if (pl_data->condition & PL_COND_FLAG_INVERSE_TIME) {
|
||||
pl_data->feed_rate *= segments;
|
||||
bit_false(pl_data->condition, PL_COND_FLAG_INVERSE_TIME); // Force as feed absolute mode over arc segments.
|
||||
}
|
||||
float theta_per_segment = angular_travel / segments;
|
||||
float linear_per_segment = (target[axis_linear] - position[axis_linear]) / segments;
|
||||
/* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector,
|
||||
and phi is the angle of rotation. Solution approach by Jens Geisler.
|
||||
r_T = [cos(phi) -sin(phi);
|
||||
sin(phi) cos(phi] * r ;
|
||||
|
||||
/* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector,
|
||||
and phi is the angle of rotation. Solution approach by Jens Geisler.
|
||||
r_T = [cos(phi) -sin(phi);
|
||||
sin(phi) cos(phi] * r ;
|
||||
For arc generation, the center of the circle is the axis of rotation and the radius vector is
|
||||
defined from the circle center to the initial position. Each line segment is formed by successive
|
||||
vector rotations. Single precision values can accumulate error greater than tool precision in rare
|
||||
cases. So, exact arc path correction is implemented. This approach avoids the problem of too many very
|
||||
expensive trig operations [sin(),cos(),tan()] which can take 100-200 usec each to compute.
|
||||
|
||||
For arc generation, the center of the circle is the axis of rotation and the radius vector is
|
||||
defined from the circle center to the initial position. Each line segment is formed by successive
|
||||
vector rotations. Single precision values can accumulate error greater than tool precision in rare
|
||||
cases. So, exact arc path correction is implemented. This approach avoids the problem of too many very
|
||||
expensive trig operations [sin(),cos(),tan()] which can take 100-200 usec each to compute.
|
||||
Small angle approximation may be used to reduce computation overhead further. A third-order approximation
|
||||
(second order sin() has too much error) holds for most, if not, all CNC applications. Note that this
|
||||
approximation will begin to accumulate a numerical drift error when theta_per_segment is greater than
|
||||
~0.25 rad(14 deg) AND the approximation is successively used without correction several dozen times. This
|
||||
scenario is extremely unlikely, since segment lengths and theta_per_segment are automatically generated
|
||||
and scaled by the arc tolerance setting. Only a very large arc tolerance setting, unrealistic for CNC
|
||||
applications, would cause this numerical drift error. However, it is best to set N_ARC_CORRECTION from a
|
||||
low of ~4 to a high of ~20 or so to avoid trig operations while keeping arc generation accurate.
|
||||
|
||||
Small angle approximation may be used to reduce computation overhead further. A third-order approximation
|
||||
(second order sin() has too much error) holds for most, if not, all CNC applications. Note that this
|
||||
approximation will begin to accumulate a numerical drift error when theta_per_segment is greater than
|
||||
~0.25 rad(14 deg) AND the approximation is successively used without correction several dozen times. This
|
||||
scenario is extremely unlikely, since segment lengths and theta_per_segment are automatically generated
|
||||
and scaled by the arc tolerance setting. Only a very large arc tolerance setting, unrealistic for CNC
|
||||
applications, would cause this numerical drift error. However, it is best to set N_ARC_CORRECTION from a
|
||||
low of ~4 to a high of ~20 or so to avoid trig operations while keeping arc generation accurate.
|
||||
|
||||
This approximation also allows mc_arc to immediately insert a line segment into the planner
|
||||
without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied
|
||||
a correction, the planner should have caught up to the lag caused by the initial mc_arc overhead.
|
||||
This is important when there are successive arc motions.
|
||||
*/
|
||||
// Computes: cos_T = 1 - theta_per_segment^2/2, sin_T = theta_per_segment - theta_per_segment^3/6) in ~52usec
|
||||
float cos_T = 2.0 - theta_per_segment*theta_per_segment;
|
||||
float sin_T = theta_per_segment*0.16666667*(cos_T + 4.0);
|
||||
cos_T *= 0.5;
|
||||
|
||||
float sin_Ti;
|
||||
float cos_Ti;
|
||||
float r_axisi;
|
||||
uint16_t i;
|
||||
uint8_t count = 0;
|
||||
|
||||
for (i = 1; i<segments; i++) { // Increment (segments-1).
|
||||
|
||||
if (count < N_ARC_CORRECTION) {
|
||||
// Apply vector rotation matrix. ~40 usec
|
||||
r_axisi = r_axis0*sin_T + r_axis1*cos_T;
|
||||
r_axis0 = r_axis0*cos_T - r_axis1*sin_T;
|
||||
r_axis1 = r_axisi;
|
||||
count++;
|
||||
} else {
|
||||
// Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments. ~375 usec
|
||||
// Compute exact location by applying transformation matrix from initial radius vector(=-offset).
|
||||
cos_Ti = cos(i*theta_per_segment);
|
||||
sin_Ti = sin(i*theta_per_segment);
|
||||
r_axis0 = -offset[axis_0]*cos_Ti + offset[axis_1]*sin_Ti;
|
||||
r_axis1 = -offset[axis_0]*sin_Ti - offset[axis_1]*cos_Ti;
|
||||
count = 0;
|
||||
}
|
||||
|
||||
// Update arc_target location
|
||||
position[axis_0] = center_axis0 + r_axis0;
|
||||
position[axis_1] = center_axis1 + r_axis1;
|
||||
position[axis_linear] += linear_per_segment;
|
||||
This approximation also allows mc_arc to immediately insert a line segment into the planner
|
||||
without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied
|
||||
a correction, the planner should have caught up to the lag caused by the initial mc_arc overhead.
|
||||
This is important when there are successive arc motions.
|
||||
*/
|
||||
// Computes: cos_T = 1 - theta_per_segment^2/2, sin_T = theta_per_segment - theta_per_segment^3/6) in ~52usec
|
||||
float cos_T = 2.0 - theta_per_segment * theta_per_segment;
|
||||
float sin_T = theta_per_segment * 0.16666667 * (cos_T + 4.0);
|
||||
cos_T *= 0.5;
|
||||
float sin_Ti;
|
||||
float cos_Ti;
|
||||
float r_axisi;
|
||||
uint16_t i;
|
||||
uint8_t count = 0;
|
||||
for (i = 1; i < segments; i++) { // Increment (segments-1).
|
||||
if (count < N_ARC_CORRECTION) {
|
||||
// Apply vector rotation matrix. ~40 usec
|
||||
r_axisi = r_axis0 * sin_T + r_axis1 * cos_T;
|
||||
r_axis0 = r_axis0 * cos_T - r_axis1 * sin_T;
|
||||
r_axis1 = r_axisi;
|
||||
count++;
|
||||
} else {
|
||||
// Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments. ~375 usec
|
||||
// Compute exact location by applying transformation matrix from initial radius vector(=-offset).
|
||||
cos_Ti = cos(i * theta_per_segment);
|
||||
sin_Ti = sin(i * theta_per_segment);
|
||||
r_axis0 = -offset[axis_0] * cos_Ti + offset[axis_1] * sin_Ti;
|
||||
r_axis1 = -offset[axis_0] * sin_Ti - offset[axis_1] * cos_Ti;
|
||||
count = 0;
|
||||
}
|
||||
// Update arc_target location
|
||||
position[axis_0] = center_axis0 + r_axis0;
|
||||
position[axis_1] = center_axis1 + r_axis1;
|
||||
position[axis_linear] += linear_per_segment;
|
||||
#ifdef USE_KINEMATICS
|
||||
mc_line_kins(position, pl_data, previous_position);
|
||||
previous_position[axis_0] = position[axis_0];
|
||||
previous_position[axis_1] = position[axis_1];
|
||||
previous_position[axis_linear] = position[axis_linear];
|
||||
mc_line_kins(position, pl_data, previous_position);
|
||||
previous_position[axis_0] = position[axis_0];
|
||||
previous_position[axis_1] = position[axis_1];
|
||||
previous_position[axis_linear] = position[axis_linear];
|
||||
#else
|
||||
mc_line(position, pl_data);
|
||||
mc_line(position, pl_data);
|
||||
#endif
|
||||
|
||||
// Bail mid-circle on system abort. Runtime command check already performed by mc_line.
|
||||
if (sys.abort) { return; }
|
||||
// Bail mid-circle on system abort. Runtime command check already performed by mc_line.
|
||||
if (sys.abort) return;
|
||||
}
|
||||
}
|
||||
}
|
||||
// Ensure last segment arrives at target location.
|
||||
// Ensure last segment arrives at target location.
|
||||
#ifdef USE_KINEMATICS
|
||||
mc_line_kins(target, pl_data, previous_position);
|
||||
mc_line_kins(target, pl_data, previous_position);
|
||||
#else
|
||||
mc_line(target, pl_data);
|
||||
mc_line(target, pl_data);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
// Execute dwell in seconds.
|
||||
void mc_dwell(float seconds)
|
||||
{
|
||||
if (sys.state == STATE_CHECK_MODE) { return; }
|
||||
protocol_buffer_synchronize();
|
||||
delay_sec(seconds, DELAY_MODE_DWELL);
|
||||
void mc_dwell(float seconds) {
|
||||
if (sys.state == STATE_CHECK_MODE) return;
|
||||
protocol_buffer_synchronize();
|
||||
delay_sec(seconds, DELAY_MODE_DWELL);
|
||||
}
|
||||
|
||||
|
||||
// Perform homing cycle to locate and set machine zero. Only '$H' executes this command.
|
||||
// NOTE: There should be no motions in the buffer and Grbl must be in an idle state before
|
||||
// executing the homing cycle. This prevents incorrect buffered plans after homing.
|
||||
void mc_homing_cycle(uint8_t cycle_mask)
|
||||
{
|
||||
#ifdef USE_CUSTOM_HOMING
|
||||
if (user_defined_homing())
|
||||
{
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
// This give kinematics a chance to do something before normal homing
|
||||
// if it returns true, the homing is canceled.
|
||||
#ifdef USE_KINEMATICS
|
||||
if (kinematics_pre_homing(cycle_mask)) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
// Check and abort homing cycle, if hard limits are already enabled. Helps prevent problems
|
||||
// with machines with limits wired on both ends of travel to one limit pin.
|
||||
// TODO: Move the pin-specific LIMIT_PIN call to limits.c as a function.
|
||||
#ifdef LIMITS_TWO_SWITCHES_ON_AXES
|
||||
void mc_homing_cycle(uint8_t cycle_mask) {
|
||||
#ifdef USE_CUSTOM_HOMING
|
||||
if (user_defined_homing())
|
||||
return;
|
||||
#endif
|
||||
// This give kinematics a chance to do something before normal homing
|
||||
// if it returns true, the homing is canceled.
|
||||
#ifdef USE_KINEMATICS
|
||||
if (kinematics_pre_homing(cycle_mask))
|
||||
return;
|
||||
#endif
|
||||
// Check and abort homing cycle, if hard limits are already enabled. Helps prevent problems
|
||||
// with machines with limits wired on both ends of travel to one limit pin.
|
||||
// TODO: Move the pin-specific LIMIT_PIN call to limits.c as a function.
|
||||
#ifdef LIMITS_TWO_SWITCHES_ON_AXES
|
||||
if (limits_get_state()) {
|
||||
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
|
||||
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT);
|
||||
return;
|
||||
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
|
||||
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
limits_disable(); // Disable hard limits pin change register for cycle duration
|
||||
|
||||
// -------------------------------------------------------------------------------------
|
||||
// Perform homing routine. NOTE: Special motion case. Only system reset works.
|
||||
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE;
|
||||
|
||||
#ifdef HOMING_SINGLE_AXIS_COMMANDS
|
||||
#endif
|
||||
limits_disable(); // Disable hard limits pin change register for cycle duration
|
||||
// -------------------------------------------------------------------------------------
|
||||
// Perform homing routine. NOTE: Special motion case. Only system reset works.
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE;
|
||||
#ifdef HOMING_SINGLE_AXIS_COMMANDS
|
||||
/*
|
||||
if (cycle_mask) { limits_go_home(cycle_mask); } // Perform homing cycle based on mask.
|
||||
else
|
||||
*/
|
||||
if (cycle_mask) {
|
||||
if (! axis_is_squared(cycle_mask))
|
||||
limits_go_home(cycle_mask); // Homing cycle 0
|
||||
else {
|
||||
ganged_mode = SQUARING_MODE_DUAL;
|
||||
n_homing_locate_cycle = 0; // don't do a second touch cycle
|
||||
limits_go_home(cycle_mask);
|
||||
ganged_mode = SQUARING_MODE_A;
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
|
||||
limits_go_home(cycle_mask);
|
||||
ganged_mode = SQUARING_MODE_B;
|
||||
limits_go_home(cycle_mask);
|
||||
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
|
||||
}
|
||||
|
||||
if (cycle_mask) {
|
||||
if (! axis_is_squared(cycle_mask))
|
||||
limits_go_home(cycle_mask); // Homing cycle 0
|
||||
else {
|
||||
ganged_mode = SQUARING_MODE_DUAL;
|
||||
n_homing_locate_cycle = 0; // don't do a second touch cycle
|
||||
limits_go_home(cycle_mask);
|
||||
ganged_mode = SQUARING_MODE_A;
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
|
||||
limits_go_home(cycle_mask);
|
||||
ganged_mode = SQUARING_MODE_B;
|
||||
limits_go_home(cycle_mask);
|
||||
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
|
||||
}
|
||||
} // Perform homing cycle based on mask.
|
||||
else
|
||||
#endif
|
||||
{
|
||||
// Search to engage all axes limit switches at faster homing seek rate.
|
||||
if (! axis_is_squared(HOMING_CYCLE_0))
|
||||
limits_go_home(HOMING_CYCLE_0); // Homing cycle 0
|
||||
else {
|
||||
ganged_mode = SQUARING_MODE_DUAL;
|
||||
n_homing_locate_cycle = 0; // don't do a second touch cycle
|
||||
limits_go_home(HOMING_CYCLE_0);
|
||||
ganged_mode = SQUARING_MODE_A;
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
|
||||
limits_go_home(HOMING_CYCLE_0);
|
||||
ganged_mode = SQUARING_MODE_B;
|
||||
limits_go_home(HOMING_CYCLE_0);
|
||||
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
|
||||
}
|
||||
|
||||
#ifdef HOMING_CYCLE_1
|
||||
if (! axis_is_squared(HOMING_CYCLE_1))
|
||||
limits_go_home(HOMING_CYCLE_1);
|
||||
else {
|
||||
ganged_mode = SQUARING_MODE_DUAL;
|
||||
n_homing_locate_cycle = 0; // don't do a second touch cycle
|
||||
limits_go_home(HOMING_CYCLE_1);
|
||||
ganged_mode = SQUARING_MODE_A;
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
|
||||
limits_go_home(HOMING_CYCLE_1);
|
||||
ganged_mode = SQUARING_MODE_B;
|
||||
limits_go_home(HOMING_CYCLE_1);
|
||||
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef HOMING_CYCLE_2
|
||||
if (! axis_is_squared(HOMING_CYCLE_2))
|
||||
limits_go_home(HOMING_CYCLE_2);
|
||||
else {
|
||||
ganged_mode = SQUARING_MODE_DUAL;
|
||||
n_homing_locate_cycle = 0; // don't do a second touch cycle
|
||||
limits_go_home(HOMING_CYCLE_2);
|
||||
ganged_mode = SQUARING_MODE_A;
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
|
||||
limits_go_home(HOMING_CYCLE_2);
|
||||
ganged_mode = SQUARING_MODE_B;
|
||||
limits_go_home(HOMING_CYCLE_2);
|
||||
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef HOMING_CYCLE_3
|
||||
limits_go_home(HOMING_CYCLE_3); // Homing cycle 3
|
||||
#endif
|
||||
#ifdef HOMING_CYCLE_4
|
||||
limits_go_home(HOMING_CYCLE_4); // Homing cycle 4
|
||||
#endif
|
||||
#ifdef HOMING_CYCLE_5
|
||||
limits_go_home(HOMING_CYCLE_5); // Homing cycle 5
|
||||
#endif
|
||||
|
||||
|
||||
}
|
||||
|
||||
protocol_execute_realtime(); // Check for reset and set system abort.
|
||||
if (sys.abort) { return; } // Did not complete. Alarm state set by mc_alarm.
|
||||
|
||||
// Homing cycle complete! Setup system for normal operation.
|
||||
// -------------------------------------------------------------------------------------
|
||||
|
||||
// Sync gcode parser and planner positions to homed position.
|
||||
gc_sync_position();
|
||||
plan_sync_position();
|
||||
|
||||
#ifdef USE_KINEMATICS
|
||||
// This give kinematics a chance to do something after normal homing
|
||||
kinematics_post_homing();
|
||||
#endif
|
||||
|
||||
// If hard limits feature enabled, re-enable hard limits pin change register after homing cycle.
|
||||
limits_init();
|
||||
#endif
|
||||
{
|
||||
// Search to engage all axes limit switches at faster homing seek rate.
|
||||
if (! axis_is_squared(HOMING_CYCLE_0))
|
||||
limits_go_home(HOMING_CYCLE_0); // Homing cycle 0
|
||||
else {
|
||||
ganged_mode = SQUARING_MODE_DUAL;
|
||||
n_homing_locate_cycle = 0; // don't do a second touch cycle
|
||||
limits_go_home(HOMING_CYCLE_0);
|
||||
ganged_mode = SQUARING_MODE_A;
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
|
||||
limits_go_home(HOMING_CYCLE_0);
|
||||
ganged_mode = SQUARING_MODE_B;
|
||||
limits_go_home(HOMING_CYCLE_0);
|
||||
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
|
||||
}
|
||||
#ifdef HOMING_CYCLE_1
|
||||
if (! axis_is_squared(HOMING_CYCLE_1))
|
||||
limits_go_home(HOMING_CYCLE_1);
|
||||
else {
|
||||
ganged_mode = SQUARING_MODE_DUAL;
|
||||
n_homing_locate_cycle = 0; // don't do a second touch cycle
|
||||
limits_go_home(HOMING_CYCLE_1);
|
||||
ganged_mode = SQUARING_MODE_A;
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
|
||||
limits_go_home(HOMING_CYCLE_1);
|
||||
ganged_mode = SQUARING_MODE_B;
|
||||
limits_go_home(HOMING_CYCLE_1);
|
||||
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
|
||||
}
|
||||
#endif
|
||||
#ifdef HOMING_CYCLE_2
|
||||
if (! axis_is_squared(HOMING_CYCLE_2))
|
||||
limits_go_home(HOMING_CYCLE_2);
|
||||
else {
|
||||
ganged_mode = SQUARING_MODE_DUAL;
|
||||
n_homing_locate_cycle = 0; // don't do a second touch cycle
|
||||
limits_go_home(HOMING_CYCLE_2);
|
||||
ganged_mode = SQUARING_MODE_A;
|
||||
n_homing_locate_cycle = N_HOMING_LOCATE_CYCLE; // restore to default value
|
||||
limits_go_home(HOMING_CYCLE_2);
|
||||
ganged_mode = SQUARING_MODE_B;
|
||||
limits_go_home(HOMING_CYCLE_2);
|
||||
ganged_mode = SQUARING_MODE_DUAL; // always return to dual
|
||||
}
|
||||
#endif
|
||||
#ifdef HOMING_CYCLE_3
|
||||
limits_go_home(HOMING_CYCLE_3); // Homing cycle 3
|
||||
#endif
|
||||
#ifdef HOMING_CYCLE_4
|
||||
limits_go_home(HOMING_CYCLE_4); // Homing cycle 4
|
||||
#endif
|
||||
#ifdef HOMING_CYCLE_5
|
||||
limits_go_home(HOMING_CYCLE_5); // Homing cycle 5
|
||||
#endif
|
||||
}
|
||||
protocol_execute_realtime(); // Check for reset and set system abort.
|
||||
if (sys.abort) return; // Did not complete. Alarm state set by mc_alarm.
|
||||
// Homing cycle complete! Setup system for normal operation.
|
||||
// -------------------------------------------------------------------------------------
|
||||
// Sync gcode parser and planner positions to homed position.
|
||||
gc_sync_position();
|
||||
plan_sync_position();
|
||||
#ifdef USE_KINEMATICS
|
||||
// This give kinematics a chance to do something after normal homing
|
||||
kinematics_post_homing();
|
||||
#endif
|
||||
// If hard limits feature enabled, re-enable hard limits pin change register after homing cycle.
|
||||
limits_init();
|
||||
}
|
||||
|
||||
|
||||
// Perform tool length probe cycle. Requires probe switch.
|
||||
// NOTE: Upon probe failure, the program will be stopped and placed into ALARM state.
|
||||
uint8_t mc_probe_cycle(float *target, plan_line_data_t *pl_data, uint8_t parser_flags)
|
||||
{
|
||||
// TODO: Need to update this cycle so it obeys a non-auto cycle start.
|
||||
if (sys.state == STATE_CHECK_MODE) { return(GC_PROBE_CHECK_MODE); }
|
||||
|
||||
// Finish all queued commands and empty planner buffer before starting probe cycle.
|
||||
protocol_buffer_synchronize();
|
||||
if (sys.abort) { return(GC_PROBE_ABORT); } // Return if system reset has been issued.
|
||||
|
||||
// Initialize probing control variables
|
||||
uint8_t is_probe_away = bit_istrue(parser_flags,GC_PARSER_PROBE_IS_AWAY);
|
||||
uint8_t is_no_error = bit_istrue(parser_flags,GC_PARSER_PROBE_IS_NO_ERROR);
|
||||
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
|
||||
probe_configure_invert_mask(is_probe_away);
|
||||
|
||||
// After syncing, check if probe is already triggered. If so, halt and issue alarm.
|
||||
// NOTE: This probe initialization error applies to all probing cycles.
|
||||
if ( probe_get_state() ) { // Check probe pin state.
|
||||
system_set_exec_alarm(EXEC_ALARM_PROBE_FAIL_INITIAL);
|
||||
protocol_execute_realtime();
|
||||
probe_configure_invert_mask(false); // Re-initialize invert mask before returning.
|
||||
return(GC_PROBE_FAIL_INIT); // Nothing else to do but bail.
|
||||
}
|
||||
|
||||
// Setup and queue probing motion. Auto cycle-start should not start the cycle.
|
||||
mc_line(target, pl_data);
|
||||
|
||||
// Activate the probing state monitor in the stepper module.
|
||||
sys_probe_state = PROBE_ACTIVE;
|
||||
|
||||
// Perform probing cycle. Wait here until probe is triggered or motion completes.
|
||||
system_set_exec_state_flag(EXEC_CYCLE_START);
|
||||
do {
|
||||
protocol_execute_realtime();
|
||||
if (sys.abort) { return(GC_PROBE_ABORT); } // Check for system abort
|
||||
} while (sys.state != STATE_IDLE);
|
||||
|
||||
// Probing cycle complete!
|
||||
|
||||
// Set state variables and error out, if the probe failed and cycle with error is enabled.
|
||||
if (sys_probe_state == PROBE_ACTIVE) {
|
||||
if (is_no_error) { memcpy(sys_probe_position, sys_position, sizeof(sys_position)); }
|
||||
else { system_set_exec_alarm(EXEC_ALARM_PROBE_FAIL_CONTACT); }
|
||||
} else {
|
||||
sys.probe_succeeded = true; // Indicate to system the probing cycle completed successfully.
|
||||
}
|
||||
sys_probe_state = PROBE_OFF; // Ensure probe state monitor is disabled.
|
||||
probe_configure_invert_mask(false); // Re-initialize invert mask.
|
||||
protocol_execute_realtime(); // Check and execute run-time commands
|
||||
|
||||
// Reset the stepper and planner buffers to remove the remainder of the probe motion.
|
||||
st_reset(); // Reset step segment buffer.
|
||||
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
|
||||
plan_sync_position(); // Sync planner position to current machine position.
|
||||
|
||||
#ifdef MESSAGE_PROBE_COORDINATES
|
||||
uint8_t mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_flags) {
|
||||
// TODO: Need to update this cycle so it obeys a non-auto cycle start.
|
||||
if (sys.state == STATE_CHECK_MODE) return (GC_PROBE_CHECK_MODE);
|
||||
// Finish all queued commands and empty planner buffer before starting probe cycle.
|
||||
protocol_buffer_synchronize();
|
||||
if (sys.abort) return (GC_PROBE_ABORT); // Return if system reset has been issued.
|
||||
// Initialize probing control variables
|
||||
uint8_t is_probe_away = bit_istrue(parser_flags, GC_PARSER_PROBE_IS_AWAY);
|
||||
uint8_t is_no_error = bit_istrue(parser_flags, GC_PARSER_PROBE_IS_NO_ERROR);
|
||||
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
|
||||
probe_configure_invert_mask(is_probe_away);
|
||||
// After syncing, check if probe is already triggered. If so, halt and issue alarm.
|
||||
// NOTE: This probe initialization error applies to all probing cycles.
|
||||
if (probe_get_state()) { // Check probe pin state.
|
||||
system_set_exec_alarm(EXEC_ALARM_PROBE_FAIL_INITIAL);
|
||||
protocol_execute_realtime();
|
||||
probe_configure_invert_mask(false); // Re-initialize invert mask before returning.
|
||||
return (GC_PROBE_FAIL_INIT); // Nothing else to do but bail.
|
||||
}
|
||||
// Setup and queue probing motion. Auto cycle-start should not start the cycle.
|
||||
mc_line(target, pl_data);
|
||||
// Activate the probing state monitor in the stepper module.
|
||||
sys_probe_state = PROBE_ACTIVE;
|
||||
// Perform probing cycle. Wait here until probe is triggered or motion completes.
|
||||
system_set_exec_state_flag(EXEC_CYCLE_START);
|
||||
do {
|
||||
protocol_execute_realtime();
|
||||
if (sys.abort) return (GC_PROBE_ABORT); // Check for system abort
|
||||
} while (sys.state != STATE_IDLE);
|
||||
// Probing cycle complete!
|
||||
// Set state variables and error out, if the probe failed and cycle with error is enabled.
|
||||
if (sys_probe_state == PROBE_ACTIVE) {
|
||||
if (is_no_error) memcpy(sys_probe_position, sys_position, sizeof(sys_position));
|
||||
else system_set_exec_alarm(EXEC_ALARM_PROBE_FAIL_CONTACT);
|
||||
} else {
|
||||
sys.probe_succeeded = true; // Indicate to system the probing cycle completed successfully.
|
||||
}
|
||||
sys_probe_state = PROBE_OFF; // Ensure probe state monitor is disabled.
|
||||
probe_configure_invert_mask(false); // Re-initialize invert mask.
|
||||
protocol_execute_realtime(); // Check and execute run-time commands
|
||||
// Reset the stepper and planner buffers to remove the remainder of the probe motion.
|
||||
st_reset(); // Reset step segment buffer.
|
||||
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
|
||||
plan_sync_position(); // Sync planner position to current machine position.
|
||||
#ifdef MESSAGE_PROBE_COORDINATES
|
||||
// All done! Output the probe position as message.
|
||||
report_probe_parameters(CLIENT_ALL);
|
||||
#endif
|
||||
|
||||
if (sys.probe_succeeded) { return(GC_PROBE_FOUND); } // Successful probe cycle.
|
||||
else { return(GC_PROBE_FAIL_END); } // Failed to trigger probe within travel. With or without error.
|
||||
#endif
|
||||
if (sys.probe_succeeded) return (GC_PROBE_FOUND); // Successful probe cycle.
|
||||
else return (GC_PROBE_FAIL_END); // Failed to trigger probe within travel. With or without error.
|
||||
}
|
||||
|
||||
|
||||
// Plans and executes the single special motion case for parking. Independent of main planner buffer.
|
||||
// NOTE: Uses the always free planner ring buffer head to store motion parameters for execution.
|
||||
void mc_parking_motion(float *parking_target, plan_line_data_t *pl_data)
|
||||
{
|
||||
if (sys.abort) { return; } // Block during abort.
|
||||
|
||||
uint8_t plan_status = plan_buffer_line(parking_target, pl_data);
|
||||
|
||||
if (plan_status) {
|
||||
bit_true(sys.step_control, STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||
bit_false(sys.step_control, STEP_CONTROL_END_MOTION); // Allow parking motion to execute, if feed hold is active.
|
||||
st_parking_setup_buffer(); // Setup step segment buffer for special parking motion case
|
||||
st_prep_buffer();
|
||||
st_wake_up();
|
||||
do {
|
||||
protocol_exec_rt_system();
|
||||
if (sys.abort) { return; }
|
||||
} while (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||
st_parking_restore_buffer(); // Restore step segment buffer to normal run state.
|
||||
} else {
|
||||
bit_false(sys.step_control, STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||
protocol_exec_rt_system();
|
||||
}
|
||||
|
||||
void mc_parking_motion(float* parking_target, plan_line_data_t* pl_data) {
|
||||
if (sys.abort) return; // Block during abort.
|
||||
uint8_t plan_status = plan_buffer_line(parking_target, pl_data);
|
||||
if (plan_status) {
|
||||
bit_true(sys.step_control, STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||
bit_false(sys.step_control, STEP_CONTROL_END_MOTION); // Allow parking motion to execute, if feed hold is active.
|
||||
st_parking_setup_buffer(); // Setup step segment buffer for special parking motion case
|
||||
st_prep_buffer();
|
||||
st_wake_up();
|
||||
do {
|
||||
protocol_exec_rt_system();
|
||||
if (sys.abort) return;
|
||||
} while (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||
st_parking_restore_buffer(); // Restore step segment buffer to normal run state.
|
||||
} else {
|
||||
bit_false(sys.step_control, STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||
protocol_exec_rt_system();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@ -467,44 +410,38 @@ void mc_parking_motion(float *parking_target, plan_line_data_t *pl_data)
|
||||
// is in a motion state. If so, kills the steppers and sets the system alarm to flag position
|
||||
// lost, since there was an abrupt uncontrolled deceleration. Called at an interrupt level by
|
||||
// realtime abort command and hard limits. So, keep to a minimum.
|
||||
void mc_reset()
|
||||
{
|
||||
// Only this function can set the system reset. Helps prevent multiple kill calls.
|
||||
if (bit_isfalse(sys_rt_exec_state, EXEC_RESET)) {
|
||||
system_set_exec_state_flag(EXEC_RESET);
|
||||
|
||||
// Kill spindle and coolant.
|
||||
spindle_stop();
|
||||
coolant_stop();
|
||||
// turn off all digital I/O
|
||||
sys_io_control(0xFF, false);
|
||||
|
||||
#ifdef ENABLE_SD_CARD
|
||||
// do we need to stop a running SD job?
|
||||
if (get_sd_state(false) == SDCARD_BUSY_PRINTING) {
|
||||
//Report print stopped
|
||||
report_feedback_message(MESSAGE_SD_FILE_QUIT);
|
||||
closeFile();
|
||||
}
|
||||
#endif
|
||||
|
||||
// Kill steppers only if in any motion state, i.e. cycle, actively holding, or homing.
|
||||
// NOTE: If steppers are kept enabled via the step idle delay setting, this also keeps
|
||||
// the steppers enabled by avoiding the go_idle call altogether, unless the motion state is
|
||||
// violated, by which, all bets are off.
|
||||
if ((sys.state & (STATE_CYCLE | STATE_HOMING | STATE_JOG)) ||
|
||||
(sys.step_control & (STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_SYS_MOTION))) {
|
||||
if (sys.state == STATE_HOMING) {
|
||||
if (!sys_rt_exec_alarm) {system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_RESET); }
|
||||
} else { system_set_exec_alarm(EXEC_ALARM_ABORT_CYCLE); }
|
||||
st_go_idle(); // Force kill steppers. Position has likely been lost.
|
||||
void mc_reset() {
|
||||
// Only this function can set the system reset. Helps prevent multiple kill calls.
|
||||
if (bit_isfalse(sys_rt_exec_state, EXEC_RESET)) {
|
||||
system_set_exec_state_flag(EXEC_RESET);
|
||||
// Kill spindle and coolant.
|
||||
spindle_stop();
|
||||
coolant_stop();
|
||||
// turn off all digital I/O
|
||||
sys_io_control(0xFF, false);
|
||||
#ifdef ENABLE_SD_CARD
|
||||
// do we need to stop a running SD job?
|
||||
if (get_sd_state(false) == SDCARD_BUSY_PRINTING) {
|
||||
//Report print stopped
|
||||
report_feedback_message(MESSAGE_SD_FILE_QUIT);
|
||||
closeFile();
|
||||
}
|
||||
#endif
|
||||
// Kill steppers only if in any motion state, i.e. cycle, actively holding, or homing.
|
||||
// NOTE: If steppers are kept enabled via the step idle delay setting, this also keeps
|
||||
// the steppers enabled by avoiding the go_idle call altogether, unless the motion state is
|
||||
// violated, by which, all bets are off.
|
||||
if ((sys.state & (STATE_CYCLE | STATE_HOMING | STATE_JOG)) ||
|
||||
(sys.step_control & (STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_SYS_MOTION))) {
|
||||
if (sys.state == STATE_HOMING) {
|
||||
if (!sys_rt_exec_alarm) system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_RESET);
|
||||
} else system_set_exec_alarm(EXEC_ALARM_ABORT_CYCLE);
|
||||
st_go_idle(); // Force kill steppers. Position has likely been lost.
|
||||
}
|
||||
#ifdef USE_GANGED_AXES
|
||||
ganged_mode = SQUARING_MODE_DUAL; // in case an error occurred during squaring
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef USE_GANGED_AXES
|
||||
ganged_mode = SQUARING_MODE_DUAL; // in case an error occurred during squaring
|
||||
#endif
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
@ -4,10 +4,10 @@
|
||||
|
||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
@ -25,8 +25,8 @@
|
||||
|
||||
|
||||
#ifndef motion_control_h
|
||||
#define motion_control_h
|
||||
|
||||
#define motion_control_h
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
|
||||
@ -46,15 +46,15 @@
|
||||
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
|
||||
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
|
||||
// (1 minute)/feed_rate time.
|
||||
void mc_line_kins(float *target, plan_line_data_t *pl_data, float *position);
|
||||
void mc_line(float *target, plan_line_data_t *pl_data);
|
||||
void mc_line_kins(float* target, plan_line_data_t* pl_data, float* position);
|
||||
void mc_line(float* target, plan_line_data_t* pl_data);
|
||||
|
||||
// Execute an arc in offset mode format. position == current xyz, target == target xyz,
|
||||
// offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is
|
||||
// the direction of helical travel, radius == circle radius, is_clockwise_arc boolean. Used
|
||||
// for vector transformation direction.
|
||||
void mc_arc(float *target, plan_line_data_t *pl_data, float *position, float *offset, float radius,
|
||||
uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc);
|
||||
void mc_arc(float* target, plan_line_data_t* pl_data, float* position, float* offset, float radius,
|
||||
uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc);
|
||||
|
||||
// Dwell for a specific number of seconds
|
||||
void mc_dwell(float seconds);
|
||||
@ -63,10 +63,10 @@ void mc_dwell(float seconds);
|
||||
void mc_homing_cycle(uint8_t cycle_mask);
|
||||
|
||||
// Perform tool length probe cycle. Requires probe switch.
|
||||
uint8_t mc_probe_cycle(float *target, plan_line_data_t *pl_data, uint8_t parser_flags);
|
||||
uint8_t mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_flags);
|
||||
|
||||
// Plans and executes the single special motion case for parking. Independent of main planner buffer.
|
||||
void mc_parking_motion(float *parking_target, plan_line_data_t *pl_data);
|
||||
void mc_parking_motion(float* parking_target, plan_line_data_t* pl_data);
|
||||
|
||||
// Performs system reset. If in motion state, kills all motion and sets system alarm.
|
||||
void mc_reset();
|
||||
|
@ -18,7 +18,7 @@
|
||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*/
|
||||
//Inspired by following sources
|
||||
//* Line :
|
||||
//* Line :
|
||||
// - https://github.com/TridentTD/TridentTD_LineNotify
|
||||
// - https://notify-bot.line.me/doc/en/
|
||||
//* Pushover:
|
||||
@ -50,24 +50,22 @@
|
||||
|
||||
NotificationsService notificationsservice;
|
||||
|
||||
bool Wait4Answer(WiFiClientSecure & client, const char * linetrigger, const char * expected_answer, uint32_t timeout)
|
||||
{
|
||||
if(client.connected()) {
|
||||
bool Wait4Answer(WiFiClientSecure& client, const char* linetrigger, const char* expected_answer, uint32_t timeout) {
|
||||
if (client.connected()) {
|
||||
String answer;
|
||||
uint32_t starttimeout = millis();
|
||||
while (client.connected() && ((millis() -starttimeout) < timeout)) {
|
||||
while (client.connected() && ((millis() - starttimeout) < timeout)) {
|
||||
answer = client.readStringUntil('\n');
|
||||
log_d("Answer: %s", answer.c_str());
|
||||
if ((answer.indexOf(linetrigger) != -1) || (strlen(linetrigger) == 0)) {
|
||||
if ((answer.indexOf(linetrigger) != -1) || (strlen(linetrigger) == 0))
|
||||
break;
|
||||
}
|
||||
COMMANDS::wait(10);
|
||||
}
|
||||
if (strlen(expected_answer) == 0) {
|
||||
log_d("Answer ignored as requested");
|
||||
return true;
|
||||
}
|
||||
if(answer.indexOf(expected_answer) == -1) {
|
||||
if (answer.indexOf(expected_answer) == -1) {
|
||||
log_d("Did not got answer!");
|
||||
return false;
|
||||
} else {
|
||||
@ -79,27 +77,23 @@ bool Wait4Answer(WiFiClientSecure & client, const char * linetrigger, const char
|
||||
return false;
|
||||
}
|
||||
|
||||
NotificationsService::NotificationsService()
|
||||
{
|
||||
NotificationsService::NotificationsService() {
|
||||
_started = false;
|
||||
_notificationType = 0;
|
||||
_token1 = "";
|
||||
_token1 = "";
|
||||
_settings = "";
|
||||
}
|
||||
NotificationsService::~NotificationsService()
|
||||
{
|
||||
NotificationsService::~NotificationsService() {
|
||||
end();
|
||||
}
|
||||
|
||||
bool NotificationsService::started()
|
||||
{
|
||||
bool NotificationsService::started() {
|
||||
return _started;
|
||||
}
|
||||
|
||||
const char * NotificationsService::getTypeString()
|
||||
{
|
||||
switch(_notificationType) {
|
||||
const char* NotificationsService::getTypeString() {
|
||||
switch (_notificationType) {
|
||||
case ESP_PUSHOVER_NOTIFICATION:
|
||||
return "Pushover";
|
||||
case ESP_EMAIL_NOTIFICATION:
|
||||
@ -112,19 +106,18 @@ const char * NotificationsService::getTypeString()
|
||||
return "None";
|
||||
}
|
||||
|
||||
bool NotificationsService::sendMSG(const char * title, const char * message)
|
||||
{
|
||||
if (!_started) return false;
|
||||
bool NotificationsService::sendMSG(const char* title, const char* message) {
|
||||
if (!_started) return false;
|
||||
if (!((strlen(title) == 0) && (strlen(message) == 0))) {
|
||||
switch(_notificationType) {
|
||||
switch (_notificationType) {
|
||||
case ESP_PUSHOVER_NOTIFICATION:
|
||||
return sendPushoverMSG(title,message);
|
||||
return sendPushoverMSG(title, message);
|
||||
break;
|
||||
case ESP_EMAIL_NOTIFICATION:
|
||||
return sendEmailMSG(title,message);
|
||||
return sendEmailMSG(title, message);
|
||||
break;
|
||||
case ESP_LINE_NOTIFICATION :
|
||||
return sendLineMSG(title,message);
|
||||
return sendLineMSG(title, message);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
@ -134,8 +127,7 @@ bool NotificationsService::sendMSG(const char * title, const char * message)
|
||||
}
|
||||
//Messages are currently limited to 1024 4-byte UTF-8 characters
|
||||
//but we do not do any check
|
||||
bool NotificationsService::sendPushoverMSG(const char * title, const char * message)
|
||||
{
|
||||
bool NotificationsService::sendPushoverMSG(const char* title, const char* message) {
|
||||
String data;
|
||||
String postcmd;
|
||||
bool res;
|
||||
@ -149,7 +141,7 @@ bool NotificationsService::sendPushoverMSG(const char * title, const char * mess
|
||||
data += _token1;
|
||||
data += "&token=";
|
||||
data += _token2;;
|
||||
data +="&title=";
|
||||
data += "&title=";
|
||||
data += title;
|
||||
data += "&message=";
|
||||
data += message;
|
||||
@ -158,8 +150,8 @@ bool NotificationsService::sendPushoverMSG(const char * title, const char * mess
|
||||
//build post query
|
||||
postcmd = "POST /1/messages.json HTTP/1.1\r\nHost: api.pushover.net\r\nConnection: close\r\nCache-Control: no-cache\r\nUser-Agent: ESP3D\r\nAccept: text/html,application/xhtml+xml,application/xml;q=0.9,*/*;q=0.8\r\nContent-Length: ";
|
||||
postcmd += data.length();
|
||||
postcmd +="\r\n\r\n";
|
||||
postcmd +=data;
|
||||
postcmd += "\r\n\r\n";
|
||||
postcmd += data;
|
||||
log_d("Query: %s", postcmd.c_str());
|
||||
//send query
|
||||
Notificationclient.print(postcmd);
|
||||
@ -167,8 +159,7 @@ bool NotificationsService::sendPushoverMSG(const char * title, const char * mess
|
||||
Notificationclient.stop();
|
||||
return res;
|
||||
}
|
||||
bool NotificationsService::sendEmailMSG(const char * title, const char * message)
|
||||
{
|
||||
bool NotificationsService::sendEmailMSG(const char* title, const char* message) {
|
||||
WiFiClientSecure Notificationclient;
|
||||
log_d("Connect to server");
|
||||
if (!Notificationclient.connect(_serveraddress.c_str(), _port)) {
|
||||
@ -176,86 +167,83 @@ bool NotificationsService::sendEmailMSG(const char * title, const char * message
|
||||
return false;
|
||||
}
|
||||
//Check answer of connection
|
||||
if(!Wait4Answer(Notificationclient, "220", "220", EMAILTIMEOUT)) {
|
||||
if (!Wait4Answer(Notificationclient, "220", "220", EMAILTIMEOUT)) {
|
||||
log_d("Connection failed!");
|
||||
return false;
|
||||
}
|
||||
//Do HELO
|
||||
log_d("HELO");
|
||||
Notificationclient.print("HELO friend\r\n");
|
||||
if(!Wait4Answer(Notificationclient, "250", "250", EMAILTIMEOUT)) {
|
||||
if (!Wait4Answer(Notificationclient, "250", "250", EMAILTIMEOUT)) {
|
||||
log_d("HELO failed!");
|
||||
return false;
|
||||
}
|
||||
log_d("AUTH LOGIN");
|
||||
//Request AUthentication
|
||||
Notificationclient.print("AUTH LOGIN\r\n");
|
||||
if(!Wait4Answer(Notificationclient, "334", "334", EMAILTIMEOUT)) {
|
||||
if (!Wait4Answer(Notificationclient, "334", "334", EMAILTIMEOUT)) {
|
||||
log_d("AUTH LOGIN failed!");
|
||||
return false;
|
||||
}
|
||||
log_d("Send LOGIN");
|
||||
//sent Login
|
||||
Notificationclient.printf("%s\r\n",_token1.c_str());
|
||||
if(!Wait4Answer(Notificationclient, "334", "334", EMAILTIMEOUT)) {
|
||||
Notificationclient.printf("%s\r\n", _token1.c_str());
|
||||
if (!Wait4Answer(Notificationclient, "334", "334", EMAILTIMEOUT)) {
|
||||
log_d("Sent login failed!");
|
||||
return false;
|
||||
}
|
||||
log_d("Send PASSWORD");
|
||||
//Send password
|
||||
Notificationclient.printf("%s\r\n",_token2.c_str());
|
||||
if(!Wait4Answer(Notificationclient, "235", "235", EMAILTIMEOUT)) {
|
||||
Notificationclient.printf("%s\r\n", _token2.c_str());
|
||||
if (!Wait4Answer(Notificationclient, "235", "235", EMAILTIMEOUT)) {
|
||||
log_d("Sent password failed!");
|
||||
return false;
|
||||
}
|
||||
log_d("MAIL FROM");
|
||||
//Send From
|
||||
Notificationclient.printf("MAIL FROM: <%s>\r\n",_settings.c_str());
|
||||
if(!Wait4Answer(Notificationclient, "250", "250", EMAILTIMEOUT)) {
|
||||
Notificationclient.printf("MAIL FROM: <%s>\r\n", _settings.c_str());
|
||||
if (!Wait4Answer(Notificationclient, "250", "250", EMAILTIMEOUT)) {
|
||||
log_d("MAIL FROM failed!");
|
||||
return false;
|
||||
}
|
||||
log_d("RCPT TO");
|
||||
//Send To
|
||||
Notificationclient.printf("RCPT TO: <%s>\r\n",_settings.c_str());
|
||||
if(!Wait4Answer(Notificationclient, "250", "250", EMAILTIMEOUT)) {
|
||||
Notificationclient.printf("RCPT TO: <%s>\r\n", _settings.c_str());
|
||||
if (!Wait4Answer(Notificationclient, "250", "250", EMAILTIMEOUT)) {
|
||||
log_d("RCPT TO failed!");
|
||||
return false;
|
||||
}
|
||||
log_d("DATA");
|
||||
//Send Data
|
||||
Notificationclient.print("DATA\r\n");
|
||||
if(!Wait4Answer(Notificationclient, "354", "354", EMAILTIMEOUT)) {
|
||||
if (!Wait4Answer(Notificationclient, "354", "354", EMAILTIMEOUT)) {
|
||||
log_d("Preparing DATA failed!");
|
||||
return false;
|
||||
}
|
||||
log_d("Send message");
|
||||
//Send message
|
||||
Notificationclient.printf("From:ESP3D<%s>\r\n",_settings.c_str());
|
||||
Notificationclient.printf("To: <%s>\r\n",_settings.c_str());
|
||||
Notificationclient.printf("Subject: %s\r\n\r\n",title);
|
||||
Notificationclient.printf("From:ESP3D<%s>\r\n", _settings.c_str());
|
||||
Notificationclient.printf("To: <%s>\r\n", _settings.c_str());
|
||||
Notificationclient.printf("Subject: %s\r\n\r\n", title);
|
||||
Notificationclient.println(message);
|
||||
|
||||
log_d("Send final dot");
|
||||
//Send Final dot
|
||||
Notificationclient.print(".\r\n");
|
||||
if(!Wait4Answer(Notificationclient, "250", "250", EMAILTIMEOUT)) {
|
||||
if (!Wait4Answer(Notificationclient, "250", "250", EMAILTIMEOUT)) {
|
||||
log_d("Sending final dot failed!");
|
||||
return false;
|
||||
}
|
||||
log_d("QUIT");
|
||||
//Quit
|
||||
Notificationclient.print("QUIT\r\n");
|
||||
if(!Wait4Answer(Notificationclient, "221", "221", EMAILTIMEOUT)) {
|
||||
if (!Wait4Answer(Notificationclient, "221", "221", EMAILTIMEOUT)) {
|
||||
log_d("QUIT failed!");
|
||||
return false;
|
||||
}
|
||||
|
||||
Notificationclient.stop();
|
||||
return true;
|
||||
}
|
||||
bool NotificationsService::sendLineMSG(const char * title, const char * message)
|
||||
{
|
||||
bool NotificationsService::sendLineMSG(const char* title, const char* message) {
|
||||
String data;
|
||||
String postcmd;
|
||||
bool res;
|
||||
@ -270,12 +258,12 @@ bool NotificationsService::sendLineMSG(const char * title, const char * message)
|
||||
data += message;
|
||||
//build post query
|
||||
postcmd = "POST /api/notify HTTP/1.1\r\nHost: notify-api.line.me\r\nConnection: close\r\nCache-Control: no-cache\r\nUser-Agent: ESP3D\r\nAccept: text/html,application/xhtml+xml,application/xml;q=0.9,*/*;q=0.8\r\nContent-Type: application/x-www-form-urlencoded\r\n";
|
||||
postcmd +="Authorization: Bearer ";
|
||||
postcmd += "Authorization: Bearer ";
|
||||
postcmd += _token1 + "\r\n";
|
||||
postcmd += "Content-Length: ";
|
||||
postcmd += data.length();
|
||||
postcmd +="\r\n\r\n";
|
||||
postcmd +=data;
|
||||
postcmd += "\r\n\r\n";
|
||||
postcmd += data;
|
||||
log_d("Query: %s", postcmd.c_str());
|
||||
//send query
|
||||
Notificationclient.print(postcmd);
|
||||
@ -284,28 +272,24 @@ bool NotificationsService::sendLineMSG(const char * title, const char * message)
|
||||
return res;
|
||||
}
|
||||
//Email#serveraddress:port
|
||||
bool NotificationsService::getPortFromSettings()
|
||||
{
|
||||
bool NotificationsService::getPortFromSettings() {
|
||||
Preferences prefs;
|
||||
String defV = DEFAULT_TOKEN;
|
||||
prefs.begin(NAMESPACE, true);
|
||||
String tmp = prefs.getString(NOTIFICATION_TS, defV);
|
||||
prefs.end();
|
||||
int pos = tmp.lastIndexOf(':');
|
||||
if (pos == -1) {
|
||||
if (pos == -1)
|
||||
return false;
|
||||
}
|
||||
_port= tmp.substring(pos+1).toInt();
|
||||
_port = tmp.substring(pos + 1).toInt();
|
||||
log_d("port : %d", _port);
|
||||
if (_port > 0) {
|
||||
if (_port > 0)
|
||||
return true;
|
||||
} else {
|
||||
else
|
||||
return false;
|
||||
}
|
||||
}
|
||||
//Email#serveraddress:port
|
||||
bool NotificationsService::getServerAddressFromSettings()
|
||||
{
|
||||
bool NotificationsService::getServerAddressFromSettings() {
|
||||
Preferences prefs;
|
||||
String defV = DEFAULT_TOKEN;
|
||||
prefs.begin(NAMESPACE, true);
|
||||
@ -313,27 +297,23 @@ bool NotificationsService::getServerAddressFromSettings()
|
||||
prefs.end();
|
||||
int pos1 = tmp.indexOf('#');
|
||||
int pos2 = tmp.lastIndexOf(':');
|
||||
if ((pos1 == -1) || (pos2 == -1)) {
|
||||
if ((pos1 == -1) || (pos2 == -1))
|
||||
return false;
|
||||
}
|
||||
|
||||
//TODO add a check for valid email ?
|
||||
_serveraddress = tmp.substring(pos1+1, pos2);
|
||||
_serveraddress = tmp.substring(pos1 + 1, pos2);
|
||||
log_d("server : %s", _serveraddress.c_str());
|
||||
return true;
|
||||
}
|
||||
//Email#serveraddress:port
|
||||
bool NotificationsService::getEmailFromSettings()
|
||||
{
|
||||
Preferences prefs;
|
||||
bool NotificationsService::getEmailFromSettings() {
|
||||
Preferences prefs;
|
||||
String defV = DEFAULT_TOKEN;
|
||||
prefs.begin(NAMESPACE, true);
|
||||
String tmp = prefs.getString(NOTIFICATION_TS, defV);
|
||||
prefs.end();
|
||||
int pos = tmp.indexOf('#');
|
||||
if (pos == -1) {
|
||||
if (pos == -1)
|
||||
return false;
|
||||
}
|
||||
_settings = tmp.substring(0, pos);
|
||||
log_d("email : %s", _settings.c_str());
|
||||
//TODO add a check for valid email ?
|
||||
@ -341,15 +321,14 @@ bool NotificationsService::getEmailFromSettings()
|
||||
}
|
||||
|
||||
|
||||
bool NotificationsService::begin()
|
||||
{
|
||||
bool NotificationsService::begin() {
|
||||
bool res = true;
|
||||
end();
|
||||
Preferences prefs;
|
||||
String defV = DEFAULT_TOKEN;
|
||||
prefs.begin(NAMESPACE, true);
|
||||
_notificationType = prefs.getChar(NOTIFICATION_TYPE, DEFAULT_NOTIFICATION_TYPE);
|
||||
switch(_notificationType) {
|
||||
switch (_notificationType) {
|
||||
case 0: //no notification = no error but no start
|
||||
return true;
|
||||
case ESP_PUSHOVER_NOTIFICATION:
|
||||
@ -368,31 +347,27 @@ bool NotificationsService::begin()
|
||||
_token2 = base64::encode(prefs.getString(NOTIFICATION_T2, defV));
|
||||
//log_d("%s",Settings_ESP3D::read_string(ESP_NOTIFICATION_TOKEN1));
|
||||
//log_d("%s",Settings_ESP3D::read_string(ESP_NOTIFICATION_TOKEN2));
|
||||
if(!getEmailFromSettings() || !getPortFromSettings()|| !getServerAddressFromSettings()) {
|
||||
prefs.end();
|
||||
if (!getEmailFromSettings() || !getPortFromSettings() || !getServerAddressFromSettings()) {
|
||||
prefs.end();
|
||||
return false;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
prefs.end();
|
||||
prefs.end();
|
||||
return false;
|
||||
break;
|
||||
}
|
||||
prefs.end();
|
||||
if(WiFi.getMode() != WIFI_STA){
|
||||
res = false;
|
||||
}
|
||||
if (!res) {
|
||||
prefs.end();
|
||||
if (WiFi.getMode() != WIFI_STA)
|
||||
res = false;
|
||||
if (!res)
|
||||
end();
|
||||
}
|
||||
_started = res;
|
||||
return _started;
|
||||
}
|
||||
void NotificationsService::end()
|
||||
{
|
||||
if(!_started) {
|
||||
void NotificationsService::end() {
|
||||
if (!_started)
|
||||
return;
|
||||
}
|
||||
_started = false;
|
||||
_notificationType = 0;
|
||||
_token1 = "";
|
||||
@ -402,8 +377,7 @@ void NotificationsService::end()
|
||||
_port = 0;
|
||||
}
|
||||
|
||||
void NotificationsService::handle()
|
||||
{
|
||||
void NotificationsService::handle() {
|
||||
if (_started) {
|
||||
}
|
||||
}
|
||||
|
@ -24,18 +24,17 @@
|
||||
#define _NOTIFICATIONS_SERVICE_H
|
||||
|
||||
|
||||
class NotificationsService
|
||||
{
|
||||
public:
|
||||
class NotificationsService {
|
||||
public:
|
||||
NotificationsService();
|
||||
~NotificationsService();
|
||||
bool begin();
|
||||
void end();
|
||||
void handle();
|
||||
bool sendMSG(const char * title, const char * message);
|
||||
const char * getTypeString();
|
||||
bool sendMSG(const char* title, const char* message);
|
||||
const char* getTypeString();
|
||||
bool started();
|
||||
private:
|
||||
private:
|
||||
bool _started;
|
||||
uint8_t _notificationType;
|
||||
String _token1;
|
||||
@ -43,9 +42,9 @@ private:
|
||||
String _settings;
|
||||
String _serveraddress;
|
||||
uint16_t _port;
|
||||
bool sendPushoverMSG(const char * title, const char * message);
|
||||
bool sendEmailMSG(const char * title, const char * message);
|
||||
bool sendLineMSG(const char * title, const char * message);
|
||||
bool sendPushoverMSG(const char* title, const char* message);
|
||||
bool sendEmailMSG(const char* title, const char* message);
|
||||
bool sendLineMSG(const char* title, const char* message);
|
||||
bool getPortFromSettings();
|
||||
bool getServerAddressFromSettings();
|
||||
bool getEmailFromSettings();
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
@ -36,152 +36,128 @@
|
||||
// Scientific notation is officially not supported by g-code, and the 'E' character may
|
||||
// be a g-code word on some CNC systems. So, 'E' notation will not be recognized.
|
||||
// NOTE: Thanks to Radu-Eosif Mihailescu for identifying the issues with using strtod().
|
||||
uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr)
|
||||
{
|
||||
char *ptr = line + *char_counter;
|
||||
unsigned char c;
|
||||
|
||||
// Grab first character and increment pointer. No spaces assumed in line.
|
||||
c = *ptr++;
|
||||
|
||||
// Capture initial positive/minus character
|
||||
bool isnegative = false;
|
||||
if (c == '-') {
|
||||
isnegative = true;
|
||||
uint8_t read_float(char* line, uint8_t* char_counter, float* float_ptr) {
|
||||
char* ptr = line + *char_counter;
|
||||
unsigned char c;
|
||||
// Grab first character and increment pointer. No spaces assumed in line.
|
||||
c = *ptr++;
|
||||
} else if (c == '+') {
|
||||
c = *ptr++;
|
||||
}
|
||||
|
||||
// Extract number into fast integer. Track decimal in terms of exponent value.
|
||||
uint32_t intval = 0;
|
||||
int8_t exp = 0;
|
||||
uint8_t ndigit = 0;
|
||||
bool isdecimal = false;
|
||||
while(1) {
|
||||
c -= '0';
|
||||
if (c <= 9) {
|
||||
ndigit++;
|
||||
if (ndigit <= MAX_INT_DIGITS) {
|
||||
if (isdecimal) { exp--; }
|
||||
intval = (((intval << 2) + intval) << 1) + c; // intval*10 + c
|
||||
} else {
|
||||
if (!(isdecimal)) { exp++; } // Drop overflow digits
|
||||
}
|
||||
} else if (c == (('.'-'0') & 0xff) && !(isdecimal)) {
|
||||
isdecimal = true;
|
||||
} else {
|
||||
break;
|
||||
// Capture initial positive/minus character
|
||||
bool isnegative = false;
|
||||
if (c == '-') {
|
||||
isnegative = true;
|
||||
c = *ptr++;
|
||||
} else if (c == '+')
|
||||
c = *ptr++;
|
||||
// Extract number into fast integer. Track decimal in terms of exponent value.
|
||||
uint32_t intval = 0;
|
||||
int8_t exp = 0;
|
||||
uint8_t ndigit = 0;
|
||||
bool isdecimal = false;
|
||||
while (1) {
|
||||
c -= '0';
|
||||
if (c <= 9) {
|
||||
ndigit++;
|
||||
if (ndigit <= MAX_INT_DIGITS) {
|
||||
if (isdecimal) exp--;
|
||||
intval = (((intval << 2) + intval) << 1) + c; // intval*10 + c
|
||||
} else {
|
||||
if (!(isdecimal)) exp++; // Drop overflow digits
|
||||
}
|
||||
} else if (c == (('.' - '0') & 0xff) && !(isdecimal))
|
||||
isdecimal = true;
|
||||
else
|
||||
break;
|
||||
c = *ptr++;
|
||||
}
|
||||
c = *ptr++;
|
||||
}
|
||||
|
||||
// Return if no digits have been read.
|
||||
if (!ndigit) { return(false); };
|
||||
|
||||
// Convert integer into floating point.
|
||||
float fval;
|
||||
fval = (float)intval;
|
||||
|
||||
// Apply decimal. Should perform no more than two floating point multiplications for the
|
||||
// expected range of E0 to E-4.
|
||||
if (fval != 0) {
|
||||
while (exp <= -2) {
|
||||
fval *= 0.01;
|
||||
exp += 2;
|
||||
// Return if no digits have been read.
|
||||
if (!ndigit) return (false); ;
|
||||
// Convert integer into floating point.
|
||||
float fval;
|
||||
fval = (float)intval;
|
||||
// Apply decimal. Should perform no more than two floating point multiplications for the
|
||||
// expected range of E0 to E-4.
|
||||
if (fval != 0) {
|
||||
while (exp <= -2) {
|
||||
fval *= 0.01;
|
||||
exp += 2;
|
||||
}
|
||||
if (exp < 0)
|
||||
fval *= 0.1;
|
||||
else if (exp > 0) {
|
||||
do {
|
||||
fval *= 10.0;
|
||||
} while (--exp > 0);
|
||||
}
|
||||
}
|
||||
if (exp < 0) {
|
||||
fval *= 0.1;
|
||||
} else if (exp > 0) {
|
||||
do {
|
||||
fval *= 10.0;
|
||||
} while (--exp > 0);
|
||||
}
|
||||
}
|
||||
|
||||
// Assign floating point value with correct sign.
|
||||
if (isnegative) {
|
||||
*float_ptr = -fval;
|
||||
} else {
|
||||
*float_ptr = fval;
|
||||
}
|
||||
|
||||
*char_counter = ptr - line - 1; // Set char_counter to next statement
|
||||
|
||||
return(true);
|
||||
// Assign floating point value with correct sign.
|
||||
if (isnegative)
|
||||
*float_ptr = -fval;
|
||||
else
|
||||
*float_ptr = fval;
|
||||
*char_counter = ptr - line - 1; // Set char_counter to next statement
|
||||
return (true);
|
||||
}
|
||||
|
||||
void delay_ms(uint16_t ms)
|
||||
{
|
||||
delay(ms);
|
||||
void delay_ms(uint16_t ms) {
|
||||
delay(ms);
|
||||
}
|
||||
|
||||
// Non-blocking delay function used for general operation and suspend features.
|
||||
void delay_sec(float seconds, uint8_t mode)
|
||||
{
|
||||
uint16_t i = ceil(1000/DWELL_TIME_STEP*seconds);
|
||||
while (i-- > 0) {
|
||||
if (sys.abort) { return; }
|
||||
if (mode == DELAY_MODE_DWELL) {
|
||||
protocol_execute_realtime();
|
||||
} else { // DELAY_MODE_SYS_SUSPEND
|
||||
// Execute rt_system() only to avoid nesting suspend loops.
|
||||
protocol_exec_rt_system();
|
||||
if (sys.suspend & SUSPEND_RESTART_RETRACT) { return; } // Bail, if safety door reopens.
|
||||
void delay_sec(float seconds, uint8_t mode) {
|
||||
uint16_t i = ceil(1000 / DWELL_TIME_STEP * seconds);
|
||||
while (i-- > 0) {
|
||||
if (sys.abort) return;
|
||||
if (mode == DELAY_MODE_DWELL)
|
||||
protocol_execute_realtime();
|
||||
else { // DELAY_MODE_SYS_SUSPEND
|
||||
// Execute rt_system() only to avoid nesting suspend loops.
|
||||
protocol_exec_rt_system();
|
||||
if (sys.suspend & SUSPEND_RESTART_RETRACT) return; // Bail, if safety door reopens.
|
||||
}
|
||||
delay(DWELL_TIME_STEP); // Delay DWELL_TIME_STEP increment
|
||||
}
|
||||
delay(DWELL_TIME_STEP); // Delay DWELL_TIME_STEP increment
|
||||
}
|
||||
}
|
||||
|
||||
// Simple hypotenuse computation function.
|
||||
float hypot_f(float x, float y) { return(sqrt(x*x + y*y)); }
|
||||
float hypot_f(float x, float y) { return (sqrt(x * x + y * y)); }
|
||||
|
||||
|
||||
float convert_delta_vector_to_unit_vector(float *vector)
|
||||
{
|
||||
uint8_t idx;
|
||||
float magnitude = 0.0;
|
||||
for (idx=0; idx<N_AXIS; idx++) {
|
||||
if (vector[idx] != 0.0) {
|
||||
magnitude += vector[idx]*vector[idx];
|
||||
float convert_delta_vector_to_unit_vector(float* vector) {
|
||||
uint8_t idx;
|
||||
float magnitude = 0.0;
|
||||
for (idx = 0; idx < N_AXIS; idx++) {
|
||||
if (vector[idx] != 0.0)
|
||||
magnitude += vector[idx] * vector[idx];
|
||||
}
|
||||
}
|
||||
magnitude = sqrt(magnitude);
|
||||
float inv_magnitude = 1.0/magnitude;
|
||||
for (idx=0; idx<N_AXIS; idx++) { vector[idx] *= inv_magnitude; }
|
||||
return(magnitude);
|
||||
magnitude = sqrt(magnitude);
|
||||
float inv_magnitude = 1.0 / magnitude;
|
||||
for (idx = 0; idx < N_AXIS; idx++) vector[idx] *= inv_magnitude;
|
||||
return (magnitude);
|
||||
}
|
||||
|
||||
float limit_value_by_axis_maximum(float *max_value, float *unit_vec)
|
||||
{
|
||||
uint8_t idx;
|
||||
float limit_value = SOME_LARGE_VALUE;
|
||||
for (idx=0; idx<N_AXIS; idx++) {
|
||||
if (unit_vec[idx] != 0) { // Avoid divide by zero.
|
||||
limit_value = MIN(limit_value,fabs(max_value[idx]/unit_vec[idx]));
|
||||
float limit_value_by_axis_maximum(float* max_value, float* unit_vec) {
|
||||
uint8_t idx;
|
||||
float limit_value = SOME_LARGE_VALUE;
|
||||
for (idx = 0; idx < N_AXIS; idx++) {
|
||||
if (unit_vec[idx] != 0) // Avoid divide by zero.
|
||||
limit_value = MIN(limit_value, fabs(max_value[idx] / unit_vec[idx]));
|
||||
}
|
||||
}
|
||||
return(limit_value);
|
||||
return (limit_value);
|
||||
}
|
||||
|
||||
float map_float(float x, float in_min, float in_max, float out_min, float out_max) // DrawBot_Badge
|
||||
{
|
||||
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||
float map_float(float x, float in_min, float in_max, float out_min, float out_max) { // DrawBot_Badge
|
||||
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||
}
|
||||
|
||||
float constrain_float(float in, float min, float max) // DrawBot_Badge
|
||||
{
|
||||
if (in < min)
|
||||
return min;
|
||||
|
||||
if (in > max)
|
||||
return max;
|
||||
|
||||
return in;
|
||||
float constrain_float(float in, float min, float max) { // DrawBot_Badge
|
||||
if (in < min)
|
||||
return min;
|
||||
if (in > max)
|
||||
return max;
|
||||
return in;
|
||||
}
|
||||
|
||||
float mapConstrain(float x, float in_min, float in_max, float out_min, float out_max)
|
||||
{
|
||||
float mapConstrain(float x, float in_min, float in_max, float out_min, float out_max) {
|
||||
x = constrain_float(x, in_min, in_max);
|
||||
return map_float(x, in_min, in_max, out_min, out_max);
|
||||
}
|
||||
|
@ -2,10 +2,10 @@
|
||||
nuts_bolts.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
|
||||
@ -30,7 +30,7 @@
|
||||
|
||||
// Axis array index values. Must start with 0 and be continuous.
|
||||
// Note: You set the number of axes used by changing N_AXIS.
|
||||
// Be sure to define pins or servos in cpu_map.h
|
||||
// Be sure to define pins or servos in the machine definition file.
|
||||
#define X_AXIS 0 // Axis indexing value.
|
||||
#define Y_AXIS 1
|
||||
#define Z_AXIS 2
|
||||
@ -73,7 +73,7 @@
|
||||
// Read a floating point value from a string. Line points to the input buffer, char_counter
|
||||
// is the indexer pointing to the current character of the line, while float_ptr is
|
||||
// a pointer to the result variable. Returns true when it succeeds
|
||||
uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr);
|
||||
uint8_t read_float(char* line, uint8_t* char_counter, float* float_ptr);
|
||||
|
||||
// Non-blocking delay function used for general operation and suspend features.
|
||||
void delay_sec(float seconds, uint8_t mode);
|
||||
@ -84,16 +84,15 @@ void delay_ms(uint16_t ms);
|
||||
// Computes hypotenuse, avoiding avr-gcc's bloated version and the extra error checking.
|
||||
float hypot_f(float x, float y);
|
||||
|
||||
float convert_delta_vector_to_unit_vector(float *vector);
|
||||
float limit_value_by_axis_maximum(float *max_value, float *unit_vec);
|
||||
float convert_delta_vector_to_unit_vector(float* vector);
|
||||
float limit_value_by_axis_maximum(float* max_value, float* unit_vec);
|
||||
|
||||
float mapConstrain(float x, float in_min, float in_max, float out_min, float out_max);
|
||||
float map_float(float x, float in_min, float in_max, float out_min, float out_max);
|
||||
float constrain_float(float in, float min, float max);
|
||||
|
||||
template <class T> void swap ( T& a, T& b )
|
||||
{
|
||||
T c(a); a=b; b=c;
|
||||
template <class T> void swap(T& a, T& b) {
|
||||
T c(a); a = b; b = c;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -5,7 +5,7 @@
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
Copyright (c) 2011 Jens Geisler
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
@ -35,30 +35,28 @@ static uint8_t block_buffer_planned; // Index of the optimally planned block
|
||||
|
||||
// Define planner variables
|
||||
typedef struct {
|
||||
int32_t position[N_AXIS]; // The planner position of the tool in absolute steps. Kept separate
|
||||
// from g-code position for movements requiring multiple line motions,
|
||||
// i.e. arcs, canned cycles, and backlash compensation.
|
||||
float previous_unit_vec[N_AXIS]; // Unit vector of previous path line segment
|
||||
float previous_nominal_speed; // Nominal speed of previous path line segment
|
||||
int32_t position[N_AXIS]; // The planner position of the tool in absolute steps. Kept separate
|
||||
// from g-code position for movements requiring multiple line motions,
|
||||
// i.e. arcs, canned cycles, and backlash compensation.
|
||||
float previous_unit_vec[N_AXIS]; // Unit vector of previous path line segment
|
||||
float previous_nominal_speed; // Nominal speed of previous path line segment
|
||||
} planner_t;
|
||||
static planner_t pl;
|
||||
|
||||
|
||||
// Returns the index of the next block in the ring buffer. Also called by stepper segment buffer.
|
||||
uint8_t plan_next_block_index(uint8_t block_index)
|
||||
{
|
||||
block_index++;
|
||||
if (block_index == BLOCK_BUFFER_SIZE) { block_index = 0; }
|
||||
return(block_index);
|
||||
uint8_t plan_next_block_index(uint8_t block_index) {
|
||||
block_index++;
|
||||
if (block_index == BLOCK_BUFFER_SIZE) block_index = 0;
|
||||
return (block_index);
|
||||
}
|
||||
|
||||
|
||||
// Returns the index of the previous block in the ring buffer
|
||||
static uint8_t plan_prev_block_index(uint8_t block_index)
|
||||
{
|
||||
if (block_index == 0) { block_index = BLOCK_BUFFER_SIZE; }
|
||||
block_index--;
|
||||
return(block_index);
|
||||
static uint8_t plan_prev_block_index(uint8_t block_index) {
|
||||
if (block_index == 0) block_index = BLOCK_BUFFER_SIZE;
|
||||
block_index--;
|
||||
return (block_index);
|
||||
}
|
||||
|
||||
|
||||
@ -127,385 +125,340 @@ static uint8_t plan_prev_block_index(uint8_t block_index)
|
||||
ARM versions should have enough memory and speed for look-ahead blocks numbering up to a hundred or more.
|
||||
|
||||
*/
|
||||
static void planner_recalculate()
|
||||
{
|
||||
// Initialize block index to the last block in the planner buffer.
|
||||
uint8_t block_index = plan_prev_block_index(block_buffer_head);
|
||||
|
||||
// Bail. Can't do anything with one only one plan-able block.
|
||||
if (block_index == block_buffer_planned) { return; }
|
||||
|
||||
// Reverse Pass: Coarsely maximize all possible deceleration curves back-planning from the last
|
||||
// block in buffer. Cease planning when the last optimal planned or tail pointer is reached.
|
||||
// NOTE: Forward pass will later refine and correct the reverse pass to create an optimal plan.
|
||||
float entry_speed_sqr;
|
||||
plan_block_t *next;
|
||||
plan_block_t *current = &block_buffer[block_index];
|
||||
|
||||
// Calculate maximum entry speed for last block in buffer, where the exit speed is always zero.
|
||||
current->entry_speed_sqr = MIN( current->max_entry_speed_sqr, 2*current->acceleration*current->millimeters);
|
||||
|
||||
block_index = plan_prev_block_index(block_index);
|
||||
if (block_index == block_buffer_planned) { // Only two plannable blocks in buffer. Reverse pass complete.
|
||||
// Check if the first block is the tail. If so, notify stepper to update its current parameters.
|
||||
if (block_index == block_buffer_tail) { st_update_plan_block_parameters(); }
|
||||
} else { // Three or more plan-able blocks
|
||||
while (block_index != block_buffer_planned) {
|
||||
next = current;
|
||||
current = &block_buffer[block_index];
|
||||
block_index = plan_prev_block_index(block_index);
|
||||
|
||||
// Check if next block is the tail block(=planned block). If so, update current stepper parameters.
|
||||
if (block_index == block_buffer_tail) { st_update_plan_block_parameters(); }
|
||||
|
||||
// Compute maximum entry speed decelerating over the current block from its exit speed.
|
||||
if (current->entry_speed_sqr != current->max_entry_speed_sqr) {
|
||||
entry_speed_sqr = next->entry_speed_sqr + 2*current->acceleration*current->millimeters;
|
||||
if (entry_speed_sqr < current->max_entry_speed_sqr) {
|
||||
current->entry_speed_sqr = entry_speed_sqr;
|
||||
} else {
|
||||
current->entry_speed_sqr = current->max_entry_speed_sqr;
|
||||
static void planner_recalculate() {
|
||||
// Initialize block index to the last block in the planner buffer.
|
||||
uint8_t block_index = plan_prev_block_index(block_buffer_head);
|
||||
// Bail. Can't do anything with one only one plan-able block.
|
||||
if (block_index == block_buffer_planned) return;
|
||||
// Reverse Pass: Coarsely maximize all possible deceleration curves back-planning from the last
|
||||
// block in buffer. Cease planning when the last optimal planned or tail pointer is reached.
|
||||
// NOTE: Forward pass will later refine and correct the reverse pass to create an optimal plan.
|
||||
float entry_speed_sqr;
|
||||
plan_block_t* next;
|
||||
plan_block_t* current = &block_buffer[block_index];
|
||||
// Calculate maximum entry speed for last block in buffer, where the exit speed is always zero.
|
||||
current->entry_speed_sqr = MIN(current->max_entry_speed_sqr, 2 * current->acceleration * current->millimeters);
|
||||
block_index = plan_prev_block_index(block_index);
|
||||
if (block_index == block_buffer_planned) { // Only two plannable blocks in buffer. Reverse pass complete.
|
||||
// Check if the first block is the tail. If so, notify stepper to update its current parameters.
|
||||
if (block_index == block_buffer_tail) st_update_plan_block_parameters();
|
||||
} else { // Three or more plan-able blocks
|
||||
while (block_index != block_buffer_planned) {
|
||||
next = current;
|
||||
current = &block_buffer[block_index];
|
||||
block_index = plan_prev_block_index(block_index);
|
||||
// Check if next block is the tail block(=planned block). If so, update current stepper parameters.
|
||||
if (block_index == block_buffer_tail) st_update_plan_block_parameters();
|
||||
// Compute maximum entry speed decelerating over the current block from its exit speed.
|
||||
if (current->entry_speed_sqr != current->max_entry_speed_sqr) {
|
||||
entry_speed_sqr = next->entry_speed_sqr + 2 * current->acceleration * current->millimeters;
|
||||
if (entry_speed_sqr < current->max_entry_speed_sqr)
|
||||
current->entry_speed_sqr = entry_speed_sqr;
|
||||
else
|
||||
current->entry_speed_sqr = current->max_entry_speed_sqr;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Forward Pass: Forward plan the acceleration curve from the planned pointer onward.
|
||||
// Also scans for optimal plan breakpoints and appropriately updates the planned pointer.
|
||||
next = &block_buffer[block_buffer_planned]; // Begin at buffer planned pointer
|
||||
block_index = plan_next_block_index(block_buffer_planned);
|
||||
while (block_index != block_buffer_head) {
|
||||
current = next;
|
||||
next = &block_buffer[block_index];
|
||||
|
||||
// Any acceleration detected in the forward pass automatically moves the optimal planned
|
||||
// pointer forward, since everything before this is all optimal. In other words, nothing
|
||||
// can improve the plan from the buffer tail to the planned pointer by logic.
|
||||
if (current->entry_speed_sqr < next->entry_speed_sqr) {
|
||||
entry_speed_sqr = current->entry_speed_sqr + 2*current->acceleration*current->millimeters;
|
||||
// If true, current block is full-acceleration and we can move the planned pointer forward.
|
||||
if (entry_speed_sqr < next->entry_speed_sqr) {
|
||||
next->entry_speed_sqr = entry_speed_sqr; // Always <= max_entry_speed_sqr. Backward pass sets this.
|
||||
block_buffer_planned = block_index; // Set optimal plan pointer.
|
||||
}
|
||||
// Forward Pass: Forward plan the acceleration curve from the planned pointer onward.
|
||||
// Also scans for optimal plan breakpoints and appropriately updates the planned pointer.
|
||||
next = &block_buffer[block_buffer_planned]; // Begin at buffer planned pointer
|
||||
block_index = plan_next_block_index(block_buffer_planned);
|
||||
while (block_index != block_buffer_head) {
|
||||
current = next;
|
||||
next = &block_buffer[block_index];
|
||||
// Any acceleration detected in the forward pass automatically moves the optimal planned
|
||||
// pointer forward, since everything before this is all optimal. In other words, nothing
|
||||
// can improve the plan from the buffer tail to the planned pointer by logic.
|
||||
if (current->entry_speed_sqr < next->entry_speed_sqr) {
|
||||
entry_speed_sqr = current->entry_speed_sqr + 2 * current->acceleration * current->millimeters;
|
||||
// If true, current block is full-acceleration and we can move the planned pointer forward.
|
||||
if (entry_speed_sqr < next->entry_speed_sqr) {
|
||||
next->entry_speed_sqr = entry_speed_sqr; // Always <= max_entry_speed_sqr. Backward pass sets this.
|
||||
block_buffer_planned = block_index; // Set optimal plan pointer.
|
||||
}
|
||||
}
|
||||
// Any block set at its maximum entry speed also creates an optimal plan up to this
|
||||
// point in the buffer. When the plan is bracketed by either the beginning of the
|
||||
// buffer and a maximum entry speed or two maximum entry speeds, every block in between
|
||||
// cannot logically be further improved. Hence, we don't have to recompute them anymore.
|
||||
if (next->entry_speed_sqr == next->max_entry_speed_sqr) block_buffer_planned = block_index;
|
||||
block_index = plan_next_block_index(block_index);
|
||||
}
|
||||
|
||||
// Any block set at its maximum entry speed also creates an optimal plan up to this
|
||||
// point in the buffer. When the plan is bracketed by either the beginning of the
|
||||
// buffer and a maximum entry speed or two maximum entry speeds, every block in between
|
||||
// cannot logically be further improved. Hence, we don't have to recompute them anymore.
|
||||
if (next->entry_speed_sqr == next->max_entry_speed_sqr) { block_buffer_planned = block_index; }
|
||||
block_index = plan_next_block_index( block_index );
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void plan_reset()
|
||||
{
|
||||
memset(&pl, 0, sizeof(planner_t)); // Clear planner struct
|
||||
plan_reset_buffer();
|
||||
void plan_reset() {
|
||||
memset(&pl, 0, sizeof(planner_t)); // Clear planner struct
|
||||
plan_reset_buffer();
|
||||
}
|
||||
|
||||
|
||||
void plan_reset_buffer()
|
||||
{
|
||||
block_buffer_tail = 0;
|
||||
block_buffer_head = 0; // Empty = tail
|
||||
next_buffer_head = 1; // plan_next_block_index(block_buffer_head)
|
||||
block_buffer_planned = 0; // = block_buffer_tail;
|
||||
void plan_reset_buffer() {
|
||||
block_buffer_tail = 0;
|
||||
block_buffer_head = 0; // Empty = tail
|
||||
next_buffer_head = 1; // plan_next_block_index(block_buffer_head)
|
||||
block_buffer_planned = 0; // = block_buffer_tail;
|
||||
}
|
||||
|
||||
|
||||
void plan_discard_current_block()
|
||||
{
|
||||
if (block_buffer_head != block_buffer_tail) { // Discard non-empty buffer.
|
||||
uint8_t block_index = plan_next_block_index( block_buffer_tail );
|
||||
// Push block_buffer_planned pointer, if encountered.
|
||||
if (block_buffer_tail == block_buffer_planned) { block_buffer_planned = block_index; }
|
||||
block_buffer_tail = block_index;
|
||||
}
|
||||
void plan_discard_current_block() {
|
||||
if (block_buffer_head != block_buffer_tail) { // Discard non-empty buffer.
|
||||
uint8_t block_index = plan_next_block_index(block_buffer_tail);
|
||||
// Push block_buffer_planned pointer, if encountered.
|
||||
if (block_buffer_tail == block_buffer_planned) block_buffer_planned = block_index;
|
||||
block_buffer_tail = block_index;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Returns address of planner buffer block used by system motions. Called by segment generator.
|
||||
plan_block_t *plan_get_system_motion_block()
|
||||
{
|
||||
return(&block_buffer[block_buffer_head]);
|
||||
plan_block_t* plan_get_system_motion_block() {
|
||||
return (&block_buffer[block_buffer_head]);
|
||||
}
|
||||
|
||||
|
||||
// Returns address of first planner block, if available. Called by various main program functions.
|
||||
plan_block_t *plan_get_current_block()
|
||||
{
|
||||
if (block_buffer_head == block_buffer_tail) { return(NULL); } // Buffer empty
|
||||
return(&block_buffer[block_buffer_tail]);
|
||||
plan_block_t* plan_get_current_block() {
|
||||
if (block_buffer_head == block_buffer_tail) return (NULL); // Buffer empty
|
||||
return (&block_buffer[block_buffer_tail]);
|
||||
}
|
||||
|
||||
|
||||
float plan_get_exec_block_exit_speed_sqr()
|
||||
{
|
||||
uint8_t block_index = plan_next_block_index(block_buffer_tail);
|
||||
if (block_index == block_buffer_head) { return( 0.0 ); }
|
||||
return( block_buffer[block_index].entry_speed_sqr );
|
||||
float plan_get_exec_block_exit_speed_sqr() {
|
||||
uint8_t block_index = plan_next_block_index(block_buffer_tail);
|
||||
if (block_index == block_buffer_head) return (0.0);
|
||||
return (block_buffer[block_index].entry_speed_sqr);
|
||||
}
|
||||
|
||||
|
||||
// Returns the availability status of the block ring buffer. True, if full.
|
||||
uint8_t plan_check_full_buffer()
|
||||
{
|
||||
if (block_buffer_tail == next_buffer_head) { return(true); }
|
||||
return(false);
|
||||
uint8_t plan_check_full_buffer() {
|
||||
if (block_buffer_tail == next_buffer_head) return (true);
|
||||
return (false);
|
||||
}
|
||||
|
||||
|
||||
// Computes and returns block nominal speed based on running condition and override values.
|
||||
// NOTE: All system motion commands, such as homing/parking, are not subject to overrides.
|
||||
float plan_compute_profile_nominal_speed(plan_block_t *block)
|
||||
{
|
||||
float nominal_speed = block->programmed_rate;
|
||||
if (block->condition & PL_COND_FLAG_RAPID_MOTION) { nominal_speed *= (0.01*sys.r_override); }
|
||||
else {
|
||||
if (!(block->condition & PL_COND_FLAG_NO_FEED_OVERRIDE)) { nominal_speed *= (0.01*sys.f_override); }
|
||||
if (nominal_speed > block->rapid_rate) { nominal_speed = block->rapid_rate; }
|
||||
}
|
||||
if (nominal_speed > MINIMUM_FEED_RATE) { return(nominal_speed); }
|
||||
return(MINIMUM_FEED_RATE);
|
||||
float plan_compute_profile_nominal_speed(plan_block_t* block) {
|
||||
float nominal_speed = block->programmed_rate;
|
||||
if (block->condition & PL_COND_FLAG_RAPID_MOTION) nominal_speed *= (0.01 * sys.r_override);
|
||||
else {
|
||||
if (!(block->condition & PL_COND_FLAG_NO_FEED_OVERRIDE)) nominal_speed *= (0.01 * sys.f_override);
|
||||
if (nominal_speed > block->rapid_rate) nominal_speed = block->rapid_rate;
|
||||
}
|
||||
if (nominal_speed > MINIMUM_FEED_RATE) return (nominal_speed);
|
||||
return (MINIMUM_FEED_RATE);
|
||||
}
|
||||
|
||||
|
||||
// Computes and updates the max entry speed (sqr) of the block, based on the minimum of the junction's
|
||||
// previous and current nominal speeds and max junction speed.
|
||||
static void plan_compute_profile_parameters(plan_block_t *block, float nominal_speed, float prev_nominal_speed)
|
||||
{
|
||||
// Compute the junction maximum entry based on the minimum of the junction speed and neighboring nominal speeds.
|
||||
if (nominal_speed > prev_nominal_speed) { block->max_entry_speed_sqr = prev_nominal_speed*prev_nominal_speed; }
|
||||
else { block->max_entry_speed_sqr = nominal_speed*nominal_speed; }
|
||||
if (block->max_entry_speed_sqr > block->max_junction_speed_sqr) { block->max_entry_speed_sqr = block->max_junction_speed_sqr; }
|
||||
static void plan_compute_profile_parameters(plan_block_t* block, float nominal_speed, float prev_nominal_speed) {
|
||||
// Compute the junction maximum entry based on the minimum of the junction speed and neighboring nominal speeds.
|
||||
if (nominal_speed > prev_nominal_speed) block->max_entry_speed_sqr = prev_nominal_speed * prev_nominal_speed;
|
||||
else block->max_entry_speed_sqr = nominal_speed * nominal_speed;
|
||||
if (block->max_entry_speed_sqr > block->max_junction_speed_sqr) block->max_entry_speed_sqr = block->max_junction_speed_sqr;
|
||||
}
|
||||
|
||||
|
||||
// Re-calculates buffered motions profile parameters upon a motion-based override change.
|
||||
void plan_update_velocity_profile_parameters()
|
||||
{
|
||||
uint8_t block_index = block_buffer_tail;
|
||||
plan_block_t *block;
|
||||
float nominal_speed;
|
||||
float prev_nominal_speed = SOME_LARGE_VALUE; // Set high for first block nominal speed calculation.
|
||||
while (block_index != block_buffer_head) {
|
||||
block = &block_buffer[block_index];
|
||||
nominal_speed = plan_compute_profile_nominal_speed(block);
|
||||
plan_compute_profile_parameters(block, nominal_speed, prev_nominal_speed);
|
||||
prev_nominal_speed = nominal_speed;
|
||||
block_index = plan_next_block_index(block_index);
|
||||
}
|
||||
pl.previous_nominal_speed = prev_nominal_speed; // Update prev nominal speed for next incoming block.
|
||||
void plan_update_velocity_profile_parameters() {
|
||||
uint8_t block_index = block_buffer_tail;
|
||||
plan_block_t* block;
|
||||
float nominal_speed;
|
||||
float prev_nominal_speed = SOME_LARGE_VALUE; // Set high for first block nominal speed calculation.
|
||||
while (block_index != block_buffer_head) {
|
||||
block = &block_buffer[block_index];
|
||||
nominal_speed = plan_compute_profile_nominal_speed(block);
|
||||
plan_compute_profile_parameters(block, nominal_speed, prev_nominal_speed);
|
||||
prev_nominal_speed = nominal_speed;
|
||||
block_index = plan_next_block_index(block_index);
|
||||
}
|
||||
pl.previous_nominal_speed = prev_nominal_speed; // Update prev nominal speed for next incoming block.
|
||||
}
|
||||
|
||||
|
||||
uint8_t plan_buffer_line(float *target, plan_line_data_t *pl_data)
|
||||
{
|
||||
// Prepare and initialize new block. Copy relevant pl_data for block execution.
|
||||
plan_block_t *block = &block_buffer[block_buffer_head];
|
||||
memset(block,0,sizeof(plan_block_t)); // Zero all block values.
|
||||
block->condition = pl_data->condition;
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
|
||||
// Prepare and initialize new block. Copy relevant pl_data for block execution.
|
||||
plan_block_t* block = &block_buffer[block_buffer_head];
|
||||
memset(block, 0, sizeof(plan_block_t)); // Zero all block values.
|
||||
block->condition = pl_data->condition;
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
block->spindle_speed = pl_data->spindle_speed;
|
||||
#endif
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
#endif
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
block->line_number = pl_data->line_number;
|
||||
#endif
|
||||
|
||||
// Compute and store initial move distance data.
|
||||
int32_t target_steps[N_AXIS], position_steps[N_AXIS];
|
||||
float unit_vec[N_AXIS], delta_mm;
|
||||
uint8_t idx;
|
||||
|
||||
// Copy position data based on type of motion being planned.
|
||||
if (block->condition & PL_COND_FLAG_SYSTEM_MOTION) {
|
||||
#ifdef COREXY
|
||||
position_steps[X_AXIS] = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||
position_steps[Y_AXIS] = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||
position_steps[Z_AXIS] = sys_position[Z_AXIS];
|
||||
#else
|
||||
memcpy(position_steps, sys_position, sizeof(sys_position));
|
||||
#endif
|
||||
} else { memcpy(position_steps, pl.position, sizeof(pl.position)); }
|
||||
|
||||
#ifdef COREXY
|
||||
target_steps[A_MOTOR] = lround(target[A_MOTOR]*settings.steps_per_mm[A_MOTOR]);
|
||||
target_steps[B_MOTOR] = lround(target[B_MOTOR]*settings.steps_per_mm[B_MOTOR]);
|
||||
block->steps[A_MOTOR] = labs((target_steps[X_AXIS]-position_steps[X_AXIS]) + (target_steps[Y_AXIS]-position_steps[Y_AXIS]));
|
||||
block->steps[B_MOTOR] = labs((target_steps[X_AXIS]-position_steps[X_AXIS]) - (target_steps[Y_AXIS]-position_steps[Y_AXIS]));
|
||||
#endif
|
||||
|
||||
for (idx=0; idx<N_AXIS; idx++) {
|
||||
// Calculate target position in absolute steps, number of steps for each axis, and determine max step events.
|
||||
// Also, compute individual axes distance for move and prep unit vector calculations.
|
||||
// NOTE: Computes true distance from converted step values.
|
||||
#ifdef COREXY
|
||||
if ( !(idx == A_MOTOR) && !(idx == B_MOTOR) ) {
|
||||
target_steps[idx] = lround(target[idx]*settings.steps_per_mm[idx]);
|
||||
block->steps[idx] = labs(target_steps[idx]-position_steps[idx]);
|
||||
}
|
||||
block->step_event_count = MAX(block->step_event_count, block->steps[idx]);
|
||||
if (idx == A_MOTOR) {
|
||||
delta_mm = (target_steps[X_AXIS]-position_steps[X_AXIS] + target_steps[Y_AXIS]-position_steps[Y_AXIS])/settings.steps_per_mm[idx];
|
||||
} else if (idx == B_MOTOR) {
|
||||
delta_mm = (target_steps[X_AXIS]-position_steps[X_AXIS] - target_steps[Y_AXIS]+position_steps[Y_AXIS])/settings.steps_per_mm[idx];
|
||||
} else {
|
||||
delta_mm = (target_steps[idx] - position_steps[idx])/settings.steps_per_mm[idx];
|
||||
}
|
||||
#else
|
||||
target_steps[idx] = lround(target[idx]*settings.steps_per_mm[idx]);
|
||||
block->steps[idx] = labs(target_steps[idx]-position_steps[idx]);
|
||||
block->step_event_count = MAX(block->step_event_count, block->steps[idx]);
|
||||
delta_mm = (target_steps[idx] - position_steps[idx])/settings.steps_per_mm[idx];
|
||||
#endif
|
||||
unit_vec[idx] = delta_mm; // Store unit vector numerator
|
||||
|
||||
// Set direction bits. Bit enabled always means direction is negative.
|
||||
if (delta_mm < 0.0 ) { block->direction_bits |= get_direction_pin_mask(idx); }
|
||||
}
|
||||
|
||||
// Bail if this is a zero-length block. Highly unlikely to occur.
|
||||
if (block->step_event_count == 0) { return(PLAN_EMPTY_BLOCK); }
|
||||
|
||||
// Calculate the unit vector of the line move and the block maximum feed rate and acceleration scaled
|
||||
// down such that no individual axes maximum values are exceeded with respect to the line direction.
|
||||
// NOTE: This calculation assumes all axes are orthogonal (Cartesian) and works with ABC-axes,
|
||||
// if they are also orthogonal/independent. Operates on the absolute value of the unit vector.
|
||||
block->millimeters = convert_delta_vector_to_unit_vector(unit_vec);
|
||||
block->acceleration = limit_value_by_axis_maximum(settings.acceleration, unit_vec);
|
||||
block->rapid_rate = limit_value_by_axis_maximum(settings.max_rate, unit_vec);
|
||||
|
||||
// Store programmed rate.
|
||||
if (block->condition & PL_COND_FLAG_RAPID_MOTION) { block->programmed_rate = block->rapid_rate; }
|
||||
else {
|
||||
block->programmed_rate = pl_data->feed_rate;
|
||||
if (block->condition & PL_COND_FLAG_INVERSE_TIME) { block->programmed_rate *= block->millimeters; }
|
||||
}
|
||||
|
||||
// TODO: Need to check this method handling zero junction speeds when starting from rest.
|
||||
if ((block_buffer_head == block_buffer_tail) || (block->condition & PL_COND_FLAG_SYSTEM_MOTION)) {
|
||||
|
||||
// Initialize block entry speed as zero. Assume it will be starting from rest. Planner will correct this later.
|
||||
// If system motion, the system motion block always is assumed to start from rest and end at a complete stop.
|
||||
block->entry_speed_sqr = 0.0;
|
||||
block->max_junction_speed_sqr = 0.0; // Starting from rest. Enforce start from zero velocity.
|
||||
|
||||
} else {
|
||||
// Compute maximum allowable entry speed at junction by centripetal acceleration approximation.
|
||||
// Let a circle be tangent to both previous and current path line segments, where the junction
|
||||
// deviation is defined as the distance from the junction to the closest edge of the circle,
|
||||
// colinear with the circle center. The circular segment joining the two paths represents the
|
||||
// path of centripetal acceleration. Solve for max velocity based on max acceleration about the
|
||||
// radius of the circle, defined indirectly by junction deviation. This may be also viewed as
|
||||
// path width or max_jerk in the previous Grbl version. This approach does not actually deviate
|
||||
// from path, but used as a robust way to compute cornering speeds, as it takes into account the
|
||||
// nonlinearities of both the junction angle and junction velocity.
|
||||
//
|
||||
// NOTE: If the junction deviation value is finite, Grbl executes the motions in an exact path
|
||||
// mode (G61). If the junction deviation value is zero, Grbl will execute the motion in an exact
|
||||
// stop mode (G61.1) manner. In the future, if continuous mode (G64) is desired, the math here
|
||||
// is exactly the same. Instead of motioning all the way to junction point, the machine will
|
||||
// just follow the arc circle defined here. The Arduino doesn't have the CPU cycles to perform
|
||||
// a continuous mode path, but ARM-based microcontrollers most certainly do.
|
||||
//
|
||||
// NOTE: The max junction speed is a fixed value, since machine acceleration limits cannot be
|
||||
// changed dynamically during operation nor can the line move geometry. This must be kept in
|
||||
// memory in the event of a feedrate override changing the nominal speeds of blocks, which can
|
||||
// change the overall maximum entry speed conditions of all blocks.
|
||||
|
||||
float junction_unit_vec[N_AXIS];
|
||||
float junction_cos_theta = 0.0;
|
||||
for (idx=0; idx<N_AXIS; idx++) {
|
||||
junction_cos_theta -= pl.previous_unit_vec[idx]*unit_vec[idx];
|
||||
junction_unit_vec[idx] = unit_vec[idx]-pl.previous_unit_vec[idx];
|
||||
#endif
|
||||
// Compute and store initial move distance data.
|
||||
int32_t target_steps[N_AXIS], position_steps[N_AXIS];
|
||||
float unit_vec[N_AXIS], delta_mm;
|
||||
uint8_t idx;
|
||||
// Copy position data based on type of motion being planned.
|
||||
if (block->condition & PL_COND_FLAG_SYSTEM_MOTION) {
|
||||
#ifdef COREXY
|
||||
position_steps[X_AXIS] = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||
position_steps[Y_AXIS] = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||
position_steps[Z_AXIS] = sys_position[Z_AXIS];
|
||||
#else
|
||||
memcpy(position_steps, sys_position, sizeof(sys_position));
|
||||
#endif
|
||||
} else memcpy(position_steps, pl.position, sizeof(pl.position));
|
||||
#ifdef COREXY
|
||||
target_steps[A_MOTOR] = lround(target[A_MOTOR] * settings.steps_per_mm[A_MOTOR]);
|
||||
target_steps[B_MOTOR] = lround(target[B_MOTOR] * settings.steps_per_mm[B_MOTOR]);
|
||||
block->steps[A_MOTOR] = labs((target_steps[X_AXIS] - position_steps[X_AXIS]) + (target_steps[Y_AXIS] - position_steps[Y_AXIS]));
|
||||
block->steps[B_MOTOR] = labs((target_steps[X_AXIS] - position_steps[X_AXIS]) - (target_steps[Y_AXIS] - position_steps[Y_AXIS]));
|
||||
#endif
|
||||
for (idx = 0; idx < N_AXIS; idx++) {
|
||||
// Calculate target position in absolute steps, number of steps for each axis, and determine max step events.
|
||||
// Also, compute individual axes distance for move and prep unit vector calculations.
|
||||
// NOTE: Computes true distance from converted step values.
|
||||
#ifdef COREXY
|
||||
if (!(idx == A_MOTOR) && !(idx == B_MOTOR)) {
|
||||
target_steps[idx] = lround(target[idx] * settings.steps_per_mm[idx]);
|
||||
block->steps[idx] = labs(target_steps[idx] - position_steps[idx]);
|
||||
}
|
||||
block->step_event_count = MAX(block->step_event_count, block->steps[idx]);
|
||||
if (idx == A_MOTOR)
|
||||
delta_mm = (target_steps[X_AXIS] - position_steps[X_AXIS] + target_steps[Y_AXIS] - position_steps[Y_AXIS]) / settings.steps_per_mm[idx];
|
||||
else if (idx == B_MOTOR)
|
||||
delta_mm = (target_steps[X_AXIS] - position_steps[X_AXIS] - target_steps[Y_AXIS] + position_steps[Y_AXIS]) / settings.steps_per_mm[idx];
|
||||
else
|
||||
delta_mm = (target_steps[idx] - position_steps[idx]) / settings.steps_per_mm[idx];
|
||||
#else
|
||||
target_steps[idx] = lround(target[idx] * settings.steps_per_mm[idx]);
|
||||
block->steps[idx] = labs(target_steps[idx] - position_steps[idx]);
|
||||
block->step_event_count = MAX(block->step_event_count, block->steps[idx]);
|
||||
delta_mm = (target_steps[idx] - position_steps[idx]) / settings.steps_per_mm[idx];
|
||||
#endif
|
||||
unit_vec[idx] = delta_mm; // Store unit vector numerator
|
||||
// Set direction bits. Bit enabled always means direction is negative.
|
||||
if (delta_mm < 0.0) block->direction_bits |= get_direction_pin_mask(idx);
|
||||
}
|
||||
|
||||
// NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta).
|
||||
if (junction_cos_theta > 0.999999) {
|
||||
// For a 0 degree acute junction, just set minimum junction speed.
|
||||
block->max_junction_speed_sqr = MINIMUM_JUNCTION_SPEED*MINIMUM_JUNCTION_SPEED;
|
||||
// Bail if this is a zero-length block. Highly unlikely to occur.
|
||||
if (block->step_event_count == 0) return (PLAN_EMPTY_BLOCK);
|
||||
// Calculate the unit vector of the line move and the block maximum feed rate and acceleration scaled
|
||||
// down such that no individual axes maximum values are exceeded with respect to the line direction.
|
||||
// NOTE: This calculation assumes all axes are orthogonal (Cartesian) and works with ABC-axes,
|
||||
// if they are also orthogonal/independent. Operates on the absolute value of the unit vector.
|
||||
block->millimeters = convert_delta_vector_to_unit_vector(unit_vec);
|
||||
block->acceleration = limit_value_by_axis_maximum(settings.acceleration, unit_vec);
|
||||
block->rapid_rate = limit_value_by_axis_maximum(settings.max_rate, unit_vec);
|
||||
// Store programmed rate.
|
||||
if (block->condition & PL_COND_FLAG_RAPID_MOTION) block->programmed_rate = block->rapid_rate;
|
||||
else {
|
||||
block->programmed_rate = pl_data->feed_rate;
|
||||
if (block->condition & PL_COND_FLAG_INVERSE_TIME) block->programmed_rate *= block->millimeters;
|
||||
}
|
||||
// TODO: Need to check this method handling zero junction speeds when starting from rest.
|
||||
if ((block_buffer_head == block_buffer_tail) || (block->condition & PL_COND_FLAG_SYSTEM_MOTION)) {
|
||||
// Initialize block entry speed as zero. Assume it will be starting from rest. Planner will correct this later.
|
||||
// If system motion, the system motion block always is assumed to start from rest and end at a complete stop.
|
||||
block->entry_speed_sqr = 0.0;
|
||||
block->max_junction_speed_sqr = 0.0; // Starting from rest. Enforce start from zero velocity.
|
||||
} else {
|
||||
if (junction_cos_theta < -0.999999) {
|
||||
// Junction is a straight line or 180 degrees. Junction speed is infinite.
|
||||
block->max_junction_speed_sqr = SOME_LARGE_VALUE;
|
||||
} else {
|
||||
convert_delta_vector_to_unit_vector(junction_unit_vec);
|
||||
float junction_acceleration = limit_value_by_axis_maximum(settings.acceleration, junction_unit_vec);
|
||||
float sin_theta_d2 = sqrt(0.5*(1.0-junction_cos_theta)); // Trig half angle identity. Always positive.
|
||||
block->max_junction_speed_sqr = MAX( MINIMUM_JUNCTION_SPEED*MINIMUM_JUNCTION_SPEED,
|
||||
(junction_acceleration * settings.junction_deviation * sin_theta_d2)/(1.0-sin_theta_d2) );
|
||||
}
|
||||
// Compute maximum allowable entry speed at junction by centripetal acceleration approximation.
|
||||
// Let a circle be tangent to both previous and current path line segments, where the junction
|
||||
// deviation is defined as the distance from the junction to the closest edge of the circle,
|
||||
// colinear with the circle center. The circular segment joining the two paths represents the
|
||||
// path of centripetal acceleration. Solve for max velocity based on max acceleration about the
|
||||
// radius of the circle, defined indirectly by junction deviation. This may be also viewed as
|
||||
// path width or max_jerk in the previous Grbl version. This approach does not actually deviate
|
||||
// from path, but used as a robust way to compute cornering speeds, as it takes into account the
|
||||
// nonlinearities of both the junction angle and junction velocity.
|
||||
//
|
||||
// NOTE: If the junction deviation value is finite, Grbl executes the motions in an exact path
|
||||
// mode (G61). If the junction deviation value is zero, Grbl will execute the motion in an exact
|
||||
// stop mode (G61.1) manner. In the future, if continuous mode (G64) is desired, the math here
|
||||
// is exactly the same. Instead of motioning all the way to junction point, the machine will
|
||||
// just follow the arc circle defined here. The Arduino doesn't have the CPU cycles to perform
|
||||
// a continuous mode path, but ARM-based microcontrollers most certainly do.
|
||||
//
|
||||
// NOTE: The max junction speed is a fixed value, since machine acceleration limits cannot be
|
||||
// changed dynamically during operation nor can the line move geometry. This must be kept in
|
||||
// memory in the event of a feedrate override changing the nominal speeds of blocks, which can
|
||||
// change the overall maximum entry speed conditions of all blocks.
|
||||
float junction_unit_vec[N_AXIS];
|
||||
float junction_cos_theta = 0.0;
|
||||
for (idx = 0; idx < N_AXIS; idx++) {
|
||||
junction_cos_theta -= pl.previous_unit_vec[idx] * unit_vec[idx];
|
||||
junction_unit_vec[idx] = unit_vec[idx] - pl.previous_unit_vec[idx];
|
||||
}
|
||||
// NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta).
|
||||
if (junction_cos_theta > 0.999999) {
|
||||
// For a 0 degree acute junction, just set minimum junction speed.
|
||||
block->max_junction_speed_sqr = MINIMUM_JUNCTION_SPEED * MINIMUM_JUNCTION_SPEED;
|
||||
} else {
|
||||
if (junction_cos_theta < -0.999999) {
|
||||
// Junction is a straight line or 180 degrees. Junction speed is infinite.
|
||||
block->max_junction_speed_sqr = SOME_LARGE_VALUE;
|
||||
} else {
|
||||
convert_delta_vector_to_unit_vector(junction_unit_vec);
|
||||
float junction_acceleration = limit_value_by_axis_maximum(settings.acceleration, junction_unit_vec);
|
||||
float sin_theta_d2 = sqrt(0.5 * (1.0 - junction_cos_theta)); // Trig half angle identity. Always positive.
|
||||
block->max_junction_speed_sqr = MAX(MINIMUM_JUNCTION_SPEED * MINIMUM_JUNCTION_SPEED,
|
||||
(junction_acceleration * settings.junction_deviation * sin_theta_d2) / (1.0 - sin_theta_d2));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Block system motion from updating this data to ensure next g-code motion is computed correctly.
|
||||
if (!(block->condition & PL_COND_FLAG_SYSTEM_MOTION)) {
|
||||
float nominal_speed = plan_compute_profile_nominal_speed(block);
|
||||
plan_compute_profile_parameters(block, nominal_speed, pl.previous_nominal_speed);
|
||||
pl.previous_nominal_speed = nominal_speed;
|
||||
|
||||
// Update previous path unit_vector and planner position.
|
||||
memcpy(pl.previous_unit_vec, unit_vec, sizeof(unit_vec)); // pl.previous_unit_vec[] = unit_vec[]
|
||||
memcpy(pl.position, target_steps, sizeof(target_steps)); // pl.position[] = target_steps[]
|
||||
|
||||
// New block is all set. Update buffer head and next buffer head indices.
|
||||
block_buffer_head = next_buffer_head;
|
||||
next_buffer_head = plan_next_block_index(block_buffer_head);
|
||||
|
||||
// Finish up by recalculating the plan with the new block.
|
||||
planner_recalculate();
|
||||
}
|
||||
return(PLAN_OK);
|
||||
// Block system motion from updating this data to ensure next g-code motion is computed correctly.
|
||||
if (!(block->condition & PL_COND_FLAG_SYSTEM_MOTION)) {
|
||||
float nominal_speed = plan_compute_profile_nominal_speed(block);
|
||||
plan_compute_profile_parameters(block, nominal_speed, pl.previous_nominal_speed);
|
||||
pl.previous_nominal_speed = nominal_speed;
|
||||
// Update previous path unit_vector and planner position.
|
||||
memcpy(pl.previous_unit_vec, unit_vec, sizeof(unit_vec)); // pl.previous_unit_vec[] = unit_vec[]
|
||||
memcpy(pl.position, target_steps, sizeof(target_steps)); // pl.position[] = target_steps[]
|
||||
// New block is all set. Update buffer head and next buffer head indices.
|
||||
block_buffer_head = next_buffer_head;
|
||||
next_buffer_head = plan_next_block_index(block_buffer_head);
|
||||
// Finish up by recalculating the plan with the new block.
|
||||
planner_recalculate();
|
||||
}
|
||||
return (PLAN_OK);
|
||||
}
|
||||
|
||||
// Reset the planner position vectors. Called by the system abort/initialization routine.
|
||||
void plan_sync_position()
|
||||
{
|
||||
// TODO: For motor configurations not in the same coordinate frame as the machine position,
|
||||
// this function needs to be updated to accomodate the difference.
|
||||
uint8_t idx;
|
||||
for (idx=0; idx<N_AXIS; idx++) {
|
||||
#ifdef COREXY
|
||||
if (idx==X_AXIS) {
|
||||
pl.position[X_AXIS] = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||
} else if (idx==Y_AXIS) {
|
||||
pl.position[Y_AXIS] = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||
} else {
|
||||
void plan_sync_position() {
|
||||
// TODO: For motor configurations not in the same coordinate frame as the machine position,
|
||||
// this function needs to be updated to accomodate the difference.
|
||||
uint8_t idx;
|
||||
for (idx = 0; idx < N_AXIS; idx++) {
|
||||
#ifdef COREXY
|
||||
if (idx == X_AXIS)
|
||||
pl.position[X_AXIS] = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||
else if (idx == Y_AXIS)
|
||||
pl.position[Y_AXIS] = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||
else
|
||||
pl.position[idx] = sys_position[idx];
|
||||
#else
|
||||
pl.position[idx] = sys_position[idx];
|
||||
}
|
||||
#else
|
||||
pl.position[idx] = sys_position[idx];
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Returns the number of available blocks are in the planner buffer.
|
||||
uint8_t plan_get_block_buffer_available()
|
||||
{
|
||||
if (block_buffer_head >= block_buffer_tail) { return((BLOCK_BUFFER_SIZE-1)-(block_buffer_head-block_buffer_tail)); }
|
||||
return((block_buffer_tail-block_buffer_head-1));
|
||||
uint8_t plan_get_block_buffer_available() {
|
||||
if (block_buffer_head >= block_buffer_tail) return ((BLOCK_BUFFER_SIZE - 1) - (block_buffer_head - block_buffer_tail));
|
||||
return ((block_buffer_tail - block_buffer_head - 1));
|
||||
}
|
||||
|
||||
|
||||
// Returns the number of active blocks are in the planner buffer.
|
||||
// NOTE: Deprecated. Not used unless classic status reports are enabled in config.h
|
||||
uint8_t plan_get_block_buffer_count()
|
||||
{
|
||||
if (block_buffer_head >= block_buffer_tail) { return(block_buffer_head-block_buffer_tail); }
|
||||
return(BLOCK_BUFFER_SIZE - (block_buffer_tail-block_buffer_head));
|
||||
uint8_t plan_get_block_buffer_count() {
|
||||
if (block_buffer_head >= block_buffer_tail) return (block_buffer_head - block_buffer_tail);
|
||||
return (BLOCK_BUFFER_SIZE - (block_buffer_tail - block_buffer_head));
|
||||
}
|
||||
|
||||
|
||||
// Re-initialize buffer plan with a partially completed block, assumed to exist at the buffer tail.
|
||||
// Called after a steppers have come to a complete stop for a feed hold and the cycle is stopped.
|
||||
void plan_cycle_reinitialize()
|
||||
{
|
||||
// Re-plan from a complete stop. Reset planner entry speeds and buffer planned pointer.
|
||||
st_update_plan_block_parameters();
|
||||
block_buffer_planned = block_buffer_tail;
|
||||
planner_recalculate();
|
||||
void plan_cycle_reinitialize() {
|
||||
// Re-plan from a complete stop. Reset planner entry speeds and buffer planned pointer.
|
||||
st_update_plan_block_parameters();
|
||||
block_buffer_planned = block_buffer_tail;
|
||||
planner_recalculate();
|
||||
}
|
||||
|
@ -1,43 +1,43 @@
|
||||
/*
|
||||
planner.h - buffers movement commands and manages the acceleration profile plan
|
||||
Part of Grbl
|
||||
|
||||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
#ifndef planner_h
|
||||
#define planner_h
|
||||
|
||||
|
||||
// The number of linear motions that can be in the plan at any give time
|
||||
#ifndef BLOCK_BUFFER_SIZE
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
#define BLOCK_BUFFER_SIZE 15
|
||||
#else
|
||||
#define BLOCK_BUFFER_SIZE 16
|
||||
#endif
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
#define BLOCK_BUFFER_SIZE 15
|
||||
#else
|
||||
#define BLOCK_BUFFER_SIZE 16
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
// Returned status message from planner.
|
||||
#define PLAN_OK true
|
||||
#define PLAN_EMPTY_BLOCK false
|
||||
|
||||
|
||||
// Define planner data condition flags. Used to denote running conditions of a block.
|
||||
#define PL_COND_FLAG_RAPID_MOTION bit(0)
|
||||
#define PL_COND_FLAG_SYSTEM_MOTION bit(1) // Single motion. Circumvents planner state. Used by home/park.
|
||||
@ -49,104 +49,104 @@
|
||||
#define PL_COND_FLAG_COOLANT_MIST bit(7)
|
||||
#define PL_COND_MOTION_MASK (PL_COND_FLAG_RAPID_MOTION|PL_COND_FLAG_SYSTEM_MOTION|PL_COND_FLAG_NO_FEED_OVERRIDE)
|
||||
#define PL_COND_ACCESSORY_MASK (PL_COND_FLAG_SPINDLE_CW|PL_COND_FLAG_SPINDLE_CCW|PL_COND_FLAG_COOLANT_FLOOD|PL_COND_FLAG_COOLANT_MIST)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
// This struct stores a linear movement of a g-code block motion with its critical "nominal" values
|
||||
// are as specified in the source g-code.
|
||||
typedef struct {
|
||||
// Fields used by the bresenham algorithm for tracing the line
|
||||
// NOTE: Used by stepper algorithm to execute the block correctly. Do not alter these values.
|
||||
uint32_t steps[N_AXIS]; // Step count along each axis
|
||||
uint32_t step_event_count; // The maximum step axis count and number of steps required to complete this block.
|
||||
uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
|
||||
|
||||
// Block condition data to ensure correct execution depending on states and overrides.
|
||||
uint8_t condition; // Block bitflag variable defining block run conditions. Copied from pl_line_data.
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
// Fields used by the bresenham algorithm for tracing the line
|
||||
// NOTE: Used by stepper algorithm to execute the block correctly. Do not alter these values.
|
||||
uint32_t steps[N_AXIS]; // Step count along each axis
|
||||
uint32_t step_event_count; // The maximum step axis count and number of steps required to complete this block.
|
||||
uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
|
||||
|
||||
// Block condition data to ensure correct execution depending on states and overrides.
|
||||
uint8_t condition; // Block bitflag variable defining block run conditions. Copied from pl_line_data.
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
int32_t line_number; // Block line number for real-time reporting. Copied from pl_line_data.
|
||||
#endif
|
||||
|
||||
// Fields used by the motion planner to manage acceleration. Some of these values may be updated
|
||||
// by the stepper module during execution of special motion cases for replanning purposes.
|
||||
float entry_speed_sqr; // The current planned entry speed at block junction in (mm/min)^2
|
||||
float max_entry_speed_sqr; // Maximum allowable entry speed based on the minimum of junction limit and
|
||||
// neighboring nominal speeds with overrides in (mm/min)^2
|
||||
float acceleration; // Axis-limit adjusted line acceleration in (mm/min^2). Does not change.
|
||||
float millimeters; // The remaining distance for this block to be executed in (mm).
|
||||
// NOTE: This value may be altered by stepper algorithm during execution.
|
||||
|
||||
// Stored rate limiting data used by planner when changes occur.
|
||||
float max_junction_speed_sqr; // Junction entry speed limit based on direction vectors in (mm/min)^2
|
||||
float rapid_rate; // Axis-limit adjusted maximum rate for this block direction in (mm/min)
|
||||
float programmed_rate; // Programmed rate of this block (mm/min).
|
||||
|
||||
//#ifdef VARIABLE_SPINDLE
|
||||
#endif
|
||||
|
||||
// Fields used by the motion planner to manage acceleration. Some of these values may be updated
|
||||
// by the stepper module during execution of special motion cases for replanning purposes.
|
||||
float entry_speed_sqr; // The current planned entry speed at block junction in (mm/min)^2
|
||||
float max_entry_speed_sqr; // Maximum allowable entry speed based on the minimum of junction limit and
|
||||
// neighboring nominal speeds with overrides in (mm/min)^2
|
||||
float acceleration; // Axis-limit adjusted line acceleration in (mm/min^2). Does not change.
|
||||
float millimeters; // The remaining distance for this block to be executed in (mm).
|
||||
// NOTE: This value may be altered by stepper algorithm during execution.
|
||||
|
||||
// Stored rate limiting data used by planner when changes occur.
|
||||
float max_junction_speed_sqr; // Junction entry speed limit based on direction vectors in (mm/min)^2
|
||||
float rapid_rate; // Axis-limit adjusted maximum rate for this block direction in (mm/min)
|
||||
float programmed_rate; // Programmed rate of this block (mm/min).
|
||||
|
||||
//#ifdef VARIABLE_SPINDLE
|
||||
// Stored spindle speed data used by spindle overrides and resuming methods.
|
||||
float spindle_speed; // Block spindle speed. Copied from pl_line_data.
|
||||
//#endif
|
||||
//#endif
|
||||
} plan_block_t;
|
||||
|
||||
|
||||
// Planner data prototype. Must be used when passing new motions to the planner.
|
||||
typedef struct {
|
||||
float feed_rate; // Desired feed rate for line motion. Value is ignored, if rapid motion.
|
||||
float spindle_speed; // Desired spindle speed through line motion.
|
||||
uint8_t condition; // Bitflag variable to indicate planner conditions. See defines above.
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
float feed_rate; // Desired feed rate for line motion. Value is ignored, if rapid motion.
|
||||
float spindle_speed; // Desired spindle speed through line motion.
|
||||
uint8_t condition; // Bitflag variable to indicate planner conditions. See defines above.
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
int32_t line_number; // Desired line number to report when executing.
|
||||
#endif
|
||||
#endif
|
||||
} plan_line_data_t;
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
// Initialize and reset the motion plan subsystem
|
||||
void plan_reset(); // Reset all
|
||||
void plan_reset_buffer(); // Reset buffer only.
|
||||
|
||||
|
||||
// Add a new linear movement to the buffer. target[N_AXIS] is the signed, absolute target position
|
||||
// in millimeters. Feed rate specifies the speed of the motion. If feed rate is inverted, the feed
|
||||
// rate is taken to mean "frequency" and would complete the operation in 1/feed_rate minutes.
|
||||
uint8_t plan_buffer_line(float *target, plan_line_data_t *pl_data);
|
||||
|
||||
uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data);
|
||||
|
||||
// Called when the current block is no longer needed. Discards the block and makes the memory
|
||||
// availible for new blocks.
|
||||
void plan_discard_current_block();
|
||||
|
||||
|
||||
// Gets the planner block for the special system motion cases. (Parking/Homing)
|
||||
plan_block_t *plan_get_system_motion_block();
|
||||
|
||||
plan_block_t* plan_get_system_motion_block();
|
||||
|
||||
// Gets the current block. Returns NULL if buffer empty
|
||||
plan_block_t *plan_get_current_block();
|
||||
|
||||
plan_block_t* plan_get_current_block();
|
||||
|
||||
// Called periodically by step segment buffer. Mostly used internally by planner.
|
||||
uint8_t plan_next_block_index(uint8_t block_index);
|
||||
|
||||
|
||||
// Called by step segment buffer when computing executing block velocity profile.
|
||||
float plan_get_exec_block_exit_speed_sqr();
|
||||
|
||||
|
||||
// Called by main program during planner calculations and step segment buffer during initialization.
|
||||
float plan_compute_profile_nominal_speed(plan_block_t *block);
|
||||
|
||||
float plan_compute_profile_nominal_speed(plan_block_t* block);
|
||||
|
||||
// Re-calculates buffered motions profile parameters upon a motion-based override change.
|
||||
void plan_update_velocity_profile_parameters();
|
||||
|
||||
|
||||
// Reset the planner position vector (in steps)
|
||||
void plan_sync_position();
|
||||
|
||||
|
||||
// Reinitialize plan with a partially completed block
|
||||
void plan_cycle_reinitialize();
|
||||
|
||||
|
||||
// Returns the number of available blocks are in the planner buffer.
|
||||
uint8_t plan_get_block_buffer_available();
|
||||
|
||||
|
||||
// Returns the number of active blocks are in the planner buffer.
|
||||
// NOTE: Deprecated. Not used unless classic status reports are enabled in config.h
|
||||
uint8_t plan_get_block_buffer_count();
|
||||
|
||||
|
||||
// Returns the status of the block ring buffer. True, if buffer is full.
|
||||
uint8_t plan_check_full_buffer();
|
||||
|
||||
void plan_get_planner_mpos(float *target);
|
||||
|
||||
|
||||
|
||||
void plan_get_planner_mpos(float* target);
|
||||
|
||||
|
||||
#endif
|
@ -1,298 +0,0 @@
|
||||
/*
|
||||
kinematics_polar_coaster.cpp - Implements simple inverse kinematics for Grbl_ESP32
|
||||
Part of Grbl_ESP32
|
||||
|
||||
Copyright (c) 2019 Barton Dring @buildlog
|
||||
|
||||
|
||||
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/>.
|
||||
|
||||
Inverse kinematics determine the joint parameters required to get to a position
|
||||
in 3D space. Grbl will still work as 3 axes of steps, but these steps could
|
||||
represent angles, etc instead of linear units.
|
||||
|
||||
Unless forward kinematics are applied to the reporting, Grbl will report raw joint
|
||||
values instead of the normal Cartesian positions
|
||||
|
||||
How it works...
|
||||
|
||||
If you tell it to go to X10 Y10 Z10 in Cartesian space, for example, the equations
|
||||
will convert those values to the required joint values. In the case of a polar machine, X represents the radius,
|
||||
Y represents the polar degrees and Z would be unchanged.
|
||||
|
||||
In most cases, a straight line in Cartesian space could cause a curve in the new system.
|
||||
To fix this, the line is broken into very small segments and each segment is converted
|
||||
to the new space. While each segment is also distorted, the amount is so small it cannot be seen.
|
||||
|
||||
This segmentation is how normal Grbl draws arcs.
|
||||
|
||||
Feed Rate
|
||||
|
||||
Feed rate is given in steps/time. Due to the new coordinate units and non linearity issues, the
|
||||
feed rate may need to be adjusted. The ratio of the step distances in the original coordinate system
|
||||
determined and applied to the feed rate.
|
||||
|
||||
TODO:
|
||||
Add y offset, for completeness
|
||||
Add ZERO_NON_HOMED_AXES option
|
||||
|
||||
|
||||
*/
|
||||
#include "grbl.h"
|
||||
#ifdef CPU_MAP_POLAR_COASTER
|
||||
#ifdef USE_KINEMATICS
|
||||
|
||||
static float last_angle = 0;
|
||||
static float last_radius = 0;
|
||||
|
||||
// this get called before homing
|
||||
// return false to complete normal home
|
||||
// return true to exit normal homing
|
||||
bool kinematics_pre_homing(uint8_t cycle_mask) {
|
||||
// cycle mask not used for polar coaster
|
||||
|
||||
// zero the axes that are not homed
|
||||
sys_position[Y_AXIS] = 0.0f;
|
||||
sys_position[Z_AXIS] = SERVO_Z_RANGE_MAX * settings.steps_per_mm[Z_AXIS]; // Move pen up.
|
||||
|
||||
return false; // finish normal homing cycle
|
||||
}
|
||||
|
||||
void kinematics_post_homing() {
|
||||
// sync the X axis (do not need sync but make it for the fail safe)
|
||||
last_radius = sys_position[X_AXIS];
|
||||
// reset the internal angle value
|
||||
last_angle = 0;
|
||||
}
|
||||
|
||||
/*
|
||||
Apply inverse kinematics for a polar system
|
||||
|
||||
float target: The desired target location in machine space
|
||||
plan_line_data_t *pl_data: Plan information like feed rate, etc
|
||||
float *position: The previous "from" location of the move
|
||||
|
||||
Note: It is assumed only the radius axis (X) is homed and only X and Z have offsets
|
||||
|
||||
|
||||
*/
|
||||
void inverse_kinematics(float *target, plan_line_data_t *pl_data, float *position)
|
||||
{
|
||||
//static float last_angle = 0;
|
||||
//static float last_radius = 0;
|
||||
|
||||
float dx, dy, dz; // distances in each cartesian axis
|
||||
float p_dx, p_dy, p_dz; // distances in each polar axis
|
||||
|
||||
float dist, polar_dist; // the distances in both systems...used to determine feed rate
|
||||
|
||||
uint32_t segment_count; // number of segments the move will be broken in to.
|
||||
float seg_target[N_AXIS]; // The target of the current segment
|
||||
|
||||
float polar[N_AXIS]; // target location in polar coordinates
|
||||
|
||||
float x_offset = gc_state.coord_system[X_AXIS]+gc_state.coord_offset[X_AXIS]; // offset from machine coordinate system
|
||||
float z_offset = gc_state.coord_system[Z_AXIS]+gc_state.coord_offset[Z_AXIS]; // offset from machine coordinate system
|
||||
|
||||
//grbl_sendf(CLIENT_SERIAL, "Position: %4.2f %4.2f %4.2f \r\n", position[X_AXIS] - x_offset, position[Y_AXIS], position[Z_AXIS]);
|
||||
//grbl_sendf(CLIENT_SERIAL, "Target: %4.2f %4.2f %4.2f \r\n", target[X_AXIS] - x_offset, target[Y_AXIS], target[Z_AXIS]);
|
||||
|
||||
// calculate cartesian move distance for each axis
|
||||
dx = target[X_AXIS] - position[X_AXIS];
|
||||
dy = target[Y_AXIS] - position[Y_AXIS];
|
||||
dz = target[Z_AXIS] - position[Z_AXIS];
|
||||
|
||||
// calculate the total X,Y axis move distance
|
||||
// Z axis is the same in both coord systems, so it is ignored
|
||||
dist = sqrt( (dx * dx) + (dy * dy) + (dz * dz));
|
||||
|
||||
if (pl_data->condition & PL_COND_FLAG_RAPID_MOTION) {
|
||||
segment_count = 1; // rapid G0 motion is not used to draw, so skip the segmentation
|
||||
} else {
|
||||
segment_count = ceil(dist / SEGMENT_LENGTH); // determine the number of segments we need ... round up so there is at least 1
|
||||
}
|
||||
|
||||
dist /= segment_count; // segment distance
|
||||
|
||||
|
||||
for(uint32_t segment = 1; segment <= segment_count; segment++) {
|
||||
// determine this segment's target
|
||||
seg_target[X_AXIS] = position[X_AXIS] + (dx / float(segment_count) * segment) - x_offset;
|
||||
seg_target[Y_AXIS] = position[Y_AXIS] + (dy / float(segment_count) * segment);
|
||||
seg_target[Z_AXIS] = position[Z_AXIS] + (dz / float(segment_count) * segment) - z_offset;
|
||||
|
||||
calc_polar(seg_target, polar, last_angle);
|
||||
|
||||
// begin determining new feed rate
|
||||
|
||||
// calculate move distance for each axis
|
||||
p_dx = polar[RADIUS_AXIS] - last_radius;
|
||||
p_dy = polar[POLAR_AXIS] - last_angle;
|
||||
p_dz = dz;
|
||||
|
||||
polar_dist = sqrt( (p_dx * p_dx) + (p_dy * p_dy) +(p_dz * p_dz)); // calculate the total move distance
|
||||
|
||||
float polar_rate_multiply = 1.0; // fail safe rate
|
||||
if (polar_dist == 0 || dist == 0) { // prevent 0 feed rate and division by 0
|
||||
polar_rate_multiply = 1.0; // default to same feed rate
|
||||
} else {
|
||||
// calc a feed rate multiplier
|
||||
polar_rate_multiply = polar_dist / dist;
|
||||
if (polar_rate_multiply < 0.5) { // prevent much slower speed
|
||||
polar_rate_multiply = 0.5;
|
||||
}
|
||||
}
|
||||
|
||||
pl_data->feed_rate *= polar_rate_multiply; // apply the distance ratio between coord systems
|
||||
|
||||
// end determining new feed rate
|
||||
|
||||
polar[RADIUS_AXIS] += x_offset;
|
||||
polar[Z_AXIS] += z_offset;
|
||||
|
||||
last_radius = polar[RADIUS_AXIS];
|
||||
last_angle = polar[POLAR_AXIS];
|
||||
|
||||
mc_line(polar, pl_data);
|
||||
}
|
||||
|
||||
// TO DO don't need a feedrate for rapids
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
Forward kinematics converts position back to the original cartesian system. It is
|
||||
typically used for reporting
|
||||
|
||||
For example, on a polar machine, you tell it to go to a place like X10Y10. It
|
||||
converts to a radius and angle using inverse kinematics. The machine posiiton is now
|
||||
in those units X14.14 (radius) and Y45 (degrees). If you want to report those units as
|
||||
X10,Y10, you would use forward kinematics
|
||||
|
||||
position = the current machine position
|
||||
converted = position with forward kinematics applied.
|
||||
|
||||
*/
|
||||
void forward_kinematics(float *position)
|
||||
{
|
||||
float original_position[N_AXIS]; // temporary storage of original
|
||||
float print_position[N_AXIS];
|
||||
int32_t current_position[N_AXIS]; // Copy current state of the system position variable
|
||||
|
||||
memcpy(current_position,sys_position,sizeof(sys_position));
|
||||
system_convert_array_steps_to_mpos(print_position,current_position);
|
||||
|
||||
original_position[X_AXIS] = print_position[X_AXIS] - gc_state.coord_system[X_AXIS]+gc_state.coord_offset[X_AXIS];
|
||||
original_position[Y_AXIS] = print_position[Y_AXIS] - gc_state.coord_system[Y_AXIS]+gc_state.coord_offset[Y_AXIS];
|
||||
original_position[Z_AXIS] = print_position[Z_AXIS] - gc_state.coord_system[Z_AXIS]+gc_state.coord_offset[Z_AXIS];
|
||||
|
||||
position[X_AXIS] = cos(radians(original_position[Y_AXIS])) * original_position[X_AXIS] * -1;
|
||||
position[Y_AXIS] = sin(radians(original_position[Y_AXIS])) * original_position[X_AXIS];
|
||||
position[Z_AXIS] = original_position[Z_AXIS]; // unchanged
|
||||
}
|
||||
|
||||
// helper functions
|
||||
|
||||
/*******************************************
|
||||
* Calculate polar values from Cartesian values
|
||||
* float target_xyz: An array of target axis positions in Cartesian (xyz) space
|
||||
* float polar: An array to return the polar values
|
||||
* float last_angle: The polar angle of the "from" point.
|
||||
*
|
||||
* Angle calculated is 0 to 360, but you don't want a line to go from 350 to 10. This would
|
||||
* be a long line backwards. You want it to go from 350 to 370. The same is true going the other way.
|
||||
*
|
||||
* This means the angle could accumulate to very high positive or negative values over the coarse of
|
||||
* a long job.
|
||||
*
|
||||
*/
|
||||
void calc_polar(float *target_xyz, float *polar, float last_angle)
|
||||
{
|
||||
float delta_ang; // the difference from the last and next angle
|
||||
|
||||
polar[RADIUS_AXIS] = hypot_f(target_xyz[X_AXIS], target_xyz[Y_AXIS]);
|
||||
|
||||
if (polar[RADIUS_AXIS] == 0) {
|
||||
polar[POLAR_AXIS] = last_angle; // don't care about angle at center
|
||||
}
|
||||
else {
|
||||
polar[POLAR_AXIS] = atan2(target_xyz[Y_AXIS], target_xyz[X_AXIS]) * 180.0 / M_PI;
|
||||
|
||||
// no negative angles...we want the absolute angle not -90, use 270
|
||||
polar[POLAR_AXIS] = abs_angle(polar[POLAR_AXIS]);
|
||||
}
|
||||
|
||||
polar[Z_AXIS] = target_xyz[Z_AXIS]; // Z is unchanged
|
||||
|
||||
delta_ang = polar[POLAR_AXIS] - abs_angle(last_angle);
|
||||
|
||||
// if the delta is above 180 degrees it means we are crossing the 0 degree line
|
||||
if ( fabs(delta_ang) <= 180.0) {
|
||||
polar[POLAR_AXIS] = last_angle + delta_ang;
|
||||
} else {
|
||||
if (delta_ang > 0.0) { // crossing zero counter clockwise
|
||||
polar[POLAR_AXIS] = last_angle - (360.0 - delta_ang);
|
||||
} else {
|
||||
polar[POLAR_AXIS] = last_angle + delta_ang + 360.0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Return a 0-360 angle ... fix above 360 and below zero
|
||||
float abs_angle(float ang) {
|
||||
ang = fmod(ang, 360.0); // 0-360 or 0 to -360
|
||||
|
||||
if (ang < 0.0) {
|
||||
ang = 360.0 + ang;
|
||||
}
|
||||
return ang;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// Polar coaster has macro buttons, this handles those button pushes.
|
||||
void user_defined_macro(uint8_t index)
|
||||
{
|
||||
switch (index) {
|
||||
#ifdef MACRO_BUTTON_0_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_0:
|
||||
inputBuffer.push("$H\r"); // home machine
|
||||
break;
|
||||
#endif
|
||||
#ifdef MACRO_BUTTON_1_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_1:
|
||||
inputBuffer.push("[ESP220]/1.nc\r"); // run SD card file 1.nc
|
||||
break;
|
||||
#endif
|
||||
#ifdef MACRO_BUTTON_2_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_2:
|
||||
inputBuffer.push("[ESP220]/2.nc\r"); // run SD card file 2.nc
|
||||
break;
|
||||
#endif
|
||||
#ifdef MACRO_BUTTON_3_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_3:
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// handle the M30 command
|
||||
void user_m30() {
|
||||
inputBuffer.push("$H\r");
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
@ -50,67 +50,58 @@
|
||||
|
||||
|
||||
// Prints an uint8 variable in base 10.
|
||||
void print_uint8_base10(uint8_t n)
|
||||
{
|
||||
uint8_t digit_a = 0;
|
||||
uint8_t digit_b = 0;
|
||||
if (n >= 100) { // 100-255
|
||||
digit_a = '0' + n % 10;
|
||||
n /= 10;
|
||||
}
|
||||
if (n >= 10) { // 10-99
|
||||
digit_b = '0' + n % 10;
|
||||
n /= 10;
|
||||
}
|
||||
serial_write('0' + n);
|
||||
if (digit_b) { serial_write(digit_b); }
|
||||
if (digit_a) { serial_write(digit_a); }
|
||||
void print_uint8_base10(uint8_t n) {
|
||||
uint8_t digit_a = 0;
|
||||
uint8_t digit_b = 0;
|
||||
if (n >= 100) { // 100-255
|
||||
digit_a = '0' + n % 10;
|
||||
n /= 10;
|
||||
}
|
||||
if (n >= 10) { // 10-99
|
||||
digit_b = '0' + n % 10;
|
||||
n /= 10;
|
||||
}
|
||||
serial_write('0' + n);
|
||||
if (digit_b) serial_write(digit_b);
|
||||
if (digit_a) serial_write(digit_a);
|
||||
}
|
||||
|
||||
|
||||
// Prints an uint8 variable in base 2 with desired number of desired digits.
|
||||
void print_uint8_base2_ndigit(uint8_t n, uint8_t digits) {
|
||||
unsigned char buf[digits];
|
||||
uint8_t i = 0;
|
||||
|
||||
for (; i < digits; i++) {
|
||||
buf[i] = n % 2 ;
|
||||
n /= 2;
|
||||
}
|
||||
|
||||
for (; i > 0; i--)
|
||||
Serial.print('0' + buf[i - 1]);
|
||||
unsigned char buf[digits];
|
||||
uint8_t i = 0;
|
||||
for (; i < digits; i++) {
|
||||
buf[i] = n % 2 ;
|
||||
n /= 2;
|
||||
}
|
||||
for (; i > 0; i--)
|
||||
Serial.print('0' + buf[i - 1]);
|
||||
}
|
||||
|
||||
|
||||
void print_uint32_base10(uint32_t n)
|
||||
{
|
||||
if (n == 0) {
|
||||
Serial.print('0');
|
||||
return;
|
||||
}
|
||||
|
||||
unsigned char buf[10];
|
||||
uint8_t i = 0;
|
||||
|
||||
while (n > 0) {
|
||||
buf[i++] = n % 10;
|
||||
n /= 10;
|
||||
}
|
||||
|
||||
for (; i > 0; i--)
|
||||
Serial.print('0' + buf[i-1]);
|
||||
void print_uint32_base10(uint32_t n) {
|
||||
if (n == 0) {
|
||||
Serial.print('0');
|
||||
return;
|
||||
}
|
||||
unsigned char buf[10];
|
||||
uint8_t i = 0;
|
||||
while (n > 0) {
|
||||
buf[i++] = n % 10;
|
||||
n /= 10;
|
||||
}
|
||||
for (; i > 0; i--)
|
||||
Serial.print('0' + buf[i - 1]);
|
||||
}
|
||||
|
||||
|
||||
void printInteger(long n)
|
||||
{
|
||||
if (n < 0) {
|
||||
Serial.print('-');
|
||||
print_uint32_base10(-n);
|
||||
} else {
|
||||
print_uint32_base10(n);
|
||||
}
|
||||
void printInteger(long n) {
|
||||
if (n < 0) {
|
||||
Serial.print('-');
|
||||
print_uint32_base10(-n);
|
||||
} else
|
||||
print_uint32_base10(n);
|
||||
}
|
||||
|
||||
|
||||
@ -119,9 +110,8 @@ void printInteger(long n)
|
||||
// may be set by the user. The integer is then efficiently converted to a string.
|
||||
// NOTE: AVR '%' and '/' integer operations are very efficient. Bitshifting speed-up
|
||||
// techniques are actually just slightly slower. Found this out the hard way.
|
||||
void printFloat(float n, uint8_t decimal_places)
|
||||
{
|
||||
Serial.print(n, decimal_places);
|
||||
void printFloat(float n, uint8_t decimal_places) {
|
||||
Serial.print(n, decimal_places);
|
||||
}
|
||||
|
||||
|
||||
@ -130,11 +120,10 @@ void printFloat(float n, uint8_t decimal_places)
|
||||
// - CoordValue: Handles all position or coordinate values in inches or mm reporting.
|
||||
// - RateValue: Handles feed rate and current velocity in inches or mm reporting.
|
||||
void printFloat_CoordValue(float n) {
|
||||
if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)) {
|
||||
printFloat(n*INCH_PER_MM,N_DECIMAL_COORDVALUE_INCH);
|
||||
} else {
|
||||
printFloat(n,N_DECIMAL_COORDVALUE_MM);
|
||||
}
|
||||
if (bit_istrue(settings.flags, BITFLAG_REPORT_INCHES))
|
||||
printFloat(n * INCH_PER_MM, N_DECIMAL_COORDVALUE_INCH);
|
||||
else
|
||||
printFloat(n, N_DECIMAL_COORDVALUE_MM);
|
||||
}
|
||||
|
||||
// Debug tool to print free memory in bytes at the called point.
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
@ -26,9 +26,9 @@
|
||||
#define print_h
|
||||
|
||||
|
||||
void printString(const char *s);
|
||||
void printString(const char* s);
|
||||
|
||||
void printPgmString(const char *s);
|
||||
void printPgmString(const char* s);
|
||||
|
||||
void printInteger(long n);
|
||||
|
||||
|
@ -3,7 +3,7 @@
|
||||
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
|
||||
|
||||
@ -29,17 +29,14 @@ uint8_t probe_invert_mask;
|
||||
|
||||
|
||||
// Probe pin initialization routine.
|
||||
void probe_init()
|
||||
{
|
||||
void probe_init() {
|
||||
#ifdef PROBE_PIN
|
||||
#ifdef DISABLE_PROBE_PIN_PULL_UP
|
||||
#ifdef DISABLE_PROBE_PIN_PULL_UP
|
||||
pinMode(PROBE_PIN, INPUT);
|
||||
#else
|
||||
#else
|
||||
pinMode(PROBE_PIN, INPUT_PULLUP); // Enable internal pull-up resistors. Normal high operation.
|
||||
#endif
|
||||
|
||||
|
||||
probe_configure_invert_mask(false); // Initialize invert mask.
|
||||
#endif
|
||||
probe_configure_invert_mask(false); // Initialize invert mask.
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -47,20 +44,18 @@ void probe_init()
|
||||
// Called by probe_init() and the mc_probe() routines. Sets up the probe pin invert mask to
|
||||
// appropriately set the pin logic according to setting for normal-high/normal-low operation
|
||||
// and the probing cycle modes for toward-workpiece/away-from-workpiece.
|
||||
void probe_configure_invert_mask(uint8_t is_probe_away)
|
||||
{
|
||||
probe_invert_mask = 0; // Initialize as zero.
|
||||
if (bit_isfalse(settings.flags,BITFLAG_INVERT_PROBE_PIN)) { probe_invert_mask ^= PROBE_MASK; }
|
||||
if (is_probe_away) { probe_invert_mask ^= PROBE_MASK; }
|
||||
void probe_configure_invert_mask(uint8_t is_probe_away) {
|
||||
probe_invert_mask = 0; // Initialize as zero.
|
||||
if (bit_isfalse(settings.flags, BITFLAG_INVERT_PROBE_PIN)) probe_invert_mask ^= PROBE_MASK;
|
||||
if (is_probe_away) probe_invert_mask ^= PROBE_MASK;
|
||||
}
|
||||
|
||||
// Returns the probe pin state. Triggered = true. Called by gcode parser and probe state monitor.
|
||||
uint8_t probe_get_state()
|
||||
{
|
||||
uint8_t probe_get_state() {
|
||||
#ifdef PROBE_PIN
|
||||
return((digitalRead(PROBE_PIN)) ^ probe_invert_mask);
|
||||
return ((digitalRead(PROBE_PIN)) ^ probe_invert_mask);
|
||||
#else
|
||||
return false;
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -68,11 +63,10 @@ uint8_t probe_get_state()
|
||||
// Monitors probe pin state and records the system position when detected. Called by the
|
||||
// stepper ISR per ISR tick.
|
||||
// NOTE: This function must be extremely efficient as to not bog down the stepper ISR.
|
||||
void probe_state_monitor()
|
||||
{
|
||||
if (probe_get_state()) {
|
||||
sys_probe_state = PROBE_OFF;
|
||||
memcpy(sys_probe_position, sys_position, sizeof(sys_position));
|
||||
bit_true(sys_rt_exec_state, EXEC_MOTION_CANCEL);
|
||||
}
|
||||
void probe_state_monitor() {
|
||||
if (probe_get_state()) {
|
||||
sys_probe_state = PROBE_OFF;
|
||||
memcpy(sys_probe_position, sys_position, sizeof(sys_position));
|
||||
bit_true(sys_rt_exec_state, EXEC_MOTION_CANCEL);
|
||||
}
|
||||
}
|
||||
|
@ -3,7 +3,7 @@
|
||||
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
|
||||
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -4,7 +4,7 @@
|
||||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
@ -32,7 +32,7 @@
|
||||
// memory space we can invest into here or we re-write the g-code parser not to have this
|
||||
// buffer.
|
||||
#ifndef LINE_BUFFER_SIZE
|
||||
#define LINE_BUFFER_SIZE 80
|
||||
#define LINE_BUFFER_SIZE 80
|
||||
#endif
|
||||
|
||||
// Starts Grbl main loop. It handles all incoming characters from the serial port and executes
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -2,10 +2,10 @@
|
||||
report.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
|
||||
@ -115,13 +115,13 @@
|
||||
#define MSG_LEVEL_VERBOSE 5
|
||||
|
||||
// functions to send data to the user.
|
||||
void grbl_send(uint8_t client, const char *text);
|
||||
void grbl_sendf(uint8_t client, const char *format, ...);
|
||||
void grbl_msg_sendf(uint8_t client, uint8_t level, const char *format, ...);
|
||||
void grbl_send(uint8_t client, const char* text);
|
||||
void grbl_sendf(uint8_t client, const char* format, ...);
|
||||
void grbl_msg_sendf(uint8_t client, uint8_t level, const char* format, ...);
|
||||
|
||||
//function to notify
|
||||
void grbl_notify(const char *title, const char *msg);
|
||||
void grbl_notifyf(const char *title, const char *format, ...);
|
||||
void grbl_notify(const char* title, const char* msg);
|
||||
void grbl_notifyf(const char* title, const char* format, ...);
|
||||
|
||||
// Prints system status messages.
|
||||
void report_status_message(uint8_t status_code, uint8_t client);
|
||||
@ -143,7 +143,7 @@ void report_grbl_help(uint8_t client);
|
||||
void report_grbl_settings(uint8_t client, uint8_t show_extended);
|
||||
|
||||
// Prints an echo of the pre-parsed line received right before execution.
|
||||
void report_echo_line_received(char *line, uint8_t client);
|
||||
void report_echo_line_received(char* line, uint8_t client);
|
||||
|
||||
// Prints realtime status report
|
||||
void report_realtime_status(uint8_t client);
|
||||
@ -158,16 +158,16 @@ void report_ngc_parameters(uint8_t client);
|
||||
void report_gcode_modes(uint8_t client);
|
||||
|
||||
// Prints startup line when requested and executed.
|
||||
void report_startup_line(uint8_t n, char *line, uint8_t client);
|
||||
void report_execute_startup_message(char *line, uint8_t status_code, uint8_t client);
|
||||
void report_startup_line(uint8_t n, char* line, uint8_t client);
|
||||
void report_execute_startup_message(char* line, uint8_t status_code, uint8_t client);
|
||||
|
||||
// Prints build info and user info
|
||||
void report_build_info(char *line, uint8_t client);
|
||||
void report_build_info(char* line, uint8_t client);
|
||||
|
||||
void report_gcode_comment(char *comment);
|
||||
void report_gcode_comment(char* comment);
|
||||
|
||||
#ifdef DEBUG
|
||||
void report_realtime_debug();
|
||||
void report_realtime_debug();
|
||||
#endif
|
||||
|
||||
|
||||
|
@ -2,10 +2,10 @@
|
||||
serial.cpp - 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 modified for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
@ -18,27 +18,27 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
What is going on here?
|
||||
|
||||
|
||||
Original Grbl only supports communication via serial port. That is why this
|
||||
file is call serial.cpp. Grbl_ESP32 supports many "clients".
|
||||
|
||||
Clients are sources of commands like the serial port or a bluetooth connection.
|
||||
Clients are sources of commands like the serial port or a bluetooth connection.
|
||||
Multiple clients can be active at a time. If a client asks for status, only the client will
|
||||
receive the reply to the command.
|
||||
|
||||
The serial port acts as the debugging port because it is always on and does not
|
||||
need to be reconnected after reboot. Messages about the configuration and other events
|
||||
need to be reconnected after reboot. Messages about the configuration and other events
|
||||
are sent to the serial port automatically, without a request command. These are in the
|
||||
[MSG: xxxxxx] format. Gcode senders are should be OK with this because Grbl has always
|
||||
send some messages like this.
|
||||
|
||||
send some messages like this.
|
||||
|
||||
Important: It is up user that the clients play well together. Ideally, if one client
|
||||
is sending the gcode, the others should just be doing status, feedhold, etc.
|
||||
|
||||
Clients send gcode, grbl commands ($$, [ESP...], etc) and realtime commands (?,!.~, etc)
|
||||
Gcode and Grbl commands are a string of printable characters followed by a '\r' or '\n'
|
||||
Realtime commands are single characters with no '\r' or '\n'
|
||||
|
||||
|
||||
After sending a gcode or grbl command, you must wait for an OK to send another.
|
||||
This is because only a certain number of commands can be buffered at a time.
|
||||
Grbl will tell you when it is ready for another one with the OK.
|
||||
@ -46,7 +46,7 @@
|
||||
Realtime commands can be sent at any time and will acted upon very quickly.
|
||||
Realtime commands can be anywhere in the stream.
|
||||
|
||||
To allow the realtime commands to be randomly mixed in the stream of data, we
|
||||
To allow the realtime commands to be randomly mixed in the stream of data, we
|
||||
read all clients as fast as possible. The realtime commands are acted upon and the other charcters are
|
||||
placed into a client_buffer[client].
|
||||
|
||||
@ -65,99 +65,79 @@ static TaskHandle_t serialCheckTaskHandle = 0;
|
||||
InputBuffer client_buffer[CLIENT_COUNT]; // create a buffer for each client
|
||||
|
||||
// Returns the number of bytes available in a client buffer.
|
||||
uint8_t serial_get_rx_buffer_available(uint8_t client)
|
||||
{
|
||||
return client_buffer[client].availableforwrite();
|
||||
uint8_t serial_get_rx_buffer_available(uint8_t client) {
|
||||
return client_buffer[client].availableforwrite();
|
||||
}
|
||||
|
||||
void serial_init()
|
||||
{
|
||||
Serial.begin(BAUD_RATE);
|
||||
|
||||
// reset all buffers
|
||||
serial_reset_read_buffer(CLIENT_ALL);
|
||||
|
||||
grbl_send(CLIENT_SERIAL,"\r\n"); // create some white space after ESP32 boot info
|
||||
|
||||
serialCheckTaskHandle = 0;
|
||||
// create a task to check for incoming data
|
||||
xTaskCreatePinnedToCore( serialCheckTask, // task
|
||||
"serialCheckTask", // name for task
|
||||
8192, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&serialCheckTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
|
||||
void serial_init() {
|
||||
Serial.begin(BAUD_RATE);
|
||||
// reset all buffers
|
||||
serial_reset_read_buffer(CLIENT_ALL);
|
||||
grbl_send(CLIENT_SERIAL, "\r\n"); // create some white space after ESP32 boot info
|
||||
serialCheckTaskHandle = 0;
|
||||
// create a task to check for incoming data
|
||||
xTaskCreatePinnedToCore(serialCheckTask, // task
|
||||
"serialCheckTask", // name for task
|
||||
8192, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&serialCheckTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
}
|
||||
|
||||
|
||||
// this task runs and checks for data on all interfaces
|
||||
// REaltime stuff is acted upon, then characters are added to the appropriate buffer
|
||||
void serialCheckTask(void *pvParameters)
|
||||
{
|
||||
uint8_t data = 0;
|
||||
uint8_t client = CLIENT_ALL; // who sent the data
|
||||
|
||||
while(true) // run continuously
|
||||
{
|
||||
while (any_client_has_data()) {
|
||||
if (Serial.available())
|
||||
{
|
||||
client = CLIENT_SERIAL;
|
||||
data = Serial.read();
|
||||
}
|
||||
else if (inputBuffer.available()){
|
||||
void serialCheckTask(void* pvParameters) {
|
||||
uint8_t data = 0;
|
||||
uint8_t client = CLIENT_ALL; // who sent the data
|
||||
while (true) { // run continuously
|
||||
while (any_client_has_data()) {
|
||||
if (Serial.available()) {
|
||||
client = CLIENT_SERIAL;
|
||||
data = Serial.read();
|
||||
} else if (inputBuffer.available()) {
|
||||
client = CLIENT_INPUT;
|
||||
data = inputBuffer.read();
|
||||
}
|
||||
else
|
||||
{ //currently is wifi or BT but better to prepare both can be live
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
if(SerialBT.hasClient() && SerialBT.available()){
|
||||
} else {
|
||||
//currently is wifi or BT but better to prepare both can be live
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
if (SerialBT.hasClient() && SerialBT.available()) {
|
||||
client = CLIENT_BT;
|
||||
data = SerialBT.read();
|
||||
data = SerialBT.read();
|
||||
//Serial.write(data); // echo all data to serial
|
||||
} else {
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
if (Serial2Socket.available()) {
|
||||
client = CLIENT_WEBUI;
|
||||
data = Serial2Socket.read();
|
||||
} else {
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
if (Serial2Socket.available()) {
|
||||
client = CLIENT_WEBUI;
|
||||
data = Serial2Socket.read();
|
||||
} else {
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_TELNET)
|
||||
if (telnet_server.available()) {
|
||||
client = CLIENT_TELNET;
|
||||
data = telnet_server.read();
|
||||
}
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
}
|
||||
else
|
||||
{
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_TELNET)
|
||||
if(telnet_server.available()){
|
||||
client = CLIENT_TELNET;
|
||||
data = telnet_server.read();
|
||||
}
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
#endif
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
}
|
||||
#endif
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
||||
// Pick off realtime command characters directly from the serial stream. These characters are
|
||||
// not passed into the main buffer, but these set system state flag bits for realtime execution.
|
||||
if (is_realtime_command(data)) {
|
||||
execute_realtime_command(data, client);
|
||||
}
|
||||
else {
|
||||
vTaskEnterCritical(&myMutex);
|
||||
client_buffer[client].write(data);
|
||||
vTaskExitCritical(&myMutex);
|
||||
}
|
||||
|
||||
|
||||
} // if something available
|
||||
#endif
|
||||
}
|
||||
// Pick off realtime command characters directly from the serial stream. These characters are
|
||||
// not passed into the main buffer, but these set system state flag bits for realtime execution.
|
||||
if (is_realtime_command(data))
|
||||
execute_realtime_command(data, client);
|
||||
else {
|
||||
vTaskEnterCritical(&myMutex);
|
||||
client_buffer[client].write(data);
|
||||
vTaskExitCritical(&myMutex);
|
||||
}
|
||||
} // if something available
|
||||
COMMANDS::handle();
|
||||
#ifdef ENABLE_WIFI
|
||||
wifi_config.handle();
|
||||
@ -168,116 +148,101 @@ void serialCheckTask(void *pvParameters)
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
Serial2Socket.handle_flush();
|
||||
#endif
|
||||
vTaskDelay(1 / portTICK_RATE_MS); // Yield to other tasks
|
||||
} // while(true)
|
||||
vTaskDelay(1 / portTICK_RATE_MS); // Yield to other tasks
|
||||
} // while(true)
|
||||
}
|
||||
|
||||
void serial_reset_read_buffer(uint8_t client)
|
||||
{
|
||||
for (uint8_t client_num = 0; client_num < CLIENT_COUNT; client_num++)
|
||||
{
|
||||
if (client == client_num || client == CLIENT_ALL)
|
||||
{
|
||||
client_buffer[client].begin();
|
||||
}
|
||||
}
|
||||
void serial_reset_read_buffer(uint8_t client) {
|
||||
for (uint8_t client_num = 0; client_num < CLIENT_COUNT; client_num++) {
|
||||
if (client == client_num || client == CLIENT_ALL)
|
||||
client_buffer[client].begin();
|
||||
}
|
||||
}
|
||||
|
||||
// Writes one byte to the TX serial buffer. Called by main program.
|
||||
void serial_write(uint8_t data) {
|
||||
Serial.write((char)data);
|
||||
Serial.write((char)data);
|
||||
}
|
||||
|
||||
// Fetches the first byte in the serial read buffer. Called by protocol loop.
|
||||
uint8_t serial_read(uint8_t client)
|
||||
{
|
||||
uint8_t data;
|
||||
|
||||
vTaskEnterCritical(&myMutex);
|
||||
if (client_buffer[client].available()) {
|
||||
data = client_buffer[client].read();
|
||||
vTaskExitCritical(&myMutex);
|
||||
//Serial.write((char)data);
|
||||
return data;
|
||||
}
|
||||
else {
|
||||
vTaskExitCritical(&myMutex);
|
||||
return SERIAL_NO_DATA;
|
||||
}
|
||||
uint8_t serial_read(uint8_t client) {
|
||||
uint8_t data;
|
||||
vTaskEnterCritical(&myMutex);
|
||||
if (client_buffer[client].available()) {
|
||||
data = client_buffer[client].read();
|
||||
vTaskExitCritical(&myMutex);
|
||||
//Serial.write((char)data);
|
||||
return data;
|
||||
} else {
|
||||
vTaskExitCritical(&myMutex);
|
||||
return SERIAL_NO_DATA;
|
||||
}
|
||||
}
|
||||
|
||||
bool any_client_has_data() {
|
||||
return (Serial.available() || inputBuffer.available()
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
|| (SerialBT.hasClient() && SerialBT.available())
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
|| Serial2Socket.available()
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_TELNET)
|
||||
|| telnet_server.available()
|
||||
#endif
|
||||
);
|
||||
return (Serial.available() || inputBuffer.available()
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
|| (SerialBT.hasClient() && SerialBT.available())
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
|| Serial2Socket.available()
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_TELNET)
|
||||
|| telnet_server.available()
|
||||
#endif
|
||||
);
|
||||
}
|
||||
|
||||
// checks to see if a character is a realtime character
|
||||
bool is_realtime_command(uint8_t data) {
|
||||
return (data == CMD_RESET || data == CMD_STATUS_REPORT || data == CMD_CYCLE_START || data == CMD_FEED_HOLD || data > 0x7F);
|
||||
return (data == CMD_RESET || data == CMD_STATUS_REPORT || data == CMD_CYCLE_START || data == CMD_FEED_HOLD || data > 0x7F);
|
||||
}
|
||||
|
||||
// Act upon a realtime character
|
||||
void execute_realtime_command(uint8_t command, uint8_t client) {
|
||||
switch (command) {
|
||||
case CMD_RESET:
|
||||
mc_reset(); // Call motion control reset routine.
|
||||
break;
|
||||
|
||||
case CMD_STATUS_REPORT:
|
||||
report_realtime_status(client); // direct call instead of setting flag
|
||||
break;
|
||||
|
||||
case CMD_CYCLE_START:
|
||||
system_set_exec_state_flag(EXEC_CYCLE_START); // Set as true
|
||||
break;
|
||||
|
||||
case CMD_FEED_HOLD:
|
||||
system_set_exec_state_flag(EXEC_FEED_HOLD); // Set as true
|
||||
break;
|
||||
|
||||
case CMD_SAFETY_DOOR:
|
||||
system_set_exec_state_flag(EXEC_SAFETY_DOOR);
|
||||
break; // Set as true
|
||||
|
||||
case CMD_JOG_CANCEL:
|
||||
if (sys.state & STATE_JOG) { // Block all other states from invoking motion cancel.
|
||||
system_set_exec_state_flag(EXEC_MOTION_CANCEL);
|
||||
}
|
||||
break;
|
||||
#ifdef DEBUG
|
||||
case CMD_DEBUG_REPORT: {uint8_t sreg = SREG; cli(); bit_true(sys_rt_exec_debug,EXEC_DEBUG_REPORT); SREG = sreg;} break;
|
||||
#endif
|
||||
case CMD_FEED_OVR_RESET: system_set_exec_motion_override_flag(EXEC_FEED_OVR_RESET); break;
|
||||
case CMD_FEED_OVR_COARSE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_PLUS); break;
|
||||
case CMD_FEED_OVR_COARSE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_MINUS); break;
|
||||
case CMD_FEED_OVR_FINE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_PLUS); break;
|
||||
case CMD_FEED_OVR_FINE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_MINUS); break;
|
||||
case CMD_RAPID_OVR_RESET: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_RESET); break;
|
||||
case CMD_RAPID_OVR_MEDIUM: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_MEDIUM); break;
|
||||
case CMD_RAPID_OVR_LOW: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_LOW); break;
|
||||
case CMD_SPINDLE_OVR_RESET: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_RESET); break;
|
||||
case CMD_SPINDLE_OVR_COARSE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_PLUS); break;
|
||||
case CMD_SPINDLE_OVR_COARSE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_MINUS); break;
|
||||
case CMD_SPINDLE_OVR_FINE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_PLUS); break;
|
||||
case CMD_SPINDLE_OVR_FINE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_MINUS); break;
|
||||
case CMD_SPINDLE_OVR_STOP: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_STOP); break;
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
case CMD_COOLANT_FLOOD_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_FLOOD_OVR_TOGGLE); break;
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
case CMD_COOLANT_MIST_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_MIST_OVR_TOGGLE); break;
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
switch (command) {
|
||||
case CMD_RESET:
|
||||
mc_reset(); // Call motion control reset routine.
|
||||
break;
|
||||
case CMD_STATUS_REPORT:
|
||||
report_realtime_status(client); // direct call instead of setting flag
|
||||
break;
|
||||
case CMD_CYCLE_START:
|
||||
system_set_exec_state_flag(EXEC_CYCLE_START); // Set as true
|
||||
break;
|
||||
case CMD_FEED_HOLD:
|
||||
system_set_exec_state_flag(EXEC_FEED_HOLD); // Set as true
|
||||
break;
|
||||
case CMD_SAFETY_DOOR:
|
||||
system_set_exec_state_flag(EXEC_SAFETY_DOOR);
|
||||
break; // Set as true
|
||||
case CMD_JOG_CANCEL:
|
||||
if (sys.state & STATE_JOG) // Block all other states from invoking motion cancel.
|
||||
system_set_exec_state_flag(EXEC_MOTION_CANCEL);
|
||||
break;
|
||||
#ifdef DEBUG
|
||||
case CMD_DEBUG_REPORT: {uint8_t sreg = SREG; cli(); bit_true(sys_rt_exec_debug, EXEC_DEBUG_REPORT); SREG = sreg;} break;
|
||||
#endif
|
||||
case CMD_FEED_OVR_RESET: system_set_exec_motion_override_flag(EXEC_FEED_OVR_RESET); break;
|
||||
case CMD_FEED_OVR_COARSE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_PLUS); break;
|
||||
case CMD_FEED_OVR_COARSE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_MINUS); break;
|
||||
case CMD_FEED_OVR_FINE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_PLUS); break;
|
||||
case CMD_FEED_OVR_FINE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_MINUS); break;
|
||||
case CMD_RAPID_OVR_RESET: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_RESET); break;
|
||||
case CMD_RAPID_OVR_MEDIUM: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_MEDIUM); break;
|
||||
case CMD_RAPID_OVR_LOW: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_LOW); break;
|
||||
case CMD_SPINDLE_OVR_RESET: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_RESET); break;
|
||||
case CMD_SPINDLE_OVR_COARSE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_PLUS); break;
|
||||
case CMD_SPINDLE_OVR_COARSE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_MINUS); break;
|
||||
case CMD_SPINDLE_OVR_FINE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_PLUS); break;
|
||||
case CMD_SPINDLE_OVR_FINE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_MINUS); break;
|
||||
case CMD_SPINDLE_OVR_STOP: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_STOP); break;
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
case CMD_COOLANT_FLOOD_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_FLOOD_OVR_TOGGLE); break;
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
case CMD_COOLANT_MIST_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_MIST_OVR_TOGGLE); break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -2,10 +2,10 @@
|
||||
serial.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
|
||||
@ -24,20 +24,20 @@
|
||||
#include "grbl.h"
|
||||
|
||||
#ifndef RX_BUFFER_SIZE
|
||||
#define RX_BUFFER_SIZE 128
|
||||
#define RX_BUFFER_SIZE 128
|
||||
#endif
|
||||
#ifndef TX_BUFFER_SIZE
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
#define TX_BUFFER_SIZE 112
|
||||
#else
|
||||
#define TX_BUFFER_SIZE 104
|
||||
#endif
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
#define TX_BUFFER_SIZE 112
|
||||
#else
|
||||
#define TX_BUFFER_SIZE 104
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define SERIAL_NO_DATA 0xff
|
||||
|
||||
// a task to read for incoming data from serial port
|
||||
void serialCheckTask(void *pvParameters);
|
||||
void serialCheckTask(void* pvParameters);
|
||||
|
||||
void serial_write(uint8_t data);
|
||||
// Fetches the first byte in the serial read buffer. Called by main program.
|
||||
|
@ -34,120 +34,115 @@
|
||||
Serial_2_Socket Serial2Socket;
|
||||
|
||||
|
||||
Serial_2_Socket::Serial_2_Socket(){
|
||||
Serial_2_Socket::Serial_2_Socket() {
|
||||
_web_socket = NULL;
|
||||
_TXbufferSize = 0;
|
||||
_RXbufferSize = 0;
|
||||
_RXbufferpos = 0;
|
||||
}
|
||||
Serial_2_Socket::~Serial_2_Socket(){
|
||||
Serial_2_Socket::~Serial_2_Socket() {
|
||||
if (_web_socket) detachWS();
|
||||
_TXbufferSize = 0;
|
||||
_RXbufferSize = 0;
|
||||
_RXbufferpos = 0;
|
||||
}
|
||||
void Serial_2_Socket::begin(long speed){
|
||||
void Serial_2_Socket::begin(long speed) {
|
||||
_TXbufferSize = 0;
|
||||
_RXbufferSize = 0;
|
||||
_RXbufferpos = 0;
|
||||
}
|
||||
|
||||
void Serial_2_Socket::end(){
|
||||
void Serial_2_Socket::end() {
|
||||
_TXbufferSize = 0;
|
||||
_RXbufferSize = 0;
|
||||
_RXbufferpos = 0;
|
||||
}
|
||||
|
||||
long Serial_2_Socket::baudRate(){
|
||||
return 0;
|
||||
long Serial_2_Socket::baudRate() {
|
||||
return 0;
|
||||
}
|
||||
|
||||
bool Serial_2_Socket::attachWS(void * web_socket){
|
||||
bool Serial_2_Socket::attachWS(void* web_socket) {
|
||||
if (web_socket) {
|
||||
_web_socket = web_socket;
|
||||
_TXbufferSize=0;
|
||||
_TXbufferSize = 0;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool Serial_2_Socket::detachWS(){
|
||||
_web_socket = NULL;
|
||||
return true;
|
||||
}
|
||||
|
||||
Serial_2_Socket::operator bool() const
|
||||
{
|
||||
bool Serial_2_Socket::detachWS() {
|
||||
_web_socket = NULL;
|
||||
return true;
|
||||
}
|
||||
int Serial_2_Socket::available(){
|
||||
|
||||
Serial_2_Socket::operator bool() const {
|
||||
return true;
|
||||
}
|
||||
int Serial_2_Socket::available() {
|
||||
return _RXbufferSize;
|
||||
}
|
||||
|
||||
|
||||
size_t Serial_2_Socket::write(uint8_t c)
|
||||
{
|
||||
if(!_web_socket) return 0;
|
||||
write(&c,1);
|
||||
size_t Serial_2_Socket::write(uint8_t c) {
|
||||
if (!_web_socket) return 0;
|
||||
write(&c, 1);
|
||||
return 1;
|
||||
}
|
||||
|
||||
size_t Serial_2_Socket::write(const uint8_t *buffer, size_t size)
|
||||
{
|
||||
if((buffer == NULL) ||(!_web_socket)) {
|
||||
if(buffer == NULL){
|
||||
log_i("[SOCKET]No buffer");
|
||||
}
|
||||
if(!_web_socket){
|
||||
log_i("[SOCKET]No socket");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
size_t Serial_2_Socket::write(const uint8_t* buffer, size_t size) {
|
||||
if ((buffer == NULL) || (!_web_socket)) {
|
||||
if (buffer == NULL)
|
||||
log_i("[SOCKET]No buffer");
|
||||
if (!_web_socket)
|
||||
log_i("[SOCKET]No socket");
|
||||
return 0;
|
||||
}
|
||||
#if defined(ENABLE_SERIAL2SOCKET_OUT)
|
||||
if (_TXbufferSize==0)_lastflush = millis();
|
||||
//send full line
|
||||
if (_TXbufferSize + size > TXBUFFERSIZE) flush();
|
||||
//need periodic check to force to flush in case of no end
|
||||
for (int i = 0; i < size;i++){
|
||||
_TXbuffer[_TXbufferSize] = buffer[i];
|
||||
_TXbufferSize++;
|
||||
}
|
||||
log_i("[SOCKET]buffer size %d",_TXbufferSize);
|
||||
handle_flush();
|
||||
if (_TXbufferSize == 0)_lastflush = millis();
|
||||
//send full line
|
||||
if (_TXbufferSize + size > TXBUFFERSIZE) flush();
|
||||
//need periodic check to force to flush in case of no end
|
||||
for (int i = 0; i < size; i++) {
|
||||
_TXbuffer[_TXbufferSize] = buffer[i];
|
||||
_TXbufferSize++;
|
||||
}
|
||||
log_i("[SOCKET]buffer size %d", _TXbufferSize);
|
||||
handle_flush();
|
||||
#endif
|
||||
return size;
|
||||
}
|
||||
|
||||
int Serial_2_Socket::peek(void){
|
||||
int Serial_2_Socket::peek(void) {
|
||||
if (_RXbufferSize > 0)return _RXbuffer[_RXbufferpos];
|
||||
else return -1;
|
||||
}
|
||||
|
||||
bool Serial_2_Socket::push (const char * data){
|
||||
bool Serial_2_Socket::push(const char* data) {
|
||||
#if defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
int data_size = strlen(data);
|
||||
if ((data_size + _RXbufferSize) <= RXBUFFERSIZE){
|
||||
if ((data_size + _RXbufferSize) <= RXBUFFERSIZE) {
|
||||
int current = _RXbufferpos + _RXbufferSize;
|
||||
if (current > RXBUFFERSIZE) current = current - RXBUFFERSIZE;
|
||||
for (int i = 0; i < data_size; i++){
|
||||
if (current > (RXBUFFERSIZE-1)) current = 0;
|
||||
_RXbuffer[current] = data[i];
|
||||
current ++;
|
||||
for (int i = 0; i < data_size; i++) {
|
||||
if (current > (RXBUFFERSIZE - 1)) current = 0;
|
||||
_RXbuffer[current] = data[i];
|
||||
current ++;
|
||||
}
|
||||
_RXbufferSize+=strlen(data);
|
||||
_RXbufferSize += strlen(data);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
#else
|
||||
return true;
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
|
||||
int Serial_2_Socket::read(void){
|
||||
int Serial_2_Socket::read(void) {
|
||||
if (_RXbufferSize > 0) {
|
||||
int v = _RXbuffer[_RXbufferpos];
|
||||
_RXbufferpos++;
|
||||
if (_RXbufferpos > (RXBUFFERSIZE-1))_RXbufferpos = 0;
|
||||
if (_RXbufferpos > (RXBUFFERSIZE - 1))_RXbufferpos = 0;
|
||||
_RXbufferSize--;
|
||||
return v;
|
||||
} else return -1;
|
||||
@ -155,21 +150,21 @@ int Serial_2_Socket::read(void){
|
||||
|
||||
void Serial_2_Socket::handle_flush() {
|
||||
if (_TXbufferSize > 0) {
|
||||
if ((_TXbufferSize>=TXBUFFERSIZE) || ((millis()- _lastflush) > FLUSHTIMEOUT)) {
|
||||
log_i("[SOCKET]need flush, buffer size %d",_TXbufferSize);
|
||||
flush();
|
||||
}
|
||||
if ((_TXbufferSize >= TXBUFFERSIZE) || ((millis() - _lastflush) > FLUSHTIMEOUT)) {
|
||||
log_i("[SOCKET]need flush, buffer size %d", _TXbufferSize);
|
||||
flush();
|
||||
}
|
||||
}
|
||||
}
|
||||
void Serial_2_Socket::flush(void){
|
||||
if (_TXbufferSize > 0){
|
||||
void Serial_2_Socket::flush(void) {
|
||||
if (_TXbufferSize > 0) {
|
||||
//if ((((AsyncWebSocket *)_web_socket)->count() > 0) && (((AsyncWebSocket *)_web_socket)->availableForWriteAll())) {
|
||||
log_i("[SOCKET]flush data, buffer size %d",_TXbufferSize);
|
||||
((WebSocketsServer *)_web_socket)->broadcastBIN(_TXbuffer,_TXbufferSize);
|
||||
// } else {
|
||||
// log_i("[SOCKET]Cannot flush, buffer size %d",_TXbufferSize);
|
||||
// }
|
||||
//refresh timout
|
||||
log_i("[SOCKET]flush data, buffer size %d", _TXbufferSize);
|
||||
((WebSocketsServer*)_web_socket)->broadcastBIN(_TXbuffer, _TXbufferSize);
|
||||
// } else {
|
||||
// log_i("[SOCKET]Cannot flush, buffer size %d",_TXbufferSize);
|
||||
// }
|
||||
//refresh timout
|
||||
_lastflush = millis();
|
||||
//reset buffer
|
||||
_TXbufferSize = 0;
|
||||
|
@ -26,31 +26,26 @@
|
||||
#define TXBUFFERSIZE 1200
|
||||
#define RXBUFFERSIZE 128
|
||||
#define FLUSHTIMEOUT 500
|
||||
class Serial_2_Socket: public Print{
|
||||
public:
|
||||
class Serial_2_Socket: public Print {
|
||||
public:
|
||||
Serial_2_Socket();
|
||||
~Serial_2_Socket();
|
||||
size_t write(uint8_t c);
|
||||
size_t write(const uint8_t *buffer, size_t size);
|
||||
size_t write(const uint8_t* buffer, size_t size);
|
||||
|
||||
inline size_t write(const char * s)
|
||||
{
|
||||
inline size_t write(const char* s) {
|
||||
return write((uint8_t*) s, strlen(s));
|
||||
}
|
||||
inline size_t write(unsigned long n)
|
||||
{
|
||||
inline size_t write(unsigned long n) {
|
||||
return write((uint8_t) n);
|
||||
}
|
||||
inline size_t write(long n)
|
||||
{
|
||||
inline size_t write(long n) {
|
||||
return write((uint8_t) n);
|
||||
}
|
||||
inline size_t write(unsigned int n)
|
||||
{
|
||||
inline size_t write(unsigned int n) {
|
||||
return write((uint8_t) n);
|
||||
}
|
||||
inline size_t write(int n)
|
||||
{
|
||||
inline size_t write(int n) {
|
||||
return write((uint8_t) n);
|
||||
}
|
||||
long baudRate();
|
||||
@ -59,15 +54,15 @@ class Serial_2_Socket: public Print{
|
||||
int available();
|
||||
int peek(void);
|
||||
int read(void);
|
||||
bool push (const char * data);
|
||||
bool push(const char* data);
|
||||
void flush(void);
|
||||
void handle_flush();
|
||||
operator bool() const;
|
||||
bool attachWS(void * web_socket);
|
||||
bool attachWS(void* web_socket);
|
||||
bool detachWS();
|
||||
private:
|
||||
private:
|
||||
uint32_t _lastflush;
|
||||
void * _web_socket;
|
||||
void* _web_socket;
|
||||
uint8_t _TXbuffer[TXBUFFERSIZE];
|
||||
uint16_t _TXbufferSize;
|
||||
uint8_t _RXbuffer[RXBUFFERSIZE];
|
||||
|
@ -17,7 +17,7 @@
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
|
||||
See servo_axis.h for more details
|
||||
|
||||
*/
|
||||
@ -29,276 +29,275 @@
|
||||
static TaskHandle_t servosSyncTaskHandle = 0;
|
||||
|
||||
#ifdef SERVO_X_PIN
|
||||
ServoAxis X_Servo_Axis(X_AXIS, SERVO_X_PIN, SERVO_X_CHANNEL_NUM);
|
||||
ServoAxis X_Servo_Axis(X_AXIS, SERVO_X_PIN, SERVO_X_CHANNEL_NUM);
|
||||
#endif
|
||||
#ifdef SERVO_Y_PIN
|
||||
ServoAxis Y_Servo_Axis(Y_AXIS, SERVO_Y_PIN, SERVO_Y_CHANNEL_NUM);
|
||||
ServoAxis Y_Servo_Axis(Y_AXIS, SERVO_Y_PIN, SERVO_Y_CHANNEL_NUM);
|
||||
#endif
|
||||
#ifdef SERVO_Z_PIN
|
||||
ServoAxis Z_Servo_Axis(Z_AXIS, SERVO_Z_PIN, SERVO_Z_CHANNEL_NUM);
|
||||
ServoAxis Z_Servo_Axis(Z_AXIS, SERVO_Z_PIN, SERVO_Z_CHANNEL_NUM);
|
||||
#endif
|
||||
|
||||
#ifdef SERVO_A_PIN
|
||||
ServoAxis A_Servo_Axis(A_AXIS, SERVO_A_PIN, SERVO_A_CHANNEL_NUM);
|
||||
ServoAxis A_Servo_Axis(A_AXIS, SERVO_A_PIN, SERVO_A_CHANNEL_NUM);
|
||||
#endif
|
||||
#ifdef SERVO_B_PIN
|
||||
ServoAxis B_Servo_Axis(B_AXIS, SERVO_B_PIN, SERVO_B_CHANNEL_NUM);
|
||||
ServoAxis B_Servo_Axis(B_AXIS, SERVO_B_PIN, SERVO_B_CHANNEL_NUM);
|
||||
#endif
|
||||
#ifdef SERVO_C_PIN
|
||||
ServoAxis C_Servo_Axis(C_AXIS, SERVO_C_PIN, SERVO_C_CHANNEL_NUM);
|
||||
ServoAxis C_Servo_Axis(C_AXIS, SERVO_C_PIN, SERVO_C_CHANNEL_NUM);
|
||||
#endif
|
||||
|
||||
void init_servos()
|
||||
{
|
||||
#ifdef SERVO_X_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "X Servo range %4.3f to %4.3f", SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
|
||||
X_Servo_Axis.init();
|
||||
X_Servo_Axis.set_range(SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
|
||||
X_Servo_Axis.set_homing_type(SERVO_HOMING_OFF);
|
||||
X_Servo_Axis.set_disable_on_alarm(false);
|
||||
X_Servo_Axis.set_disable_with_steppers(false);
|
||||
#endif
|
||||
#ifdef SERVO_Y_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Y Servo range %4.3f to %4.3f", SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
|
||||
Y_Servo_Axis.init();
|
||||
Y_Servo_Axis.set_range(SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
|
||||
#endif
|
||||
#ifdef SERVO_Z_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Z Servo range %4.3f to %4.3f", SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
|
||||
Z_Servo_Axis.init();
|
||||
Z_Servo_Axis.set_range(SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
|
||||
#ifdef SERVO_Z_HOMING_TYPE
|
||||
Z_Servo_Axis.set_homing_type(SERVO_Z_HOMING_TYPE);
|
||||
#endif
|
||||
#ifdef SERVO_Z_HOME_POS
|
||||
Z_Servo_Axis.set_homing_position(SERVO_Z_HOME_POS);
|
||||
#endif
|
||||
#ifdef SERVO_Z_MPOS // value should be true or false
|
||||
Z_Servo_Axis.set_use_mpos(SERVO_Z_MPOS);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef SERVO_A_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "A Servo range %4.3f to %4.3f", SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX);
|
||||
A_Servo_Axis.init();
|
||||
A_Servo_Axis.set_range(SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX);
|
||||
A_Servo_Axis.set_homing_type(SERVO_HOMING_OFF);
|
||||
A_Servo_Axis.set_disable_on_alarm(false);
|
||||
A_Servo_Axis.set_disable_with_steppers(false);
|
||||
#endif
|
||||
#ifdef SERVO_B_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "B Servo range %4.3f to %4.3f", SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX);
|
||||
B_Servo_Axis.init();
|
||||
B_Servo_Axis.set_range(SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX);
|
||||
#endif
|
||||
#ifdef SERVO_C_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "C Servo range %4.3f to %4.3f", SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX);
|
||||
C_Servo_Axis.init();
|
||||
C_Servo_Axis.set_range(SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX);
|
||||
//C_Servo_Axis.set_homing_type(SERVO_HOMING_TARGET);
|
||||
//C_Servo_Axis.set_homing_position(SERVO_C_RANGE_MAX);
|
||||
#ifdef SERVO_C_HOMING_TYPE
|
||||
C_Servo_Axis.set_homing_type(SERVO_C_HOMING_TYPE);
|
||||
#endif
|
||||
#ifdef SERVO_C_HOME_POS
|
||||
C_Servo_Axis.set_homing_position(SERVO_C_HOME_POS);
|
||||
#endif
|
||||
#ifdef SERVO_C_MPOS // value should be true or false
|
||||
C_Servo_Axis.set_use_mpos(SERVO_C_MPOS);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
// setup a task that will calculate the determine and set the servo positions
|
||||
xTaskCreatePinnedToCore( servosSyncTask, // task
|
||||
"servosSyncTask", // name for task
|
||||
4096, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&servosSyncTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
void init_servos() {
|
||||
// ======================== X Axis ===========================
|
||||
#ifdef SERVO_X_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "X Servo range %4.3f to %4.3f", SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
|
||||
X_Servo_Axis.init();
|
||||
X_Servo_Axis.set_range(SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
|
||||
#ifdef SERVO_X_HOMING_TYPE
|
||||
X_Servo_Axis.set_homing_type(SERVO_X_HOMING_TYPE);
|
||||
#endif
|
||||
#ifdef SERVO_X_HOME_POS
|
||||
X_Servo_Axis.set_homing_position(SERVO_X_HOME_POS);
|
||||
#endif
|
||||
#ifdef SERVO_X_MPOS // value should be true or false
|
||||
X_Servo_Axis.set_use_mpos(SERVO_X_MPOS);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// ======================== Y Axis ===========================
|
||||
#ifdef SERVO_Y_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Y Servo range %4.3f to %4.3f", SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
|
||||
Y_Servo_Axis.init();
|
||||
Y_Servo_Axis.set_range(SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
|
||||
#ifdef SERVO_Y_HOMING_TYPE
|
||||
Y_Servo_Axis.set_homing_type(SERVO_Y_HOMING_TYPE);
|
||||
#endif
|
||||
#ifdef SERVO_Y_HOME_POS
|
||||
Y_Servo_Axis.set_homing_position(SERVO_Y_HOME_POS);
|
||||
#endif
|
||||
#ifdef SERVO_Y_MPOS // value should be true or false
|
||||
Y_Servo_Axis.set_use_mpos(SERVO_Y_MPOS);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// ======================== Z Axis ===========================
|
||||
#ifdef SERVO_Z_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Z Servo range %4.3f to %4.3f", SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
|
||||
Z_Servo_Axis.init();
|
||||
Z_Servo_Axis.set_range(SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
|
||||
#ifdef SERVO_Z_HOMING_TYPE
|
||||
Z_Servo_Axis.set_homing_type(SERVO_Z_HOMING_TYPE);
|
||||
#endif
|
||||
#ifdef SERVO_Z_HOME_POS
|
||||
Z_Servo_Axis.set_homing_position(SERVO_Z_HOME_POS);
|
||||
#endif
|
||||
#ifdef SERVO_Z_MPOS // value should be true or false
|
||||
Z_Servo_Axis.set_use_mpos(SERVO_Z_MPOS);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// ======================== A Axis ===========================
|
||||
#ifdef SERVO_A_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "A Servo range %4.3f to %4.3f", SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX);
|
||||
A_Servo_Axis.init();
|
||||
A_Servo_Axis.set_range(SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX);
|
||||
#ifdef SERVO_A_HOMING_TYPE
|
||||
A_Servo_Axis.set_homing_type(SERVO_A_HOMING_TYPE);
|
||||
#endif
|
||||
#ifdef SERVO_A_HOME_POS
|
||||
A_Servo_Axis.set_homing_position(SERVO_A_HOME_POS);
|
||||
#endif
|
||||
#ifdef SERVO_A_MPOS // value should be true or false
|
||||
A_Servo_Axis.set_use_mpos(SERVO_A_MPOS);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// ======================== B Axis ===========================
|
||||
#ifdef SERVO_B_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "B Servo range %4.3f to %4.3f", SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX);
|
||||
B_Servo_Axis.init();
|
||||
B_Servo_Axis.set_range(SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX);
|
||||
#ifdef SERVO_B_HOMING_TYPE
|
||||
B_Servo_Axis.set_homing_type(SERVO_B_HOMING_TYPE);
|
||||
#endif
|
||||
#ifdef SERVO_B_HOME_POS
|
||||
B_Servo_Axis.set_homing_position(SERVO_B_HOME_POS);
|
||||
#endif
|
||||
#ifdef SERVO_B_MPOS // value should be true or false
|
||||
B_Servo_Axis.set_use_mpos(SERVO_B_MPOS);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// ======================== C Axis ===========================
|
||||
#ifdef SERVO_C_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "C Servo range %4.3f to %4.3f", SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX);
|
||||
C_Servo_Axis.init();
|
||||
C_Servo_Axis.set_range(SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX);
|
||||
#ifdef SERVO_C_HOMING_TYPE
|
||||
C_Servo_Axis.set_homing_type(SERVO_C_HOMING_TYPE);
|
||||
#endif
|
||||
#ifdef SERVO_C_HOME_POS
|
||||
C_Servo_Axis.set_homing_position(SERVO_C_HOME_POS);
|
||||
#endif
|
||||
#ifdef SERVO_C_MPOS // value should be true or false
|
||||
C_Servo_Axis.set_use_mpos(SERVO_C_MPOS);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// setup a task that will calculate the determine and set the servo positions
|
||||
xTaskCreatePinnedToCore(servosSyncTask, // task
|
||||
"servosSyncTask", // name for task
|
||||
4096, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&servosSyncTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
}
|
||||
|
||||
|
||||
// this is the task
|
||||
void servosSyncTask(void *pvParameters)
|
||||
{
|
||||
TickType_t xLastWakeTime;
|
||||
const TickType_t xServoFrequency = SERVO_TIMER_INT_FREQ; // in ticks (typically ms)
|
||||
|
||||
|
||||
|
||||
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
|
||||
while(true) { // don't ever return from this or the task dies
|
||||
#ifdef SERVO_X_PIN
|
||||
X_Servo_Axis.set_location();
|
||||
#endif
|
||||
#ifdef SERVO_Y_PIN
|
||||
Y_Servo_Axis.set_location();
|
||||
#endif
|
||||
#ifdef SERVO_Z_PIN
|
||||
Z_Servo_Axis.set_location();
|
||||
#endif
|
||||
#ifdef SERVO_A_PIN
|
||||
A_Servo_Axis.set_location();
|
||||
#endif
|
||||
#ifdef SERVO_B_PIN
|
||||
B_Servo_Axis.set_location();
|
||||
#endif
|
||||
#ifdef SERVO_C_PIN
|
||||
C_Servo_Axis.set_location();
|
||||
#endif
|
||||
|
||||
vTaskDelayUntil(&xLastWakeTime, xServoFrequency);
|
||||
}
|
||||
}
|
||||
void servosSyncTask(void* pvParameters) {
|
||||
TickType_t xLastWakeTime;
|
||||
const TickType_t xServoFrequency = SERVO_TIMER_INT_FREQ; // in ticks (typically ms)
|
||||
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
|
||||
while (true) { // don't ever return from this or the task dies
|
||||
#ifdef SERVO_X_PIN
|
||||
X_Servo_Axis.set_location();
|
||||
#endif
|
||||
#ifdef SERVO_Y_PIN
|
||||
Y_Servo_Axis.set_location();
|
||||
#endif
|
||||
#ifdef SERVO_Z_PIN
|
||||
Z_Servo_Axis.set_location();
|
||||
#endif
|
||||
#ifdef SERVO_A_PIN
|
||||
A_Servo_Axis.set_location();
|
||||
#endif
|
||||
#ifdef SERVO_B_PIN
|
||||
B_Servo_Axis.set_location();
|
||||
#endif
|
||||
#ifdef SERVO_C_PIN
|
||||
C_Servo_Axis.set_location();
|
||||
#endif
|
||||
vTaskDelayUntil(&xLastWakeTime, xServoFrequency);
|
||||
}
|
||||
}
|
||||
|
||||
// =============================== Class Stuff ================================= //
|
||||
|
||||
ServoAxis::ServoAxis(uint8_t axis, uint8_t pin_num, uint8_t channel_num) // constructor
|
||||
{
|
||||
_axis = axis;
|
||||
_pin_num = pin_num;
|
||||
_channel_num = channel_num;
|
||||
_showError = true; // this will be used to show calibration error only once
|
||||
_use_mpos = true; // default is to use the machine position rather than work position
|
||||
ServoAxis::ServoAxis(uint8_t axis, uint8_t pin_num, uint8_t channel_num) { // constructor
|
||||
_axis = axis;
|
||||
_pin_num = pin_num;
|
||||
_channel_num = channel_num;
|
||||
_showError = true; // this will be used to show calibration error only once
|
||||
_use_mpos = true; // default is to use the machine position rather than work position
|
||||
}
|
||||
|
||||
void ServoAxis::init()
|
||||
{
|
||||
_cal_is_valid();
|
||||
ledcSetup(_channel_num, _pwm_freq, _pwm_resolution_bits);
|
||||
ledcAttachPin(_pin_num, _channel_num);
|
||||
disable();
|
||||
void ServoAxis::init() {
|
||||
_cal_is_valid();
|
||||
ledcSetup(_channel_num, _pwm_freq, _pwm_resolution_bits);
|
||||
ledcAttachPin(_pin_num, _channel_num);
|
||||
disable();
|
||||
}
|
||||
|
||||
void ServoAxis::set_location()
|
||||
{
|
||||
// These are the pulse lengths for the minimum and maximum positions
|
||||
// Note: Some machines will have the physical max/min inverted with pulse length max/min due to invert setting $3=...
|
||||
float servo_pulse_min, servo_pulse_max;
|
||||
float min_pulse_cal, max_pulse_cal; // calibration values in percent 110% = 1.1
|
||||
uint32_t servo_pulse_len;
|
||||
float servo_pos, mpos, offset;
|
||||
|
||||
|
||||
|
||||
// skip location if we are in alarm mode
|
||||
if (_disable_on_alarm && (sys.state == STATE_ALARM)) {
|
||||
disable();
|
||||
return;
|
||||
}
|
||||
|
||||
// track the disable status of the steppers if desired.
|
||||
if (_disable_with_steppers && get_stepper_disable()) {
|
||||
disable();
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
if ( (_homing_type == SERVO_HOMING_TARGET) && (sys.state == STATE_HOMING) ) {
|
||||
servo_pos = _homing_position; // go to servos home position
|
||||
}
|
||||
else {
|
||||
mpos = system_convert_axis_steps_to_mpos(sys_position, _axis); // get the axis machine position in mm
|
||||
if (_use_mpos) {
|
||||
servo_pos = mpos;
|
||||
}
|
||||
else {
|
||||
offset = gc_state.coord_system[_axis] + gc_state.coord_offset[_axis]; // get the current axis work offset
|
||||
servo_pos = mpos - offset; // determine the current work position
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// 1. Get the pulse ranges of the servos
|
||||
// 2. Invert if selected in the settings
|
||||
// 3. Get the calibration values from the settings
|
||||
// 4. Adjust the calibration offset direction of the cal based on the direction
|
||||
// 5. Apply the calibrarion
|
||||
|
||||
|
||||
servo_pulse_min = SERVO_MIN_PULSE;
|
||||
servo_pulse_max = SERVO_MAX_PULSE;
|
||||
|
||||
if (bit_istrue(settings.dir_invert_mask,bit(_axis))) { // this allows the user to change the direction via settings
|
||||
swap(servo_pulse_min, servo_pulse_max);
|
||||
}
|
||||
|
||||
// get the calibration values
|
||||
if (_cal_is_valid()) { // if calibration settings are OK then apply them
|
||||
// apply a calibration
|
||||
// the cals apply differently if the direction is reverse (i.e. longer pulse is lower position)
|
||||
if (bit_isfalse(settings.dir_invert_mask,bit(_axis))) { // normal direction
|
||||
min_pulse_cal = 2.0 - (settings.steps_per_mm[_axis] / 100.0);
|
||||
max_pulse_cal = (settings.max_travel[_axis] / -100.0);
|
||||
}
|
||||
else { // inverted direction
|
||||
min_pulse_cal = (settings.steps_per_mm[_axis] / 100.0);
|
||||
max_pulse_cal = 2.0 - (settings.max_travel[_axis] / -100.0);
|
||||
}
|
||||
}
|
||||
else { // settings are not valid so don't apply any calibration
|
||||
min_pulse_cal = 1.0;
|
||||
max_pulse_cal = 1.0;
|
||||
}
|
||||
|
||||
// apply the calibrations
|
||||
servo_pulse_min *= min_pulse_cal;
|
||||
servo_pulse_max *= max_pulse_cal;
|
||||
|
||||
// determine the pulse length
|
||||
servo_pulse_len = (uint32_t)mapConstrain(servo_pos, _position_min, _position_max, servo_pulse_min, servo_pulse_max );
|
||||
_write_pwm(servo_pulse_len);
|
||||
void ServoAxis::set_location() {
|
||||
// These are the pulse lengths for the minimum and maximum positions
|
||||
// Note: Some machines will have the physical max/min inverted with pulse length max/min due to invert setting $3=...
|
||||
float servo_pulse_min, servo_pulse_max;
|
||||
float min_pulse_cal, max_pulse_cal; // calibration values in percent 110% = 1.1
|
||||
uint32_t servo_pulse_len;
|
||||
float servo_pos, mpos, offset;
|
||||
// skip location if we are in alarm mode
|
||||
if (_disable_on_alarm && (sys.state == STATE_ALARM)) {
|
||||
disable();
|
||||
return;
|
||||
}
|
||||
// track the disable status of the steppers if desired.
|
||||
if (_disable_with_steppers && get_stepper_disable()) {
|
||||
disable();
|
||||
return;
|
||||
}
|
||||
if ((_homing_type == SERVO_HOMING_TARGET) && (sys.state == STATE_HOMING)) {
|
||||
servo_pos = _homing_position; // go to servos home position
|
||||
} else {
|
||||
mpos = system_convert_axis_steps_to_mpos(sys_position, _axis); // get the axis machine position in mm
|
||||
if (_use_mpos)
|
||||
servo_pos = mpos;
|
||||
else {
|
||||
offset = gc_state.coord_system[_axis] + gc_state.coord_offset[_axis]; // get the current axis work offset
|
||||
servo_pos = mpos - offset; // determine the current work position
|
||||
}
|
||||
}
|
||||
// 1. Get the pulse ranges of the servos
|
||||
// 2. Invert if selected in the settings
|
||||
// 3. Get the calibration values from the settings
|
||||
// 4. Adjust the calibration offset direction of the cal based on the direction
|
||||
// 5. Apply the calibrarion
|
||||
servo_pulse_min = SERVO_MIN_PULSE;
|
||||
servo_pulse_max = SERVO_MAX_PULSE;
|
||||
if (bit_istrue(settings.dir_invert_mask, bit(_axis))) // this allows the user to change the direction via settings
|
||||
swap(servo_pulse_min, servo_pulse_max);
|
||||
// get the calibration values
|
||||
if (_cal_is_valid()) { // if calibration settings are OK then apply them
|
||||
// apply a calibration
|
||||
// the cals apply differently if the direction is reverse (i.e. longer pulse is lower position)
|
||||
if (bit_isfalse(settings.dir_invert_mask, bit(_axis))) { // normal direction
|
||||
min_pulse_cal = 2.0 - (settings.steps_per_mm[_axis] / 100.0);
|
||||
max_pulse_cal = (settings.max_travel[_axis] / -100.0);
|
||||
} else { // inverted direction
|
||||
min_pulse_cal = (settings.steps_per_mm[_axis] / 100.0);
|
||||
max_pulse_cal = 2.0 - (settings.max_travel[_axis] / -100.0);
|
||||
}
|
||||
} else { // settings are not valid so don't apply any calibration
|
||||
min_pulse_cal = 1.0;
|
||||
max_pulse_cal = 1.0;
|
||||
}
|
||||
// apply the calibrations
|
||||
servo_pulse_min *= min_pulse_cal;
|
||||
servo_pulse_max *= max_pulse_cal;
|
||||
// determine the pulse length
|
||||
servo_pulse_len = (uint32_t)mapConstrain(servo_pos, _position_min, _position_max, servo_pulse_min, servo_pulse_max);
|
||||
_write_pwm(servo_pulse_len);
|
||||
}
|
||||
|
||||
void ServoAxis::_write_pwm(uint32_t duty)
|
||||
{
|
||||
if (ledcRead(_channel_num) != duty) { // only write if it is changing
|
||||
ledcWrite(_channel_num, duty);
|
||||
}
|
||||
void ServoAxis::_write_pwm(uint32_t duty) {
|
||||
if (ledcRead(_channel_num) != duty) // only write if it is changing
|
||||
ledcWrite(_channel_num, duty);
|
||||
}
|
||||
|
||||
// sets the PWM to zero. This allows most servos to be manually moved
|
||||
void ServoAxis::disable()
|
||||
{
|
||||
_write_pwm(0);
|
||||
void ServoAxis::disable() {
|
||||
_write_pwm(0);
|
||||
}
|
||||
|
||||
// checks to see if calibration values are in an acceptable range
|
||||
// vebose = true if you want an error sent to serial port
|
||||
bool ServoAxis::_cal_is_valid()
|
||||
{
|
||||
bool settingsOK = true;
|
||||
|
||||
if ( (settings.steps_per_mm[_axis] < SERVO_CAL_MIN) || (settings.steps_per_mm[_axis] > SERVO_CAL_MAX) ) {
|
||||
if (_showError) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo calibration ($10%d) value error. Reset to 100", _axis);
|
||||
settings.steps_per_mm[_axis] = 100;
|
||||
write_global_settings();
|
||||
}
|
||||
settingsOK = false;
|
||||
}
|
||||
|
||||
// Note: Max travel is set positive via $$, but stored as a negative number
|
||||
if ( (settings.max_travel[_axis] < -SERVO_CAL_MAX) || (settings.max_travel[_axis] > -SERVO_CAL_MIN) ) {
|
||||
if (_showError) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo calibration ($13%d) value error. Reset to 100", _axis);
|
||||
settings.max_travel[_axis] = -100;
|
||||
write_global_settings();
|
||||
}
|
||||
settingsOK = false;
|
||||
}
|
||||
|
||||
_showError = false; // to show error once
|
||||
|
||||
if (! settingsOK) {
|
||||
write_global_settings(); // they were changed so write them to
|
||||
}
|
||||
|
||||
return settingsOK;
|
||||
bool ServoAxis::_cal_is_valid() {
|
||||
bool settingsOK = true;
|
||||
if ((settings.steps_per_mm[_axis] < SERVO_CAL_MIN) || (settings.steps_per_mm[_axis] > SERVO_CAL_MAX)) {
|
||||
if (_showError) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo calibration ($10%d) value error. Reset to 100", _axis);
|
||||
settings.steps_per_mm[_axis] = 100;
|
||||
write_global_settings();
|
||||
}
|
||||
settingsOK = false;
|
||||
}
|
||||
// Note: Max travel is set positive via $$, but stored as a negative number
|
||||
if ((settings.max_travel[_axis] < -SERVO_CAL_MAX) || (settings.max_travel[_axis] > -SERVO_CAL_MIN)) {
|
||||
if (_showError) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo calibration ($13%d) value error. Reset to 100", _axis);
|
||||
settings.max_travel[_axis] = -100;
|
||||
write_global_settings();
|
||||
}
|
||||
settingsOK = false;
|
||||
}
|
||||
_showError = false; // to show error once
|
||||
if (! settingsOK) {
|
||||
write_global_settings(); // they were changed so write them to
|
||||
}
|
||||
return settingsOK;
|
||||
}
|
||||
|
||||
/*
|
||||
@ -306,46 +305,41 @@ bool ServoAxis::_cal_is_valid()
|
||||
This is used when mapping pulse length to the position
|
||||
*/
|
||||
void ServoAxis::set_range(float min, float max) {
|
||||
if (min < max) {
|
||||
_position_min = min;
|
||||
_position_max = max;
|
||||
}
|
||||
else {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Error setting range. Min not smaller than max");
|
||||
}
|
||||
if (min < max) {
|
||||
_position_min = min;
|
||||
_position_max = max;
|
||||
} else
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Error setting range. Min not smaller than max");
|
||||
}
|
||||
|
||||
/*
|
||||
Sets the mode the servo will be in during homing
|
||||
See servo_axis.h for SERVO_HOMING_xxxxx types
|
||||
*/
|
||||
void ServoAxis::set_homing_type(uint8_t homing_type)
|
||||
{
|
||||
if (homing_type <= SERVO_HOMING_TARGET)
|
||||
_homing_type = homing_type;
|
||||
void ServoAxis::set_homing_type(uint8_t homing_type) {
|
||||
if (homing_type <= SERVO_HOMING_TARGET)
|
||||
_homing_type = homing_type;
|
||||
}
|
||||
|
||||
/*
|
||||
Use this to set the homing position the servo will be commanded to go if
|
||||
the current homing mode is SERVO_HOMING_TARGET
|
||||
*/
|
||||
void ServoAxis::set_homing_position(float homing_position)
|
||||
{
|
||||
_homing_position = homing_position;
|
||||
void ServoAxis::set_homing_position(float homing_position) {
|
||||
_homing_position = homing_position;
|
||||
}
|
||||
|
||||
/*
|
||||
Use this to set the disable on alarm feature. If true, then hobby servo PWM
|
||||
will be disable in Grbl alarm mode (like before homing). Typical hobby servo
|
||||
will be disable in Grbl alarm mode (like before homing). Typical hobby servo
|
||||
can be moved by hand in this mode
|
||||
*/
|
||||
void ServoAxis::set_disable_on_alarm (bool disable_on_alarm)
|
||||
{
|
||||
_disable_on_alarm = disable_on_alarm;
|
||||
void ServoAxis::set_disable_on_alarm(bool disable_on_alarm) {
|
||||
_disable_on_alarm = disable_on_alarm;
|
||||
}
|
||||
|
||||
void ServoAxis::set_disable_with_steppers(bool disable_with_steppers) {
|
||||
_disable_with_steppers = disable_with_steppers;
|
||||
_disable_with_steppers = disable_with_steppers;
|
||||
}
|
||||
|
||||
/*
|
||||
@ -353,7 +347,7 @@ void ServoAxis::set_disable_with_steppers(bool disable_with_steppers) {
|
||||
Offsets will not be applied
|
||||
*/
|
||||
void ServoAxis::set_use_mpos(bool use_mpos) {
|
||||
_use_mpos = use_mpos;
|
||||
_use_mpos = use_mpos;
|
||||
}
|
||||
|
||||
|
||||
|
@ -23,37 +23,37 @@
|
||||
The Servo axis feature allows you to use a hobby servo on any axis.
|
||||
This is done using a repeating RTOS task. Grbl continues to calculate
|
||||
the position of the axis in real time. The task looks at the current position of
|
||||
the axis and calculates the required PWM value to go to that location. You define the travel
|
||||
of the servo in millimeters.
|
||||
the axis and calculates the required PWM value to go to that location. You define the travel
|
||||
of the servo in millimeters.
|
||||
|
||||
Grbl still uses the acceleration and speed values you have in the settings, so it
|
||||
will coordinate servo axes with stepper motor axes. This assumes these values are within the
|
||||
will coordinate servo axes with stepper motor axes. This assumes these values are within the
|
||||
capabilities of the servo
|
||||
|
||||
Usage
|
||||
|
||||
1. In config.h un-comment #define USE_SERVO_AXES
|
||||
|
||||
2. In a cpu_map.h section, define servo pins and PWM channels like this ....
|
||||
Usage
|
||||
|
||||
1. In config.h un-comment #define USE_SERVO_AXES
|
||||
|
||||
2. In the machine definition file in Machines/, define servo pins and PWM channels like this ....
|
||||
#define SERVO_Y_PIN GPIO_NUM_14
|
||||
#define SERVO_Y_CHANNEL_NUM 6
|
||||
|
||||
|
||||
undefine any step and direction pins associated with that axis
|
||||
|
||||
|
||||
3. In servo_axis.cpp init_servos() function, configure servos like this ....
|
||||
X_Servo_Axis.set_range(0.0, 20.0); // millimeter
|
||||
X_Servo_Axis.set_homing_type(SERVO_HOMING_OFF);
|
||||
X_Servo_Axis.set_disable_on_alarm(true);
|
||||
|
||||
|
||||
|
||||
The positions can be calibrated using the settings. $10x (resolution) settings adjust the minimum
|
||||
position and $13x (max travel) settings adjust the maximum position. If the servo is traveling
|
||||
backwards from what you want, you can use the $3 direction setting to compensate.
|
||||
position and $13x (max travel) settings adjust the maximum position. If the servo is traveling
|
||||
backwards from what you want, you can use the $3 direction setting to compensate.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef servo_axis_h
|
||||
#define servo_axis_h
|
||||
#define servo_axis_h
|
||||
|
||||
|
||||
|
||||
@ -88,46 +88,46 @@
|
||||
extern float my_location;
|
||||
|
||||
void init_servos();
|
||||
void servosSyncTask(void *pvParameters);
|
||||
void servosSyncTask(void* pvParameters);
|
||||
|
||||
|
||||
class ServoAxis{
|
||||
public:
|
||||
ServoAxis(uint8_t axis, uint8_t pin_num, uint8_t channel_num); // constructor
|
||||
void init();
|
||||
void set_location();
|
||||
void disable(); // sets PWM to 0% duty cycle. Most servos can be manually moved in this state
|
||||
void set_range(float min, float max);
|
||||
void set_homing_type(uint8_t homing_type);
|
||||
void set_homing_position(float homing_position);
|
||||
void set_disable_on_alarm (bool disable_on_alarm);
|
||||
void set_disable_with_steppers(bool disable_with_steppers);
|
||||
void set_use_mpos(bool use_mpos);
|
||||
|
||||
private:
|
||||
int _axis; // these should be assign in constructor using Grbl X_AXIS type values
|
||||
int _pin_num; // The GPIO pin being used
|
||||
int _channel_num; // The PWM channel
|
||||
bool _showError;
|
||||
|
||||
uint32_t _pwm_freq = SERVO_PULSE_FREQ;
|
||||
uint32_t _pwm_resolution_bits = SERVO_PULSE_RES_BITS;
|
||||
float _pulse_min = SERVO_MIN_PULSE; // in pwm counts
|
||||
float _pulse_max = SERVO_MAX_PULSE; // in pwm counts
|
||||
float _position_min = SERVO_POSITION_MIN_DEFAULT; // position in millimeters
|
||||
float _position_max = SERVO_POSITION_MAX_DEFAULT; // position in millimeters
|
||||
|
||||
|
||||
uint8_t _homing_type = SERVO_HOMING_OFF;
|
||||
float _homing_position = SERVO_POSITION_MAX_DEFAULT;
|
||||
bool _disable_on_alarm = true;
|
||||
bool _disable_with_steppers = false;
|
||||
bool _use_mpos = true;
|
||||
|
||||
bool _validate_cal_settings();
|
||||
void _write_pwm(uint32_t duty);
|
||||
bool _cal_is_valid(); // checks to see if calibration values are in acceptable range
|
||||
|
||||
class ServoAxis {
|
||||
public:
|
||||
ServoAxis(uint8_t axis, uint8_t pin_num, uint8_t channel_num); // constructor
|
||||
void init();
|
||||
void set_location();
|
||||
void disable(); // sets PWM to 0% duty cycle. Most servos can be manually moved in this state
|
||||
void set_range(float min, float max);
|
||||
void set_homing_type(uint8_t homing_type);
|
||||
void set_homing_position(float homing_position);
|
||||
void set_disable_on_alarm(bool disable_on_alarm);
|
||||
void set_disable_with_steppers(bool disable_with_steppers);
|
||||
void set_use_mpos(bool use_mpos);
|
||||
|
||||
private:
|
||||
int _axis; // these should be assign in constructor using Grbl X_AXIS type values
|
||||
int _pin_num; // The GPIO pin being used
|
||||
int _channel_num; // The PWM channel
|
||||
bool _showError;
|
||||
|
||||
uint32_t _pwm_freq = SERVO_PULSE_FREQ;
|
||||
uint32_t _pwm_resolution_bits = SERVO_PULSE_RES_BITS;
|
||||
float _pulse_min = SERVO_MIN_PULSE; // in pwm counts
|
||||
float _pulse_max = SERVO_MAX_PULSE; // in pwm counts
|
||||
float _position_min = SERVO_POSITION_MIN_DEFAULT; // position in millimeters
|
||||
float _position_max = SERVO_POSITION_MAX_DEFAULT; // position in millimeters
|
||||
|
||||
|
||||
uint8_t _homing_type = SERVO_HOMING_OFF;
|
||||
float _homing_position = SERVO_POSITION_MAX_DEFAULT;
|
||||
bool _disable_on_alarm = true;
|
||||
bool _disable_with_steppers = false;
|
||||
bool _use_mpos = true;
|
||||
|
||||
bool _validate_cal_settings();
|
||||
void _write_pwm(uint32_t duty);
|
||||
bool _cal_is_valid(); // checks to see if calibration values are in acceptable range
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
@ -27,440 +27,397 @@
|
||||
settings_t settings;
|
||||
|
||||
// Method to store startup lines into EEPROM
|
||||
void settings_store_startup_line(uint8_t n, char *line)
|
||||
{
|
||||
#ifdef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE
|
||||
protocol_buffer_synchronize(); // A startup line may contain a motion and be executing.
|
||||
#endif
|
||||
uint32_t addr = n*(LINE_BUFFER_SIZE+1)+EEPROM_ADDR_STARTUP_BLOCK;
|
||||
memcpy_to_eeprom_with_checksum(addr,(char*)line, LINE_BUFFER_SIZE);
|
||||
void settings_store_startup_line(uint8_t n, char* line) {
|
||||
#ifdef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE
|
||||
protocol_buffer_synchronize(); // A startup line may contain a motion and be executing.
|
||||
#endif
|
||||
uint32_t addr = n * (LINE_BUFFER_SIZE + 1) + EEPROM_ADDR_STARTUP_BLOCK;
|
||||
memcpy_to_eeprom_with_checksum(addr, (char*)line, LINE_BUFFER_SIZE);
|
||||
}
|
||||
|
||||
void settings_init()
|
||||
{
|
||||
EEPROM.begin(EEPROM_SIZE);
|
||||
|
||||
if(!read_global_settings()) {
|
||||
report_status_message(STATUS_SETTING_READ_FAIL, CLIENT_SERIAL);
|
||||
settings_restore(SETTINGS_RESTORE_ALL); // Force restore all EEPROM data.
|
||||
report_grbl_settings(CLIENT_SERIAL, false); // only the serial could be working at this point
|
||||
}
|
||||
void settings_init() {
|
||||
EEPROM.begin(EEPROM_SIZE);
|
||||
if (!read_global_settings()) {
|
||||
report_status_message(STATUS_SETTING_READ_FAIL, CLIENT_SERIAL);
|
||||
settings_restore(SETTINGS_RESTORE_ALL); // Force restore all EEPROM data.
|
||||
report_grbl_settings(CLIENT_SERIAL, false); // only the serial could be working at this point
|
||||
}
|
||||
}
|
||||
|
||||
// Method to restore EEPROM-saved Grbl global settings back to defaults.
|
||||
void settings_restore(uint8_t restore_flag) {
|
||||
#if defined(ENABLE_BLUETOOTH) || defined(ENABLE_WIFI)
|
||||
if (restore_flag & SETTINGS_RESTORE_WIFI_SETTINGS){
|
||||
if (restore_flag & SETTINGS_RESTORE_WIFI_SETTINGS) {
|
||||
#ifdef ENABLE_WIFI
|
||||
wifi_config.reset_settings();
|
||||
wifi_config.reset_settings();
|
||||
#endif
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
bt_config.reset_settings();
|
||||
bt_config.reset_settings();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
if (restore_flag & SETTINGS_RESTORE_DEFAULTS) {
|
||||
settings.pulse_microseconds = DEFAULT_STEP_PULSE_MICROSECONDS;
|
||||
settings.stepper_idle_lock_time = DEFAULT_STEPPER_IDLE_LOCK_TIME;
|
||||
settings.step_invert_mask = DEFAULT_STEPPING_INVERT_MASK;
|
||||
settings.dir_invert_mask = DEFAULT_DIRECTION_INVERT_MASK;
|
||||
settings.status_report_mask = DEFAULT_STATUS_REPORT_MASK;
|
||||
settings.junction_deviation = DEFAULT_JUNCTION_DEVIATION;
|
||||
|
||||
settings.arc_tolerance = DEFAULT_ARC_TOLERANCE;
|
||||
|
||||
settings.spindle_pwm_freq = DEFAULT_SPINDLE_FREQ; // $33 Hz (extended set)
|
||||
settings.spindle_pwm_off_value = DEFAULT_SPINDLE_OFF_VALUE; // $34 Percent (extended set)
|
||||
settings.spindle_pwm_min_value = DEFAULT_SPINDLE_MIN_VALUE; // $35 Percent (extended set)
|
||||
settings.spindle_pwm_max_value = DEFAULT_SPINDLE_MAX_VALUE; // $36 Percent (extended set)
|
||||
|
||||
settings.rpm_max = DEFAULT_SPINDLE_RPM_MAX;
|
||||
settings.rpm_min = DEFAULT_SPINDLE_RPM_MIN;
|
||||
|
||||
settings.homing_dir_mask = DEFAULT_HOMING_DIR_MASK;
|
||||
settings.homing_feed_rate = DEFAULT_HOMING_FEED_RATE;
|
||||
settings.homing_seek_rate = DEFAULT_HOMING_SEEK_RATE;
|
||||
settings.homing_debounce_delay = DEFAULT_HOMING_DEBOUNCE_DELAY;
|
||||
settings.homing_pulloff = DEFAULT_HOMING_PULLOFF;
|
||||
|
||||
settings.flags = 0;
|
||||
if (DEFAULT_REPORT_INCHES) { settings.flags |= BITFLAG_REPORT_INCHES; }
|
||||
if (DEFAULT_LASER_MODE) { settings.flags |= BITFLAG_LASER_MODE; }
|
||||
if (DEFAULT_INVERT_ST_ENABLE) { settings.flags |= BITFLAG_INVERT_ST_ENABLE; }
|
||||
if (DEFAULT_HARD_LIMIT_ENABLE) { settings.flags |= BITFLAG_HARD_LIMIT_ENABLE; }
|
||||
if (DEFAULT_HOMING_ENABLE) { settings.flags |= BITFLAG_HOMING_ENABLE; }
|
||||
if (DEFAULT_SOFT_LIMIT_ENABLE) { settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE; }
|
||||
if (DEFAULT_INVERT_LIMIT_PINS) { settings.flags |= BITFLAG_INVERT_LIMIT_PINS; }
|
||||
if (DEFAULT_INVERT_PROBE_PIN) { settings.flags |= BITFLAG_INVERT_PROBE_PIN; }
|
||||
|
||||
settings.steps_per_mm[X_AXIS] = DEFAULT_X_STEPS_PER_MM;
|
||||
settings.steps_per_mm[Y_AXIS] = DEFAULT_Y_STEPS_PER_MM;
|
||||
settings.steps_per_mm[Z_AXIS] = DEFAULT_Z_STEPS_PER_MM;
|
||||
|
||||
settings.max_rate[X_AXIS] = DEFAULT_X_MAX_RATE;
|
||||
settings.max_rate[Y_AXIS] = DEFAULT_Y_MAX_RATE;
|
||||
settings.max_rate[Z_AXIS] = DEFAULT_Z_MAX_RATE;
|
||||
|
||||
settings.acceleration[X_AXIS] = DEFAULT_X_ACCELERATION;
|
||||
settings.acceleration[Y_AXIS] = DEFAULT_Y_ACCELERATION;
|
||||
settings.acceleration[Z_AXIS] = DEFAULT_Z_ACCELERATION;
|
||||
|
||||
settings.max_travel[X_AXIS] = (-DEFAULT_X_MAX_TRAVEL);
|
||||
settings.max_travel[Y_AXIS] = (-DEFAULT_Y_MAX_TRAVEL);
|
||||
settings.max_travel[Z_AXIS] = (-DEFAULT_Z_MAX_TRAVEL);
|
||||
|
||||
settings.current[X_AXIS] = DEFAULT_X_CURRENT;
|
||||
settings.current[Y_AXIS] = DEFAULT_Y_CURRENT;
|
||||
settings.current[Z_AXIS] = DEFAULT_Z_CURRENT;
|
||||
|
||||
settings.hold_current[X_AXIS] = DEFAULT_X_HOLD_CURRENT;
|
||||
settings.hold_current[Y_AXIS] = DEFAULT_Y_HOLD_CURRENT;
|
||||
settings.hold_current[Z_AXIS] = DEFAULT_Z_HOLD_CURRENT;
|
||||
|
||||
settings.microsteps[X_AXIS] = DEFAULT_X_MICROSTEPS;
|
||||
settings.microsteps[Y_AXIS] = DEFAULT_Y_MICROSTEPS;
|
||||
settings.microsteps[Z_AXIS] = DEFAULT_Z_MICROSTEPS;
|
||||
|
||||
settings.stallguard[X_AXIS] = DEFAULT_X_STALLGUARD;
|
||||
settings.stallguard[Y_AXIS] = DEFAULT_Y_STALLGUARD;
|
||||
settings.stallguard[Z_AXIS] = DEFAULT_Z_STALLGUARD;
|
||||
|
||||
#if (N_AXIS > A_AXIS)
|
||||
settings.steps_per_mm[A_AXIS] = DEFAULT_A_STEPS_PER_MM;
|
||||
settings.max_rate[A_AXIS] = DEFAULT_A_MAX_RATE;
|
||||
settings.acceleration[A_AXIS] = DEFAULT_A_ACCELERATION;
|
||||
settings.max_travel[A_AXIS] = (-DEFAULT_A_MAX_TRAVEL);
|
||||
settings.current[A_AXIS] = DEFAULT_A_CURRENT;
|
||||
settings.hold_current[A_AXIS] = DEFAULT_A_HOLD_CURRENT;
|
||||
settings.microsteps[A_AXIS] = DEFAULT_A_MICROSTEPS;
|
||||
settings.stallguard[A_AXIS] = DEFAULT_Z_STALLGUARD;
|
||||
#endif
|
||||
|
||||
#if (N_AXIS > B_AXIS)
|
||||
settings.steps_per_mm[B_AXIS] = DEFAULT_B_STEPS_PER_MM;
|
||||
settings.max_rate[B_AXIS] = DEFAULT_B_MAX_RATE;
|
||||
settings.acceleration[B_AXIS] = DEFAULT_B_ACCELERATION;
|
||||
settings.max_travel[B_AXIS] = (-DEFAULT_B_MAX_TRAVEL);
|
||||
settings.current[B_AXIS] = DEFAULT_B_CURRENT;
|
||||
settings.hold_current[B_AXIS] = DEFAULT_B_HOLD_CURRENT;
|
||||
settings.microsteps[B_AXIS] = DEFAULT_B_MICROSTEPS;
|
||||
settings.stallguard[B_AXIS] = DEFAULT_Z_STALLGUARD;
|
||||
#endif
|
||||
|
||||
#if (N_AXIS > C_AXIS)
|
||||
settings.steps_per_mm[C_AXIS] = DEFAULT_C_STEPS_PER_MM;
|
||||
settings.max_rate[C_AXIS] = DEFAULT_C_MAX_RATE;
|
||||
settings.acceleration[C_AXIS] = DEFAULT_C_ACCELERATION;
|
||||
settings.max_travel[C_AXIS] = (-DEFAULT_C_MAX_TRAVEL);
|
||||
settings.current[C_AXIS] = DEFAULT_C_CURRENT;
|
||||
settings.hold_current[C_AXIS] = DEFAULT_C_HOLD_CURRENT;
|
||||
settings.microsteps[C_AXIS] = DEFAULT_C_MICROSTEPS;
|
||||
settings.stallguard[C_AXIS] = DEFAULT_Z_STALLGUARD;
|
||||
#endif
|
||||
|
||||
// TODO figure out a clean way to add actual default values
|
||||
for (uint8_t index = 0; index<USER_SETTING_COUNT; index++) {
|
||||
settings.machine_int16[index] = 0;
|
||||
settings.machine_float[index] = 0.0;
|
||||
}
|
||||
|
||||
// User Integer values
|
||||
settings.machine_int16[0] = DEFAULT_USER_INT_80;
|
||||
settings.machine_int16[1] = DEFAULT_USER_INT_81;
|
||||
settings.machine_int16[2] = DEFAULT_USER_INT_82;
|
||||
settings.machine_int16[3] = DEFAULT_USER_INT_83;
|
||||
settings.machine_int16[4] = DEFAULT_USER_INT_84;
|
||||
|
||||
// User Integer values
|
||||
settings.machine_float[0] = DEFAULT_USER_FLOAT_90;
|
||||
settings.machine_float[1] = DEFAULT_USER_FLOAT_91;
|
||||
settings.machine_float[2] = DEFAULT_USER_FLOAT_92;
|
||||
settings.machine_float[3] = DEFAULT_USER_FLOAT_93;
|
||||
settings.machine_float[4] = DEFAULT_USER_FLOAT_94;
|
||||
|
||||
|
||||
write_global_settings();
|
||||
}
|
||||
|
||||
if (restore_flag & SETTINGS_RESTORE_PARAMETERS) {
|
||||
uint8_t idx;
|
||||
float coord_data[N_AXIS];
|
||||
memset(&coord_data, 0, sizeof(coord_data));
|
||||
for (idx=0; idx <= SETTING_INDEX_NCOORD; idx++) { settings_write_coord_data(idx, coord_data); }
|
||||
}
|
||||
|
||||
if (restore_flag & SETTINGS_RESTORE_STARTUP_LINES) {
|
||||
#if N_STARTUP_LINE > 0
|
||||
EEPROM.write(EEPROM_ADDR_STARTUP_BLOCK, 0);
|
||||
EEPROM.write(EEPROM_ADDR_STARTUP_BLOCK+1, 0); // Checksum
|
||||
EEPROM.commit();
|
||||
#endif
|
||||
#if N_STARTUP_LINE > 1
|
||||
EEPROM.write(EEPROM_ADDR_STARTUP_BLOCK+(LINE_BUFFER_SIZE+1), 0);
|
||||
EEPROM.write(EEPROM_ADDR_STARTUP_BLOCK+(LINE_BUFFER_SIZE+2), 0); // Checksum
|
||||
EEPROM.commit();
|
||||
#endif
|
||||
}
|
||||
|
||||
if (restore_flag & SETTINGS_RESTORE_BUILD_INFO) {
|
||||
EEPROM.write(EEPROM_ADDR_BUILD_INFO , 0);
|
||||
EEPROM.write(EEPROM_ADDR_BUILD_INFO+1 , 0); // Checksum
|
||||
EEPROM.commit();
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
if (restore_flag & SETTINGS_RESTORE_DEFAULTS) {
|
||||
settings.pulse_microseconds = DEFAULT_STEP_PULSE_MICROSECONDS;
|
||||
settings.stepper_idle_lock_time = DEFAULT_STEPPER_IDLE_LOCK_TIME;
|
||||
settings.step_invert_mask = DEFAULT_STEPPING_INVERT_MASK;
|
||||
settings.dir_invert_mask = DEFAULT_DIRECTION_INVERT_MASK;
|
||||
settings.status_report_mask = DEFAULT_STATUS_REPORT_MASK;
|
||||
settings.junction_deviation = DEFAULT_JUNCTION_DEVIATION;
|
||||
settings.arc_tolerance = DEFAULT_ARC_TOLERANCE;
|
||||
settings.spindle_pwm_freq = DEFAULT_SPINDLE_FREQ; // $33 Hz (extended set)
|
||||
settings.spindle_pwm_off_value = DEFAULT_SPINDLE_OFF_VALUE; // $34 Percent (extended set)
|
||||
settings.spindle_pwm_min_value = DEFAULT_SPINDLE_MIN_VALUE; // $35 Percent (extended set)
|
||||
settings.spindle_pwm_max_value = DEFAULT_SPINDLE_MAX_VALUE; // $36 Percent (extended set)
|
||||
settings.rpm_max = DEFAULT_SPINDLE_RPM_MAX;
|
||||
settings.rpm_min = DEFAULT_SPINDLE_RPM_MIN;
|
||||
settings.homing_dir_mask = DEFAULT_HOMING_DIR_MASK;
|
||||
settings.homing_feed_rate = DEFAULT_HOMING_FEED_RATE;
|
||||
settings.homing_seek_rate = DEFAULT_HOMING_SEEK_RATE;
|
||||
settings.homing_debounce_delay = DEFAULT_HOMING_DEBOUNCE_DELAY;
|
||||
settings.homing_pulloff = DEFAULT_HOMING_PULLOFF;
|
||||
settings.flags = 0;
|
||||
if (DEFAULT_REPORT_INCHES) settings.flags |= BITFLAG_REPORT_INCHES;
|
||||
if (DEFAULT_LASER_MODE) settings.flags |= BITFLAG_LASER_MODE;
|
||||
if (DEFAULT_INVERT_ST_ENABLE) settings.flags |= BITFLAG_INVERT_ST_ENABLE;
|
||||
if (DEFAULT_HARD_LIMIT_ENABLE) settings.flags |= BITFLAG_HARD_LIMIT_ENABLE;
|
||||
if (DEFAULT_HOMING_ENABLE) settings.flags |= BITFLAG_HOMING_ENABLE;
|
||||
if (DEFAULT_SOFT_LIMIT_ENABLE) settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE;
|
||||
if (DEFAULT_INVERT_LIMIT_PINS) settings.flags |= BITFLAG_INVERT_LIMIT_PINS;
|
||||
if (DEFAULT_INVERT_PROBE_PIN) settings.flags |= BITFLAG_INVERT_PROBE_PIN;
|
||||
settings.steps_per_mm[X_AXIS] = DEFAULT_X_STEPS_PER_MM;
|
||||
settings.steps_per_mm[Y_AXIS] = DEFAULT_Y_STEPS_PER_MM;
|
||||
settings.steps_per_mm[Z_AXIS] = DEFAULT_Z_STEPS_PER_MM;
|
||||
settings.max_rate[X_AXIS] = DEFAULT_X_MAX_RATE;
|
||||
settings.max_rate[Y_AXIS] = DEFAULT_Y_MAX_RATE;
|
||||
settings.max_rate[Z_AXIS] = DEFAULT_Z_MAX_RATE;
|
||||
settings.acceleration[X_AXIS] = DEFAULT_X_ACCELERATION;
|
||||
settings.acceleration[Y_AXIS] = DEFAULT_Y_ACCELERATION;
|
||||
settings.acceleration[Z_AXIS] = DEFAULT_Z_ACCELERATION;
|
||||
settings.max_travel[X_AXIS] = (-DEFAULT_X_MAX_TRAVEL);
|
||||
settings.max_travel[Y_AXIS] = (-DEFAULT_Y_MAX_TRAVEL);
|
||||
settings.max_travel[Z_AXIS] = (-DEFAULT_Z_MAX_TRAVEL);
|
||||
settings.current[X_AXIS] = DEFAULT_X_CURRENT;
|
||||
settings.current[Y_AXIS] = DEFAULT_Y_CURRENT;
|
||||
settings.current[Z_AXIS] = DEFAULT_Z_CURRENT;
|
||||
settings.hold_current[X_AXIS] = DEFAULT_X_HOLD_CURRENT;
|
||||
settings.hold_current[Y_AXIS] = DEFAULT_Y_HOLD_CURRENT;
|
||||
settings.hold_current[Z_AXIS] = DEFAULT_Z_HOLD_CURRENT;
|
||||
settings.microsteps[X_AXIS] = DEFAULT_X_MICROSTEPS;
|
||||
settings.microsteps[Y_AXIS] = DEFAULT_Y_MICROSTEPS;
|
||||
settings.microsteps[Z_AXIS] = DEFAULT_Z_MICROSTEPS;
|
||||
settings.stallguard[X_AXIS] = DEFAULT_X_STALLGUARD;
|
||||
settings.stallguard[Y_AXIS] = DEFAULT_Y_STALLGUARD;
|
||||
settings.stallguard[Z_AXIS] = DEFAULT_Z_STALLGUARD;
|
||||
#if (N_AXIS > A_AXIS)
|
||||
settings.steps_per_mm[A_AXIS] = DEFAULT_A_STEPS_PER_MM;
|
||||
settings.max_rate[A_AXIS] = DEFAULT_A_MAX_RATE;
|
||||
settings.acceleration[A_AXIS] = DEFAULT_A_ACCELERATION;
|
||||
settings.max_travel[A_AXIS] = (-DEFAULT_A_MAX_TRAVEL);
|
||||
settings.current[A_AXIS] = DEFAULT_A_CURRENT;
|
||||
settings.hold_current[A_AXIS] = DEFAULT_A_HOLD_CURRENT;
|
||||
settings.microsteps[A_AXIS] = DEFAULT_A_MICROSTEPS;
|
||||
settings.stallguard[A_AXIS] = DEFAULT_Z_STALLGUARD;
|
||||
#endif
|
||||
#if (N_AXIS > B_AXIS)
|
||||
settings.steps_per_mm[B_AXIS] = DEFAULT_B_STEPS_PER_MM;
|
||||
settings.max_rate[B_AXIS] = DEFAULT_B_MAX_RATE;
|
||||
settings.acceleration[B_AXIS] = DEFAULT_B_ACCELERATION;
|
||||
settings.max_travel[B_AXIS] = (-DEFAULT_B_MAX_TRAVEL);
|
||||
settings.current[B_AXIS] = DEFAULT_B_CURRENT;
|
||||
settings.hold_current[B_AXIS] = DEFAULT_B_HOLD_CURRENT;
|
||||
settings.microsteps[B_AXIS] = DEFAULT_B_MICROSTEPS;
|
||||
settings.stallguard[B_AXIS] = DEFAULT_Z_STALLGUARD;
|
||||
#endif
|
||||
#if (N_AXIS > C_AXIS)
|
||||
settings.steps_per_mm[C_AXIS] = DEFAULT_C_STEPS_PER_MM;
|
||||
settings.max_rate[C_AXIS] = DEFAULT_C_MAX_RATE;
|
||||
settings.acceleration[C_AXIS] = DEFAULT_C_ACCELERATION;
|
||||
settings.max_travel[C_AXIS] = (-DEFAULT_C_MAX_TRAVEL);
|
||||
settings.current[C_AXIS] = DEFAULT_C_CURRENT;
|
||||
settings.hold_current[C_AXIS] = DEFAULT_C_HOLD_CURRENT;
|
||||
settings.microsteps[C_AXIS] = DEFAULT_C_MICROSTEPS;
|
||||
settings.stallguard[C_AXIS] = DEFAULT_Z_STALLGUARD;
|
||||
#endif
|
||||
// TODO figure out a clean way to add actual default values
|
||||
for (uint8_t index = 0; index < USER_SETTING_COUNT; index++) {
|
||||
settings.machine_int16[index] = 0;
|
||||
settings.machine_float[index] = 0.0;
|
||||
}
|
||||
// User Integer values
|
||||
settings.machine_int16[0] = DEFAULT_USER_INT_80;
|
||||
settings.machine_int16[1] = DEFAULT_USER_INT_81;
|
||||
settings.machine_int16[2] = DEFAULT_USER_INT_82;
|
||||
settings.machine_int16[3] = DEFAULT_USER_INT_83;
|
||||
settings.machine_int16[4] = DEFAULT_USER_INT_84;
|
||||
// User Integer values
|
||||
settings.machine_float[0] = DEFAULT_USER_FLOAT_90;
|
||||
settings.machine_float[1] = DEFAULT_USER_FLOAT_91;
|
||||
settings.machine_float[2] = DEFAULT_USER_FLOAT_92;
|
||||
settings.machine_float[3] = DEFAULT_USER_FLOAT_93;
|
||||
settings.machine_float[4] = DEFAULT_USER_FLOAT_94;
|
||||
write_global_settings();
|
||||
}
|
||||
if (restore_flag & SETTINGS_RESTORE_PARAMETERS) {
|
||||
uint8_t idx;
|
||||
float coord_data[N_AXIS];
|
||||
memset(&coord_data, 0, sizeof(coord_data));
|
||||
for (idx = 0; idx <= SETTING_INDEX_NCOORD; idx++) settings_write_coord_data(idx, coord_data);
|
||||
}
|
||||
if (restore_flag & SETTINGS_RESTORE_STARTUP_LINES) {
|
||||
#if N_STARTUP_LINE > 0
|
||||
EEPROM.write(EEPROM_ADDR_STARTUP_BLOCK, 0);
|
||||
EEPROM.write(EEPROM_ADDR_STARTUP_BLOCK + 1, 0); // Checksum
|
||||
EEPROM.commit();
|
||||
#endif
|
||||
#if N_STARTUP_LINE > 1
|
||||
EEPROM.write(EEPROM_ADDR_STARTUP_BLOCK + (LINE_BUFFER_SIZE + 1), 0);
|
||||
EEPROM.write(EEPROM_ADDR_STARTUP_BLOCK + (LINE_BUFFER_SIZE + 2), 0); // Checksum
|
||||
EEPROM.commit();
|
||||
#endif
|
||||
}
|
||||
if (restore_flag & SETTINGS_RESTORE_BUILD_INFO) {
|
||||
EEPROM.write(EEPROM_ADDR_BUILD_INFO, 0);
|
||||
EEPROM.write(EEPROM_ADDR_BUILD_INFO + 1, 0); // Checksum
|
||||
EEPROM.commit();
|
||||
}
|
||||
}
|
||||
|
||||
// Reads Grbl global settings struct from EEPROM.
|
||||
uint8_t read_global_settings() {
|
||||
// Check version-byte of eeprom
|
||||
uint8_t version = EEPROM.read(0);
|
||||
if (version == SETTINGS_VERSION) {
|
||||
// Read settings-record and check checksum
|
||||
if (!(memcpy_from_eeprom_with_checksum((char*)&settings, EEPROM_ADDR_GLOBAL, sizeof(settings_t)))) {
|
||||
return(false);
|
||||
}
|
||||
} else {
|
||||
return(false);
|
||||
}
|
||||
return(true);
|
||||
// Check version-byte of eeprom
|
||||
uint8_t version = EEPROM.read(0);
|
||||
if (version == SETTINGS_VERSION) {
|
||||
// Read settings-record and check checksum
|
||||
if (!(memcpy_from_eeprom_with_checksum((char*)&settings, EEPROM_ADDR_GLOBAL, sizeof(settings_t))))
|
||||
return (false);
|
||||
} else
|
||||
return (false);
|
||||
return (true);
|
||||
}
|
||||
|
||||
// Method to store Grbl global settings struct and version number into EEPROM
|
||||
// NOTE: This function can only be called in IDLE state.
|
||||
void write_global_settings()
|
||||
{
|
||||
EEPROM.write(0, SETTINGS_VERSION);
|
||||
memcpy_to_eeprom_with_checksum(EEPROM_ADDR_GLOBAL, (char*)&settings, sizeof(settings_t));
|
||||
|
||||
void write_global_settings() {
|
||||
EEPROM.write(0, SETTINGS_VERSION);
|
||||
memcpy_to_eeprom_with_checksum(EEPROM_ADDR_GLOBAL, (char*)&settings, sizeof(settings_t));
|
||||
}
|
||||
|
||||
// Read selected coordinate data from EEPROM. Updates pointed coord_data value.
|
||||
uint8_t settings_read_coord_data(uint8_t coord_select, float *coord_data)
|
||||
{
|
||||
uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS;
|
||||
if (!(memcpy_from_eeprom_with_checksum((char*)coord_data, addr, sizeof(float)*N_AXIS))) {
|
||||
// Reset with default zero vector
|
||||
clear_vector_float(coord_data);
|
||||
settings_write_coord_data(coord_select,coord_data);
|
||||
return(false);
|
||||
}
|
||||
return(true);
|
||||
uint8_t settings_read_coord_data(uint8_t coord_select, float* coord_data) {
|
||||
uint32_t addr = coord_select * (sizeof(float) * N_AXIS + 1) + EEPROM_ADDR_PARAMETERS;
|
||||
if (!(memcpy_from_eeprom_with_checksum((char*)coord_data, addr, sizeof(float)*N_AXIS))) {
|
||||
// Reset with default zero vector
|
||||
clear_vector_float(coord_data);
|
||||
settings_write_coord_data(coord_select, coord_data);
|
||||
return (false);
|
||||
}
|
||||
return (true);
|
||||
}
|
||||
|
||||
// Method to store coord data parameters into EEPROM
|
||||
void settings_write_coord_data(uint8_t coord_select, float *coord_data)
|
||||
{
|
||||
#ifdef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE
|
||||
void settings_write_coord_data(uint8_t coord_select, float* coord_data) {
|
||||
#ifdef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE
|
||||
protocol_buffer_synchronize();
|
||||
#endif
|
||||
uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS;
|
||||
memcpy_to_eeprom_with_checksum(addr,(char*)coord_data, sizeof(float)*N_AXIS);
|
||||
#endif
|
||||
uint32_t addr = coord_select * (sizeof(float) * N_AXIS + 1) + EEPROM_ADDR_PARAMETERS;
|
||||
memcpy_to_eeprom_with_checksum(addr, (char*)coord_data, sizeof(float)*N_AXIS);
|
||||
}
|
||||
|
||||
// Method to store build info into EEPROM
|
||||
// NOTE: This function can only be called in IDLE state.
|
||||
void settings_store_build_info(char *line)
|
||||
{
|
||||
// Build info can only be stored when state is IDLE.
|
||||
memcpy_to_eeprom_with_checksum(EEPROM_ADDR_BUILD_INFO,(char*)line, LINE_BUFFER_SIZE);
|
||||
void settings_store_build_info(char* line) {
|
||||
// Build info can only be stored when state is IDLE.
|
||||
memcpy_to_eeprom_with_checksum(EEPROM_ADDR_BUILD_INFO, (char*)line, LINE_BUFFER_SIZE);
|
||||
}
|
||||
|
||||
// Reads startup line from EEPROM. Updated pointed line string data.
|
||||
uint8_t settings_read_build_info(char *line)
|
||||
{
|
||||
if (!(memcpy_from_eeprom_with_checksum((char*)line, EEPROM_ADDR_BUILD_INFO, LINE_BUFFER_SIZE))) {
|
||||
// Reset line with default value
|
||||
line[0] = 0; // Empty line
|
||||
settings_store_build_info(line);
|
||||
return(false);
|
||||
}
|
||||
return(true);
|
||||
uint8_t settings_read_build_info(char* line) {
|
||||
if (!(memcpy_from_eeprom_with_checksum((char*)line, EEPROM_ADDR_BUILD_INFO, LINE_BUFFER_SIZE))) {
|
||||
// Reset line with default value
|
||||
line[0] = 0; // Empty line
|
||||
settings_store_build_info(line);
|
||||
return (false);
|
||||
}
|
||||
return (true);
|
||||
}
|
||||
|
||||
|
||||
|
||||
// Reads startup line from EEPROM. Updated pointed line string data.
|
||||
uint8_t settings_read_startup_line(uint8_t n, char *line)
|
||||
{
|
||||
uint32_t addr = n*(LINE_BUFFER_SIZE+1)+EEPROM_ADDR_STARTUP_BLOCK;
|
||||
if (!(memcpy_from_eeprom_with_checksum((char*)line, addr, LINE_BUFFER_SIZE))) {
|
||||
// Reset line with default value
|
||||
line[0] = 0; // Empty line
|
||||
settings_store_startup_line(n, line);
|
||||
return(false);
|
||||
}
|
||||
return(true);
|
||||
uint8_t settings_read_startup_line(uint8_t n, char* line) {
|
||||
uint32_t addr = n * (LINE_BUFFER_SIZE + 1) + EEPROM_ADDR_STARTUP_BLOCK;
|
||||
if (!(memcpy_from_eeprom_with_checksum((char*)line, addr, LINE_BUFFER_SIZE))) {
|
||||
// Reset line with default value
|
||||
line[0] = 0; // Empty line
|
||||
settings_store_startup_line(n, line);
|
||||
return (false);
|
||||
}
|
||||
return (true);
|
||||
}
|
||||
|
||||
// A helper method to set settings from command line
|
||||
uint8_t settings_store_global_setting(uint8_t parameter, float value) {
|
||||
if (value < 0.0) { return(STATUS_NEGATIVE_VALUE); }
|
||||
uint8_t int_value = trunc(value); // integer version
|
||||
if (parameter >= AXIS_SETTINGS_START_VAL) {
|
||||
// Store axis configuration. Axis numbering sequence set by AXIS_SETTING defines.
|
||||
// NOTE: Ensure the setting index corresponds to the report.c settings printout.
|
||||
parameter -= AXIS_SETTINGS_START_VAL;
|
||||
uint8_t set_idx = 0;
|
||||
while (set_idx < AXIS_N_SETTINGS) {
|
||||
if (parameter < N_AXIS) {
|
||||
// Valid axis setting found.
|
||||
switch (set_idx) {
|
||||
case 0:
|
||||
#ifdef MAX_STEP_RATE_HZ
|
||||
if (value*settings.max_rate[parameter] > (MAX_STEP_RATE_HZ*60.0)) { return(STATUS_MAX_STEP_RATE_EXCEEDED); }
|
||||
#endif
|
||||
settings.steps_per_mm[parameter] = value;
|
||||
break;
|
||||
case 1:
|
||||
#ifdef MAX_STEP_RATE_HZ
|
||||
if (value*settings.steps_per_mm[parameter] > (MAX_STEP_RATE_HZ*60.0)) { return(STATUS_MAX_STEP_RATE_EXCEEDED); }
|
||||
#endif
|
||||
settings.max_rate[parameter] = value;
|
||||
break;
|
||||
case 2: settings.acceleration[parameter] = value*60*60; break; // Convert to mm/min^2 for grbl internal use.
|
||||
case 3: settings.max_travel[parameter] = -value; break; // Store as negative for grbl internal use.
|
||||
case 4: // run current
|
||||
settings.current[parameter] = value;
|
||||
settings_spi_driver_init();
|
||||
break;
|
||||
case 5: // hold current
|
||||
settings.hold_current[parameter] = value;
|
||||
settings_spi_driver_init();
|
||||
break;
|
||||
case 6: // microstepping
|
||||
settings.microsteps[parameter] = int_value;
|
||||
settings_spi_driver_init();
|
||||
break;
|
||||
case 7: // stallguard
|
||||
settings.stallguard[parameter] = int_value;
|
||||
settings_spi_driver_init();
|
||||
break;
|
||||
if (value < 0.0) return (STATUS_NEGATIVE_VALUE);
|
||||
uint8_t int_value = trunc(value); // integer version
|
||||
if (parameter >= AXIS_SETTINGS_START_VAL) {
|
||||
// Store axis configuration. Axis numbering sequence set by AXIS_SETTING defines.
|
||||
// NOTE: Ensure the setting index corresponds to the report.c settings printout.
|
||||
parameter -= AXIS_SETTINGS_START_VAL;
|
||||
uint8_t set_idx = 0;
|
||||
while (set_idx < AXIS_N_SETTINGS) {
|
||||
if (parameter < N_AXIS) {
|
||||
// Valid axis setting found.
|
||||
switch (set_idx) {
|
||||
case 0:
|
||||
#ifdef MAX_STEP_RATE_HZ
|
||||
if (value * settings.max_rate[parameter] > (MAX_STEP_RATE_HZ * 60.0)) return (STATUS_MAX_STEP_RATE_EXCEEDED);
|
||||
#endif
|
||||
settings.steps_per_mm[parameter] = value;
|
||||
break;
|
||||
case 1:
|
||||
#ifdef MAX_STEP_RATE_HZ
|
||||
if (value * settings.steps_per_mm[parameter] > (MAX_STEP_RATE_HZ * 60.0)) return (STATUS_MAX_STEP_RATE_EXCEEDED);
|
||||
#endif
|
||||
settings.max_rate[parameter] = value;
|
||||
break;
|
||||
case 2: settings.acceleration[parameter] = value * 60 * 60; break; // Convert to mm/min^2 for grbl internal use.
|
||||
case 3: settings.max_travel[parameter] = -value; break; // Store as negative for grbl internal use.
|
||||
case 4: // run current
|
||||
settings.current[parameter] = value;
|
||||
settings_spi_driver_init();
|
||||
break;
|
||||
case 5: // hold current
|
||||
settings.hold_current[parameter] = value;
|
||||
settings_spi_driver_init();
|
||||
break;
|
||||
case 6: // microstepping
|
||||
settings.microsteps[parameter] = int_value;
|
||||
settings_spi_driver_init();
|
||||
break;
|
||||
case 7: // stallguard
|
||||
settings.stallguard[parameter] = int_value;
|
||||
settings_spi_driver_init();
|
||||
break;
|
||||
}
|
||||
break; // Exit while-loop after setting has been configured and proceed to the EEPROM write call.
|
||||
} else {
|
||||
set_idx++;
|
||||
// If axis index greater than N_AXIS or setting index greater than number of axis settings, error out.
|
||||
if ((parameter < AXIS_SETTINGS_INCREMENT) || (set_idx == AXIS_N_SETTINGS)) return (STATUS_INVALID_STATEMENT);
|
||||
parameter -= AXIS_SETTINGS_INCREMENT;
|
||||
}
|
||||
}
|
||||
break; // Exit while-loop after setting has been configured and proceed to the EEPROM write call.
|
||||
} else {
|
||||
set_idx++;
|
||||
// If axis index greater than N_AXIS or setting index greater than number of axis settings, error out.
|
||||
if ((parameter < AXIS_SETTINGS_INCREMENT) || (set_idx == AXIS_N_SETTINGS)) { return(STATUS_INVALID_STATEMENT); }
|
||||
parameter -= AXIS_SETTINGS_INCREMENT;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
// Store non-axis Grbl settings
|
||||
|
||||
switch(parameter) {
|
||||
case 0:
|
||||
if (int_value < 3) { return(STATUS_SETTING_STEP_PULSE_MIN); }
|
||||
settings.pulse_microseconds = int_value; break;
|
||||
case 1: settings.stepper_idle_lock_time = int_value; break;
|
||||
case 2:
|
||||
settings.step_invert_mask = int_value;
|
||||
st_generate_step_dir_invert_masks(); // Regenerate step and direction port invert masks.
|
||||
break;
|
||||
case 3:
|
||||
settings.dir_invert_mask = int_value;
|
||||
st_generate_step_dir_invert_masks(); // Regenerate step and direction port invert masks.
|
||||
break;
|
||||
case 4: // Reset to ensure change. Immediate re-init may cause problems.
|
||||
if (int_value) { settings.flags |= BITFLAG_INVERT_ST_ENABLE; }
|
||||
else { settings.flags &= ~BITFLAG_INVERT_ST_ENABLE; }
|
||||
break;
|
||||
case 5: // Reset to ensure change. Immediate re-init may cause problems.
|
||||
if (int_value) { settings.flags |= BITFLAG_INVERT_LIMIT_PINS; }
|
||||
else { settings.flags &= ~BITFLAG_INVERT_LIMIT_PINS; }
|
||||
break;
|
||||
case 6: // Reset to ensure change. Immediate re-init may cause problems.
|
||||
if (int_value) { settings.flags |= BITFLAG_INVERT_PROBE_PIN; }
|
||||
else { settings.flags &= ~BITFLAG_INVERT_PROBE_PIN; }
|
||||
probe_configure_invert_mask(false);
|
||||
break;
|
||||
case 10: settings.status_report_mask = int_value; break;
|
||||
case 11: settings.junction_deviation = value; break;
|
||||
case 12: settings.arc_tolerance = value; break;
|
||||
case 13:
|
||||
if (int_value) { settings.flags |= BITFLAG_REPORT_INCHES; }
|
||||
else { settings.flags &= ~BITFLAG_REPORT_INCHES; }
|
||||
system_flag_wco_change(); // Make sure WCO is immediately updated.
|
||||
break;
|
||||
case 20:
|
||||
if (int_value) {
|
||||
if (bit_isfalse(settings.flags, BITFLAG_HOMING_ENABLE)) { return(STATUS_SOFT_LIMIT_ERROR); }
|
||||
settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE;
|
||||
} else { settings.flags &= ~BITFLAG_SOFT_LIMIT_ENABLE; }
|
||||
break;
|
||||
case 21:
|
||||
if (int_value) { settings.flags |= BITFLAG_HARD_LIMIT_ENABLE; }
|
||||
else { settings.flags &= ~BITFLAG_HARD_LIMIT_ENABLE; }
|
||||
limits_init(); // Re-init to immediately change. NOTE: Nice to have but could be problematic later.
|
||||
break;
|
||||
case 22:
|
||||
if (int_value) { settings.flags |= BITFLAG_HOMING_ENABLE; }
|
||||
else {
|
||||
settings.flags &= ~BITFLAG_HOMING_ENABLE;
|
||||
settings.flags &= ~BITFLAG_SOFT_LIMIT_ENABLE; // Force disable soft-limits.
|
||||
} else {
|
||||
// Store non-axis Grbl settings
|
||||
switch (parameter) {
|
||||
case 0:
|
||||
if (int_value < 3) return (STATUS_SETTING_STEP_PULSE_MIN);
|
||||
settings.pulse_microseconds = int_value; break;
|
||||
case 1: settings.stepper_idle_lock_time = int_value; break;
|
||||
case 2:
|
||||
settings.step_invert_mask = int_value;
|
||||
st_generate_step_dir_invert_masks(); // Regenerate step and direction port invert masks.
|
||||
break;
|
||||
case 3:
|
||||
settings.dir_invert_mask = int_value;
|
||||
st_generate_step_dir_invert_masks(); // Regenerate step and direction port invert masks.
|
||||
break;
|
||||
case 4: // Reset to ensure change. Immediate re-init may cause problems.
|
||||
if (int_value) settings.flags |= BITFLAG_INVERT_ST_ENABLE;
|
||||
else settings.flags &= ~BITFLAG_INVERT_ST_ENABLE;
|
||||
break;
|
||||
case 5: // Reset to ensure change. Immediate re-init may cause problems.
|
||||
if (int_value) settings.flags |= BITFLAG_INVERT_LIMIT_PINS;
|
||||
else settings.flags &= ~BITFLAG_INVERT_LIMIT_PINS;
|
||||
break;
|
||||
case 6: // Reset to ensure change. Immediate re-init may cause problems.
|
||||
if (int_value) settings.flags |= BITFLAG_INVERT_PROBE_PIN;
|
||||
else settings.flags &= ~BITFLAG_INVERT_PROBE_PIN;
|
||||
probe_configure_invert_mask(false);
|
||||
break;
|
||||
case 10: settings.status_report_mask = int_value; break;
|
||||
case 11: settings.junction_deviation = value; break;
|
||||
case 12: settings.arc_tolerance = value; break;
|
||||
case 13:
|
||||
if (int_value) settings.flags |= BITFLAG_REPORT_INCHES;
|
||||
else settings.flags &= ~BITFLAG_REPORT_INCHES;
|
||||
system_flag_wco_change(); // Make sure WCO is immediately updated.
|
||||
break;
|
||||
case 20:
|
||||
if (int_value) {
|
||||
if (bit_isfalse(settings.flags, BITFLAG_HOMING_ENABLE)) return (STATUS_SOFT_LIMIT_ERROR);
|
||||
settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE;
|
||||
} else settings.flags &= ~BITFLAG_SOFT_LIMIT_ENABLE;
|
||||
break;
|
||||
case 21:
|
||||
if (int_value) settings.flags |= BITFLAG_HARD_LIMIT_ENABLE;
|
||||
else settings.flags &= ~BITFLAG_HARD_LIMIT_ENABLE;
|
||||
limits_init(); // Re-init to immediately change. NOTE: Nice to have but could be problematic later.
|
||||
break;
|
||||
case 22:
|
||||
if (int_value) settings.flags |= BITFLAG_HOMING_ENABLE;
|
||||
else {
|
||||
settings.flags &= ~BITFLAG_HOMING_ENABLE;
|
||||
settings.flags &= ~BITFLAG_SOFT_LIMIT_ENABLE; // Force disable soft-limits.
|
||||
}
|
||||
break;
|
||||
case 23: settings.homing_dir_mask = int_value; break;
|
||||
case 24: settings.homing_feed_rate = value; break;
|
||||
case 25: settings.homing_seek_rate = value; break;
|
||||
case 26: settings.homing_debounce_delay = int_value; break;
|
||||
case 27: settings.homing_pulloff = value; break;
|
||||
case 30: settings.rpm_max = value; spindle_init(); break; // Re-initialize spindle rpm calibration
|
||||
case 31: settings.rpm_min = value; spindle_init(); break; // Re-initialize spindle rpm calibration
|
||||
case 32:
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
if (int_value) settings.flags |= BITFLAG_LASER_MODE;
|
||||
else settings.flags &= ~BITFLAG_LASER_MODE;
|
||||
#else
|
||||
return (STATUS_SETTING_DISABLED_LASER);
|
||||
#endif
|
||||
break;
|
||||
case 33: settings.spindle_pwm_freq = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
||||
case 34: settings.spindle_pwm_off_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
||||
case 35: settings.spindle_pwm_min_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
||||
case 36: settings.spindle_pwm_max_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
||||
case 80:
|
||||
case 81:
|
||||
case 82:
|
||||
case 83:
|
||||
case 84:
|
||||
settings.machine_int16[parameter - 80] = (uint16_t)value;
|
||||
break;
|
||||
case 90:
|
||||
case 91:
|
||||
case 92:
|
||||
case 93:
|
||||
case 94:
|
||||
settings.machine_float[parameter - 90] = value;
|
||||
break;
|
||||
default:
|
||||
return (STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
break;
|
||||
case 23: settings.homing_dir_mask = int_value; break;
|
||||
case 24: settings.homing_feed_rate = value; break;
|
||||
case 25: settings.homing_seek_rate = value; break;
|
||||
case 26: settings.homing_debounce_delay = int_value; break;
|
||||
case 27: settings.homing_pulloff = value; break;
|
||||
case 30: settings.rpm_max = value; spindle_init(); break; // Re-initialize spindle rpm calibration
|
||||
case 31: settings.rpm_min = value; spindle_init(); break; // Re-initialize spindle rpm calibration
|
||||
case 32:
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
if (int_value) { settings.flags |= BITFLAG_LASER_MODE; }
|
||||
else { settings.flags &= ~BITFLAG_LASER_MODE; }
|
||||
#else
|
||||
return(STATUS_SETTING_DISABLED_LASER);
|
||||
#endif
|
||||
break;
|
||||
case 33: settings.spindle_pwm_freq = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
||||
case 34: settings.spindle_pwm_off_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
||||
case 35: settings.spindle_pwm_min_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
||||
case 36: settings.spindle_pwm_max_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
||||
|
||||
case 80:
|
||||
case 81:
|
||||
case 82:
|
||||
case 83:
|
||||
case 84:
|
||||
settings.machine_int16[parameter - 80] = (uint16_t)value;
|
||||
break;
|
||||
|
||||
case 90:
|
||||
case 91:
|
||||
case 92:
|
||||
case 93:
|
||||
case 94:
|
||||
settings.machine_float[parameter - 90] = value;
|
||||
break;
|
||||
default:
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
}
|
||||
write_global_settings();
|
||||
return(STATUS_OK);
|
||||
write_global_settings();
|
||||
return (STATUS_OK);
|
||||
}
|
||||
|
||||
// Returns step pin mask according to Grbl internal axis indexing.
|
||||
uint8_t get_step_pin_mask(uint8_t axis_idx)
|
||||
{
|
||||
// todo clean this up further up stream
|
||||
return(1<<axis_idx);
|
||||
uint8_t get_step_pin_mask(uint8_t axis_idx) {
|
||||
// todo clean this up further up stream
|
||||
return (1 << axis_idx);
|
||||
}
|
||||
|
||||
// Returns direction pin mask according to Grbl internal axis indexing.
|
||||
uint8_t get_direction_pin_mask(uint8_t axis_idx)
|
||||
{
|
||||
return(1<<axis_idx);
|
||||
uint8_t get_direction_pin_mask(uint8_t axis_idx) {
|
||||
return (1 << axis_idx);
|
||||
}
|
||||
|
||||
// this allows a conditional re-init of the trinamic settings
|
||||
void settings_spi_driver_init() {
|
||||
#ifdef USE_TRINAMIC
|
||||
trinamic_change_settings();
|
||||
#else
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No SPI drivers setup");
|
||||
#endif
|
||||
#ifdef USE_TRINAMIC
|
||||
trinamic_change_settings();
|
||||
#else
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No SPI drivers setup");
|
||||
#endif
|
||||
}
|
@ -4,7 +4,7 @@
|
||||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
@ -53,7 +53,7 @@
|
||||
#define SETTINGS_RESTORE_BUILD_INFO bit(3)
|
||||
#define SETTINGS_RESTORE_WIFI_SETTINGS bit(4)
|
||||
#ifndef SETTINGS_RESTORE_ALL
|
||||
#define SETTINGS_RESTORE_ALL 0xFF // All bitflags
|
||||
#define SETTINGS_RESTORE_ALL 0xFF // All bitflags
|
||||
#endif
|
||||
|
||||
// Define EEPROM memory address location values for Grbl settings and parameters
|
||||
@ -84,66 +84,66 @@
|
||||
|
||||
// Global persistent settings (Stored from byte EEPROM_ADDR_GLOBAL onwards)
|
||||
typedef struct {
|
||||
// Axis settings
|
||||
float steps_per_mm[N_AXIS];
|
||||
float max_rate[N_AXIS];
|
||||
float acceleration[N_AXIS];
|
||||
float max_travel[N_AXIS];
|
||||
float current[N_AXIS]; // $140... run current (extended set)
|
||||
float hold_current[N_AXIS]; // $150 percent of run current (extended set)
|
||||
uint16_t microsteps[N_AXIS]; // $160... (extended set)
|
||||
uint8_t stallguard[N_AXIS]; // $170... (extended set)
|
||||
// Axis settings
|
||||
float steps_per_mm[N_AXIS];
|
||||
float max_rate[N_AXIS];
|
||||
float acceleration[N_AXIS];
|
||||
float max_travel[N_AXIS];
|
||||
float current[N_AXIS]; // $140... run current (extended set)
|
||||
float hold_current[N_AXIS]; // $150 percent of run current (extended set)
|
||||
uint16_t microsteps[N_AXIS]; // $160... (extended set)
|
||||
uint8_t stallguard[N_AXIS]; // $170... (extended set)
|
||||
|
||||
// Remaining Grbl settings
|
||||
uint8_t pulse_microseconds;
|
||||
uint8_t step_invert_mask;
|
||||
uint8_t dir_invert_mask;
|
||||
uint8_t stepper_idle_lock_time; // If max value 255, steppers do not disable.
|
||||
uint8_t status_report_mask; // Mask to indicate desired report data.
|
||||
float junction_deviation;
|
||||
float arc_tolerance;
|
||||
|
||||
float spindle_pwm_freq; // $33 Hz (extended set)
|
||||
float spindle_pwm_off_value; // $34 Percent (extended set)
|
||||
float spindle_pwm_min_value; // $35 Percent (extended set)
|
||||
float spindle_pwm_max_value; // $36 Percent (extended set)
|
||||
|
||||
float rpm_max;
|
||||
float rpm_min;
|
||||
// Remaining Grbl settings
|
||||
uint8_t pulse_microseconds;
|
||||
uint8_t step_invert_mask;
|
||||
uint8_t dir_invert_mask;
|
||||
uint8_t stepper_idle_lock_time; // If max value 255, steppers do not disable.
|
||||
uint8_t status_report_mask; // Mask to indicate desired report data.
|
||||
float junction_deviation;
|
||||
float arc_tolerance;
|
||||
|
||||
uint8_t flags; // Contains default boolean settings
|
||||
float spindle_pwm_freq; // $33 Hz (extended set)
|
||||
float spindle_pwm_off_value; // $34 Percent (extended set)
|
||||
float spindle_pwm_min_value; // $35 Percent (extended set)
|
||||
float spindle_pwm_max_value; // $36 Percent (extended set)
|
||||
|
||||
uint8_t homing_dir_mask;
|
||||
float homing_feed_rate;
|
||||
float homing_seek_rate;
|
||||
uint16_t homing_debounce_delay;
|
||||
float homing_pulloff;
|
||||
float rpm_max;
|
||||
float rpm_min;
|
||||
|
||||
int16_t machine_int16[USER_SETTING_COUNT]; // settings starting at 80 to be defined by the user
|
||||
float machine_float[USER_SETTING_COUNT]; // settings starting at 80 to be defined by the user
|
||||
uint8_t flags; // Contains default boolean settings
|
||||
|
||||
uint8_t homing_dir_mask;
|
||||
float homing_feed_rate;
|
||||
float homing_seek_rate;
|
||||
uint16_t homing_debounce_delay;
|
||||
float homing_pulloff;
|
||||
|
||||
int16_t machine_int16[USER_SETTING_COUNT]; // settings starting at 80 to be defined by the user
|
||||
float machine_float[USER_SETTING_COUNT]; // settings starting at 80 to be defined by the user
|
||||
|
||||
} settings_t;
|
||||
extern settings_t settings;
|
||||
|
||||
// Initialize the configuration subsystem (load settings from EEPROM)
|
||||
void settings_init();
|
||||
void settings_init();
|
||||
void settings_restore(uint8_t restore_flag);
|
||||
void write_global_settings();
|
||||
uint8_t read_global_settings();
|
||||
|
||||
uint8_t settings_read_startup_line(uint8_t n, char *line);
|
||||
void settings_store_startup_line(uint8_t n, char *line);
|
||||
uint8_t settings_read_startup_line(uint8_t n, char* line);
|
||||
void settings_store_startup_line(uint8_t n, char* line);
|
||||
|
||||
uint8_t settings_read_build_info(char *line);
|
||||
void settings_store_build_info(char *line);
|
||||
uint8_t settings_read_build_info(char* line);
|
||||
void settings_store_build_info(char* line);
|
||||
|
||||
uint8_t settings_store_global_setting(uint8_t parameter, float value);
|
||||
|
||||
// Writes selected coordinate data to EEPROM
|
||||
void settings_write_coord_data(uint8_t coord_select, float *coord_data);
|
||||
void settings_write_coord_data(uint8_t coord_select, float* coord_data);
|
||||
|
||||
// Reads selected coordinate data from EEPROM
|
||||
uint8_t settings_read_coord_data(uint8_t coord_select, float *coord_data);
|
||||
uint8_t settings_read_coord_data(uint8_t coord_select, float* coord_data);
|
||||
|
||||
// Returns the step pin mask according to Grbl's internal axis numbering
|
||||
uint8_t get_step_pin_mask(uint8_t i);
|
||||
|
@ -1,10 +1,10 @@
|
||||
/*
|
||||
solenoid_pen.cpp
|
||||
Part of Grbl_ESP32
|
||||
|
||||
|
||||
copyright (c) 2018 - Bart Dring This file was modified for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
@ -17,7 +17,7 @@
|
||||
|
||||
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"
|
||||
|
||||
@ -26,97 +26,79 @@
|
||||
static TaskHandle_t solenoidSyncTaskHandle = 0;
|
||||
|
||||
// used to delay turn on
|
||||
bool solenoid_pen_enable;
|
||||
bool solenoid_pen_enable;
|
||||
uint16_t solenoide_hold_count;
|
||||
|
||||
void solenoid_init()
|
||||
{
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:Solenoid Mode]\r\n"); // startup message
|
||||
//validate_servo_settings(true); // display any calibration errors
|
||||
|
||||
solenoid_pen_enable = false; // start delay has not completed yet.
|
||||
solenoide_hold_count = 0; // initialize
|
||||
|
||||
// setup PWM channel
|
||||
ledcSetup(SOLENOID_CHANNEL_NUM, SOLENOID_PWM_FREQ, SOLENOID_PWM_RES_BITS);
|
||||
ledcAttachPin(SOLENOID_PEN_PIN, SOLENOID_CHANNEL_NUM);
|
||||
|
||||
solenoid_disable(); // start it it off
|
||||
|
||||
// setup a task that will calculate the determine and set the servo position
|
||||
xTaskCreatePinnedToCore( solenoidSyncTask, // task
|
||||
"solenoidSyncTask", // name for task
|
||||
4096, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&solenoidSyncTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
void solenoid_init() {
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:Solenoid Mode]\r\n"); // startup message
|
||||
//validate_servo_settings(true); // display any calibration errors
|
||||
solenoid_pen_enable = false; // start delay has not completed yet.
|
||||
solenoide_hold_count = 0; // initialize
|
||||
// setup PWM channel
|
||||
ledcSetup(SOLENOID_CHANNEL_NUM, SOLENOID_PWM_FREQ, SOLENOID_PWM_RES_BITS);
|
||||
ledcAttachPin(SOLENOID_PEN_PIN, SOLENOID_CHANNEL_NUM);
|
||||
solenoid_disable(); // start it it off
|
||||
// setup a task that will calculate the determine and set the servo position
|
||||
xTaskCreatePinnedToCore(solenoidSyncTask, // task
|
||||
"solenoidSyncTask", // name for task
|
||||
4096, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&solenoidSyncTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
}
|
||||
|
||||
// turn off the PWM (0 duty)
|
||||
void solenoid_disable()
|
||||
{
|
||||
ledcWrite(SOLENOID_CHANNEL_NUM, 0);
|
||||
void solenoid_disable() {
|
||||
ledcWrite(SOLENOID_CHANNEL_NUM, 0);
|
||||
}
|
||||
|
||||
// this is the task
|
||||
void solenoidSyncTask(void *pvParameters)
|
||||
{
|
||||
int32_t current_position[N_AXIS]; // copy of current location
|
||||
float m_pos[N_AXIS]; // machine position in mm
|
||||
TickType_t xLastWakeTime;
|
||||
const TickType_t xSolenoidFrequency = SOLENOID_TIMER_INT_FREQ; // in ticks (typically ms)
|
||||
uint16_t solenoid_delay_counter = 0;
|
||||
|
||||
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
|
||||
while(true) { // don't ever return from this or the task dies
|
||||
if (!solenoid_pen_enable) {
|
||||
solenoid_delay_counter++;
|
||||
solenoid_pen_enable = (solenoid_delay_counter > SOLENOID_TURNON_DELAY);
|
||||
}
|
||||
else {
|
||||
memcpy(current_position,sys_position,sizeof(sys_position)); // get current position in step
|
||||
system_convert_array_steps_to_mpos(m_pos,current_position); // convert to millimeters
|
||||
calc_solenoid(m_pos[Z_AXIS]); // calculate kinematics and move the servos
|
||||
}
|
||||
vTaskDelayUntil(&xLastWakeTime, xSolenoidFrequency);
|
||||
void solenoidSyncTask(void* pvParameters) {
|
||||
int32_t current_position[N_AXIS]; // copy of current location
|
||||
float m_pos[N_AXIS]; // machine position in mm
|
||||
TickType_t xLastWakeTime;
|
||||
const TickType_t xSolenoidFrequency = SOLENOID_TIMER_INT_FREQ; // in ticks (typically ms)
|
||||
uint16_t solenoid_delay_counter = 0;
|
||||
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
|
||||
while (true) { // don't ever return from this or the task dies
|
||||
if (!solenoid_pen_enable) {
|
||||
solenoid_delay_counter++;
|
||||
solenoid_pen_enable = (solenoid_delay_counter > SOLENOID_TURNON_DELAY);
|
||||
} else {
|
||||
memcpy(current_position, sys_position, sizeof(sys_position)); // get current position in step
|
||||
system_convert_array_steps_to_mpos(m_pos, current_position); // convert to millimeters
|
||||
calc_solenoid(m_pos[Z_AXIS]); // calculate kinematics and move the servos
|
||||
}
|
||||
vTaskDelayUntil(&xLastWakeTime, xSolenoidFrequency);
|
||||
}
|
||||
}
|
||||
|
||||
// calculate and set the PWM value for the servo
|
||||
void calc_solenoid(float penZ)
|
||||
{
|
||||
uint32_t solenoid_pen_pulse_len;
|
||||
|
||||
if (!solenoid_pen_enable) // only proceed if startup delay as expired
|
||||
return;
|
||||
|
||||
if (penZ < 0 && (sys.state != STATE_ALARM)) { // alarm also makes it go up
|
||||
solenoide_hold_count = 0; // reset this count
|
||||
solenoid_pen_pulse_len = 0; //
|
||||
}
|
||||
else {
|
||||
if (solenoide_hold_count < SOLENOID_PULSE_LEN_HOLD) {
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_UP;
|
||||
solenoide_hold_count++;
|
||||
}
|
||||
else {
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_HOLD;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// skip setting value if it is unchanged
|
||||
if (ledcRead(SOLENOID_CHANNEL_NUM) == solenoid_pen_pulse_len)
|
||||
return;
|
||||
|
||||
// update the PWM value
|
||||
// ledcWrite appears to have issues with interrupts, so make this a critical section
|
||||
portMUX_TYPE myMutex = portMUX_INITIALIZER_UNLOCKED;
|
||||
portENTER_CRITICAL(&myMutex);
|
||||
ledcWrite(SOLENOID_CHANNEL_NUM, solenoid_pen_pulse_len);
|
||||
portEXIT_CRITICAL(&myMutex);
|
||||
void calc_solenoid(float penZ) {
|
||||
uint32_t solenoid_pen_pulse_len;
|
||||
if (!solenoid_pen_enable) // only proceed if startup delay as expired
|
||||
return;
|
||||
if (penZ < 0 && (sys.state != STATE_ALARM)) { // alarm also makes it go up
|
||||
solenoide_hold_count = 0; // reset this count
|
||||
solenoid_pen_pulse_len = 0; //
|
||||
} else {
|
||||
if (solenoide_hold_count < SOLENOID_PULSE_LEN_HOLD) {
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_UP;
|
||||
solenoide_hold_count++;
|
||||
} else
|
||||
solenoid_pen_pulse_len = SOLENOID_PULSE_LEN_HOLD;
|
||||
}
|
||||
// skip setting value if it is unchanged
|
||||
if (ledcRead(SOLENOID_CHANNEL_NUM) == solenoid_pen_pulse_len)
|
||||
return;
|
||||
// update the PWM value
|
||||
// ledcWrite appears to have issues with interrupts, so make this a critical section
|
||||
portMUX_TYPE myMutex = portMUX_INITIALIZER_UNLOCKED;
|
||||
portENTER_CRITICAL(&myMutex);
|
||||
ledcWrite(SOLENOID_CHANNEL_NUM, solenoid_pen_pulse_len);
|
||||
portEXIT_CRITICAL(&myMutex);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -23,7 +23,7 @@
|
||||
When the current Z location is below zero the pen is down
|
||||
If the Z goes to zero or above the pen goes up.
|
||||
There are two power levels, the initial pull up strength, then the hold strength
|
||||
|
||||
|
||||
|
||||
Note: There is a still a virtual Z axis that has a finite speed.
|
||||
If your gcode is commanding long travels in Z, there will be delays
|
||||
@ -32,22 +32,40 @@
|
||||
|
||||
*/
|
||||
|
||||
#define SOLENOID_PWM_FREQ 5000
|
||||
#define SOLENOID_PWM_RES_BITS 8
|
||||
#ifndef SOLENOID_PWM_FREQ
|
||||
#define SOLENOID_PWM_FREQ 5000
|
||||
#endif
|
||||
|
||||
#define SOLENOID_TURNON_DELAY (SOLENOID_TIMER_INT_FREQ/2)
|
||||
#define SOLENOID_PULSE_LEN_UP 255
|
||||
#define SOLENOID_HOLD_DELAY (SOLENOID_TIMER_INT_FREQ/2) // in task counts...after this delay power will change to hold level
|
||||
#define SOLENOID_PULSE_LEN_HOLD 80 // solenoid hold level ... typically a lower value to prevent overheating
|
||||
#ifndef SOLENOID_PWM_RES_BITS
|
||||
#define SOLENOID_PWM_RES_BITS 8
|
||||
#endif
|
||||
|
||||
#define SOLENOID_TIMER_INT_FREQ 50
|
||||
#ifndef SOLENOID_TURNON_DELAY
|
||||
#define SOLENOID_TURNON_DELAY (SOLENOID_TIMER_INT_FREQ/2)
|
||||
#endif
|
||||
|
||||
#ifndef SOLENOID_PULSE_LEN_UP
|
||||
#define SOLENOID_PULSE_LEN_UP 255
|
||||
#endif
|
||||
|
||||
#ifndef SOLENOID_HOLD_DELAY
|
||||
#define SOLENOID_HOLD_DELAY (SOLENOID_TIMER_INT_FREQ/2) // in task counts...after this delay power will change to hold level
|
||||
#endif
|
||||
|
||||
#ifndef SOLENOID_PULSE_LEN_HOLD
|
||||
#define SOLENOID_PULSE_LEN_HOLD 80 // solenoid hold level ... typically a lower value to prevent overheating
|
||||
#endif
|
||||
|
||||
#ifndef SOLENOID_TIMER_INT_FREQ
|
||||
#define SOLENOID_TIMER_INT_FREQ 50
|
||||
#endif
|
||||
|
||||
#ifndef solenoid_h
|
||||
#define solenoid_h
|
||||
#define solenoid_h
|
||||
|
||||
void solenoid_init();
|
||||
void solenoid_disable();
|
||||
void solenoidSyncTask(void *pvParameters);
|
||||
void calc_solenoid(float penZ);
|
||||
void solenoid_init();
|
||||
void solenoid_disable();
|
||||
void solenoidSyncTask(void* pvParameters);
|
||||
void calc_solenoid(float penZ);
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
@ -2,10 +2,10 @@
|
||||
spindle_control.cpp - 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 modified for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
@ -21,235 +21,202 @@
|
||||
#include "grbl.h"
|
||||
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
|
||||
uint32_t spindle_pwm_period; // how many counts in 1 period
|
||||
uint32_t spindle_pwm_off_value;
|
||||
uint32_t spindle_pwm_min_value;
|
||||
uint32_t spindle_pwm_max_value;
|
||||
static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
|
||||
uint32_t spindle_pwm_period; // how many counts in 1 period
|
||||
uint32_t spindle_pwm_off_value;
|
||||
uint32_t spindle_pwm_min_value;
|
||||
uint32_t spindle_pwm_max_value;
|
||||
#endif
|
||||
|
||||
void spindle_init()
|
||||
{
|
||||
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
|
||||
#ifdef INVERT_SPINDLE_PWM
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "INVERT_SPINDLE_PWM");
|
||||
#endif
|
||||
|
||||
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "INVERT_SPINDLE_ENABLE_PIN");
|
||||
#endif
|
||||
|
||||
// determine how many PWM counts are in eqach PWM cycle
|
||||
spindle_pwm_period = ((1<<SPINDLE_PWM_BIT_PRECISION) -1);
|
||||
|
||||
if (settings.spindle_pwm_min_value > settings.spindle_pwm_min_value) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning spindle min pwm is greater than max. Check $35 and $36");
|
||||
}
|
||||
|
||||
// pre-caculate some PWM count values
|
||||
spindle_pwm_off_value = (spindle_pwm_period * settings.spindle_pwm_off_value / 100.0);
|
||||
spindle_pwm_min_value = (spindle_pwm_period * settings.spindle_pwm_min_value / 100.0);
|
||||
spindle_pwm_max_value = (spindle_pwm_period * settings.spindle_pwm_max_value / 100.0);
|
||||
|
||||
// The pwm_gradient is the pwm duty cycle units per rpm
|
||||
pwm_gradient = (spindle_pwm_max_value-spindle_pwm_min_value)/(settings.rpm_max-settings.rpm_min);
|
||||
|
||||
// Use DIR and Enable if pins are defined
|
||||
#ifdef SPINDLE_ENABLE_PIN
|
||||
pinMode(SPINDLE_ENABLE_PIN, OUTPUT);
|
||||
#endif
|
||||
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
pinMode(SPINDLE_DIR_PIN, OUTPUT);
|
||||
#endif
|
||||
|
||||
// use the LED control feature to setup PWM https://docs.espressif.com/projects/esp-idf/en/latest/api-reference/peripherals/ledc.html
|
||||
ledcSetup(SPINDLE_PWM_CHANNEL, (double)settings.spindle_pwm_freq, SPINDLE_PWM_BIT_PRECISION); // setup the channel
|
||||
ledcAttachPin(SPINDLE_PWM_PIN, SPINDLE_PWM_CHANNEL); // attach the PWM to the pin
|
||||
|
||||
// Start with spindle off off
|
||||
spindle_stop();
|
||||
#endif
|
||||
void spindle_init() {
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
#ifdef INVERT_SPINDLE_PWM
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "INVERT_SPINDLE_PWM");
|
||||
#endif
|
||||
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "INVERT_SPINDLE_ENABLE_PIN");
|
||||
#endif
|
||||
// determine how many PWM counts are in eqach PWM cycle
|
||||
spindle_pwm_period = ((1 << SPINDLE_PWM_BIT_PRECISION) - 1);
|
||||
if (settings.spindle_pwm_min_value > settings.spindle_pwm_min_value)
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning spindle min pwm is greater than max. Check $35 and $36");
|
||||
// pre-caculate some PWM count values
|
||||
spindle_pwm_off_value = (spindle_pwm_period * settings.spindle_pwm_off_value / 100.0);
|
||||
spindle_pwm_min_value = (spindle_pwm_period * settings.spindle_pwm_min_value / 100.0);
|
||||
spindle_pwm_max_value = (spindle_pwm_period * settings.spindle_pwm_max_value / 100.0);
|
||||
// The pwm_gradient is the pwm duty cycle units per rpm
|
||||
pwm_gradient = (spindle_pwm_max_value - spindle_pwm_min_value) / (settings.rpm_max - settings.rpm_min);
|
||||
// Use DIR and Enable if pins are defined
|
||||
#ifdef SPINDLE_ENABLE_PIN
|
||||
pinMode(SPINDLE_ENABLE_PIN, OUTPUT);
|
||||
#endif
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
pinMode(SPINDLE_DIR_PIN, OUTPUT);
|
||||
#endif
|
||||
// use the LED control feature to setup PWM https://docs.espressif.com/projects/esp-idf/en/latest/api-reference/peripherals/ledc.html
|
||||
ledcSetup(SPINDLE_PWM_CHANNEL, (double)settings.spindle_pwm_freq, SPINDLE_PWM_BIT_PRECISION); // setup the channel
|
||||
ledcAttachPin(SPINDLE_PWM_PIN, SPINDLE_PWM_CHANNEL); // attach the PWM to the pin
|
||||
// Start with spindle off off
|
||||
spindle_stop();
|
||||
#endif
|
||||
}
|
||||
|
||||
void spindle_stop()
|
||||
{
|
||||
spindle_set_enable(false);
|
||||
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
#ifndef INVERT_SPINDLE_PWM
|
||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, spindle_pwm_off_value);
|
||||
#else
|
||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, (1<<SPINDLE_PWM_BIT_PRECISION)); // TO DO...wrong for min_pwm
|
||||
#endif
|
||||
#endif
|
||||
void spindle_stop() {
|
||||
spindle_set_enable(false);
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
#ifndef INVERT_SPINDLE_PWM
|
||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, spindle_pwm_off_value);
|
||||
#else
|
||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, (1 << SPINDLE_PWM_BIT_PRECISION)); // TO DO...wrong for min_pwm
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t spindle_get_state() // returns SPINDLE_STATE_DISABLE, SPINDLE_STATE_CW or SPINDLE_STATE_CCW
|
||||
{
|
||||
// TODO Update this when direction and enable pin are added
|
||||
#ifndef SPINDLE_PWM_PIN
|
||||
return(SPINDLE_STATE_DISABLE);
|
||||
#else
|
||||
|
||||
if (ledcRead(SPINDLE_PWM_CHANNEL) == 0) // Check the PWM value
|
||||
return(SPINDLE_STATE_DISABLE);
|
||||
else
|
||||
{
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
if (digitalRead(SPINDLE_DIR_PIN))
|
||||
return (SPINDLE_STATE_CW);
|
||||
else
|
||||
return(SPINDLE_STATE_CCW);
|
||||
#else
|
||||
return(SPINDLE_STATE_CW);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
uint8_t spindle_get_state() { // returns SPINDLE_STATE_DISABLE, SPINDLE_STATE_CW or SPINDLE_STATE_CCW
|
||||
// TODO Update this when direction and enable pin are added
|
||||
#ifndef SPINDLE_PWM_PIN
|
||||
return (SPINDLE_STATE_DISABLE);
|
||||
#else
|
||||
if (ledcRead(SPINDLE_PWM_CHANNEL) == 0) // Check the PWM value
|
||||
return (SPINDLE_STATE_DISABLE);
|
||||
else {
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
if (digitalRead(SPINDLE_DIR_PIN))
|
||||
return (SPINDLE_STATE_CW);
|
||||
else
|
||||
return (SPINDLE_STATE_CCW);
|
||||
#else
|
||||
return (SPINDLE_STATE_CW);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void spindle_set_speed(uint32_t pwm_value)
|
||||
{
|
||||
#ifndef SPINDLE_PWM_PIN
|
||||
//grbl_sendf(CLIENT_SERIAL, "[MSG: set speed...no pin defined]\r\n");
|
||||
return;
|
||||
#else
|
||||
#ifndef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
||||
spindle_set_enable(true);
|
||||
#else
|
||||
spindle_set_enable(pwm_value != 0);
|
||||
#endif
|
||||
|
||||
#ifndef INVERT_SPINDLE_PWM
|
||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, pwm_value);
|
||||
#else
|
||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, (1<<SPINDLE_PWM_BIT_PRECISION) - pwm_value);
|
||||
#endif
|
||||
|
||||
#endif
|
||||
void spindle_set_speed(uint32_t pwm_value) {
|
||||
#ifndef SPINDLE_PWM_PIN
|
||||
//grbl_sendf(CLIENT_SERIAL, "[MSG: set speed...no pin defined]\r\n");
|
||||
return;
|
||||
#else
|
||||
#ifndef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
||||
spindle_set_enable(true);
|
||||
#else
|
||||
spindle_set_enable(pwm_value != 0);
|
||||
#endif
|
||||
#ifndef INVERT_SPINDLE_PWM
|
||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, pwm_value);
|
||||
#else
|
||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, (1 << SPINDLE_PWM_BIT_PRECISION) - pwm_value);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
uint32_t spindle_compute_pwm_value(float rpm){
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
uint32_t pwm_value;
|
||||
rpm *= (0.010*sys.spindle_speed_ovr); // Scale by spindle speed override value.
|
||||
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
|
||||
if ((settings.rpm_min >= settings.rpm_max) || (rpm >= settings.rpm_max)) {
|
||||
// No PWM range possible. Set simple on/off spindle control pin state.
|
||||
sys.spindle_speed = settings.rpm_max;
|
||||
pwm_value = spindle_pwm_max_value;
|
||||
} else if (rpm <= settings.rpm_min) {
|
||||
if (rpm == 0.0) { // S0 disables spindle
|
||||
sys.spindle_speed = 0.0;
|
||||
pwm_value = spindle_pwm_off_value;
|
||||
} else { // Set minimum PWM output
|
||||
sys.spindle_speed = settings.rpm_min;
|
||||
pwm_value = spindle_pwm_min_value;
|
||||
}
|
||||
} else {
|
||||
// Compute intermediate PWM value with linear spindle speed model.
|
||||
// NOTE: A nonlinear model could be installed here, if required, but keep it VERY light-weight.
|
||||
sys.spindle_speed = rpm;
|
||||
#ifdef ENABLE_PIECEWISE_LINEAR_SPINDLE
|
||||
pwm_value = piecewise_linear_fit(rpm);
|
||||
#else
|
||||
pwm_value = floor((rpm - settings.rpm_min)*pwm_gradient) + spindle_pwm_min_value;
|
||||
#endif
|
||||
}
|
||||
return(pwm_value);
|
||||
#else
|
||||
return(0); // no SPINDLE_PWM_PIN
|
||||
#endif
|
||||
uint32_t spindle_compute_pwm_value(float rpm) {
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
uint32_t pwm_value;
|
||||
rpm *= (0.010 * sys.spindle_speed_ovr); // Scale by spindle speed override value.
|
||||
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
|
||||
if ((settings.rpm_min >= settings.rpm_max) || (rpm >= settings.rpm_max)) {
|
||||
// No PWM range possible. Set simple on/off spindle control pin state.
|
||||
sys.spindle_speed = settings.rpm_max;
|
||||
pwm_value = spindle_pwm_max_value;
|
||||
} else if (rpm <= settings.rpm_min) {
|
||||
if (rpm == 0.0) { // S0 disables spindle
|
||||
sys.spindle_speed = 0.0;
|
||||
pwm_value = spindle_pwm_off_value;
|
||||
} else { // Set minimum PWM output
|
||||
sys.spindle_speed = settings.rpm_min;
|
||||
pwm_value = spindle_pwm_min_value;
|
||||
}
|
||||
} else {
|
||||
// Compute intermediate PWM value with linear spindle speed model.
|
||||
// NOTE: A nonlinear model could be installed here, if required, but keep it VERY light-weight.
|
||||
sys.spindle_speed = rpm;
|
||||
#ifdef ENABLE_PIECEWISE_LINEAR_SPINDLE
|
||||
pwm_value = piecewise_linear_fit(rpm);
|
||||
#else
|
||||
pwm_value = floor((rpm - settings.rpm_min) * pwm_gradient) + spindle_pwm_min_value;
|
||||
#endif
|
||||
}
|
||||
return (pwm_value);
|
||||
#else
|
||||
return (0); // no SPINDLE_PWM_PIN
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
// Called by spindle_set_state() and step segment generator. Keep routine small and efficient.
|
||||
void spindle_set_state(uint8_t state, float rpm)
|
||||
{
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
if (sys.abort) { return; } // Block during abort.
|
||||
if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
|
||||
sys.spindle_speed = 0.0;
|
||||
spindle_stop();
|
||||
} else {
|
||||
|
||||
// TODO ESP32 Enable and direction control
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
digitalWrite(SPINDLE_DIR_PIN, state == SPINDLE_ENABLE_CW);
|
||||
#endif
|
||||
|
||||
// NOTE: Assumes all calls to this function is when Grbl is not moving or must remain off.
|
||||
if (settings.flags & BITFLAG_LASER_MODE) {
|
||||
if (state == SPINDLE_ENABLE_CCW) { rpm = 0.0; } // TODO: May need to be rpm_min*(100/MAX_SPINDLE_SPEED_OVERRIDE);
|
||||
}
|
||||
|
||||
spindle_set_speed(spindle_compute_pwm_value(rpm));
|
||||
}
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
#endif
|
||||
void spindle_set_state(uint8_t state, float rpm) {
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
if (sys.abort) return; // Block during abort.
|
||||
if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
|
||||
sys.spindle_speed = 0.0;
|
||||
spindle_stop();
|
||||
} else {
|
||||
// TODO ESP32 Enable and direction control
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
digitalWrite(SPINDLE_DIR_PIN, state == SPINDLE_ENABLE_CW);
|
||||
#endif
|
||||
// NOTE: Assumes all calls to this function is when Grbl is not moving or must remain off.
|
||||
if (settings.flags & BITFLAG_LASER_MODE) {
|
||||
if (state == SPINDLE_ENABLE_CCW) rpm = 0.0; // TODO: May need to be rpm_min*(100/MAX_SPINDLE_SPEED_OVERRIDE);
|
||||
}
|
||||
spindle_set_speed(spindle_compute_pwm_value(rpm));
|
||||
}
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
void spindle_sync(uint8_t state, float rpm)
|
||||
{
|
||||
if (sys.state == STATE_CHECK_MODE) {
|
||||
return;
|
||||
}
|
||||
|
||||
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
||||
spindle_set_state(state,rpm);
|
||||
void spindle_sync(uint8_t state, float rpm) {
|
||||
if (sys.state == STATE_CHECK_MODE)
|
||||
return;
|
||||
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
||||
spindle_set_state(state, rpm);
|
||||
}
|
||||
|
||||
|
||||
void grbl_analogWrite(uint8_t chan, uint32_t duty)
|
||||
{
|
||||
// Remember the old duty cycle in memory instead of reading
|
||||
// it from the I/O peripheral because I/O reads are quite
|
||||
// a bit slower than memory reads.
|
||||
static uint32_t old_duty = 0;
|
||||
|
||||
if (old_duty != duty) // reduce unnecessary calls to ledcWrite()
|
||||
{
|
||||
old_duty = duty;
|
||||
ledcWrite(chan, duty);
|
||||
}
|
||||
void grbl_analogWrite(uint8_t chan, uint32_t duty) {
|
||||
// Remember the old duty cycle in memory instead of reading
|
||||
// it from the I/O peripheral because I/O reads are quite
|
||||
// a bit slower than memory reads.
|
||||
static uint32_t old_duty = 0;
|
||||
if (old_duty != duty) { // reduce unnecessary calls to ledcWrite()
|
||||
old_duty = duty;
|
||||
ledcWrite(chan, duty);
|
||||
}
|
||||
}
|
||||
|
||||
void spindle_set_enable(bool enable)
|
||||
{
|
||||
#ifdef SPINDLE_ENABLE_PIN
|
||||
#ifndef INVERT_SPINDLE_ENABLE_PIN
|
||||
digitalWrite(SPINDLE_ENABLE_PIN, enable); // turn off (low) with zero speed
|
||||
#else
|
||||
digitalWrite(SPINDLE_ENABLE_PIN, !enable); // turn off (high) with zero speed
|
||||
#endif
|
||||
#endif
|
||||
void spindle_set_enable(bool enable) {
|
||||
#ifdef SPINDLE_ENABLE_PIN
|
||||
#ifndef INVERT_SPINDLE_ENABLE_PIN
|
||||
digitalWrite(SPINDLE_ENABLE_PIN, enable); // turn off (low) with zero speed
|
||||
#else
|
||||
digitalWrite(SPINDLE_ENABLE_PIN, !enable); // turn off (high) with zero speed
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
uint32_t piecewise_linear_fit(float rpm) {
|
||||
uint32_t pwm_value;
|
||||
|
||||
#if (N_PIECES > 3)
|
||||
if (rpm > RPM_POINT34) {
|
||||
pwm_value = floor(RPM_LINE_A4*rpm - RPM_LINE_B4);
|
||||
} else
|
||||
#endif
|
||||
#if (N_PIECES > 2)
|
||||
if (rpm > RPM_POINT23) {
|
||||
pwm_value = floor(RPM_LINE_A3*rpm - RPM_LINE_B3);
|
||||
} else
|
||||
#endif
|
||||
#if (N_PIECES > 1)
|
||||
if (rpm > RPM_POINT12) {
|
||||
pwm_value = floor(RPM_LINE_A2*rpm - RPM_LINE_B2);
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
pwm_value = floor(RPM_LINE_A1*rpm - RPM_LINE_B1);
|
||||
}
|
||||
return pwm_value;
|
||||
uint32_t pwm_value;
|
||||
#if (N_PIECES > 3)
|
||||
if (rpm > RPM_POINT34)
|
||||
pwm_value = floor(RPM_LINE_A4 * rpm - RPM_LINE_B4);
|
||||
else
|
||||
#endif
|
||||
#if (N_PIECES > 2)
|
||||
if (rpm > RPM_POINT23)
|
||||
pwm_value = floor(RPM_LINE_A3 * rpm - RPM_LINE_B3);
|
||||
else
|
||||
#endif
|
||||
#if (N_PIECES > 1)
|
||||
if (rpm > RPM_POINT12)
|
||||
pwm_value = floor(RPM_LINE_A2 * rpm - RPM_LINE_B2);
|
||||
else
|
||||
#endif
|
||||
{
|
||||
pwm_value = floor(RPM_LINE_A1 * rpm - RPM_LINE_B1);
|
||||
}
|
||||
return pwm_value;
|
||||
}
|
||||
|
||||
|
||||
|
@ -2,10 +2,10 @@
|
||||
spindle.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 modified for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
@ -19,10 +19,10 @@
|
||||
*/
|
||||
|
||||
#ifndef spindle_control_h
|
||||
#define spindle_control_h
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
#define spindle_control_h
|
||||
|
||||
#include "grbl.h"
|
||||
|
||||
|
||||
#define SPINDLE_NO_SYNC false
|
||||
#define SPINDLE_FORCE_SYNC true
|
||||
@ -32,16 +32,16 @@
|
||||
#define SPINDLE_STATE_CCW bit(1)
|
||||
|
||||
extern uint32_t spindle_pwm_off_value;
|
||||
|
||||
void spindle_init();
|
||||
void spindle_stop();
|
||||
uint8_t spindle_get_state();
|
||||
void spindle_set_speed(uint32_t pwm_value);
|
||||
uint32_t spindle_compute_pwm_value(float rpm);
|
||||
void spindle_set_state(uint8_t state, float rpm);
|
||||
void spindle_sync(uint8_t state, float rpm);
|
||||
void grbl_analogWrite(uint8_t chan, uint32_t duty);
|
||||
void spindle_set_enable(bool enable);
|
||||
uint32_t piecewise_linear_fit(float rpm);
|
||||
|
||||
void spindle_init();
|
||||
void spindle_stop();
|
||||
uint8_t spindle_get_state();
|
||||
void spindle_set_speed(uint32_t pwm_value);
|
||||
uint32_t spindle_compute_pwm_value(float rpm);
|
||||
void spindle_set_state(uint8_t state, float rpm);
|
||||
void spindle_sync(uint8_t state, float rpm);
|
||||
void grbl_analogWrite(uint8_t chan, uint32_t duty);
|
||||
void spindle_set_enable(bool enable);
|
||||
uint32_t piecewise_linear_fit(float rpm);
|
||||
|
||||
#endif
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -4,7 +4,7 @@
|
||||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
@ -26,7 +26,7 @@
|
||||
#define stepper_h
|
||||
|
||||
#ifndef SEGMENT_BUFFER_SIZE
|
||||
#define SEGMENT_BUFFER_SIZE 6
|
||||
#define SEGMENT_BUFFER_SIZE 6
|
||||
#endif
|
||||
|
||||
|
||||
@ -57,20 +57,20 @@
|
||||
// NOTE: Current settings are set to overdrive the ISR to no more than 16kHz, balancing CPU overhead
|
||||
// and timer accuracy. Do not alter these settings unless you know what you are doing.
|
||||
///#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
|
||||
#define MAX_AMASS_LEVEL 3
|
||||
// AMASS_LEVEL0: Normal operation. No AMASS. No upper cutoff frequency. Starts at LEVEL1 cutoff frequency.
|
||||
// Note ESP32 use F_STEPPER_TIMER rather than the AVR F_CPU
|
||||
#define AMASS_LEVEL1 (F_STEPPER_TIMER/8000) // Over-drives ISR (x2). Defined as F_CPU/(Cutoff frequency in Hz)
|
||||
#define AMASS_LEVEL2 (F_STEPPER_TIMER/4000) // Over-drives ISR (x4)
|
||||
#define AMASS_LEVEL3 (F_STEPPER_TIMER/2000) // Over-drives ISR (x8)
|
||||
#define MAX_AMASS_LEVEL 3
|
||||
// AMASS_LEVEL0: Normal operation. No AMASS. No upper cutoff frequency. Starts at LEVEL1 cutoff frequency.
|
||||
// Note ESP32 use F_STEPPER_TIMER rather than the AVR F_CPU
|
||||
#define AMASS_LEVEL1 (F_STEPPER_TIMER/8000) // Over-drives ISR (x2). Defined as F_CPU/(Cutoff frequency in Hz)
|
||||
#define AMASS_LEVEL2 (F_STEPPER_TIMER/4000) // Over-drives ISR (x4)
|
||||
#define AMASS_LEVEL3 (F_STEPPER_TIMER/2000) // Over-drives ISR (x8)
|
||||
|
||||
#if MAX_AMASS_LEVEL <= 0
|
||||
#if MAX_AMASS_LEVEL <= 0
|
||||
error "AMASS must have 1 or more levels to operate correctly."
|
||||
#endif
|
||||
#endif
|
||||
//#endif
|
||||
|
||||
#define STEP_TIMER_GROUP TIMER_GROUP_0
|
||||
#define STEP_TIMER_INDEX TIMER_0
|
||||
#define STEP_TIMER_INDEX TIMER_0
|
||||
|
||||
// esp32 work around for diable in main loop
|
||||
extern uint64_t stepper_idle_counter;
|
||||
@ -83,10 +83,10 @@ void IRAM_ATTR onSteppertimer();
|
||||
void IRAM_ATTR onStepperOffTimer();
|
||||
|
||||
#ifdef USE_RMT_STEPS
|
||||
void initRMT();
|
||||
void initRMT();
|
||||
#endif
|
||||
|
||||
void stepper_init();
|
||||
void stepper_init();
|
||||
|
||||
// Enable steppers, but cycle does not start unless called by motion control or realtime command.
|
||||
void st_wake_up();
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -2,10 +2,10 @@
|
||||
system.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
|
||||
@ -19,31 +19,31 @@
|
||||
*/
|
||||
|
||||
#ifndef system_h
|
||||
#define system_h
|
||||
#include "grbl.h"
|
||||
#include "tdef.h"
|
||||
#define system_h
|
||||
#include "grbl.h"
|
||||
#include "tdef.h"
|
||||
|
||||
// Define global system variables
|
||||
typedef struct {
|
||||
uint8_t state; // Tracks the current system state of Grbl.
|
||||
uint8_t abort; // System abort flag. Forces exit back to main loop for reset.
|
||||
uint8_t suspend; // System suspend bitflag variable that manages holds, cancels, and safety door.
|
||||
uint8_t soft_limit; // Tracks soft limit errors for the state machine. (boolean)
|
||||
uint8_t step_control; // Governs the step segment generator depending on system state.
|
||||
uint8_t probe_succeeded; // Tracks if last probing cycle was successful.
|
||||
uint8_t homing_axis_lock; // Locks axes when limits engage. Used as an axis motion mask in the stepper ISR.
|
||||
uint8_t f_override; // Feed rate override value in percent
|
||||
uint8_t r_override; // Rapids override value in percent
|
||||
uint8_t spindle_speed_ovr; // Spindle speed value in percent
|
||||
uint8_t spindle_stop_ovr; // Tracks spindle stop override states
|
||||
uint8_t report_ovr_counter; // Tracks when to add override data to status reports.
|
||||
uint8_t report_wco_counter; // Tracks when to add work coordinate offset data to status reports.
|
||||
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
|
||||
uint8_t state; // Tracks the current system state of Grbl.
|
||||
uint8_t abort; // System abort flag. Forces exit back to main loop for reset.
|
||||
uint8_t suspend; // System suspend bitflag variable that manages holds, cancels, and safety door.
|
||||
uint8_t soft_limit; // Tracks soft limit errors for the state machine. (boolean)
|
||||
uint8_t step_control; // Governs the step segment generator depending on system state.
|
||||
uint8_t probe_succeeded; // Tracks if last probing cycle was successful.
|
||||
uint8_t homing_axis_lock; // Locks axes when limits engage. Used as an axis motion mask in the stepper ISR.
|
||||
uint8_t f_override; // Feed rate override value in percent
|
||||
uint8_t r_override; // Rapids override value in percent
|
||||
uint8_t spindle_speed_ovr; // Spindle speed value in percent
|
||||
uint8_t spindle_stop_ovr; // Tracks spindle stop override states
|
||||
uint8_t report_ovr_counter; // Tracks when to add override data to status reports.
|
||||
uint8_t report_wco_counter; // Tracks when to add work coordinate offset data to status reports.
|
||||
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
|
||||
uint8_t override_ctrl; // Tracks override control states.
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
float spindle_speed;
|
||||
|
||||
|
||||
} system_t;
|
||||
extern system_t sys;
|
||||
|
||||
@ -129,20 +129,20 @@ extern system_t sys;
|
||||
|
||||
// Define control pin index for Grbl internal use. Pin maps may change, but these values don't.
|
||||
//#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
|
||||
#define N_CONTROL_PIN 4
|
||||
#define CONTROL_PIN_INDEX_SAFETY_DOOR bit(0)
|
||||
#define CONTROL_PIN_INDEX_RESET bit(1)
|
||||
#define CONTROL_PIN_INDEX_FEED_HOLD bit(2)
|
||||
#define CONTROL_PIN_INDEX_CYCLE_START bit(3)
|
||||
#define CONTROL_PIN_INDEX_MACRO_0 bit(4)
|
||||
#define CONTROL_PIN_INDEX_MACRO_1 bit(5)
|
||||
#define CONTROL_PIN_INDEX_MACRO_2 bit(6)
|
||||
#define CONTROL_PIN_INDEX_MACRO_3 bit(7)
|
||||
#define N_CONTROL_PIN 4
|
||||
#define CONTROL_PIN_INDEX_SAFETY_DOOR bit(0)
|
||||
#define CONTROL_PIN_INDEX_RESET bit(1)
|
||||
#define CONTROL_PIN_INDEX_FEED_HOLD bit(2)
|
||||
#define CONTROL_PIN_INDEX_CYCLE_START bit(3)
|
||||
#define CONTROL_PIN_INDEX_MACRO_0 bit(4)
|
||||
#define CONTROL_PIN_INDEX_MACRO_1 bit(5)
|
||||
#define CONTROL_PIN_INDEX_MACRO_2 bit(6)
|
||||
#define CONTROL_PIN_INDEX_MACRO_3 bit(7)
|
||||
//#else
|
||||
//#define N_CONTROL_PIN 3
|
||||
//#define CONTROL_PIN_INDEX_RESET bit(0)
|
||||
//#define CONTROL_PIN_INDEX_FEED_HOLD bit(1)
|
||||
//#define CONTROL_PIN_INDEX_CYCLE_START bit(2)
|
||||
//#define N_CONTROL_PIN 3
|
||||
//#define CONTROL_PIN_INDEX_RESET bit(0)
|
||||
//#define CONTROL_PIN_INDEX_FEED_HOLD bit(1)
|
||||
//#define CONTROL_PIN_INDEX_CYCLE_START bit(2)
|
||||
//#endif
|
||||
|
||||
// Define spindle stop override control states.
|
||||
@ -166,8 +166,8 @@ extern volatile uint8_t sys_rt_exec_motion_override; // Global realtime executor
|
||||
extern volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bitflag variable for spindle/coolant overrides.
|
||||
|
||||
#ifdef DEBUG
|
||||
#define EXEC_DEBUG_REPORT bit(0)
|
||||
extern volatile uint8_t sys_rt_exec_debug;
|
||||
#define EXEC_DEBUG_REPORT bit(0)
|
||||
extern volatile uint8_t sys_rt_exec_debug;
|
||||
#endif
|
||||
|
||||
|
||||
@ -192,19 +192,19 @@ void system_clear_exec_motion_overrides();
|
||||
void system_clear_exec_accessory_overrides();
|
||||
|
||||
// Execute the startup script lines stored in EEPROM upon initialization
|
||||
void system_execute_startup(char *line);
|
||||
uint8_t system_execute_line(char *line, uint8_t client);
|
||||
void system_execute_startup(char* line);
|
||||
uint8_t system_execute_line(char* line, uint8_t client);
|
||||
|
||||
void system_flag_wco_change();
|
||||
|
||||
// Returns machine position of axis 'idx'. Must be sent a 'step' array.
|
||||
float system_convert_axis_steps_to_mpos(int32_t *steps, uint8_t idx);
|
||||
float system_convert_axis_steps_to_mpos(int32_t* steps, uint8_t idx);
|
||||
|
||||
// Updates a machine 'position' array based on the 'step' array sent.
|
||||
void system_convert_array_steps_to_mpos(float *position, int32_t *steps);
|
||||
void system_convert_array_steps_to_mpos(float* position, int32_t* steps);
|
||||
|
||||
// Checks and reports if target array exceeds machine travel limits.
|
||||
uint8_t system_check_travel_limits(float *target);
|
||||
uint8_t system_check_travel_limits(float* target);
|
||||
uint8_t get_limit_pin_mask(uint8_t axis_idx);
|
||||
|
||||
// Special handlers for setting and clearing Grbl's real-time execution flags.
|
||||
@ -218,16 +218,16 @@ void system_clear_exec_motion_overrides();
|
||||
void system_clear_exec_accessory_overrides();
|
||||
|
||||
|
||||
int32_t system_convert_corexy_to_x_axis_steps(int32_t *steps);
|
||||
int32_t system_convert_corexy_to_y_axis_steps(int32_t *steps);
|
||||
int32_t system_convert_corexy_to_x_axis_steps(int32_t* steps);
|
||||
int32_t system_convert_corexy_to_y_axis_steps(int32_t* steps);
|
||||
|
||||
// A task that runs after a control switch interrupt for debouncing.
|
||||
void controlCheckTask(void *pvParameters);
|
||||
void controlCheckTask(void* pvParameters);
|
||||
void system_exec_control_pin(uint8_t pin);
|
||||
|
||||
void sys_io_control(uint8_t io_num_mask, bool turnOn);
|
||||
|
||||
//
|
||||
//
|
||||
int8_t sys_get_next_RMT_chan_num();
|
||||
|
||||
#endif
|
||||
|
@ -39,23 +39,22 @@
|
||||
Telnet_Server telnet_server;
|
||||
bool Telnet_Server::_setupdone = false;
|
||||
uint16_t Telnet_Server::_port = 0;
|
||||
WiFiServer * Telnet_Server::_telnetserver = NULL;
|
||||
WiFiServer* Telnet_Server::_telnetserver = NULL;
|
||||
WiFiClient Telnet_Server::_telnetClients[MAX_TLNT_CLIENTS];
|
||||
#ifdef ENABLE_TELNET_WELCOME_MSG
|
||||
IPAddress Telnet_Server::_telnetClientsIP[MAX_TLNT_CLIENTS];
|
||||
IPAddress Telnet_Server::_telnetClientsIP[MAX_TLNT_CLIENTS];
|
||||
#endif
|
||||
|
||||
Telnet_Server::Telnet_Server(){
|
||||
Telnet_Server::Telnet_Server() {
|
||||
_RXbufferSize = 0;
|
||||
_RXbufferpos = 0;
|
||||
}
|
||||
Telnet_Server::~Telnet_Server(){
|
||||
Telnet_Server::~Telnet_Server() {
|
||||
end();
|
||||
}
|
||||
|
||||
|
||||
bool Telnet_Server::begin(){
|
||||
|
||||
bool Telnet_Server::begin() {
|
||||
bool no_error = true;
|
||||
end();
|
||||
Preferences prefs;
|
||||
@ -66,20 +65,19 @@ bool Telnet_Server::begin(){
|
||||
//Get telnet port
|
||||
_port = prefs.getUShort(TELNET_PORT_ENTRY, DEFAULT_TELNETSERVER_PORT);
|
||||
prefs.end();
|
||||
|
||||
if (penabled == 0) return false;
|
||||
//create instance
|
||||
_telnetserver= new WiFiServer(_port, MAX_TLNT_CLIENTS);
|
||||
_telnetserver = new WiFiServer(_port, MAX_TLNT_CLIENTS);
|
||||
_telnetserver->setNoDelay(true);
|
||||
String s = "[MSG:TELNET Started " + String(_port) + "]\r\n";
|
||||
grbl_send(CLIENT_ALL,(char *)s.c_str());
|
||||
grbl_send(CLIENT_ALL, (char*)s.c_str());
|
||||
//start telnet server
|
||||
_telnetserver->begin();
|
||||
_setupdone = true;
|
||||
return no_error;
|
||||
}
|
||||
|
||||
void Telnet_Server::end(){
|
||||
void Telnet_Server::end() {
|
||||
_setupdone = false;
|
||||
_RXbufferSize = 0;
|
||||
_RXbufferpos = 0;
|
||||
@ -89,146 +87,142 @@ void Telnet_Server::end(){
|
||||
}
|
||||
}
|
||||
|
||||
void Telnet_Server::clearClients(){
|
||||
//check if there are any new clients
|
||||
if (_telnetserver->hasClient()){
|
||||
uint8_t i;
|
||||
for(i = 0; i < MAX_TLNT_CLIENTS; i++){
|
||||
//find free/disconnected spot
|
||||
if (!_telnetClients[i] || !_telnetClients[i].connected()){
|
||||
void Telnet_Server::clearClients() {
|
||||
//check if there are any new clients
|
||||
if (_telnetserver->hasClient()) {
|
||||
uint8_t i;
|
||||
for (i = 0; i < MAX_TLNT_CLIENTS; i++) {
|
||||
//find free/disconnected spot
|
||||
if (!_telnetClients[i] || !_telnetClients[i].connected()) {
|
||||
#ifdef ENABLE_TELNET_WELCOME_MSG
|
||||
_telnetClientsIP[i] = IPAddress(0, 0, 0, 0);
|
||||
_telnetClientsIP[i] = IPAddress(0, 0, 0, 0);
|
||||
#endif
|
||||
if(_telnetClients[i]) _telnetClients[i].stop();
|
||||
_telnetClients[i] = _telnetserver->available();
|
||||
break;
|
||||
if (_telnetClients[i]) _telnetClients[i].stop();
|
||||
_telnetClients[i] = _telnetserver->available();
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (i >= MAX_TLNT_CLIENTS) {
|
||||
//no free/disconnected spot so reject
|
||||
_telnetserver->available().stop();
|
||||
}
|
||||
}
|
||||
if (i >= MAX_TLNT_CLIENTS) {
|
||||
//no free/disconnected spot so reject
|
||||
_telnetserver->available().stop();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
size_t Telnet_Server::write(const uint8_t *buffer, size_t size){
|
||||
|
||||
size_t Telnet_Server::write(const uint8_t* buffer, size_t size) {
|
||||
size_t wsize = 0;
|
||||
if ( !_setupdone || _telnetserver == NULL) {
|
||||
if (!_setupdone || _telnetserver == NULL) {
|
||||
log_d("[TELNET out blocked]");
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
clearClients();
|
||||
//log_d("[TELNET out]");
|
||||
//push UART data to all connected telnet clients
|
||||
for(uint8_t i = 0; i < MAX_TLNT_CLIENTS; i++){
|
||||
if (_telnetClients[i] && _telnetClients[i].connected()){
|
||||
for (uint8_t i = 0; i < MAX_TLNT_CLIENTS; i++) {
|
||||
if (_telnetClients[i] && _telnetClients[i].connected()) {
|
||||
//log_d("[TELNET out connected]");
|
||||
wsize = _telnetClients[i].write(buffer, size);
|
||||
COMMANDS::wait(0);
|
||||
wsize = _telnetClients[i].write(buffer, size);
|
||||
COMMANDS::wait(0);
|
||||
}
|
||||
}
|
||||
return wsize;
|
||||
}
|
||||
|
||||
void Telnet_Server::handle(){
|
||||
void Telnet_Server::handle() {
|
||||
COMMANDS::wait(0);
|
||||
//check if can read
|
||||
if ( !_setupdone || _telnetserver == NULL) {
|
||||
if (!_setupdone || _telnetserver == NULL)
|
||||
return;
|
||||
}
|
||||
clearClients();
|
||||
//check clients for data
|
||||
//uint8_t c;
|
||||
for(uint8_t i = 0; i < MAX_TLNT_CLIENTS; i++){
|
||||
if (_telnetClients[i] && _telnetClients[i].connected()){
|
||||
for (uint8_t i = 0; i < MAX_TLNT_CLIENTS; i++) {
|
||||
if (_telnetClients[i] && _telnetClients[i].connected()) {
|
||||
#ifdef ENABLE_TELNET_WELCOME_MSG
|
||||
if (_telnetClientsIP[i] != _telnetClients[i].remoteIP()){
|
||||
report_init_message(CLIENT_TELNET);
|
||||
_telnetClientsIP[i] = _telnetClients[i].remoteIP();
|
||||
if (_telnetClientsIP[i] != _telnetClients[i].remoteIP()) {
|
||||
report_init_message(CLIENT_TELNET);
|
||||
_telnetClientsIP[i] = _telnetClients[i].remoteIP();
|
||||
}
|
||||
#endif
|
||||
if(_telnetClients[i].available()){
|
||||
uint8_t buf[1024];
|
||||
COMMANDS::wait(0);
|
||||
int readlen = _telnetClients[i].available();
|
||||
int writelen = TELNETRXBUFFERSIZE - available();
|
||||
if (readlen > 1024) readlen = 1024;
|
||||
if (readlen > writelen) readlen = writelen;
|
||||
if (readlen > 0) {
|
||||
_telnetClients[i].read(buf, readlen);
|
||||
push(buf, readlen);
|
||||
}
|
||||
return;
|
||||
}
|
||||
}
|
||||
else {
|
||||
if (_telnetClients[i]) {
|
||||
if (_telnetClients[i].available()) {
|
||||
uint8_t buf[1024];
|
||||
COMMANDS::wait(0);
|
||||
int readlen = _telnetClients[i].available();
|
||||
int writelen = TELNETRXBUFFERSIZE - available();
|
||||
if (readlen > 1024) readlen = 1024;
|
||||
if (readlen > writelen) readlen = writelen;
|
||||
if (readlen > 0) {
|
||||
_telnetClients[i].read(buf, readlen);
|
||||
push(buf, readlen);
|
||||
}
|
||||
return;
|
||||
}
|
||||
} else {
|
||||
if (_telnetClients[i]) {
|
||||
#ifdef ENABLE_TELNET_WELCOME_MSG
|
||||
_telnetClientsIP[i] = IPAddress(0, 0, 0, 0);
|
||||
_telnetClientsIP[i] = IPAddress(0, 0, 0, 0);
|
||||
#endif
|
||||
_telnetClients[i].stop();
|
||||
_telnetClients[i].stop();
|
||||
}
|
||||
}
|
||||
}
|
||||
COMMANDS::wait(0);
|
||||
COMMANDS::wait(0);
|
||||
}
|
||||
}
|
||||
|
||||
int Telnet_Server::peek(void){
|
||||
int Telnet_Server::peek(void) {
|
||||
if (_RXbufferSize > 0)return _RXbuffer[_RXbufferpos];
|
||||
else return -1;
|
||||
}
|
||||
|
||||
int Telnet_Server::available(){
|
||||
int Telnet_Server::available() {
|
||||
return _RXbufferSize;
|
||||
}
|
||||
|
||||
int Telnet_Server::get_rx_buffer_available(){
|
||||
int Telnet_Server::get_rx_buffer_available() {
|
||||
return TELNETRXBUFFERSIZE - _RXbufferSize;
|
||||
}
|
||||
|
||||
bool Telnet_Server::push (uint8_t data){
|
||||
log_i("[TELNET]push %c",data);
|
||||
if ((1 + _RXbufferSize) <= TELNETRXBUFFERSIZE){
|
||||
bool Telnet_Server::push(uint8_t data) {
|
||||
log_i("[TELNET]push %c", data);
|
||||
if ((1 + _RXbufferSize) <= TELNETRXBUFFERSIZE) {
|
||||
int current = _RXbufferpos + _RXbufferSize;
|
||||
if (current > TELNETRXBUFFERSIZE) current = current - TELNETRXBUFFERSIZE;
|
||||
if (current > (TELNETRXBUFFERSIZE-1)) current = 0;
|
||||
if (current > (TELNETRXBUFFERSIZE - 1)) current = 0;
|
||||
_RXbuffer[current] = data;
|
||||
_RXbufferSize++;
|
||||
log_i("[TELNET]buffer size %d",_RXbufferSize);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool Telnet_Server::push (const uint8_t * data, int data_size){
|
||||
if ((data_size + _RXbufferSize) <= TELNETRXBUFFERSIZE){
|
||||
int data_processed = 0;
|
||||
int current = _RXbufferpos + _RXbufferSize;
|
||||
if (current > TELNETRXBUFFERSIZE) current = current - TELNETRXBUFFERSIZE;
|
||||
for (int i = 0; i < data_size; i++){
|
||||
if (current > (TELNETRXBUFFERSIZE-1)) current = 0;
|
||||
if (char(data[i]) != '\r') {
|
||||
_RXbuffer[current] = data[i];
|
||||
current ++;
|
||||
data_processed++;
|
||||
}
|
||||
COMMANDS::wait(0);
|
||||
//vTaskDelay(1 / portTICK_RATE_MS); // Yield to other tasks
|
||||
}
|
||||
_RXbufferSize+=data_processed;
|
||||
log_i("[TELNET]buffer size %d", _RXbufferSize);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
int Telnet_Server::read(void){
|
||||
|
||||
bool Telnet_Server::push(const uint8_t* data, int data_size) {
|
||||
if ((data_size + _RXbufferSize) <= TELNETRXBUFFERSIZE) {
|
||||
int data_processed = 0;
|
||||
int current = _RXbufferpos + _RXbufferSize;
|
||||
if (current > TELNETRXBUFFERSIZE) current = current - TELNETRXBUFFERSIZE;
|
||||
for (int i = 0; i < data_size; i++) {
|
||||
if (current > (TELNETRXBUFFERSIZE - 1)) current = 0;
|
||||
if (char(data[i]) != '\r') {
|
||||
_RXbuffer[current] = data[i];
|
||||
current ++;
|
||||
data_processed++;
|
||||
}
|
||||
COMMANDS::wait(0);
|
||||
//vTaskDelay(1 / portTICK_RATE_MS); // Yield to other tasks
|
||||
}
|
||||
_RXbufferSize += data_processed;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
int Telnet_Server::read(void) {
|
||||
if (_RXbufferSize > 0) {
|
||||
int v = _RXbuffer[_RXbufferpos];
|
||||
//log_d("[TELNET]read %c",char(v));
|
||||
_RXbufferpos++;
|
||||
if (_RXbufferpos > (TELNETRXBUFFERSIZE-1))_RXbufferpos = 0;
|
||||
if (_RXbufferpos > (TELNETRXBUFFERSIZE - 1))_RXbufferpos = 0;
|
||||
_RXbufferSize--;
|
||||
return v;
|
||||
} else return -1;
|
||||
|
@ -33,23 +33,23 @@ class WiFiClient;
|
||||
#define FLUSHTIMEOUT 500
|
||||
|
||||
class Telnet_Server {
|
||||
public:
|
||||
public:
|
||||
Telnet_Server();
|
||||
~Telnet_Server();
|
||||
bool begin();
|
||||
void end();
|
||||
void handle();
|
||||
size_t write(const uint8_t *buffer, size_t size);
|
||||
size_t write(const uint8_t* buffer, size_t size);
|
||||
int read(void);
|
||||
int peek(void);
|
||||
int available();
|
||||
int get_rx_buffer_available();
|
||||
bool push (uint8_t data);
|
||||
bool push (const uint8_t * data, int datasize);
|
||||
static uint16_t port(){return _port;}
|
||||
private:
|
||||
bool push(uint8_t data);
|
||||
bool push(const uint8_t* data, int datasize);
|
||||
static uint16_t port() {return _port;}
|
||||
private:
|
||||
static bool _setupdone;
|
||||
static WiFiServer * _telnetserver;
|
||||
static WiFiServer* _telnetserver;
|
||||
static WiFiClient _telnetClients[MAX_TLNT_CLIENTS];
|
||||
#ifdef ENABLE_TELNET_WELCOME_MSG
|
||||
static IPAddress _telnetClientsIP[MAX_TLNT_CLIENTS];
|
||||
|
@ -35,54 +35,54 @@ struct auth_ip {
|
||||
char userID[17];
|
||||
char sessionID[17];
|
||||
uint32_t last_time;
|
||||
auth_ip * _next;
|
||||
auth_ip* _next;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
class Web_Server {
|
||||
public:
|
||||
public:
|
||||
Web_Server();
|
||||
~Web_Server();
|
||||
bool begin();
|
||||
void end();
|
||||
void handle();
|
||||
static long get_client_ID();
|
||||
static uint16_t port(){return _port;}
|
||||
private:
|
||||
static uint16_t port() {return _port;}
|
||||
private:
|
||||
static bool _setupdone;
|
||||
static WebServer * _webserver;
|
||||
static WebServer* _webserver;
|
||||
static long _id_connection;
|
||||
static WebSocketsServer * _socket_server;
|
||||
static WebSocketsServer* _socket_server;
|
||||
static uint16_t _port;
|
||||
static uint8_t _upload_status;
|
||||
static String getContentType (String filename);
|
||||
static String getContentType(String filename);
|
||||
static String get_Splited_Value(String data, char separator, int index);
|
||||
static level_authenticate_type is_authenticated();
|
||||
#ifdef ENABLE_AUTHENTICATION
|
||||
static auth_ip * _head;
|
||||
static auth_ip* _head;
|
||||
static uint8_t _nb_ip;
|
||||
static bool AddAuthIP (auth_ip * item);
|
||||
static char * create_session_ID();
|
||||
static bool ClearAuthIP (IPAddress ip, const char * sessionID);
|
||||
static auth_ip * GetAuth (IPAddress ip, const char * sessionID);
|
||||
static level_authenticate_type ResetAuthIP (IPAddress ip, const char * sessionID);
|
||||
static bool AddAuthIP(auth_ip* item);
|
||||
static char* create_session_ID();
|
||||
static bool ClearAuthIP(IPAddress ip, const char* sessionID);
|
||||
static auth_ip* GetAuth(IPAddress ip, const char* sessionID);
|
||||
static level_authenticate_type ResetAuthIP(IPAddress ip, const char* sessionID);
|
||||
#endif
|
||||
#ifdef ENABLE_SSDP
|
||||
static void handle_SSDP ();
|
||||
static void handle_SSDP();
|
||||
#endif
|
||||
static void handle_root();
|
||||
static void handle_login();
|
||||
static void handle_not_found ();
|
||||
static void handle_web_command ();
|
||||
static void handle_web_command_silent ();
|
||||
static void handle_Websocket_Event(uint8_t num, uint8_t type, uint8_t * payload, size_t length);
|
||||
static void SPIFFSFileupload ();
|
||||
static void handleFileList ();
|
||||
static void handleUpdate ();
|
||||
static void WebUpdateUpload ();
|
||||
static void handle_not_found();
|
||||
static void handle_web_command();
|
||||
static void handle_web_command_silent();
|
||||
static void handle_Websocket_Event(uint8_t num, uint8_t type, uint8_t* payload, size_t length);
|
||||
static void SPIFFSFileupload();
|
||||
static void handleFileList();
|
||||
static void handleUpdate();
|
||||
static void WebUpdateUpload();
|
||||
static bool is_realtime_cmd(char c);
|
||||
static void pushError(int code, const char * st, bool web_error = 500, uint16_t timeout = 1000);
|
||||
static void pushError(int code, const char* st, bool web_error = 500, uint16_t timeout = 1000);
|
||||
static void cancelUpload();
|
||||
#ifdef ENABLE_SD_CARD
|
||||
static void handle_direct_SDFileList();
|
||||
|
@ -39,57 +39,53 @@ WiFiConfig wifi_config;
|
||||
|
||||
String WiFiConfig::_hostname = "";
|
||||
bool WiFiConfig::_events_registered = false;
|
||||
WiFiConfig::WiFiConfig(){
|
||||
WiFiConfig::WiFiConfig() {
|
||||
}
|
||||
|
||||
WiFiConfig::~WiFiConfig(){
|
||||
|
||||
WiFiConfig::~WiFiConfig() {
|
||||
end();
|
||||
}
|
||||
|
||||
//just simple helper to convert mac address to string
|
||||
char * WiFiConfig::mac2str (uint8_t mac [8])
|
||||
{
|
||||
char* WiFiConfig::mac2str(uint8_t mac [8]) {
|
||||
static char macstr [18];
|
||||
if (0 > sprintf (macstr, "%02X:%02X:%02X:%02X:%02X:%02X", mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]) ) {
|
||||
strcpy (macstr, "00:00:00:00:00:00");
|
||||
}
|
||||
if (0 > sprintf(macstr, "%02X:%02X:%02X:%02X:%02X:%02X", mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]))
|
||||
strcpy(macstr, "00:00:00:00:00:00");
|
||||
return macstr;
|
||||
}
|
||||
|
||||
const char *WiFiConfig::info(){
|
||||
const char* WiFiConfig::info() {
|
||||
static String result;
|
||||
String tmp;
|
||||
result = "[MSG:";
|
||||
if((WiFi.getMode() == WIFI_MODE_STA ) || (WiFi.getMode() == WIFI_MODE_APSTA )) {
|
||||
if ((WiFi.getMode() == WIFI_MODE_STA) || (WiFi.getMode() == WIFI_MODE_APSTA)) {
|
||||
result += "Mode=STA:SSID=";
|
||||
result += WiFi.SSID();
|
||||
result += ":Status=";
|
||||
result += (WiFi.status()==WL_CONNECTED)?"Connected":"Not connected";
|
||||
result += (WiFi.status() == WL_CONNECTED) ? "Connected" : "Not connected";
|
||||
result += ":IP=";
|
||||
result += WiFi.localIP().toString();
|
||||
result += ":MAC=";
|
||||
tmp = WiFi.macAddress();
|
||||
tmp.replace(":","-");
|
||||
tmp.replace(":", "-");
|
||||
result += tmp;
|
||||
|
||||
}
|
||||
if((WiFi.getMode() == WIFI_MODE_AP ) || (WiFi.getMode() == WIFI_MODE_APSTA )) {
|
||||
if(WiFi.getMode() == WIFI_MODE_APSTA ) {
|
||||
result+= "]\r\n[MSG:";
|
||||
}
|
||||
result+="Mode=AP:SSDI=";
|
||||
}
|
||||
if ((WiFi.getMode() == WIFI_MODE_AP) || (WiFi.getMode() == WIFI_MODE_APSTA)) {
|
||||
if (WiFi.getMode() == WIFI_MODE_APSTA)
|
||||
result += "]\r\n[MSG:";
|
||||
result += "Mode=AP:SSDI=";
|
||||
wifi_config_t conf;
|
||||
esp_wifi_get_config (ESP_IF_WIFI_AP, &conf);
|
||||
result+= (const char*)conf.ap.ssid;
|
||||
result+=":IP=";
|
||||
result+=WiFi.softAPIP().toString();
|
||||
result+=":MAC=";
|
||||
esp_wifi_get_config(ESP_IF_WIFI_AP, &conf);
|
||||
result += (const char*)conf.ap.ssid;
|
||||
result += ":IP=";
|
||||
result += WiFi.softAPIP().toString();
|
||||
result += ":MAC=";
|
||||
tmp = WiFi.softAPmacAddress();
|
||||
tmp.replace(":","-");
|
||||
tmp.replace(":", "-");
|
||||
result += tmp;
|
||||
}
|
||||
if(WiFi.getMode() == WIFI_MODE_NULL)result+="No Wifi";
|
||||
result+= "]\r\n";
|
||||
}
|
||||
if (WiFi.getMode() == WIFI_MODE_NULL)result += "No Wifi";
|
||||
result += "]\r\n";
|
||||
return result.c_str();
|
||||
}
|
||||
|
||||
@ -97,7 +93,7 @@ const char *WiFiConfig::info(){
|
||||
* Helper to convert IP string to int
|
||||
*/
|
||||
|
||||
uint32_t WiFiConfig::IP_int_from_string(String & s){
|
||||
uint32_t WiFiConfig::IP_int_from_string(String& s) {
|
||||
uint32_t ip_int = 0;
|
||||
IPAddress ipaddr;
|
||||
if (ipaddr.fromString(s)) ip_int = ipaddr;
|
||||
@ -108,7 +104,7 @@ uint32_t WiFiConfig::IP_int_from_string(String & s){
|
||||
* Helper to convert int to IP string
|
||||
*/
|
||||
|
||||
String WiFiConfig::IP_string_from_int(uint32_t ip_int){
|
||||
String WiFiConfig::IP_string_from_int(uint32_t ip_int) {
|
||||
IPAddress ipaddr(ip_int);
|
||||
return ipaddr.toString();
|
||||
}
|
||||
@ -117,22 +113,18 @@ String WiFiConfig::IP_string_from_int(uint32_t ip_int){
|
||||
* Check if Hostname string is valid
|
||||
*/
|
||||
|
||||
bool WiFiConfig::isHostnameValid (const char * hostname)
|
||||
{
|
||||
bool WiFiConfig::isHostnameValid(const char* hostname) {
|
||||
//limited size
|
||||
char c;
|
||||
if (strlen (hostname) > MAX_HOSTNAME_LENGTH || strlen (hostname) < MIN_HOSTNAME_LENGTH) {
|
||||
if (strlen(hostname) > MAX_HOSTNAME_LENGTH || strlen(hostname) < MIN_HOSTNAME_LENGTH)
|
||||
return false;
|
||||
}
|
||||
//only letter and digit
|
||||
for (int i = 0; i < strlen (hostname); i++) {
|
||||
for (int i = 0; i < strlen(hostname); i++) {
|
||||
c = hostname[i];
|
||||
if (! (isdigit (c) || isalpha (c) || c == '-') ) {
|
||||
if (!(isdigit(c) || isalpha(c) || c == '-'))
|
||||
return false;
|
||||
}
|
||||
if (c == ' ') {
|
||||
if (c == ' ')
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
@ -142,18 +134,15 @@ bool WiFiConfig::isHostnameValid (const char * hostname)
|
||||
* Check if SSID string is valid
|
||||
*/
|
||||
|
||||
bool WiFiConfig::isSSIDValid (const char * ssid)
|
||||
{
|
||||
bool WiFiConfig::isSSIDValid(const char* ssid) {
|
||||
//limited size
|
||||
//char c;
|
||||
if (strlen (ssid) > MAX_SSID_LENGTH || strlen (ssid) < MIN_SSID_LENGTH) {
|
||||
if (strlen(ssid) > MAX_SSID_LENGTH || strlen(ssid) < MIN_SSID_LENGTH)
|
||||
return false;
|
||||
}
|
||||
//only printable
|
||||
for (int i = 0; i < strlen (ssid); i++) {
|
||||
if (!isPrintable (ssid[i]) ) {
|
||||
for (int i = 0; i < strlen(ssid); i++) {
|
||||
if (!isPrintable(ssid[i]))
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
@ -162,32 +151,30 @@ bool WiFiConfig::isSSIDValid (const char * ssid)
|
||||
* Check if password string is valid
|
||||
*/
|
||||
|
||||
bool WiFiConfig::isPasswordValid (const char * password)
|
||||
{
|
||||
if (strlen (password) == 0) return true; //open network
|
||||
bool WiFiConfig::isPasswordValid(const char* password) {
|
||||
if (strlen(password) == 0) return true; //open network
|
||||
//limited size
|
||||
if ((strlen (password) > MAX_PASSWORD_LENGTH) || (strlen (password) < MIN_PASSWORD_LENGTH)) {
|
||||
if ((strlen(password) > MAX_PASSWORD_LENGTH) || (strlen(password) < MIN_PASSWORD_LENGTH))
|
||||
return false;
|
||||
}
|
||||
//no space allowed ?
|
||||
/* for (int i = 0; i < strlen (password); i++)
|
||||
if (password[i] == ' ') {
|
||||
return false;
|
||||
}*/
|
||||
/* for (int i = 0; i < strlen (password); i++)
|
||||
if (password[i] == ' ') {
|
||||
return false;
|
||||
}*/
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if IP string is valid
|
||||
*/
|
||||
bool WiFiConfig::isValidIP(const char * string){
|
||||
bool WiFiConfig::isValidIP(const char* string) {
|
||||
IPAddress ip;
|
||||
return ip.fromString(string);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* WiFi events
|
||||
* WiFi events
|
||||
* SYSTEM_EVENT_WIFI_READY < ESP32 WiFi ready
|
||||
* SYSTEM_EVENT_SCAN_DONE < ESP32 finish scanning AP
|
||||
* SYSTEM_EVENT_STA_START < ESP32 station start
|
||||
@ -215,15 +202,13 @@ bool WiFiConfig::isValidIP(const char * string){
|
||||
* SYSTEM_EVENT_MAX
|
||||
*/
|
||||
|
||||
void WiFiConfig::WiFiEvent(WiFiEvent_t event)
|
||||
{
|
||||
switch (event)
|
||||
{
|
||||
void WiFiConfig::WiFiEvent(WiFiEvent_t event) {
|
||||
switch (event) {
|
||||
case SYSTEM_EVENT_STA_GOT_IP:
|
||||
grbl_sendf(CLIENT_ALL,"[MSG:Connected with %s]\r\n",WiFi.localIP().toString().c_str());
|
||||
grbl_sendf(CLIENT_ALL, "[MSG:Connected with %s]\r\n", WiFi.localIP().toString().c_str());
|
||||
break;
|
||||
case SYSTEM_EVENT_STA_DISCONNECTED:
|
||||
grbl_send(CLIENT_ALL,"[MSG:Disconnected]\r\n");
|
||||
grbl_send(CLIENT_ALL, "[MSG:Disconnected]\r\n");
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
@ -233,52 +218,48 @@ void WiFiConfig::WiFiEvent(WiFiEvent_t event)
|
||||
/*
|
||||
* Get WiFi signal strength
|
||||
*/
|
||||
int32_t WiFiConfig::getSignal (int32_t RSSI)
|
||||
{
|
||||
if (RSSI <= -100) {
|
||||
int32_t WiFiConfig::getSignal(int32_t RSSI) {
|
||||
if (RSSI <= -100)
|
||||
return 0;
|
||||
}
|
||||
if (RSSI >= -50) {
|
||||
if (RSSI >= -50)
|
||||
return 100;
|
||||
}
|
||||
return (2 * (RSSI + 100) );
|
||||
return (2 * (RSSI + 100));
|
||||
}
|
||||
|
||||
/*
|
||||
* Connect client to AP
|
||||
*/
|
||||
|
||||
bool WiFiConfig::ConnectSTA2AP(){
|
||||
bool WiFiConfig::ConnectSTA2AP() {
|
||||
String msg, msg_out;
|
||||
uint8_t count = 0;
|
||||
uint8_t dot = 0;
|
||||
wl_status_t status = WiFi.status();
|
||||
while (status != WL_CONNECTED && count < 40) {
|
||||
|
||||
switch (status) {
|
||||
case WL_NO_SSID_AVAIL:
|
||||
msg="No SSID";
|
||||
break;
|
||||
case WL_CONNECT_FAILED:
|
||||
msg="Connection failed";
|
||||
break;
|
||||
case WL_CONNECTED:
|
||||
break;
|
||||
default:
|
||||
if ((dot>3) || (dot==0) ){
|
||||
dot=0;
|
||||
msg_out = "Connecting";
|
||||
}
|
||||
msg_out+=".";
|
||||
msg= msg_out;
|
||||
dot++;
|
||||
break;
|
||||
switch (status) {
|
||||
case WL_NO_SSID_AVAIL:
|
||||
msg = "No SSID";
|
||||
break;
|
||||
case WL_CONNECT_FAILED:
|
||||
msg = "Connection failed";
|
||||
break;
|
||||
case WL_CONNECTED:
|
||||
break;
|
||||
default:
|
||||
if ((dot > 3) || (dot == 0)) {
|
||||
dot = 0;
|
||||
msg_out = "Connecting";
|
||||
}
|
||||
msg_out += ".";
|
||||
msg = msg_out;
|
||||
dot++;
|
||||
break;
|
||||
}
|
||||
grbl_sendf(CLIENT_ALL,"[MSG:%s]\r\n",msg.c_str());
|
||||
COMMANDS::wait (500);
|
||||
grbl_sendf(CLIENT_ALL, "[MSG:%s]\r\n", msg.c_str());
|
||||
COMMANDS::wait(500);
|
||||
count++;
|
||||
status = WiFi.status();
|
||||
}
|
||||
}
|
||||
return (status == WL_CONNECTED);
|
||||
}
|
||||
|
||||
@ -286,15 +267,15 @@ bool WiFiConfig::ConnectSTA2AP(){
|
||||
* Start client mode (Station)
|
||||
*/
|
||||
|
||||
bool WiFiConfig::StartSTA(){
|
||||
bool WiFiConfig::StartSTA() {
|
||||
String defV;
|
||||
Preferences prefs;
|
||||
//stop active service
|
||||
wifi_services.end();
|
||||
//Sanity check
|
||||
if((WiFi.getMode() == WIFI_STA) || (WiFi.getMode() == WIFI_AP_STA))WiFi.disconnect();
|
||||
if((WiFi.getMode() == WIFI_AP) || (WiFi.getMode() == WIFI_AP_STA))WiFi.softAPdisconnect();
|
||||
WiFi.enableAP (false);
|
||||
if ((WiFi.getMode() == WIFI_STA) || (WiFi.getMode() == WIFI_AP_STA))WiFi.disconnect();
|
||||
if ((WiFi.getMode() == WIFI_AP) || (WiFi.getMode() == WIFI_AP_STA))WiFi.softAPdisconnect();
|
||||
WiFi.enableAP(false);
|
||||
WiFi.mode(WIFI_STA);
|
||||
//Get parameters for STA
|
||||
prefs.begin(NAMESPACE, true);
|
||||
@ -318,18 +299,18 @@ bool WiFiConfig::StartSTA(){
|
||||
//MK
|
||||
defV = DEFAULT_STA_MK;
|
||||
int32_t MK = prefs.getInt(STA_MK_ENTRY, IP_int_from_string(defV));
|
||||
prefs.end();
|
||||
prefs.end();
|
||||
//if not DHCP
|
||||
if (IP_mode != DHCP_MODE) {
|
||||
IPAddress ip(IP), mask(MK), gateway(GW);
|
||||
WiFi.config(ip, gateway,mask);
|
||||
WiFi.config(ip, gateway, mask);
|
||||
}
|
||||
if (WiFi.begin(SSID.c_str(), (password.length() > 0)?password.c_str():NULL)){
|
||||
grbl_send(CLIENT_ALL,"\n[MSG:Client Started]\r\n");
|
||||
grbl_sendf(CLIENT_ALL,"[MSG:Connecting %s]\r\n", SSID.c_str());
|
||||
if (WiFi.begin(SSID.c_str(), (password.length() > 0) ? password.c_str() : NULL)) {
|
||||
grbl_send(CLIENT_ALL, "\n[MSG:Client Started]\r\n");
|
||||
grbl_sendf(CLIENT_ALL, "[MSG:Connecting %s]\r\n", SSID.c_str());
|
||||
return ConnectSTA2AP();
|
||||
} else {
|
||||
grbl_send(CLIENT_ALL,"[MSG:Starting client failed]\r\n");
|
||||
grbl_send(CLIENT_ALL, "[MSG:Starting client failed]\r\n");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@ -338,15 +319,15 @@ bool WiFiConfig::StartSTA(){
|
||||
* Setup and start Access point
|
||||
*/
|
||||
|
||||
bool WiFiConfig::StartAP(){
|
||||
bool WiFiConfig::StartAP() {
|
||||
String defV;
|
||||
Preferences prefs;
|
||||
//stop active services
|
||||
wifi_services.end();
|
||||
//Sanity check
|
||||
if((WiFi.getMode() == WIFI_STA) || (WiFi.getMode() == WIFI_AP_STA))WiFi.disconnect();
|
||||
if((WiFi.getMode() == WIFI_AP) || (WiFi.getMode() == WIFI_AP_STA))WiFi.softAPdisconnect();
|
||||
WiFi.enableSTA (false);
|
||||
if ((WiFi.getMode() == WIFI_STA) || (WiFi.getMode() == WIFI_AP_STA))WiFi.disconnect();
|
||||
if ((WiFi.getMode() == WIFI_AP) || (WiFi.getMode() == WIFI_AP_STA))WiFi.softAPdisconnect();
|
||||
WiFi.enableSTA(false);
|
||||
WiFi.mode(WIFI_AP);
|
||||
//Get parameters for AP
|
||||
prefs.begin(NAMESPACE, true);
|
||||
@ -363,21 +344,20 @@ bool WiFiConfig::StartAP(){
|
||||
//IP
|
||||
defV = DEFAULT_AP_IP;
|
||||
int32_t IP = prefs.getInt(AP_IP_ENTRY, IP_int_from_string(defV));
|
||||
if (IP==0){
|
||||
if (IP == 0)
|
||||
IP = IP_int_from_string(defV);
|
||||
}
|
||||
prefs.end();
|
||||
prefs.end();
|
||||
IPAddress ip(IP);
|
||||
IPAddress mask;
|
||||
mask.fromString(DEFAULT_AP_MK);
|
||||
//Set static IP
|
||||
WiFi.softAPConfig(ip, ip, mask);
|
||||
//Start AP
|
||||
if(WiFi.softAP(SSID.c_str(), (password.length() > 0)?password.c_str():NULL, channel)) {
|
||||
grbl_sendf(CLIENT_ALL,"\n[MSG:Local access point %s started, %s]\r\n", SSID.c_str(), WiFi.softAPIP().toString().c_str());
|
||||
if (WiFi.softAP(SSID.c_str(), (password.length() > 0) ? password.c_str() : NULL, channel)) {
|
||||
grbl_sendf(CLIENT_ALL, "\n[MSG:Local access point %s started, %s]\r\n", SSID.c_str(), WiFi.softAPIP().toString().c_str());
|
||||
return true;
|
||||
} else {
|
||||
grbl_send(CLIENT_ALL,"[MSG:Starting AP failed]\r\n");
|
||||
grbl_send(CLIENT_ALL, "[MSG:Starting AP failed]\r\n");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@ -386,15 +366,15 @@ bool WiFiConfig::StartAP(){
|
||||
* Stop WiFi
|
||||
*/
|
||||
|
||||
void WiFiConfig::StopWiFi(){
|
||||
void WiFiConfig::StopWiFi() {
|
||||
//Sanity check
|
||||
if((WiFi.getMode() == WIFI_STA) || (WiFi.getMode() == WIFI_AP_STA))WiFi.disconnect(true);
|
||||
if((WiFi.getMode() == WIFI_AP) || (WiFi.getMode() == WIFI_AP_STA))WiFi.softAPdisconnect(true);
|
||||
if ((WiFi.getMode() == WIFI_STA) || (WiFi.getMode() == WIFI_AP_STA))WiFi.disconnect(true);
|
||||
if ((WiFi.getMode() == WIFI_AP) || (WiFi.getMode() == WIFI_AP_STA))WiFi.softAPdisconnect(true);
|
||||
wifi_services.end();
|
||||
WiFi.enableSTA (false);
|
||||
WiFi.enableAP (false);
|
||||
WiFi.enableSTA(false);
|
||||
WiFi.enableAP(false);
|
||||
WiFi.mode(WIFI_OFF);
|
||||
grbl_send(CLIENT_ALL,"\n[MSG:WiFi Off]\r\n");
|
||||
grbl_send(CLIENT_ALL, "\n[MSG:WiFi Off]\r\n");
|
||||
}
|
||||
|
||||
/**
|
||||
@ -406,7 +386,7 @@ void WiFiConfig::begin() {
|
||||
wifi_services.end();
|
||||
//setup events
|
||||
if (!_events_registered) {
|
||||
//cumulative function and no remove so only do once
|
||||
//cumulative function and no remove so only do once
|
||||
WiFi.onEvent(WiFiConfig::WiFiEvent);
|
||||
_events_registered = true;
|
||||
}
|
||||
@ -416,25 +396,24 @@ void WiFiConfig::begin() {
|
||||
String defV = DEFAULT_HOSTNAME;
|
||||
_hostname = prefs.getString(HOSTNAME_ENTRY, defV);
|
||||
int8_t wifiMode = prefs.getChar(ESP_RADIO_MODE, DEFAULT_RADIO_MODE);
|
||||
|
||||
if (wifiMode == ESP_WIFI_AP) {
|
||||
StartAP();
|
||||
//start services
|
||||
wifi_services.begin();
|
||||
} else if (wifiMode == ESP_WIFI_STA){
|
||||
if(!StartSTA()){
|
||||
defV = DEFAULT_STA_SSID;
|
||||
grbl_sendf(CLIENT_ALL,"[MSG:Cannot connect to %s]\r\n", prefs.getString(STA_SSID_ENTRY, defV).c_str());
|
||||
StartAP();
|
||||
}
|
||||
//start services
|
||||
wifi_services.begin();
|
||||
}else WiFi.mode(WIFI_OFF);
|
||||
StartAP();
|
||||
//start services
|
||||
wifi_services.begin();
|
||||
} else if (wifiMode == ESP_WIFI_STA) {
|
||||
if (!StartSTA()) {
|
||||
defV = DEFAULT_STA_SSID;
|
||||
grbl_sendf(CLIENT_ALL, "[MSG:Cannot connect to %s]\r\n", prefs.getString(STA_SSID_ENTRY, defV).c_str());
|
||||
StartAP();
|
||||
}
|
||||
//start services
|
||||
wifi_services.begin();
|
||||
} else WiFi.mode(WIFI_OFF);
|
||||
prefs.end();
|
||||
}
|
||||
|
||||
/**
|
||||
* End WiFi
|
||||
* End WiFi
|
||||
*/
|
||||
void WiFiConfig::end() {
|
||||
StopWiFi();
|
||||
@ -443,7 +422,7 @@ void WiFiConfig::end() {
|
||||
/**
|
||||
* Reset ESP
|
||||
*/
|
||||
void WiFiConfig::reset_settings(){
|
||||
void WiFiConfig::reset_settings() {
|
||||
Preferences prefs;
|
||||
prefs.begin(NAMESPACE, false);
|
||||
String sval;
|
||||
@ -451,101 +430,77 @@ void WiFiConfig::reset_settings(){
|
||||
int16_t ibuf;
|
||||
bool error = false;
|
||||
sval = DEFAULT_HOSTNAME;
|
||||
if (prefs.putString(HOSTNAME_ENTRY, sval) == 0){
|
||||
if (prefs.putString(HOSTNAME_ENTRY, sval) == 0)
|
||||
error = true;
|
||||
}
|
||||
|
||||
bbuf = DEFAULT_NOTIFICATION_TYPE;
|
||||
if (prefs.putChar(NOTIFICATION_TYPE, bbuf) ==0 ) {
|
||||
error = true;
|
||||
}
|
||||
sval = DEFAULT_TOKEN;
|
||||
if (prefs.putString(NOTIFICATION_T1, sval) != sval.length()){
|
||||
error = true;
|
||||
}
|
||||
if (prefs.putString(NOTIFICATION_T2, sval) != sval.length()){
|
||||
error = true;
|
||||
}
|
||||
if (prefs.putString(NOTIFICATION_TS, sval) != sval.length()){
|
||||
error = true;
|
||||
}
|
||||
|
||||
if (prefs.putChar(NOTIFICATION_TYPE, bbuf) == 0)
|
||||
error = true;
|
||||
sval = DEFAULT_TOKEN;
|
||||
if (prefs.putString(NOTIFICATION_T1, sval) != sval.length())
|
||||
error = true;
|
||||
if (prefs.putString(NOTIFICATION_T2, sval) != sval.length())
|
||||
error = true;
|
||||
if (prefs.putString(NOTIFICATION_TS, sval) != sval.length())
|
||||
error = true;
|
||||
sval = DEFAULT_STA_SSID;
|
||||
if (prefs.putString(STA_SSID_ENTRY, sval) == 0){
|
||||
if (prefs.putString(STA_SSID_ENTRY, sval) == 0)
|
||||
error = true;
|
||||
}
|
||||
sval = DEFAULT_STA_PWD;
|
||||
if (prefs.putString(STA_PWD_ENTRY, sval) != sval.length()){
|
||||
if (prefs.putString(STA_PWD_ENTRY, sval) != sval.length())
|
||||
error = true;
|
||||
}
|
||||
sval = DEFAULT_AP_SSID;
|
||||
if (prefs.putString(AP_SSID_ENTRY, sval) == 0){
|
||||
if (prefs.putString(AP_SSID_ENTRY, sval) == 0)
|
||||
error = true;
|
||||
}
|
||||
sval = DEFAULT_AP_PWD;
|
||||
if (prefs.putString(AP_PWD_ENTRY, sval) != sval.length()){
|
||||
if (prefs.putString(AP_PWD_ENTRY, sval) != sval.length())
|
||||
error = true;
|
||||
}
|
||||
|
||||
bbuf = DEFAULT_AP_CHANNEL;
|
||||
if (prefs.putChar(AP_CHANNEL_ENTRY, bbuf) ==0 ) {
|
||||
if (prefs.putChar(AP_CHANNEL_ENTRY, bbuf) == 0)
|
||||
error = true;
|
||||
}
|
||||
bbuf = DEFAULT_STA_IP_MODE;
|
||||
if (prefs.putChar(STA_IP_MODE_ENTRY, bbuf) ==0 ) {
|
||||
if (prefs.putChar(STA_IP_MODE_ENTRY, bbuf) == 0)
|
||||
error = true;
|
||||
}
|
||||
bbuf = DEFAULT_HTTP_STATE;
|
||||
if (prefs.putChar(HTTP_ENABLE_ENTRY, bbuf) ==0 ) {
|
||||
if (prefs.putChar(HTTP_ENABLE_ENTRY, bbuf) == 0)
|
||||
error = true;
|
||||
}
|
||||
bbuf = DEFAULT_TELNET_STATE;
|
||||
if (prefs.putChar(TELNET_ENABLE_ENTRY, bbuf) ==0 ) {
|
||||
if (prefs.putChar(TELNET_ENABLE_ENTRY, bbuf) == 0)
|
||||
error = true;
|
||||
}
|
||||
bbuf = DEFAULT_RADIO_MODE;
|
||||
if (prefs.putChar(ESP_RADIO_MODE, bbuf) ==0 ) {
|
||||
if (prefs.putChar(ESP_RADIO_MODE, bbuf) == 0)
|
||||
error = true;
|
||||
}
|
||||
ibuf = DEFAULT_WEBSERVER_PORT;
|
||||
if (prefs.putUShort(HTTP_PORT_ENTRY, ibuf) == 0) {
|
||||
if (prefs.putUShort(HTTP_PORT_ENTRY, ibuf) == 0)
|
||||
error = true;
|
||||
}
|
||||
ibuf = DEFAULT_TELNETSERVER_PORT;
|
||||
if (prefs.putUShort(TELNET_PORT_ENTRY, ibuf) == 0) {
|
||||
if (prefs.putUShort(TELNET_PORT_ENTRY, ibuf) == 0)
|
||||
error = true;
|
||||
}
|
||||
sval = DEFAULT_STA_IP;
|
||||
if (prefs.putInt(STA_IP_ENTRY, wifi_config.IP_int_from_string(sval)) == 0) {
|
||||
if (prefs.putInt(STA_IP_ENTRY, wifi_config.IP_int_from_string(sval)) == 0)
|
||||
error = true;
|
||||
}
|
||||
sval = DEFAULT_STA_GW;
|
||||
if (prefs.putInt(STA_GW_ENTRY, wifi_config.IP_int_from_string(sval)) == 0) {
|
||||
if (prefs.putInt(STA_GW_ENTRY, wifi_config.IP_int_from_string(sval)) == 0)
|
||||
error = true;
|
||||
}
|
||||
sval = DEFAULT_STA_MK;
|
||||
if (prefs.putInt(STA_MK_ENTRY, wifi_config.IP_int_from_string(sval)) == 0) {
|
||||
if (prefs.putInt(STA_MK_ENTRY, wifi_config.IP_int_from_string(sval)) == 0)
|
||||
error = true;
|
||||
}
|
||||
sval = DEFAULT_AP_IP;
|
||||
if (prefs.putInt(AP_IP_ENTRY, wifi_config.IP_int_from_string(sval)) == 0) {
|
||||
if (prefs.putInt(AP_IP_ENTRY, wifi_config.IP_int_from_string(sval)) == 0)
|
||||
error = true;
|
||||
}
|
||||
prefs.end();
|
||||
if (error) {
|
||||
grbl_send(CLIENT_ALL,"[MSG:WiFi reset error]\r\n");
|
||||
} else {
|
||||
grbl_send(CLIENT_ALL,"[MSG:WiFi reset done]\r\n");
|
||||
}
|
||||
if (error)
|
||||
grbl_send(CLIENT_ALL, "[MSG:WiFi reset error]\r\n");
|
||||
else
|
||||
grbl_send(CLIENT_ALL, "[MSG:WiFi reset done]\r\n");
|
||||
}
|
||||
bool WiFiConfig::Is_WiFi_on(){
|
||||
bool WiFiConfig::Is_WiFi_on() {
|
||||
return !(WiFi.getMode() == WIFI_MODE_NULL);
|
||||
}
|
||||
|
||||
/**
|
||||
* Handle not critical actions that must be done in sync environement
|
||||
*/
|
||||
void WiFiConfig::handle() {
|
||||
void WiFiConfig::handle() {
|
||||
//Services
|
||||
COMMANDS::wait(0);
|
||||
wifi_services.handle();
|
||||
|
@ -47,18 +47,18 @@
|
||||
#define DHCP_MODE 0
|
||||
#define STATIC_MODE 1
|
||||
|
||||
//Switch
|
||||
//Switch
|
||||
#define ESP_SAVE_ONLY 0
|
||||
#define ESP_APPLY_NOW 1
|
||||
|
||||
//defaults values
|
||||
#define DEFAULT_HOSTNAME "grblesp"
|
||||
#ifdef CONNECT_TO_SSID
|
||||
#define DEFAULT_STA_SSID CONNECT_TO_SSID
|
||||
#define DEFAULT_STA_PWD SSID_PASSWORD
|
||||
#define DEFAULT_STA_SSID CONNECT_TO_SSID
|
||||
#define DEFAULT_STA_PWD SSID_PASSWORD
|
||||
#else //!CONNECT_TO_SSID
|
||||
#define DEFAULT_STA_SSID "GRBL_ESP"
|
||||
#define DEFAULT_STA_PWD "12345678"
|
||||
#define DEFAULT_STA_SSID "GRBL_ESP"
|
||||
#define DEFAULT_STA_PWD "12345678"
|
||||
#endif //CONNECT_TO_SSID
|
||||
#define DEFAULT_STA_IP "0.0.0.0"
|
||||
#define DEFAULT_STA_GW "0.0.0.0"
|
||||
@ -101,28 +101,28 @@
|
||||
#include "WiFi.h"
|
||||
|
||||
class WiFiConfig {
|
||||
public:
|
||||
public:
|
||||
WiFiConfig();
|
||||
~WiFiConfig();
|
||||
static const char *info();
|
||||
static bool isValidIP(const char * string);
|
||||
static bool isPasswordValid (const char * password);
|
||||
static bool isSSIDValid (const char * ssid);
|
||||
static bool isHostnameValid (const char * hostname);
|
||||
static uint32_t IP_int_from_string(String & s);
|
||||
static const char* info();
|
||||
static bool isValidIP(const char* string);
|
||||
static bool isPasswordValid(const char* password);
|
||||
static bool isSSIDValid(const char* ssid);
|
||||
static bool isHostnameValid(const char* hostname);
|
||||
static uint32_t IP_int_from_string(String& s);
|
||||
static String IP_string_from_int(uint32_t ip_int);
|
||||
static String Hostname(){return _hostname;}
|
||||
static char * mac2str (uint8_t mac [8]);
|
||||
static String Hostname() {return _hostname;}
|
||||
static char* mac2str(uint8_t mac [8]);
|
||||
static bool StartAP();
|
||||
static bool StartSTA();
|
||||
static void StopWiFi();
|
||||
static int32_t getSignal (int32_t RSSI);
|
||||
static int32_t getSignal(int32_t RSSI);
|
||||
static void begin();
|
||||
static void end();
|
||||
static void handle();
|
||||
static void reset_settings();
|
||||
static bool Is_WiFi_on();
|
||||
private :
|
||||
private :
|
||||
static bool ConnectSTA2AP();
|
||||
static void WiFiEvent(WiFiEvent_t event);
|
||||
static String _hostname;
|
||||
|
@ -32,34 +32,34 @@
|
||||
#include "wificonfig.h"
|
||||
#include "wifiservices.h"
|
||||
#ifdef ENABLE_MDNS
|
||||
#include <ESPmDNS.h>
|
||||
#include <ESPmDNS.h>
|
||||
#endif
|
||||
#ifdef ENABLE_OTA
|
||||
#include <ArduinoOTA.h>
|
||||
#include <ArduinoOTA.h>
|
||||
#endif
|
||||
#ifdef ENABLE_HTTP
|
||||
#include "web_server.h"
|
||||
#include "web_server.h"
|
||||
#endif
|
||||
#ifdef ENABLE_TELNET
|
||||
#include "telnet_server.h"
|
||||
#include "telnet_server.h"
|
||||
#endif
|
||||
#ifdef ENABLE_NOTIFICATIONS
|
||||
#include "notifications_service.h"
|
||||
#include "notifications_service.h"
|
||||
#endif
|
||||
#include "commands.h"
|
||||
|
||||
WiFiServices wifi_services;
|
||||
|
||||
WiFiServices::WiFiServices(){
|
||||
WiFiServices::WiFiServices() {
|
||||
}
|
||||
WiFiServices::~WiFiServices(){
|
||||
WiFiServices::~WiFiServices() {
|
||||
end();
|
||||
}
|
||||
|
||||
bool WiFiServices::begin(){
|
||||
bool WiFiServices::begin() {
|
||||
bool no_error = true;
|
||||
//Sanity check
|
||||
if(WiFi.getMode() == WIFI_OFF) return false;
|
||||
if (WiFi.getMode() == WIFI_OFF) return false;
|
||||
String h;
|
||||
Preferences prefs;
|
||||
//Get hostname
|
||||
@ -69,47 +69,44 @@ bool WiFiServices::begin(){
|
||||
prefs.end();
|
||||
//Start SPIFFS
|
||||
SPIFFS.begin(true);
|
||||
|
||||
#ifdef ENABLE_OTA
|
||||
ArduinoOTA
|
||||
.onStart([]() {
|
||||
String type;
|
||||
if (ArduinoOTA.getCommand() == U_FLASH)
|
||||
type = "sketch";
|
||||
else {// U_SPIFFS
|
||||
// NOTE: if updating SPIFFS this would be the place to unmount SPIFFS using SPIFFS.end()
|
||||
type = "filesystem";
|
||||
SPIFFS.end();
|
||||
String type;
|
||||
if (ArduinoOTA.getCommand() == U_FLASH)
|
||||
type = "sketch";
|
||||
else {// U_SPIFFS
|
||||
// NOTE: if updating SPIFFS this would be the place to unmount SPIFFS using SPIFFS.end()
|
||||
type = "filesystem";
|
||||
SPIFFS.end();
|
||||
}
|
||||
grbl_sendf(CLIENT_ALL,"[MSG:Start OTA updating %s]\r\n", type.c_str());
|
||||
grbl_sendf(CLIENT_ALL, "[MSG:Start OTA updating %s]\r\n", type.c_str());
|
||||
})
|
||||
.onEnd([]() {
|
||||
grbl_sendf(CLIENT_ALL,"[MSG:End OTA]\r\n");
|
||||
|
||||
grbl_sendf(CLIENT_ALL, "[MSG:End OTA]\r\n");
|
||||
})
|
||||
.onProgress([](unsigned int progress, unsigned int total) {
|
||||
grbl_sendf(CLIENT_ALL,"[MSG:OTA Progress: %u%%]\r\n", (progress / (total / 100)));
|
||||
grbl_sendf(CLIENT_ALL, "[MSG:OTA Progress: %u%%]\r\n", (progress / (total / 100)));
|
||||
})
|
||||
.onError([](ota_error_t error) {
|
||||
grbl_sendf(CLIENT_ALL,"[MSG:OTA Error(%u):]\r\n", error);
|
||||
if (error == OTA_AUTH_ERROR) grbl_send(CLIENT_ALL,"[MSG:Auth Failed]\r\n");
|
||||
else if (error == OTA_BEGIN_ERROR) grbl_send(CLIENT_ALL,"[MSG:Begin Failed]\r\n");
|
||||
else if (error == OTA_CONNECT_ERROR) grbl_send(CLIENT_ALL,"[MSG:Connect Failed]\r\n");
|
||||
else if (error == OTA_RECEIVE_ERROR) grbl_send(CLIENT_ALL,"[MSG:Receive Failed]\r\n");
|
||||
else if (error == OTA_END_ERROR) grbl_send(CLIENT_ALL,"[MSG:End Failed]\r\n");
|
||||
grbl_sendf(CLIENT_ALL, "[MSG:OTA Error(%u):]\r\n", error);
|
||||
if (error == OTA_AUTH_ERROR) grbl_send(CLIENT_ALL, "[MSG:Auth Failed]\r\n");
|
||||
else if (error == OTA_BEGIN_ERROR) grbl_send(CLIENT_ALL, "[MSG:Begin Failed]\r\n");
|
||||
else if (error == OTA_CONNECT_ERROR) grbl_send(CLIENT_ALL, "[MSG:Connect Failed]\r\n");
|
||||
else if (error == OTA_RECEIVE_ERROR) grbl_send(CLIENT_ALL, "[MSG:Receive Failed]\r\n");
|
||||
else if (error == OTA_END_ERROR) grbl_send(CLIENT_ALL, "[MSG:End Failed]\r\n");
|
||||
});
|
||||
ArduinoOTA.begin();
|
||||
ArduinoOTA.begin();
|
||||
#endif
|
||||
#ifdef ENABLE_MDNS
|
||||
//no need in AP mode
|
||||
if(WiFi.getMode() == WIFI_STA){
|
||||
//no need in AP mode
|
||||
if (WiFi.getMode() == WIFI_STA) {
|
||||
//start mDns
|
||||
if (!MDNS.begin(h.c_str())) {
|
||||
grbl_send(CLIENT_ALL,"[MSG:Cannot start mDNS]\r\n");
|
||||
grbl_send(CLIENT_ALL, "[MSG:Cannot start mDNS]\r\n");
|
||||
no_error = false;
|
||||
} else {
|
||||
grbl_sendf(CLIENT_ALL,"[MSG:Start mDNS with hostname:http://%s.local/]\r\n",h.c_str());
|
||||
}
|
||||
} else
|
||||
grbl_sendf(CLIENT_ALL, "[MSG:Start mDNS with hostname:http://%s.local/]\r\n", h.c_str());
|
||||
}
|
||||
#endif
|
||||
#ifdef ENABLE_HTTP
|
||||
@ -119,20 +116,19 @@ bool WiFiServices::begin(){
|
||||
telnet_server.begin();
|
||||
#endif
|
||||
#ifdef ENABLE_NOTIFICATIONS
|
||||
notificationsservice.begin();
|
||||
notificationsservice.begin();
|
||||
#endif
|
||||
//be sure we are not is mixed mode in setup
|
||||
WiFi.scanNetworks (true);
|
||||
WiFi.scanNetworks(true);
|
||||
return no_error;
|
||||
}
|
||||
void WiFiServices::end(){
|
||||
void WiFiServices::end() {
|
||||
#ifdef ENABLE_NOTIFICATIONS
|
||||
notificationsservice.end();
|
||||
notificationsservice.end();
|
||||
#endif
|
||||
#ifdef ENABLE_TELNET
|
||||
telnet_server.end();
|
||||
#endif
|
||||
|
||||
#ifdef ENABLE_HTTP
|
||||
web_server.end();
|
||||
#endif
|
||||
@ -142,20 +138,18 @@ void WiFiServices::end(){
|
||||
#endif
|
||||
//Stop SPIFFS
|
||||
SPIFFS.end();
|
||||
|
||||
#ifdef ENABLE_MDNS
|
||||
//Stop mDNS
|
||||
MDNS.end();
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
void WiFiServices::handle(){
|
||||
void WiFiServices::handle() {
|
||||
COMMANDS::wait(0);
|
||||
//to avoid mixed mode due to scan network
|
||||
if (WiFi.getMode() == WIFI_AP_STA) {
|
||||
if (WiFi.scanComplete() != WIFI_SCAN_RUNNING) {
|
||||
WiFi.enableSTA (false);
|
||||
}
|
||||
if (WiFi.scanComplete() != WIFI_SCAN_RUNNING)
|
||||
WiFi.enableSTA(false);
|
||||
}
|
||||
#ifdef ENABLE_OTA
|
||||
ArduinoOTA.handle();
|
||||
|
@ -25,7 +25,7 @@
|
||||
|
||||
|
||||
class WiFiServices {
|
||||
public:
|
||||
public:
|
||||
WiFiServices();
|
||||
~WiFiServices();
|
||||
static bool begin();
|
||||
|
32
build-all.ps1
Normal file
32
build-all.ps1
Normal file
@ -0,0 +1,32 @@
|
||||
# This Windows PowerShell script uses PlatformIO to compile Grbl_ESP32
|
||||
# for every machine configuration in the Machines/ directory.
|
||||
# It is useful for automated testing.
|
||||
|
||||
# Setting PYTHONIOENCODING avoids an obscure crash related to code page mismatch
|
||||
$env:PYTHONIOENCODING="utf-8"
|
||||
|
||||
Function BuildMachine($names) {
|
||||
$basename = $names[0]
|
||||
$addname = $names[1]
|
||||
$env:PLATFORMIO_BUILD_FLAGS = "-DMACHINE_FILENAME=$basename"
|
||||
$displayname = $basename
|
||||
if ($addname -ne "") {
|
||||
$env:PLATFORMIO_BUILD_FLAGS += " -DMACHINE_FILENAME2=$addname"
|
||||
$displayname += " + $addname"
|
||||
}
|
||||
Write-Output "Building machine $displayname"
|
||||
platformio run 2>&1 | Select-String error,Took
|
||||
Write-Output " "
|
||||
}
|
||||
|
||||
# First build all the base configurations with names that do not start with add_
|
||||
foreach ($filepath in Get-ChildItem -file .\Grbl_Esp32\Machines\* -Exclude add_*) {
|
||||
BuildMachine($filepath.name, "")
|
||||
}
|
||||
|
||||
# Then build all of the add-ons on top of a single base
|
||||
$base="3axis_v4.h"
|
||||
foreach ($filepath in Get-ChildItem -file .\Grbl_Esp32\Machines\add_*) {
|
||||
BuildMachine($base, $filepath.name)
|
||||
}
|
||||
Remove-Item env:PLATFORMIO_BUILD_FLAGS
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user