1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-08-31 10:01:48 +02:00

Merge pull request #131 from bdring/Devt

updates from devt branch
This commit is contained in:
bdring
2019-04-28 14:07:23 -05:00
committed by GitHub
8 changed files with 1061 additions and 825 deletions

View File

@@ -49,6 +49,7 @@ Some features should not be changed. See notes below.
#define CPU_MAP_ESP32 // these are defined in cpu_map.h
#define VERBOSE_HELP // adds addition help info, but could confuse some senders
// Serial baud rate
#define BAUD_RATE 115200
@@ -501,6 +502,15 @@ Some features should not be changed. See notes below.
// time step. Also, keep in mind that the Arduino delay timer is not very accurate for long delays.
#define DWELL_TIME_STEP 50 // Integer (1-255) (milliseconds)
// For test use only. This uses the ESP32's RMT perifieral to generate step pulses
// It allows the use of the STEP_PULSE_DELAY (see below) and it automatically ends the
// pulse in one operation.
// Dir Pin ____|--------------------
// Step Pin _______|--|____________
// While this is experimental, it is intended to be the future default method after testing
//#define USE_RMT_STEPS
// Creates a delay between the direction pin setting and corresponding step pulse by creating
// another interrupt (Timer2 compare) to manage it. The main Grbl interrupt (Timer1 compare)
// sets the direction pins, and does not immediately set the stepper pins, as it would in
@@ -510,8 +520,8 @@ Some features should not be changed. See notes below.
// NOTE: Uncomment to enable. The recommended delay must be > 3us, and, when added with the
// user-supplied step pulse time, the total time must not exceed 127us. Reported successful
// values for certain setups have ranged from 5 to 20us.
// !!!!! ESP32 Not currently implemented
// #define STEP_PULSE_DELAY 10 // Step pulse delay in microseconds. Default disabled.
// must use #define USE_RMT_STEPS for this to work
//#define STEP_PULSE_DELAY 10 // Step pulse delay in microseconds. Default disabled.
// The number of linear motions in the planner buffer to be planned at any give time. The vast
// majority of RAM that Grbl uses is based on this buffer size. Only increase if there is extra
@@ -551,14 +561,11 @@ 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 interrupt
// monitoring the hard limit switch pins will enable the Arduino's watchdog timer to re-check
// the limit pin state after a delay of about 32msec. This can help with CNC machines with
// problematic false triggering of their hard limit switches, but it WILL NOT fix issues with
// electrical interference on the signal cables from external sources. It's recommended to first
// use shielded signal cables with their shielding connected to ground (old USB/computer cables
// work well and are cheap to find) and wire in a low-pass circuit into each limit pin.
// #define ENABLE_SOFTWARE_DEBOUNCE // Default disabled. Uncomment to enable.
// 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
// Configures the position after a probing cycle during Grbl's check mode. Disabled sets
// the position to the probe target, when enabled sets the position to the start position.

View File

@@ -35,7 +35,9 @@
with AVR grbl
*/
#ifdef CPU_MAP_ESP32
// This is the CPU Map for the ESP32 CNC Controller R2
@@ -43,13 +45,17 @@
// won't affect operation except that there will be no output
// form the pins. Grbl will virtually move the axis. This could
// be handy if you are using a servo, etc. for another axis.
#define X_STEP_PIN GPIO_NUM_12
#define Y_STEP_PIN GPIO_NUM_14
#define Z_STEP_PIN GPIO_NUM_27
#define X_STEP_PIN GPIO_NUM_12
#define X_DIRECTION_PIN GPIO_NUM_26
#define X_RMT_CHANNEL 0
#define X_DIRECTION_PIN GPIO_NUM_26
#define Y_DIRECTION_PIN GPIO_NUM_25
#define Z_DIRECTION_PIN GPIO_NUM_33
#define Y_STEP_PIN GPIO_NUM_14
#define Y_DIRECTION_PIN GPIO_NUM_25
#define Y_RMT_CHANNEL 1
#define Z_STEP_PIN GPIO_NUM_27
#define Z_DIRECTION_PIN GPIO_NUM_33
#define Z_RMT_CHANNEL 2
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
@@ -851,4 +857,3 @@
#endif

Binary file not shown.

View File

@@ -27,7 +27,7 @@
#include "grbl.h"
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
@@ -39,25 +39,32 @@
void IRAM_ATTR isr_limit_switches()
{
// Ignore limit switches if already in an alarm state or in-process of executing an alarm.
// 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 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
}
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
}
}
}
@@ -300,15 +307,17 @@ void limits_init()
limits_disable();
}
// TODO Debounce
/*
#ifdef ENABLE_SOFTWARE_DEBOUNCE
MCUSR &= ~(1<<WDRF);
WDTCSR |= (1<<WDCE) | (1<<WDE);
WDTCSR = (1<<WDP0); // Set time-out at ~32msec.
#endif
*/
// setup task used for debouncing
limit_sw_queue = xQueueCreate(10, sizeof( int ));
xTaskCreate(limitCheckTask,
"limitCheckTask",
2048,
NULL,
5, // priority
NULL);
}
@@ -326,63 +335,57 @@ void limits_disable()
// 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;
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 INVERT_LIMIT_PIN_MASK // not normally used..unless you have both normal and inverted switches
pin ^= INVERT_LIMIT_PIN_MASK;
#endif
pin ^= INVERT_LIMIT_PIN_MASK;
#endif
if (bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS))
{
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);
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 );
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
@@ -390,6 +393,21 @@ void limits_soft_check(float *target)
}
}
// 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
if (limits_get_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

View File

@@ -32,8 +32,6 @@
#define SQUARING_MODE_A 1 // A motor runs
#define SQUARING_MODE_B 2 // B motor runs
// Initialize the limits module
void limits_init();
@@ -53,4 +51,7 @@ 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);
#endif

File diff suppressed because it is too large Load Diff

View File

@@ -82,6 +82,8 @@ extern uint8_t ganged_mode;
void IRAM_ATTR onSteppertimer();
void IRAM_ATTR onStepperOffTimer();
void stepper_init();
void initRMT();
inline IRAM_ATTR static void stepperRMT_Outputs();
// Enable steppers, but cycle does not start unless called by motion control or realtime command.
void st_wake_up();

View File

@@ -522,6 +522,10 @@ void Web_Server::handle_web_command ()
uint8_t sindex = 0;
scmd = get_Splited_Value(cmd,'\n', sindex);
while ( scmd != "" ){
if ((scmd.length() == 2) && (scmd[0] == 0xC2)){
scmd[0]=scmd[1];
scmd.remove(1,1);
}
if (scmd.length() > 1)scmd += "\n";
else if (!is_realtime_cmd(scmd[0]) )scmd += "\n";
if (!Serial2Socket.push(scmd.c_str()))res = "Error";