Code refactoring; Changed input handling;

Signed-off-by: Patrick Felixberger <robomaniac8@googlemail.com>
software
Patrick Felixberger 2024-03-18 23:56:56 +01:00
rodzic 43accf772e
commit 7d4ad4c054
24 zmienionych plików z 488 dodań i 356 usunięć

Wyświetl plik

@ -150,7 +150,7 @@ void Spi_Init(SPI_TypeDef *SPIx, SPI_Mode mode)
// Deselect chip
GPIO_SetBits(SPI3_CS_GPIO_PORT, SPI3_CS_PIN);
}
}
SPI_CalculateCRC(SPIx, DISABLE);

Wyświetl plik

@ -53,8 +53,6 @@
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
volatile uint8_t DebounceCounterControl = 0;
volatile uint8_t DebounceCounterLimits = 0;
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
@ -87,39 +85,43 @@ void ProcessReceive(char c)
// not passed into the main buffer, but these set system state flag bits for realtime execution.
switch(c)
{
case CMD_RESET: MC_Reset(); break; // Call motion control reset routine.
case CMD_RESET_HARD: NVIC_SystemReset(); // Perform hard reset
case CMD_STATUS_REPORT: System_SetExecStateFlag(EXEC_STATUS_REPORT);break;
case CMD_CYCLE_START: System_SetExecStateFlag(EXEC_CYCLE_START); break; // Set as true
case CMD_FEED_HOLD: System_SetExecStateFlag(EXEC_FEED_HOLD); break; // Set as true
case CMD_STEPPER_DISABLE: Stepper_Disable(1); break; // Set as true
case CMD_RESET: MC_Reset(); break; // Call motion control reset routine.
case CMD_RESET_HARD: NVIC_SystemReset(); // Perform hard reset
case CMD_STATUS_REPORT: System_SetExecStateFlag(EXEC_STATUS_REPORT);break;
case CMD_CYCLE_START: System_SetExecStateFlag(EXEC_CYCLE_START); break; // Set as true
case CMD_FEED_HOLD: System_SetExecStateFlag(EXEC_FEED_HOLD); break; // Set as true
case CMD_STEPPER_DISABLE: Stepper_Disable(1); break; // Set as true
default:
if(c > 0x7F) { // Real-time control characters are extended ACSII only.
if(c > 0x7F)
{
// Real-time control characters are extended ACSII only.
switch(c)
{
case CMD_SAFETY_DOOR: System_SetExecStateFlag(EXEC_SAFETY_DOOR); break; // Set as true
case CMD_JOG_CANCEL:
if(sys.state & STATE_JOG) { // Block all other states from invoking motion cancel.
if(sys.state & STATE_JOG)
{
// Block all other states from invoking motion cancel.
System_SetExecStateFlag(EXEC_MOTION_CANCEL);
}
break;
case CMD_FEED_OVR_RESET: System_SetExecMotionOverrideFlag(EXEC_FEED_OVR_RESET); break;
case CMD_FEED_OVR_COARSE_PLUS: System_SetExecMotionOverrideFlag(EXEC_FEED_OVR_COARSE_PLUS); break;
case CMD_FEED_OVR_COARSE_MINUS: System_SetExecMotionOverrideFlag(EXEC_FEED_OVR_COARSE_MINUS); break;
case CMD_FEED_OVR_FINE_PLUS: System_SetExecMotionOverrideFlag(EXEC_FEED_OVR_FINE_PLUS); break;
case CMD_FEED_OVR_FINE_MINUS: System_SetExecMotionOverrideFlag(EXEC_FEED_OVR_FINE_MINUS); break;
case CMD_RAPID_OVR_RESET: System_SetExecMotionOverrideFlag(EXEC_RAPID_OVR_RESET); break;
case CMD_RAPID_OVR_MEDIUM: System_SetExecMotionOverrideFlag(EXEC_RAPID_OVR_MEDIUM); break;
case CMD_RAPID_OVR_LOW: System_SetExecMotionOverrideFlag(EXEC_RAPID_OVR_LOW); break;
case CMD_SPINDLE_OVR_RESET: System_SetExecAccessoryOverrideFlag(EXEC_SPINDLE_OVR_RESET); break;
case CMD_SPINDLE_OVR_COARSE_PLUS: System_SetExecAccessoryOverrideFlag(EXEC_SPINDLE_OVR_COARSE_PLUS); break;
case CMD_SPINDLE_OVR_COARSE_MINUS: System_SetExecAccessoryOverrideFlag(EXEC_SPINDLE_OVR_COARSE_MINUS); break;
case CMD_SPINDLE_OVR_FINE_PLUS: System_SetExecAccessoryOverrideFlag(EXEC_SPINDLE_OVR_FINE_PLUS); break;
case CMD_SPINDLE_OVR_FINE_MINUS: System_SetExecAccessoryOverrideFlag(EXEC_SPINDLE_OVR_FINE_MINUS); break;
case CMD_SPINDLE_OVR_STOP: System_SetExecAccessoryOverrideFlag(EXEC_SPINDLE_OVR_STOP); break;
case CMD_COOLANT_FLOOD_OVR_TOGGLE: System_SetExecAccessoryOverrideFlag(EXEC_COOLANT_FLOOD_OVR_TOGGLE); break;
case CMD_FEED_OVR_RESET: System_SetExecMotionOverrideFlag(EXEC_FEED_OVR_RESET); break;
case CMD_FEED_OVR_COARSE_PLUS: System_SetExecMotionOverrideFlag(EXEC_FEED_OVR_COARSE_PLUS); break;
case CMD_FEED_OVR_COARSE_MINUS: System_SetExecMotionOverrideFlag(EXEC_FEED_OVR_COARSE_MINUS); break;
case CMD_FEED_OVR_FINE_PLUS: System_SetExecMotionOverrideFlag(EXEC_FEED_OVR_FINE_PLUS); break;
case CMD_FEED_OVR_FINE_MINUS: System_SetExecMotionOverrideFlag(EXEC_FEED_OVR_FINE_MINUS); break;
case CMD_RAPID_OVR_RESET: System_SetExecMotionOverrideFlag(EXEC_RAPID_OVR_RESET); break;
case CMD_RAPID_OVR_MEDIUM: System_SetExecMotionOverrideFlag(EXEC_RAPID_OVR_MEDIUM); break;
case CMD_RAPID_OVR_LOW: System_SetExecMotionOverrideFlag(EXEC_RAPID_OVR_LOW); break;
case CMD_SPINDLE_OVR_RESET: System_SetExecAccessoryOverrideFlag(EXEC_SPINDLE_OVR_RESET); break;
case CMD_SPINDLE_OVR_COARSE_PLUS: System_SetExecAccessoryOverrideFlag(EXEC_SPINDLE_OVR_COARSE_PLUS); break;
case CMD_SPINDLE_OVR_COARSE_MINUS: System_SetExecAccessoryOverrideFlag(EXEC_SPINDLE_OVR_COARSE_MINUS); break;
case CMD_SPINDLE_OVR_FINE_PLUS: System_SetExecAccessoryOverrideFlag(EXEC_SPINDLE_OVR_FINE_PLUS); break;
case CMD_SPINDLE_OVR_FINE_MINUS: System_SetExecAccessoryOverrideFlag(EXEC_SPINDLE_OVR_FINE_MINUS); break;
case CMD_SPINDLE_OVR_STOP: System_SetExecAccessoryOverrideFlag(EXEC_SPINDLE_OVR_STOP); break;
case CMD_COOLANT_FLOOD_OVR_TOGGLE: System_SetExecAccessoryOverrideFlag(EXEC_COOLANT_FLOOD_OVR_TOGGLE); break;
case CMD_COOLANT_MIST_OVR_TOGGLE:
if (BIT_IS_TRUE(settings.flags_ext, BITFLAG_ENABLE_M7))
{
@ -129,7 +131,8 @@ void ProcessReceive(char c)
}
// Throw away any unfound extended-ASCII character by not passing it to the serial buffer.
}
else {
else
{
// Write character to buffer
FifoUsart_Insert(USART2_NUM, USART_DIR_RX, c);
}
@ -245,48 +248,29 @@ void SysTick_Handler(void)
* Therefore we just poll them in this 1ms task, which is hopefully fast
* enough for critical events. Debouncing pins is also implemented here.
*/
uint8_t limits = Limits_GetState();
if(limits)
uint8_t limits = Limits_GetState(false);
if (limits && (sys.system_flags & BITFLAG_ENABLE_LIMITS))
{
// X-Y-Z Limit
if((DebounceCounterLimits == 0) && (settings.system_flags & BITFLAG_ENABLE_LIMITS))
{
DebounceCounterLimits = 20;
Limit_PinChangeISR();
}
}
// X-Y-Z Limit
Limit_PinChangeISR();
}
uint8_t controls = System_GetControlState();
if(controls)
uint8_t controls = System_GetControlState(false);
if (controls && (sys.system_flags & BITFLAG_ENABLE_SYSTEM_INPUT))
{
// System control
if(DebounceCounterControl == 0)
{
DebounceCounterControl = 20;
System_PinChangeISR();
}
}
System_PinChangeISR();
}
if(DebounceCounterLimits && !limits)
{
DebounceCounterLimits--;
}
if(DebounceCounterControl && !controls)
{
DebounceCounterControl--;
}
gMillis++;
gMillis++;
if(gMillis%16 == 0)
{
// Update sync motion
MC_UpdateSyncMove();
// Update sync motion
MC_UpdateSyncMove();
}
if(gMillis%32 == 0)
if(gMillis%32 == 0)
{
// 25ms Task (min 7 RPM)
uint16_t cnt = (uint16_t)Encoder_GetValue();
uint32_t cnt_diff = 0;
@ -302,11 +286,14 @@ void SysTick_Handler(void)
}
// Calculate RPM and smooth it
float rpm = ((cnt_diff * 31.25) / settings.enc_ppr) * 60.0;
rpm_arr[rpm_idx++] = (uint32_t)rpm;
if(rpm_idx > (RPM_FILTER_NUM-1))
if (settings.enc_ppr > 0)
{
rpm_idx = 0;
float rpm = ((cnt_diff * 31.25) / settings.enc_ppr) * 60.0;
rpm_arr[rpm_idx++] = (uint32_t)rpm;
if (rpm_idx > (RPM_FILTER_NUM - 1))
{
rpm_idx = 0;
}
}
// Assign smoothed RPM
@ -369,10 +356,10 @@ void TIM4_IRQHandler(void)
Encoder_OvfISR();
// Spindle at zero position
if(sys.sync_move && sys.state == STATE_HOLD)
/*if(sys.sync_move && sys.state == STATE_HOLD)
{
MC_LineSyncStart();
}
}*/
}
}
@ -394,7 +381,8 @@ void EXTI9_5_IRQHandler(void)
*/
void USART1_IRQHandler(void)
{
if(USART_GetITStatus(USART1, USART_IT_RXNE) != RESET) {
if(USART_GetITStatus(USART1, USART_IT_RXNE) != RESET)
{
/* Read one byte from the receive data register */
unsigned char c = (USART_ReceiveData(USART1) & 0xFF);
@ -402,22 +390,26 @@ void USART1_IRQHandler(void)
FifoUsart_Insert(USART1_NUM, USART_DIR_RX, c);
}
if(USART_GetITStatus(USART1, USART_IT_TXE) != RESET) {
if(USART_GetITStatus(USART1, USART_IT_TXE) != RESET)
{
char c;
if(FifoUsart_Get(USART1_NUM, USART_DIR_TX, &c) == 0) {
if(FifoUsart_Get(USART1_NUM, USART_DIR_TX, &c) == 0)
{
/* Write one byte to the transmit data register */
while(USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET);
USART_SendData(USART1, c);
}
else {
else
{
// Nothing to transmit - disable interrupt
USART_ITConfig(USART1, USART_IT_TXE, DISABLE);
}
}
/* If overrun condition occurs, clear the ORE flag and recover communication */
if(USART_GetFlagStatus(USART1, USART_FLAG_ORE) != RESET) {
if(USART_GetFlagStatus(USART1, USART_FLAG_ORE) != RESET)
{
(void)USART_ReceiveData(USART1);
}
}
@ -430,29 +422,34 @@ void USART1_IRQHandler(void)
*/
void USART2_IRQHandler(void)
{
if(USART_GetITStatus(USART2, USART_IT_RXNE) != RESET) {
if(USART_GetITStatus(USART2, USART_IT_RXNE) != RESET)
{
/* Read one byte from the receive data register */
unsigned char c = (USART_ReceiveData(USART2) & 0xFF);
ProcessReceive(c);
}
if(USART_GetITStatus(USART2, USART_IT_TXE) != RESET) {
if(USART_GetITStatus(USART2, USART_IT_TXE) != RESET)
{
char c;
if(FifoUsart_Get(USART2_NUM, USART_DIR_TX, &c) == 0) {
if(FifoUsart_Get(USART2_NUM, USART_DIR_TX, &c) == 0)
{
/* Write one byte to the transmit data register */
while(USART_GetFlagStatus(USART2, USART_FLAG_TC) == RESET);
USART_SendData(USART2, c);
}
else {
else
{
// Nothing to transmit - disable interrupt
USART_ITConfig(USART2, USART_IT_TXE, DISABLE);
}
}
/* If overrun condition occurs, clear the ORE flag and recover communication */
if(USART_GetFlagStatus(USART2, USART_FLAG_ORE) != RESET) {
if(USART_GetFlagStatus(USART2, USART_FLAG_ORE) != RESET)
{
(void)USART_ReceiveData(USART2);
}
}
@ -465,7 +462,8 @@ void USART2_IRQHandler(void)
*/
void USART6_IRQHandler(void)
{
if(USART_GetITStatus(USART6, USART_IT_RXNE) != RESET) {
if(USART_GetITStatus(USART6, USART_IT_RXNE) != RESET)
{
/* Read one byte from the receive data register */
unsigned char c = (USART_ReceiveData(USART6) & 0xFF);
@ -473,22 +471,26 @@ void USART6_IRQHandler(void)
FifoUsart_Insert(USART6_NUM, USART_DIR_RX, c);
}
if(USART_GetITStatus(USART6, USART_IT_TXE) != RESET) {
if(USART_GetITStatus(USART6, USART_IT_TXE) != RESET)
{
char c;
if(FifoUsart_Get(USART6_NUM, USART_DIR_TX, &c) == 0) {
if(FifoUsart_Get(USART6_NUM, USART_DIR_TX, &c) == 0)
{
/* Write one byte to the transmit data register */
while(USART_GetFlagStatus(USART6, USART_FLAG_TC) == RESET);
USART_SendData(USART6, c);
}
else {
else
{
// Nothing to transmit - disable interrupt
USART_ITConfig(USART6, USART_IT_TXE, DISABLE);
}
}
/* If overrun condition occurs, clear the ORE flag and recover communication */
if(USART_GetFlagStatus(USART6, USART_FLAG_ORE) != RESET) {
if(USART_GetFlagStatus(USART6, USART_FLAG_ORE) != RESET)
{
(void)USART_ReceiveData(USART6);
}
}

Wyświetl plik

@ -26,6 +26,7 @@ static uint32_t OvfCnt = 0;
static uint32_t CntValue = 0;
static uint16_t PulsesPerRev = 360;
static bool isZero = false;
void Encoder_Init(uint16_t ppr)
@ -40,6 +41,7 @@ void Encoder_Reset(void)
{
OvfCnt = 0;
CntValue = 0;
isZero = false;
}
@ -61,8 +63,20 @@ void Encoder_SetValue(uint32_t val)
}
bool Encoder_Zero(void)
{
if(isZero)
{
isZero = false;
return true;
}
return false;
}
void Encoder_OvfISR(void)
{
OvfCnt++;
CntValue += PulsesPerRev;
isZero = true;
}

Wyświetl plik

@ -3,6 +3,7 @@
#include <stdint.h>
#include <stdbool.h>
#ifdef __cplusplus
@ -18,6 +19,8 @@ void Encoder_SetPulsesPerRev(uint16_t ppr);
uint32_t Encoder_GetValue(void);
void Encoder_SetValue(uint32_t val);
bool Encoder_Zero(void);
void Encoder_OvfISR(void);

Wyświetl plik

@ -53,7 +53,7 @@ endif
# options for code generation
#---------------------------------------------------------------------------------
FLAGS := -mfloat-abi=hard -mcpu=cortex-m4 -gdwarf-2 -mfpu=fpv4-sp-d16 -mthumb -Wno-misleading-indentation
CFLAGS := -O2 -g1 -std=c11 -Wall -Wextra $(INCLUDE) -fno-common -fsingle-precision-constant -fdata-sections \
CFLAGS := -O2 -g1 -std=c17 -Wall -Wextra $(INCLUDE) -fno-common -fsingle-precision-constant -fdata-sections \
-ffunction-sections -fomit-frame-pointer -mlittle-endian -DUSE_STDPERIPH_DRIVER -D__FPU_USED -DARM_MATH_CM4 -Wimplicit-fallthrough=0
CXXFLAGS := $(CFLAGS)

Wyświetl plik

@ -72,22 +72,22 @@
// used, if they are available per user setup. Also, extended ASCII codes (>127), which are never in
// g-code programs, maybe selected for interface programs.
// NOTE: If changed, manually update help message in report.c.
#define CMD_STEPPER_DISABLE 0x17
#define CMD_RESET 0x18 // ctrl-x.
#define CMD_RESET_HARD 0x19 // ctrl-y.
#define CMD_STATUS_REPORT '?'
#define CMD_CYCLE_START '~'
#define CMD_FEED_HOLD '!'
#define CMD_STEPPER_DISABLE 0x17
// NOTE: All override realtime commands must be in the extended ASCII character set, starting
// at character value 128 (0x80) and up to 255 (0xFF). If the normal set of realtime commands,
// such as status reports, feed hold, reset, and cycle start, are moved to the extended set
// space, RX ISR will need to be modified to accomodate the change.
// #define CMD_RESET 0x80
// #define CMD_STATUS_REPORT 0x81
// #define CMD_CYCLE_START 0x82
// #define CMD_FEED_HOLD 0x83
// #define CMD_RESET 0x80
// #define CMD_STATUS_REPORT 0x81
// #define CMD_CYCLE_START 0x82
// #define CMD_FEED_HOLD 0x83
#define CMD_SAFETY_DOOR 0x84
#define CMD_JOG_CANCEL 0x85
#define CMD_DEBUG_REPORT 0x86 // Only when DEBUG enabled, sends debug report in '{}' braces.
@ -222,20 +222,6 @@
//#define INVERT_LIMIT_PIN_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)) // Default disabled. Uncomment to enable.
// Inverts the spindle enable pin from low-disabled/high-enabled to low-enabled/high-disabled. Useful
// for some pre-built electronic boards.
// NOTE: If VARIABLE_SPINDLE is enabled(default), this option has no effect as the PWM output and
// spindle enable are combined to one pin. If you need both this option and spindle speed PWM,
// uncomment the config option USE_SPINDLE_DIR_AS_ENABLE_PIN below.
//#define INVERT_SPINDLE_ENABLE_PIN // Default disabled. Uncomment to enable.
// Inverts the selected coolant pin from low-disabled/high-enabled to low-enabled/high-disabled. Useful
// for some pre-built electronic boards.
//#define INVERT_COOLANT_FLOOD_PIN // Default disabled. Uncomment to enable.
//#define INVERT_COOLANT_MIST_PIN // Default disabled. Note: Enable M7 mist coolant in Config.h
// When Grbl powers-cycles or is hard reset with the Arduino reset button, Grbl boots up with no ALARM
// by default. This is to make it as simple as possible for new users to start using Grbl. When homing
// is enabled and a user has installed limit switches, Grbl will boot up in an ALARM state to indicate
@ -512,8 +498,8 @@
// uses the homing pull-off distance setting times the LOCATE_SCALAR to pull-off and re-engage
// the limit switch.
// NOTE: Both of these values must be greater than 1.0 to ensure proper function.
//#define HOMING_AXIS_SEARCH_SCALAR 1.5 // Uncomment to override defaults in limits.c.
//#define HOMING_AXIS_LOCATE_SCALAR 10.0 // Uncomment to override defaults in limits.c.
//#define HOMING_AXIS_SEARCH_SCALAR 1.5 // Uncomment to override defaults in limits.c.
//#define HOMING_AXIS_LOCATE_SCALAR 10.0 // Uncomment to override defaults in limits.c.
// Enable the '$RST=*', '$RST=$', and '$RST=#' eeprom restore commands. There are cases where
@ -580,11 +566,11 @@
// Configure options for the parking motion, if enabled.
#define PARKING_AXIS Z_AXIS // Define which axis that performs the parking motion
#define PARKING_TARGET -10.0 // Parking axis target. In mm, as machine coordinate [-max_travel,0].
#define PARKING_RATE 800.0 // Parking fast rate after pull-out in mm/min.
#define PARKING_PULLOUT_RATE 300.0 // Pull-out/plunge slow feed rate in mm/min.
#define PARKING_PULLOUT_INCREMENT 10.0 // Spindle pull-out and plunge distance in mm. Incremental distance.
#define PARKING_AXIS Z_AXIS // Define which axis that performs the parking motion
#define PARKING_TARGET -10.0 // Parking axis target. In mm, as machine coordinate [-max_travel,0].
#define PARKING_RATE 800.0 // Parking fast rate after pull-out in mm/min.
#define PARKING_PULLOUT_RATE 300.0 // Pull-out/plunge slow feed rate in mm/min.
#define PARKING_PULLOUT_INCREMENT 10.0 // Spindle pull-out and plunge distance in mm. Incremental distance.
// Must be positive value or equal to zero.

Wyświetl plik

@ -3,7 +3,7 @@
Part of Grbl-Advanced
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
Copyright (c) 2017 Patrick F.
Copyright (c) 2017-2024 Patrick F.
Grbl-Advanced is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
@ -38,19 +38,25 @@ void Coolant_Init(void)
// an interrupt-level. No report flag set, but only called by routines that don't need it.
void Coolant_Stop(void)
{
#ifdef INVERT_COOLANT_FLOOD_PIN
GPIO_SetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
#else
GPIO_ResetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
#endif
if (BIT_IS_TRUE(settings.input_invert_mask, BITFLAG_INVERT_FLOOD_PIN))
{
GPIO_SetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
}
else
{
GPIO_ResetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
}
if (BIT_IS_TRUE(settings.flags_ext, BITFLAG_ENABLE_M7))
{
#ifdef INVERT_COOLANT_MIST_PIN
GPIO_SetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
#else
GPIO_ResetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
#endif
if (BIT_IS_TRUE(settings.input_invert_mask, BITFLAG_INVERT_MIST_PIN))
{
GPIO_SetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
}
else
{
GPIO_ResetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
}
}
}
@ -59,26 +65,28 @@ uint8_t Coolant_GetState(void)
{
uint8_t cl_state = COOLANT_STATE_DISABLE;
uint8_t flood_state = GPIO_ReadInputDataBit(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
uint8_t mist_state = GPIO_ReadInputDataBit(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
if (BIT_IS_TRUE(settings.input_invert_mask, BITFLAG_INVERT_FLOOD_PIN))
{
flood_state = !flood_state;
}
if (BIT_IS_TRUE(settings.input_invert_mask, BITFLAG_INVERT_MIST_PIN))
{
mist_state = !mist_state;
}
// TODO: Check if reading works
#ifdef INVERT_COOLANT_FLOOD_PIN
if(!GPIO_ReadInputDataBit(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN))
if (flood_state)
{
#else
if(GPIO_ReadInputDataBit(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN))
{
#endif
cl_state |= COOLANT_STATE_FLOOD;
}
if (BIT_IS_TRUE(settings.flags_ext, BITFLAG_ENABLE_M7))
{
#ifdef INVERT_COOLANT_MIST_PIN
if (!GPIO_ReadInputDataBit(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN))
if (mist_state)
{
#else
if (GPIO_ReadInputDataBit(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN))
{
#endif
cl_state |= COOLANT_STATE_MIST;
}
}
@ -101,38 +109,50 @@ void Coolant_SetState(const uint8_t mode)
if (mode & COOLANT_FLOOD_ENABLE)
{
#ifdef INVERT_COOLANT_FLOOD_PIN
GPIO_ResetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
#else
GPIO_SetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
#endif
if (BIT_IS_TRUE(settings.input_invert_mask, BITFLAG_INVERT_FLOOD_PIN))
{
GPIO_ResetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
}
else
{
GPIO_SetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
}
}
else
{
#ifdef INVERT_COOLANT_FLOOD_PIN
GPIO_SetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
#else
GPIO_ResetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
#endif
if (BIT_IS_TRUE(settings.input_invert_mask, BITFLAG_INVERT_FLOOD_PIN))
{
GPIO_SetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
}
else
{
GPIO_ResetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
}
}
if (BIT_IS_TRUE(settings.flags_ext, BITFLAG_ENABLE_M7))
{
if (mode & COOLANT_MIST_ENABLE)
{
#ifdef INVERT_COOLANT_MIST_PIN
GPIO_ResetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
#else
GPIO_SetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
#endif
if (BIT_IS_TRUE(settings.input_invert_mask, BITFLAG_INVERT_MIST_PIN))
{
GPIO_ResetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
}
else
{
GPIO_SetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
}
}
else
{
#ifdef INVERT_COOLANT_MIST_PIN
GPIO_SetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
#else
GPIO_ResetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
#endif
if (BIT_IS_TRUE(settings.input_invert_mask, BITFLAG_INVERT_MIST_PIN))
{
GPIO_SetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
}
else
{
GPIO_ResetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
}
}
}

Wyświetl plik

@ -39,11 +39,11 @@
// Modal Group M9: Override control
#ifdef DEACTIVATE_PARKING_UPON_INIT
#define OVERRIDE_DISABLED 0 // (Default: Must be zero)
#define OVERRIDE_PARKING_MOTION 1 // M56
#define OVERRIDE_DISABLED 0 // (Default: Must be zero)
#define OVERRIDE_PARKING_MOTION 1 // M56
#else
#define OVERRIDE_PARKING_MOTION 0 // M56 (Default: Must be zero)
#define OVERRIDE_DISABLED 1 // Parking disabled.
#define OVERRIDE_PARKING_MOTION 0 // M56 (Default: Must be zero)
#define OVERRIDE_DISABLED 1 // Parking disabled.
#endif
@ -105,29 +105,40 @@ uint8_t GC_ExecuteLine(const char *line)
uint8_t axis_command = AXIS_COMMAND_NONE;
uint8_t axis_0, axis_1, axis_linear;
uint8_t coord_select = 0; // Tracks G10 P coordinate selection for execution
// Tracks G10 P coordinate selection for execution
uint8_t coord_select = 0;
// Initialize bitflag tracking variables for axis indices compatible operations.
uint8_t axis_words = 0; // XYZ tracking
uint8_t ijk_words = 0; // IJK tracking
// XYZ tracking
uint8_t axis_words = 0;
// IJK tracking
uint8_t ijk_words = 0;
// Initialize command and value words and parser flags variables.
uint16_t command_words = 0; // Tracks G and M command words. Also used for modal group violations.
uint16_t value_words = 0; // Tracks value words.
// Tracks G and M command words. Also used for modal group violations.
uint16_t command_words = 0;
// Tracks value words.
uint16_t value_words = 0;
uint8_t gc_parser_flags = GC_PARSER_NONE;
memset(&gc_block, 0, sizeof(Parser_Block_t)); // Initialize the parser block struct.
memcpy(&gc_block.modal,&gc_state.modal,sizeof(GC_Modal_t)); // Copy current modes
// Initialize the parser block struct.
memset(&gc_block, 0, sizeof(Parser_Block_t));
// Copy current modes
memcpy(&gc_block.modal, &gc_state.modal, sizeof(GC_Modal_t));
// Determine if the line is a jogging motion or a normal g-code block.
if(line[0] == '$') // NOTE: `$J=` already parsed when passed to this function.
// NOTE: `$J=` already parsed when passed to this function.
if(line[0] == '$')
{
// Set G1 and G94 enforced modes to ensure accurate error checks.
gc_parser_flags |= GC_PARSER_JOG_MOTION;
gc_block.modal.motion = MOTION_MODE_LINEAR;
gc_block.modal.feed_rate = FEED_RATE_MODE_UNITS_PER_MIN;
gc_block.values.n = JOG_LINE_NUMBER; // Initialize default line number reported during jog.
// Initialize default line number reported during jog.
gc_block.values.n = JOG_LINE_NUMBER;
}
/* -------------------------------------------------------------------------------------
@ -143,7 +154,7 @@ uint8_t GC_ExecuteLine(const char *line)
float value = 0.0;
uint16_t int_value = 0;
uint16_t mantissa = 0;
float old_xyz[N_AXIS] = {0.0};
float old_xyz[N_AXIS] = {};
uint8_t change_tool = 0, update_tooltable = 0, apply_tool = 0;
uint8_t io_cmd = 0;
@ -357,9 +368,9 @@ uint8_t GC_ExecuteLine(const char *line)
axis_command = AXIS_COMMAND_MOTION_MODE;
break;
// Set retract mode
case 98:
case 99:
// Set retract mode
word_bit = MODAL_GROUP_G10;
gc_block.modal.retract = int_value - 98;
break;
@ -628,6 +639,7 @@ uint8_t GC_ExecuteLine(const char *line)
axis_words |= (1 << A_AXIS);
}
break;
case 'B':
if (BIT_IS_TRUE(settings.flags_ext, BITFLAG_ENABLE_MULTI_AXIS))
{
@ -636,63 +648,78 @@ uint8_t GC_ExecuteLine(const char *line)
axis_words |= (1 << B_AXIS);
}
break;
// case 'C': // Not supported
case 'D':
word_bit = WORD_D;
gc_block.values.d = int_value;
break; // Maybe float?
case 'F':
word_bit = WORD_F;
gc_block.values.f = value;
break;
case 'H':
word_bit = WORD_H;
gc_block.values.h = int_value;
break;
case 'E':
word_bit = WORD_E;
gc_block.values.e = value;
break;
case 'I':
word_bit = WORD_I;
gc_block.values.ijk[X_AXIS] = value;
ijk_words |= (1<<X_AXIS);
break;
case 'J':
word_bit = WORD_J;
gc_block.values.ijk[Y_AXIS] = value;
ijk_words |= (1<<Y_AXIS);
break;
case 'K':
word_bit = WORD_K;
gc_block.values.ijk[Z_AXIS] = value;
ijk_words |= (1<<Z_AXIS);
break;
case 'L':
word_bit = WORD_L;
gc_block.values.l = int_value;
break;
case 'N':
word_bit = WORD_N;
gc_block.values.n = truncf(value);
break;
case 'P':
// NOTE: For certain commands, P value must be an integer.
word_bit = WORD_P;
gc_block.values.p = value;
break;
// NOTE: For certain commands, P value must be an integer.
case 'Q':
word_bit = WORD_Q;
gc_block.values.q = value;
break;
case 'R':
word_bit = WORD_R;
gc_block.values.r = value;
break;
case 'S':
word_bit = WORD_S;
gc_block.values.s = value;
break;
case 'T':
word_bit = WORD_T;
if(value > MAX_TOOL_NUMBER)
@ -707,16 +734,19 @@ uint8_t GC_ExecuteLine(const char *line)
gc_block.values.xyz[X_AXIS] = value;
axis_words |= (1<<X_AXIS);
break;
case 'Y':
word_bit = WORD_Y;
gc_block.values.xyz[Y_AXIS] = value;
axis_words |= (1<<Y_AXIS);
break;
case 'Z':
word_bit = WORD_Z;
gc_block.values.xyz[Z_AXIS] = value;
axis_words |= (1<<Z_AXIS);
break;
default:
return STATUS_GCODE_UNSUPPORTED_COMMAND;
}
@ -740,7 +770,6 @@ uint8_t GC_ExecuteLine(const char *line)
}
// Flag to indicate parameter assigned.
value_words |= BIT(word_bit);
}
}
// Parsing complete!

Wyświetl plik

@ -41,15 +41,18 @@
#endif
static uint8_t last_state = 0;
void Limits_Init(void)
{
GPIO_InitGPIO(GPIO_LIMIT);
last_state = 0;
// TODO: Hard limits via interrupt
if(BIT_IS_TRUE(settings.flags, BITFLAG_HARD_LIMIT_ENABLE))
if (BIT_IS_TRUE(settings.flags, BITFLAG_HARD_LIMIT_ENABLE))
{
// Enable hard limits
settings.system_flags |= BITFLAG_ENABLE_LIMITS;
sys.system_flags |= BITFLAG_ENABLE_LIMITS;
}
else
{
@ -61,22 +64,20 @@ void Limits_Init(void)
void Limits_Disable(void)
{
// Disables hard limits.
settings.system_flags &= ~BITFLAG_ENABLE_LIMITS;
sys.system_flags &= ~BITFLAG_ENABLE_LIMITS;
}
// 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_GetState(void)
uint8_t Limits_GetState(bool held)
{
uint8_t limit_state = 0;
// First limit
limit_state = (GPIO_ReadInputDataBit(GPIO_LIM_X_PORT, GPIO_LIM_X_PIN) << X1_LIMIT_BIT);
if (BIT_IS_FALSE(settings.flags_ext, BITFLAG_LATHE_MODE))
{
limit_state |= (GPIO_ReadInputDataBit(GPIO_LIM_Y_PORT, GPIO_LIM_Y_PIN) << Y1_LIMIT_BIT);
}
limit_state |= (GPIO_ReadInputDataBit(GPIO_LIM_Y_PORT, GPIO_LIM_Y_PIN) << Y1_LIMIT_BIT);
limit_state |= (GPIO_ReadInputDataBit(GPIO_LIM_Z_PORT, GPIO_LIM_Z_PIN) << Z1_LIMIT_BIT);
// Second limit
@ -84,7 +85,7 @@ uint8_t Limits_GetState(void)
limit_state |= (GPIO_ReadInputDataBit(GPIOC, GPIO_Pin_5)<<Y2_LIMIT_BIT);
limit_state |= (GPIO_ReadInputDataBit(GPIOC, GPIO_Pin_6)<<Z2_LIMIT_BIT);
if(BIT_IS_FALSE(settings.flags, BITFLAG_INVERT_LIMIT_PINS))
if(BIT_IS_TRUE(settings.flags, BITFLAG_INVERT_LIMIT_PINS))
{
limit_state ^= LIMIT_MASK;
}
@ -95,7 +96,17 @@ uint8_t Limits_GetState(void)
limit_state &= ~(1 << Y1_LIMIT_BIT | 1 << Y2_LIMIT_BIT);
}
return limit_state;
uint8_t tmp_state = limit_state ^ last_state;
tmp_state &= limit_state;
if (held)
{
tmp_state = limit_state;
}
last_state = limit_state;
return tmp_state;
}
@ -123,8 +134,8 @@ void Limit_PinChangeISR(void) // DEFAULT: Limit pin change interrupt process.
{
if (BIT_IS_TRUE(settings.flags_ext, BITFLAG_FORCE_HARD_LIMIT_CHECK))
{
Delay_us(25);
uint8_t lim = Limits_GetState();
Delay_ms(2);
uint8_t lim = Limits_GetState(true);
// Check limit pin state.
if(lim)
@ -280,7 +291,7 @@ void Limits_GoHome(uint8_t cycle_mask)
if(approach)
{
// Check limit state. Lock out cycle axes when they change.
limit_state = Limits_GetState();
limit_state = Limits_GetState(true);
for(idx = 0; idx < N_AXIS; idx++)
{
if(axislock & step_pin[idx])
@ -325,7 +336,7 @@ void Limits_GoHome(uint8_t cycle_mask)
System_SetExecAlarm(EXEC_ALARM_HOMING_FAIL_DOOR);
}
// Homing failure condition: Limit switch still engaged after pull-off motion
if(!approach && (Limits_GetState() & cycle_mask))
if(!approach && (Limits_GetState(true) & cycle_mask))
{
System_SetExecAlarm(EXEC_ALARM_HOMING_FAIL_PULLOFF);
}

Wyświetl plik

@ -32,7 +32,7 @@ void Limits_Init(void);
void Limits_Disable(void);
// Returns limit state as a bit-wise uint8 variable.
uint8_t Limits_GetState(void);
uint8_t Limits_GetState(bool held);
void Limit_PinChangeISR(void);

Wyświetl plik

@ -318,8 +318,11 @@ void MC_LineSync(const float *target, const Planner_LineData_t *pl_data, float p
MC_Line(target, pl_data);
sys.sync_move = 1;
// Clear
Encoder_Zero();
// Wait for spindle sync
while(wait_spindle == 0)
while(!Encoder_Zero())
{
Protocol_ExecuteRealtime(); // Check for any run-time commands

Wyświetl plik

@ -285,9 +285,10 @@ uint8_t Planner_BufferLine(const float *target, const Planner_LineData_t *pl_dat
}
else
{
// Block contains backlash compensation data, which must be excluded from planner
// Update previous path unit_vector and planner position.
memcpy(planner.previous_unit_vec, unit_vec_orig, sizeof(unit_vec_orig)); // pl.previous_unit_vec[] = unit_vec[]
memcpy(planner.position, target_steps_orig, sizeof(target_steps_orig)); // pl.position[] = target_steps[]
memcpy(planner.previous_unit_vec, unit_vec_orig, sizeof(unit_vec_orig));
memcpy(planner.position, target_steps_orig, sizeof(target_steps_orig));
}
// New block is all set. Update buffer head and next buffer head indices.
@ -420,8 +421,7 @@ void Planner_SyncPosition(void)
{
// 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++)
for (uint8_t idx = 0; idx < N_AXIS; idx++)
{
#ifdef COREXY
if(idx==X_AXIS)

Wyświetl plik

@ -70,7 +70,7 @@ void Protocol_MainLoop(void)
{
if (BIT_IS_TRUE(settings.flags, BITFLAG_HARD_LIMIT_ENABLE))
{
if (Limits_GetState())
if (Limits_GetState(true))
{
sys.state = STATE_ALARM; // Ensure alarm state is active.
Report_FeedbackMessage(MESSAGE_CHECK_LIMITS);
@ -78,6 +78,11 @@ void Protocol_MainLoop(void)
}
}
if (System_GetControlState(true) & CONTROL_BTN_MASK)
{
Report_FeedbackMessage(MESSAGE_CHECK_INPUTS);
}
// Check for and report alarm state after a reset, error, or an initial power up.
// NOTE: Sleep mode disables the stepper drivers and position can't be guaranteed.
// Re-initialize the sleep state as an ALARM mode to ensure user homes or acknowledges.
@ -297,7 +302,9 @@ void Protocol_ExecuteRealtime(void)
#if (USE_ETH_IF)
ServerTCP_Update();
GrIP_Update();
if(GrIP_Receive(&packet))
{
for(int i = 0; i < packet.RX_Header.Length; i++)
@ -644,7 +651,8 @@ void Protocol_ExecRtSystem(void)
rt_exec = sys_rt_exec_accessory_override;
if(rt_exec)
{
System_ClearExecAccessoryOverrides(); // Clear all accessory override flags.
// Clear all accessory override flags.
System_ClearExecAccessoryOverrides();
// NOTE: Unlike motion overrides, spindle overrides do not require a planner reinitialization.
uint8_t last_s_override = sys.spindle_speed_ovr;
@ -823,6 +831,7 @@ static void Protocol_ExecRtSuspend(void)
#if (USE_ETH_IF)
GrIP_Update();
if(GrIP_Receive(&packet))
{
for(int i = 0; i < packet.RX_Header.Length; i++)
@ -913,9 +922,7 @@ static void Protocol_ExecRtSuspend(void)
Coolant_SetState(COOLANT_DISABLE); // De-energize
}
#endif
sys.suspend &= ~(SUSPEND_RESTART_RETRACT);
sys.suspend |= SUSPEND_RETRACT_COMPLETE;
@ -933,10 +940,11 @@ static void Protocol_ExecRtSuspend(void)
while(!(sys.abort))
{
// Do nothing until reset.
Protocol_ExecRtSystem();
} // Do nothing until reset.
return; // Abort received. Return to re-initialize.
}
// Abort received. Return to re-initialize.
return;
}
// Allows resuming from parking/safety door. Actively checks if safety door is closed and ready to resume.
@ -944,7 +952,8 @@ static void Protocol_ExecRtSuspend(void)
{
if(!(System_CheckSafetyDoorAjar()))
{
sys.suspend &= ~(SUSPEND_SAFETY_DOOR_AJAR); // Reset door ajar flag to denote ready to resume.
// Reset door ajar flag to denote ready to resume.
sys.suspend &= ~(SUSPEND_SAFETY_DOOR_AJAR);
}
}
@ -1054,7 +1063,8 @@ static void Protocol_ExecRtSuspend(void)
}
else
{
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED; // Clear stop override state
// Clear stop override state
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED;
}
// Handles restoring of spindle state
}
@ -1077,8 +1087,8 @@ static void Protocol_ExecRtSuspend(void)
{
System_SetExecStateFlag(EXEC_CYCLE_START); // Set to resume program.
}
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED; // Clear stop override state
// Clear stop override state
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED;
}
}
else

Wyświetl plik

@ -47,9 +47,7 @@
// Internal report utilities to reduce flash with repetitive tasks turned into functions.
static void Report_SettingPrefix(uint8_t n)
{
Printf("$");
Printf("%d", n);
Printf("=");
Printf("$%d=", n);
}
@ -60,20 +58,20 @@ static void Report_LineFeed(void)
}
static void report_util_feedback_line_feed(void)
static void Report_UtilFeedback_LineFeed(void)
{
Printf("]");
Report_LineFeed();
}
static void report_util_gcode_modes_G(void)
static void Report_UtilGCodeModes_G(void)
{
Printf(" G");
}
static void report_util_gcode_modes_M(void)
static void Report_UtilGCodeModes_M(void)
{
Printf(" M");
}
@ -137,8 +135,7 @@ void Report_StatusMessage(uint8_t status_code)
break;
default:
Printf("error:");
Printf("%d\r\n", status_code);
Printf("error:%d\r\n", status_code);
Printf_Flush();
}
}
@ -147,12 +144,11 @@ void Report_StatusMessage(uint8_t status_code)
// Prints alarm messages.
void Report_AlarmMessage(uint8_t alarm_code)
{
Printf("ALARM:");
Printf("%d", alarm_code);
Printf("ALARM:%d", alarm_code);
Report_LineFeed();
// Force delay to ensure message clears serial write buffer.
Delay_ms(100);
Delay_ms(50);
}
@ -214,9 +210,28 @@ void Report_FeedbackMessage(uint8_t message_code)
case MESSAGE_INVALID_TOOL:
Printf("Invalid Tool Number");
break;
case MESSAGE_CHECK_INPUTS:
{
uint8_t control = System_GetControlState(true);
Printf("Check input buttons:");
if (BIT_IS_TRUE(control, CONTROL_PIN_INDEX_RESET))
{
Printf(" RST");
}
if (BIT_IS_TRUE(control, CONTROL_PIN_INDEX_FEED_HOLD))
{
Printf(" HLD");
}
if (BIT_IS_TRUE(control, CONTROL_PIN_INDEX_CYCLE_START))
{
Printf(" RUN");
}
break;
}
}
report_util_feedback_line_feed();
Report_UtilFeedback_LineFeed();
}
@ -248,7 +263,7 @@ void Report_GrblHelp(void)
void Report_GrblSettings(void)
{
// Print Grbl settings.
report_util_uint8_setting(0, settings.system_flags);
report_util_uint8_setting(0, settings.input_invert_mask);
report_util_uint8_setting(1, settings.stepper_idle_lock_time);
report_util_uint8_setting(2, settings.step_invert_mask);
report_util_uint8_setting(3, settings.dir_invert_mask);
@ -360,7 +375,7 @@ void Report_ProbeParams(void)
}
Printf(":%d", sys.probe_succeeded);
report_util_feedback_line_feed();
Report_UtilFeedback_LineFeed();
}
@ -383,7 +398,7 @@ void Report_TLSParams(void)
}
Printf(":%d", settings.tls_valid);
report_util_feedback_line_feed();
Report_UtilFeedback_LineFeed();
}
@ -400,7 +415,7 @@ void Report_ToolParams(uint8_t tool_nr)
PrintFloat_CoordValue(params.z_offset);
Printf(":");
PrintFloat_CoordValue(params.reserved);
report_util_feedback_line_feed();
Report_UtilFeedback_LineFeed();
}
@ -440,13 +455,13 @@ void Report_NgcParams(void)
Printf(":");
Report_AxisValue(coord_data);
report_util_feedback_line_feed();
Report_UtilFeedback_LineFeed();
}
// Print G92,G92.1 which are not persistent in memory
Printf("[G92:");
Report_AxisValue(gc_state.coord_offset);
report_util_feedback_line_feed();
Report_UtilFeedback_LineFeed();
// Print tool length offset value
Printf("[TLO:");
for(uint8_t idx = 0; idx < N_LINEAR_AXIS; idx++)
@ -457,7 +472,7 @@ void Report_NgcParams(void)
Printf(",");
}
}
report_util_feedback_line_feed();
Report_UtilFeedback_LineFeed();
// Print probe parameters. Not persistent in memory.
Report_ProbeParams();
// Print tls position. Persistent in memory.
@ -474,35 +489,34 @@ void Report_GCodeModes(void)
if(gc_state.modal.motion >= MOTION_MODE_PROBE_TOWARD)
{
Printf("38.");
Printf("%d", gc_state.modal.motion - (MOTION_MODE_PROBE_TOWARD-2));
Printf("38.%d", gc_state.modal.motion - (MOTION_MODE_PROBE_TOWARD - 2));
}
else
{
Printf("%d", gc_state.modal.motion);
}
report_util_gcode_modes_G();
Report_UtilGCodeModes_G();
Printf("%d", gc_state.modal.coord_select+54);
report_util_gcode_modes_G();
Report_UtilGCodeModes_G();
Printf("%d", gc_state.modal.plane_select+17);
report_util_gcode_modes_G();
Report_UtilGCodeModes_G();
Printf("%d", 21-gc_state.modal.units);
report_util_gcode_modes_G();
Report_UtilGCodeModes_G();
Printf("%d", gc_state.modal.distance+90);
report_util_gcode_modes_G();
Report_UtilGCodeModes_G();
Printf("%d", 94-gc_state.modal.feed_rate);
report_util_gcode_modes_G();
Report_UtilGCodeModes_G();
Printf("%d", 98+gc_state.modal.retract);
if(gc_state.modal.program_flow)
{
report_util_gcode_modes_M();
Report_UtilGCodeModes_M();
switch(gc_state.modal.program_flow)
{
@ -510,7 +524,7 @@ void Report_GCodeModes(void)
Printf("0");
break;
// case PROGRAM_FLOW_OPTIONAL_STOP : Putc('1'); break; // M1 is ignored and not supported.
// case PROGRAM_FLOW_OPTIONAL_STOP : Putc('1'); break; // M1 is ignored and not supported.
case PROGRAM_FLOW_COMPLETED_M2:
case PROGRAM_FLOW_COMPLETED_M30:
Printf("%d", gc_state.modal.program_flow);
@ -521,7 +535,7 @@ void Report_GCodeModes(void)
}
}
report_util_gcode_modes_M();
Report_UtilGCodeModes_M();
switch(gc_state.modal.spindle)
{
@ -545,18 +559,18 @@ void Report_GCodeModes(void)
{
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_MIST)
{
report_util_gcode_modes_M();
Report_UtilGCodeModes_M();
Printf("7");
}
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_FLOOD)
{
report_util_gcode_modes_M();
Report_UtilGCodeModes_M();
Printf("8");
}
}
else
{
report_util_gcode_modes_M();
Report_UtilGCodeModes_M();
Printf("9");
}
}
@ -564,40 +578,35 @@ void Report_GCodeModes(void)
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
if(sys.override_ctrl == OVERRIDE_PARKING_MOTION)
{
report_util_gcode_modes_M();
Report_UtilGCodeModes_M();
Printf("%d", 56);
}
#endif
Printf(" T");
Printf("%d", gc_state.tool);
Printf(" T%d", gc_state.tool);
Printf(" F");
PrintFloat_RateValue(gc_state.feed_rate);
Printf(" S");
//PrintFloat(gc_state.spindle_speed, N_DECIMAL_RPMVALUE);
Printf("%d", Spindle_GetRPM());
Printf_Float(gc_state.spindle_speed, N_DECIMAL_RPMVALUE);
//Printf(" S%d", Spindle_GetRPM());
report_util_feedback_line_feed();
Report_UtilFeedback_LineFeed();
}
// Prints specified startup line
void Report_StartupLine(uint8_t n, const char *line)
{
Printf("$N");
Printf("%d", n);
Printf("=%s", line);
Printf("$N%d=%s", n, line);
Report_LineFeed();
}
void Report_ExecuteStartupMessage(const char *line, uint8_t status_code)
{
Printf(">");
Printf("%s", line);
Printf(":");
Printf(">%s:", line);
Report_StatusMessage(status_code);
}
@ -606,12 +615,12 @@ void Report_ExecuteStartupMessage(const char *line, uint8_t status_code)
void Report_BuildInfo(const char *line)
{
#ifdef GRBL_COMPATIBLE
Printf("[VER: 1.1, %s: ", GRBL_VERSION_BUILD);
Printf("[VER:1.1h.20240101: ");
#else
Printf("[VER: %s, %s, GCC %s: ", GRBL_VERSION, GRBL_VERSION_BUILD, __VERSION__);
#endif
Printf("%s", line);
report_util_feedback_line_feed();
Report_UtilFeedback_LineFeed();
Printf("[OPT:");
Printf("V");
Printf("N");
@ -689,7 +698,7 @@ void Report_BuildInfo(const char *line)
Printf(",%d", BLOCK_BUFFER_SIZE-1);
Printf(",%d", LINE_BUFFER_SIZE);
report_util_feedback_line_feed();
Report_UtilFeedback_LineFeed();
}
@ -697,16 +706,15 @@ void Report_BuildInfo(const char *line)
// and has been sent into protocol_execute_line() routine to be executed by Grbl.
void Report_EchoLineReceived(char *line)
{
Printf("[echo: ");
Printf("%s", line);
report_util_feedback_line_feed();
Printf("[echo: %s", line);
Report_UtilFeedback_LineFeed();
}
// Prints real-time data. This function grabs a real-time snapshot of the stepper subprogram
// and the actual location of the CNC machine. Users may change the following function to their
// specific needs, but the desired real-time data report must be as short as possible. This is
// requires as it minimizes the computational overhead and allows grbl to keep running smoothly,
// required as it minimizes the computational overhead and allows grbl to keep running smoothly,
// especially during g-code programs with fast, short line segments and high frequency reports (5-20Hz).
void Report_RealtimeStatus(void)
{
@ -718,7 +726,6 @@ void Report_RealtimeStatus(void)
System_ConvertArraySteps2Mpos(print_position, current_position);
// Report current machine state and sub-states
// For better syncing purposes
Printf("<");
switch(sys.state)
@ -870,13 +877,20 @@ void Report_RealtimeStatus(void)
Printf("|FS:");
PrintFloat_RateValue(Stepper_GetRealtimeRate());
Printf(",");
Printf_Float(sys.spindle_speed, N_DECIMAL_RPMVALUE);
if(settings.enc_ppr > 0)
{
Printf_Float(Spindle_GetRPM(), N_DECIMAL_RPMVALUE);
}
else
{
Printf_Float(sys.spindle_speed, N_DECIMAL_RPMVALUE);
}
}
if (BIT_IS_TRUE(settings.flags_report, BITFLAG_REPORT_FIELD_PIN_STATE))
{
uint8_t lim_pin_state = Limits_GetState();
uint8_t ctrl_pin_state = System_GetControlState();
uint8_t lim_pin_state = Limits_GetState(true);
uint8_t ctrl_pin_state = System_GetControlState(true);
uint8_t prb_pin_state = Probe_GetState();
if (lim_pin_state | ctrl_pin_state | prb_pin_state)

Wyświetl plik

@ -45,6 +45,7 @@
#define STATUS_SETTING_DISABLED_LASER 17
#define STATUS_MACHINE_NOT_HOMED 18
#define STATUS_TLS_NOT_SET 19
#define STATUS_CHECK_INPUT 20
#define STATUS_GCODE_UNSUPPORTED_COMMAND 20
#define STATUS_GCODE_MODAL_GROUP_VIOLATION 21
@ -93,6 +94,7 @@
#define MESSAGE_SPINDLE_RESTORE 10
#define MESSAGE_SLEEP_MODE 11
#define MESSAGE_INVALID_TOOL 12
#define MESSAGE_CHECK_INPUTS 13
// Prints system status messages.

Wyświetl plik

@ -61,14 +61,14 @@ void Settings_Init(void)
// Method to restore EEPROM-saved Grbl global settings back to defaults.
void Settings_Restore(uint8_t restore_flag)
void Settings_Restore(const uint8_t restore_flag)
{
sys.state = STATE_BUSY;
Report_RealtimeStatus();
if (restore_flag & SETTINGS_RESTORE_DEFAULTS)
{
settings.system_flags = DEFAULT_SYSTEM_INVERT_MASK;
settings.input_invert_mask = DEFAULT_SYSTEM_INVERT_MASK;
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;
@ -230,12 +230,11 @@ void Settings_Restore(uint8_t restore_flag)
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++)
for (uint8_t idx = 0; idx <= SETTING_INDEX_NCOORD; idx++)
{
Settings_WriteCoordData(idx, coord_data);
}
@ -441,7 +440,7 @@ uint8_t Settings_StoreGlobalSetting(uint8_t parameter, float value)
#ifdef MAX_STEP_RATE_HZ
if (value*settings.max_rate[parameter] > (MAX_STEP_RATE_HZ*60.0))
{
return(STATUS_MAX_STEP_RATE_EXCEEDED);
return (STATUS_MAX_STEP_RATE_EXCEEDED);
}
#endif
settings.steps_per_mm[parameter] = value;
@ -451,7 +450,7 @@ uint8_t Settings_StoreGlobalSetting(uint8_t parameter, float value)
#ifdef MAX_STEP_RATE_HZ
if (value*settings.steps_per_mm[parameter] > (MAX_STEP_RATE_HZ*60.0))
{
return(STATUS_MAX_STEP_RATE_EXCEEDED);
return (STATUS_MAX_STEP_RATE_EXCEEDED);
}
#endif
settings.max_rate[parameter] = value;
@ -478,7 +477,7 @@ uint8_t Settings_StoreGlobalSetting(uint8_t parameter, float value)
// 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);
return (STATUS_INVALID_STATEMENT);
}
parameter -= AXIS_SETTINGS_INCREMENT;
}
@ -492,7 +491,7 @@ uint8_t Settings_StoreGlobalSetting(uint8_t parameter, float value)
switch(parameter)
{
case 0:
settings.system_flags = int_value & CONTROL_MASK;
settings.input_invert_mask = int_value & CONTROL_MASK;
break;
case 1:
@ -899,7 +898,7 @@ static void WriteGlobalSettings(void)
static uint8_t ReadGlobalSettings(void)
{
// Check version-byte of eeprom
uint8_t version = Nvm_ReadByte(0);
uint8_t version = Nvm_ReadByte(EEPROM_ADDR_VERSION);
if (version == SETTINGS_VERSION)
{

Wyświetl plik

@ -32,12 +32,18 @@
#define SETTINGS_VERSION 8 // NOTE: Check settings_reset() when moving to next version.
// Define bit flag masks for the boolean settings in settings.system_flags
// Define bit flag masks for the boolean settings in settings.input_invert_mask
#define BITFLAG_INVERT_RESET_PIN BIT(0)
#define BITFLAG_INVERT_FEED_PIN BIT(1)
#define BITFLAG_INVERT_CYCLE_PIN BIT(2)
#define BITFLAG_INVERT_SAFETY_PIN BIT(3)
#define BITFLAG_ENABLE_LIMITS BIT(4)
#define BITFLAG_INVERT_SPINDLE_PIN BIT(4)
#define BITFLAG_INVERT_FLOOD_PIN BIT(5)
#define BITFLAG_INVERT_MIST_PIN BIT(6)
// Define bit flag masks for the boolean settings in settings.system_flags
#define BITFLAG_ENABLE_SYSTEM_INPUT BIT(0)
#define BITFLAG_ENABLE_LIMITS BIT(1)
// Define bit flag masks for the boolean settings in settings.flags.
#define BITFLAG_REPORT_INCHES BIT(0)
@ -85,6 +91,7 @@
// NOTE: Default 1KB EEPROM. The upper half is reserved for parameters and
// the startup script. The lower half contains the global settings and space for future
// developments.
#define EEPROM_ADDR_VERSION 0U
#define EEPROM_ADDR_GLOBAL 1U // +163
#define EEPROM_ADDR_TOOLTABLE 180U // +320
#define EEPROM_ADDR_PARAMETERS 512U // +160
@ -134,7 +141,7 @@ typedef struct
uint8_t tls_valid;
// Remaining Grbl settings
uint8_t system_flags;
uint8_t input_invert_mask;
uint8_t step_invert_mask;
uint8_t dir_invert_mask;
uint8_t stepper_idle_lock_time; // If max value 255, steppers do not disable.
@ -166,7 +173,7 @@ extern Settings_t settings;
void Settings_Init(void);
// Helper function to clear and restore EEPROM defaults
void Settings_Restore(uint8_t restore_flag);
void Settings_Restore(const uint8_t restore_flag);
// A helper method to set new settings from command line
uint8_t Settings_StoreGlobalSetting(uint8_t parameter, float value);
@ -180,7 +187,7 @@ void Settings_StoreStartupLine(uint8_t n, const char *line);
// Stores tool table in EEPROM
void Settings_StoreToolTable(const ToolTable_t *table);
void Settings_StoreToolParams(uint8_t tool_nr, const ToolParams_t *params);
//void Settings_StoreToolParams(uint8_t tool_nr, const ToolParams_t *params);
// Read tool table
uint8_t Settings_ReadToolTable(ToolTable_t *table);

Wyświetl plik

@ -4,7 +4,7 @@
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2017-2020 Patrick F.
Copyright (c) 2017-2024 Patrick F.
Grbl-Advanced is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
@ -44,7 +44,7 @@ void Spindle_Init(void)
GPIO_InitGPIO(GPIO_SPINDLE);
TIM1_Init();
//TIM3_Init();
if (BIT_IS_TRUE(settings.flags_ext, BITFLAG_LATHE_MODE))
{
Encoder_Init(settings.enc_ppr);
@ -65,11 +65,14 @@ void Spindle_Stop(void)
TIM1->CCR1 = TIM1_INIT; // Disable PWM. Output voltage is zero.
spindle_enabled = 0;
#ifdef INVERT_SPINDLE_ENABLE_PIN
GPIO_SetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
#else
GPIO_ResetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
#endif
if (BIT_IS_TRUE(settings.input_invert_mask, BITFLAG_INVERT_SPINDLE_PIN))
{
GPIO_SetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
}
else
{
GPIO_ResetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
}
}
@ -105,15 +108,18 @@ void Spindle_SetSpeed(uint8_t pwm_value)
else
{
TIM_Cmd(TIM1, ENABLE); // Ensure PWM output is enabled.
#ifdef INVERT_SPINDLE_ENABLE_PIN
GPIO_ResetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
#else
GPIO_SetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
#endif
if (BIT_IS_TRUE(settings.input_invert_mask, BITFLAG_INVERT_SPINDLE_PIN))
{
GPIO_ResetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
}
else
{
GPIO_SetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
}
spindle_enabled = 1;
}
#else
if(pwm_value == SPINDLE_PWM_OFF_VALUE)
if (pwm_value == SPINDLE_PWM_OFF_VALUE)
{
TIM1->CCR1 = TIM1_INIT; // Disable PWM. Output voltage is zero.
TIM_Cmd(TIM1, DISABLE); // Disable PWM. Output voltage is zero.
@ -202,11 +208,14 @@ void Spindle_SetState(uint8_t state, float rpm)
spindle_dir_cw = 0;
}
#ifdef INVERT_SPINDLE_ENABLE_PIN
GPIO_ResetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
#else
GPIO_SetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
#endif
if (BIT_IS_TRUE(settings.input_invert_mask, BITFLAG_INVERT_SPINDLE_PIN))
{
GPIO_ResetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
}
else
{
GPIO_SetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
}
// NOTE: Assumes all calls to this function is when Grbl is not moving or must remain off.
if (BIT_IS_TRUE(settings.flags, BITFLAG_LASER_MODE))

Wyświetl plik

@ -51,10 +51,17 @@ volatile uint8_t sys_rt_exec_motion_override;
// Global realtime executor bitflag variable for spindle/coolant overrides.
volatile uint8_t sys_rt_exec_accessory_override;
//static uint8_t initial_state = 0;
static uint8_t last_state = 0;
void System_Init(void)
{
GPIO_InitGPIO(GPIO_SYSTEM);
last_state = 0;
sys.system_flags |= BITFLAG_ENABLE_SYSTEM_INPUT;
System_GetControlState(false);
}
@ -67,6 +74,8 @@ void System_Clear(void)
sys.f_override = DEFAULT_FEED_OVERRIDE;
sys.r_override = DEFAULT_RAPID_OVERRIDE;
sys.spindle_speed_ovr = DEFAULT_SPINDLE_SPEED_OVERRIDE;
sys.system_flags |= BITFLAG_ENABLE_SYSTEM_INPUT;
}
@ -80,7 +89,7 @@ void System_ResetPosition(void)
// Returns control pin state as a uint8 bitfield. Each bit indicates the input pin state, where
// triggered is 1 and not triggered is 0. Invert mask is applied. Bitfield organization is
// defined by the CONTROL_PIN_INDEX in the header file.
uint8_t System_GetControlState(void)
uint8_t System_GetControlState(bool held)
{
uint8_t control_state = 0;
uint8_t pin = ((GPIO_ReadInputDataBit(GPIOA, GPIO_Pin_0)<<CONTROL_RESET_BIT) |
@ -89,19 +98,30 @@ uint8_t System_GetControlState(void)
(GPIO_ReadInputDataBit(GPIOB, GPIO_Pin_8)<<CONTROL_SAFETY_DOOR_BIT));
// Invert control pins if necessary
pin ^= CONTROL_MASK & settings.system_flags;
pin ^= CONTROL_MASK & settings.input_invert_mask;
if(pin)
// XOR: Only get changed
uint8_t tmp_state = pin ^ last_state;
// Only get active
tmp_state &= pin;
if(held)
{
if(BIT_IS_TRUE(pin, (1<<CONTROL_RESET_BIT)))
// Get current state of inputs
tmp_state = pin;
}
if (tmp_state)
{
if (BIT_IS_TRUE(tmp_state, (1 << CONTROL_RESET_BIT)))
{
control_state |= CONTROL_PIN_INDEX_RESET;
}
if(BIT_IS_TRUE(pin, (1<<CONTROL_FEED_HOLD_BIT)))
if (BIT_IS_TRUE(tmp_state, (1 << CONTROL_FEED_HOLD_BIT)))
{
control_state |= CONTROL_PIN_INDEX_FEED_HOLD;
}
if(BIT_IS_TRUE(pin, (1<<CONTROL_CYCLE_START_BIT)))
if (BIT_IS_TRUE(tmp_state, (1 << CONTROL_CYCLE_START_BIT)))
{
control_state |= CONTROL_PIN_INDEX_CYCLE_START;
}
@ -111,6 +131,8 @@ uint8_t System_GetControlState(void)
}*/
}
last_state = pin;
return control_state;
}
@ -121,7 +143,7 @@ uint8_t System_GetControlState(void)
// directly from the incoming serial data stream.
void System_PinChangeISR(void)
{
uint8_t pin = System_GetControlState();
uint8_t pin = System_GetControlState(true);
if(pin)
{
@ -148,7 +170,7 @@ void System_PinChangeISR(void)
// Returns if safety door is ajar(T) or closed(F), based on pin state.
uint8_t System_CheckSafetyDoorAjar(void)
{
return (System_GetControlState() & CONTROL_PIN_INDEX_SAFETY_DOOR);
return (System_GetControlState(true) & CONTROL_PIN_INDEX_SAFETY_DOOR);
}
@ -215,7 +237,7 @@ uint8_t System_ExecuteLine(char *line)
case 'X':
if(line[2] != 0)
{
return(STATUS_INVALID_STATEMENT);
return (STATUS_INVALID_STATEMENT);
}
switch(line[1])
@ -224,7 +246,7 @@ uint8_t System_ExecuteLine(char *line)
if(sys.state & (STATE_CYCLE | STATE_HOLD))
{
// Block during cycle. Takes too long to print.
return(STATUS_IDLE_ERROR);
return (STATUS_IDLE_ERROR);
}
else
{
@ -260,19 +282,24 @@ uint8_t System_ExecuteLine(char *line)
break;
case 'X': // Disable alarm lock [ALARM]
if(sys.state == STATE_ALARM)
if(BIT_IS_TRUE(sys.state, STATE_ALARM))
{
// Block if safety door is ajar.
if(System_CheckSafetyDoorAjar())
{
return(STATUS_CHECK_DOOR);
return (STATUS_CHECK_DOOR);
}
if (System_GetControlState(true))
{
return (STATUS_CHECK_INPUT);
}
Report_FeedbackMessage(MESSAGE_ALARM_UNLOCK);
sys.state = STATE_IDLE;
Stepper_WakeUp();
// Don't run startup script. Prevents stored moves in startup from causing accidents.
} // Otherwise, no effect.
}
// Otherwise, no effect.
break;
}
break;
@ -343,7 +370,7 @@ uint8_t System_ExecuteLine(char *line)
float value_f[4] = {};
// Read floats [x.x:x.x:x.x:x.x]
for(int i = 0; i < 4; i++)
for (uint8_t i = 0; i < 4; i++)
{
t = ExtractFloat(&line[char_counter], t, tmp_float);
@ -393,9 +420,9 @@ uint8_t System_ExecuteLine(char *line)
default:
// Block any system command that requires the state as IDLE/ALARM. (i.e. EEPROM, homing)
if(!(sys.state == STATE_IDLE || sys.state == STATE_ALARM) )
if(!(sys.state == STATE_IDLE || sys.state == STATE_ALARM))
{
return(STATUS_IDLE_ERROR);
return (STATUS_IDLE_ERROR);
}
switch(line[1])
@ -414,7 +441,7 @@ uint8_t System_ExecuteLine(char *line)
case 'H': // Perform homing cycle [IDLE/ALARM]
if(BIT_IS_FALSE(settings.flags, BITFLAG_HOMING_ENABLE))
{
return(STATUS_SETTING_DISABLED);
return (STATUS_SETTING_DISABLED);
}
if(System_CheckSafetyDoorAjar())
{
@ -482,7 +509,7 @@ uint8_t System_ExecuteLine(char *line)
case 'S': // Puts Grbl to sleep [IDLE/ALARM]
if((line[2] != 'L') || (line[3] != 'P') || (line[4] != 0))
{
return(STATUS_INVALID_STATEMENT);
return (STATUS_INVALID_STATEMENT);
}
System_SetExecStateFlag(EXEC_SLEEP); // Set to execute sleep mode immediately
break;
@ -517,7 +544,7 @@ uint8_t System_ExecuteLine(char *line)
case 'R': // Restore defaults [IDLE/ALARM]
if((line[2] != 'S') || (line[3] != 'T') || (line[4] != '=') || (line[6] != 0))
{
return(STATUS_INVALID_STATEMENT);
return (STATUS_INVALID_STATEMENT);
}
switch(line[5])
@ -611,7 +638,7 @@ uint8_t System_ExecuteLine(char *line)
}
if(line[char_counter++] != '=')
{
return(STATUS_INVALID_STATEMENT);
return (STATUS_INVALID_STATEMENT);
}
if(helper_var) // Store startup line
{
@ -772,7 +799,7 @@ uint8_t System_CheckTravelLimits(const float *target)
// Special handlers for setting and clearing Grbl's real-time execution flags.
void System_SetExecStateFlag(uint16_t mask)
inline void System_SetExecStateFlag(uint16_t mask)
{
uint32_t primask = __get_PRIMASK();
__disable_irq();
@ -783,7 +810,7 @@ void System_SetExecStateFlag(uint16_t mask)
}
void System_ClearExecStateFlag(uint16_t mask)
inline void System_ClearExecStateFlag(uint16_t mask)
{
uint32_t primask = __get_PRIMASK();
__disable_irq();
@ -794,7 +821,7 @@ void System_ClearExecStateFlag(uint16_t mask)
}
void System_SetExecAlarm(uint8_t code)
inline void System_SetExecAlarm(uint8_t code)
{
uint32_t primask = __get_PRIMASK();
__disable_irq();
@ -805,7 +832,7 @@ void System_SetExecAlarm(uint8_t code)
}
void System_ClearExecAlarm(void)
inline void System_ClearExecAlarm(void)
{
uint32_t primask = __get_PRIMASK();
__disable_irq();
@ -816,7 +843,7 @@ void System_ClearExecAlarm(void)
}
void System_SetExecMotionOverrideFlag(uint8_t mask)
inline void System_SetExecMotionOverrideFlag(uint8_t mask)
{
uint32_t primask = __get_PRIMASK();
__disable_irq();
@ -827,7 +854,7 @@ void System_SetExecMotionOverrideFlag(uint8_t mask)
}
void System_SetExecAccessoryOverrideFlag(uint8_t mask)
inline void System_SetExecAccessoryOverrideFlag(uint8_t mask)
{
uint32_t primask = __get_PRIMASK();
__disable_irq();
@ -838,7 +865,7 @@ void System_SetExecAccessoryOverrideFlag(uint8_t mask)
}
void System_ClearExecMotionOverride(void)
inline void System_ClearExecMotionOverride(void)
{
uint32_t primask = __get_PRIMASK();
__disable_irq();
@ -849,7 +876,7 @@ void System_ClearExecMotionOverride(void)
}
void System_ClearExecAccessoryOverrides(void)
inline void System_ClearExecAccessoryOverrides(void)
{
uint32_t primask = __get_PRIMASK();
__disable_irq();

Wyświetl plik

@ -22,6 +22,7 @@
#define SYSTEM_H
#include <stdint.h>
#include <stdbool.h>
#include "util.h"
@ -97,6 +98,7 @@
#define STATE_FEED_DWELL BIT(8) // Dwell
#define STATE_TOOL_CHANGE BIT(9) // Tool change in progress
#define STATE_BUSY BIT(10) // Writing NVM etc.
#define STATE_ALARM_INPUT BIT(11)
// Define system suspend flags. Used in various ways to manage suspend states and procedures.
#define SUSPEND_DISABLE 0 // Must be zero.
@ -117,7 +119,7 @@
#define STEP_CONTROL_UPDATE_SPINDLE_PWM BIT(3)
// Define control pin index for Grbl internal use. Pin maps may change, but these values don't.
#define N_CONTROL_PIN 4
#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)
@ -155,6 +157,8 @@ typedef struct
uint8_t is_homed;
uint8_t sync_move;
float x_pos; // Current x-position of tool (for G96)
uint8_t system_flags; // Runtime flags
} System_t;
extern System_t sys;
@ -178,7 +182,7 @@ void System_Clear(void);
void System_ResetPosition(void);
// Returns bitfield of control pin states, organized by CONTROL_PIN_INDEX. (1=triggered, 0=not triggered).
uint8_t System_GetControlState(void);
uint8_t System_GetControlState(bool held);
// Returns if safety door is open or closed, based on pin state.
uint8_t System_CheckSafetyDoorAjar(void);

Wyświetl plik

@ -31,32 +31,32 @@
#ifdef DEFAULTS_GENERIC
// Grbl generic default settings. Should work across different machines.
#define DEFAULT_X_STEPS_PER_MM 400.0
#define DEFAULT_Y_STEPS_PER_MM 400.0
#define DEFAULT_Z_STEPS_PER_MM 400.0
#define DEFAULT_A_STEPS_PER_DEG 10.0
#define DEFAULT_B_STEPS_PER_DEG 10.0
#define DEFAULT_X_MAX_RATE 1000.0 // mm/min
#define DEFAULT_Y_MAX_RATE 1000.0 // mm/min
#define DEFAULT_Z_MAX_RATE 1000.0 // mm/min
#define DEFAULT_A_MAX_RATE 10000.0 // °/min
#define DEFAULT_B_MAX_RATE 10000.0 // °/min
#define DEFAULT_X_ACCELERATION (30.0*60*60) // 30*60*60 mm/min^2 = 30 mm/sec^2
#define DEFAULT_Y_ACCELERATION (30.0*60*60) // 30*60*60 mm/min^2 = 30 mm/sec^2
#define DEFAULT_Z_ACCELERATION (30.0*60*60) // 30*60*60 mm/min^2 = 30 mm/sec^2
#define DEFAULT_A_ACCELERATION (100.0*60*60) // 100*60*60 mm/min^2 = 100 mm/sec^2
#define DEFAULT_B_ACCELERATION (100.0*60*60) // 100*60*60 mm/min^2 = 100 mm/sec^2
#define DEFAULT_X_MAX_TRAVEL 400.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 500.0 // mm NOTE: Must be a positive value.
#define DEFAULT_A_MAX_TRAVEL 360.0 // °
#define DEFAULT_B_MAX_TRAVEL 360.0 // °
#define DEFAULT_SPINDLE_RPM_MAX 3000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_X_STEPS_PER_MM 400.0
#define DEFAULT_Y_STEPS_PER_MM 400.0
#define DEFAULT_Z_STEPS_PER_MM 400.0
#define DEFAULT_A_STEPS_PER_DEG 100.0
#define DEFAULT_B_STEPS_PER_DEG 100.0
#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_A_MAX_RATE 10000.0 // °/min
#define DEFAULT_B_MAX_RATE 10000.0 // °/min
#define DEFAULT_X_ACCELERATION (60.0*60*60) // 30*60*60 mm/min^2 = 30 mm/sec^2
#define DEFAULT_Y_ACCELERATION (60.0*60*60) // 30*60*60 mm/min^2 = 30 mm/sec^2
#define DEFAULT_Z_ACCELERATION (60.0*60*60) // 30*60*60 mm/min^2 = 30 mm/sec^2
#define DEFAULT_A_ACCELERATION (100.0*60*60) // 100*60*60 mm/min^2 = 100 mm/sec^2
#define DEFAULT_B_ACCELERATION (100.0*60*60) // 100*60*60 mm/min^2 = 100 mm/sec^2
#define DEFAULT_X_MAX_TRAVEL 400.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 400.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 500.0 // mm NOTE: Must be a positive value.
#define DEFAULT_A_MAX_TRAVEL 360.0 // °
#define DEFAULT_B_MAX_TRAVEL 360.0 // °
#define DEFAULT_SPINDLE_RPM_MAX 3000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_X_BACKLASH 0.01 // mm
#define DEFAULT_Y_BACKLASH 0.01 // mm
#define DEFAULT_Z_BACKLASH 0.01 // mm
#define DEFAULT_X_BACKLASH 0.01 // mm
#define DEFAULT_Y_BACKLASH 0.01 // mm
#define DEFAULT_Z_BACKLASH 0.01 // mm
#define DEFAULT_SYSTEM_INVERT_MASK 0
#define DEFAULT_STEPPING_INVERT_MASK 0
@ -67,7 +67,7 @@
#define DEFAULT_ARC_TOLERANCE 0.001 // mm
#define DEFAULT_REPORT_INCHES 0 // false
#define DEFAULT_INVERT_ST_ENABLE 0 // false
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
#define DEFAULT_INVERT_LIMIT_PINS 1 // false
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
#define DEFAULT_HARD_LIMIT_ENABLE 1 // false
#define DEFAULT_INVERT_PROBE_PIN 0 // false

Wyświetl plik

@ -247,11 +247,6 @@ void Delay_sec(float seconds, uint8_t mode)
}
}
// Simple hypotenuse computation function.
/*float hypot_f(float x, float y)
{
return sqrtf(x*x + y*y);
}*/
bool isEqual_f(float a, float b)
{

Wyświetl plik

@ -81,6 +81,7 @@
#define CONTROL_CYCLE_START_BIT 2
#define CONTROL_SAFETY_DOOR_BIT 3
#define CONTROL_MASK ((1<<CONTROL_RESET_BIT) | (1<<CONTROL_FEED_HOLD_BIT) | (1<<CONTROL_CYCLE_START_BIT) | (1<<CONTROL_SAFETY_DOOR_BIT))
#define CONTROL_BTN_MASK ((1<<CONTROL_RESET_BIT) | (1<<CONTROL_FEED_HOLD_BIT) | (1<<CONTROL_CYCLE_START_BIT))
#define DELAY_MODE_DWELL 0
@ -95,7 +96,7 @@
// Conversions
#define MM_PER_INCH (25.40)
#define INCH_PER_MM (0.0393701)
#define INCH_PER_MM (0.039370079)
#define TICKS_PER_MICROSECOND (24UL)
@ -129,7 +130,6 @@ void PrintFloat_RateValue(float n);
void Delay_sec(float seconds, uint8_t mode);
// Computes hypotenuse, avoiding avr-gcc's bloated version and the extra error checking.
float hypot_f(float x, float y);
bool isEqual_f(float a, float b);
float convert_delta_vector_to_unit_vector(float *vector);
float limit_value_by_axis_maximum(float *max_value, float *unit_vec);

9
main.c
Wyświetl plik

@ -24,11 +24,8 @@
#include "ServerTCP.h"
#include "System32.h"
#include "grbl_advance.h"
#include "w5500.h"
#include "Print.h"
#include "FIFO_USART.h"
#include "ComIf.h"
#include "Platform.h"
@ -43,14 +40,14 @@ int main(void)
// Initialize GrIP protocol
GrIP_Init();
System_Init();
Settings_Init();
System_Init();
Stepper_Init();
Limits_Init();
System_ResetPosition();
Limits_Init();
#if (USE_ETH_IF)
// Initialize TCP server
ServerTCP_Init(ETH_SOCK, ETH_PORT);