kopia lustrzana https://github.com/Schildkroet/GRBL-Advanced
Code formating
rodzic
03926b5a3b
commit
e50fcc46d0
|
@ -1,9 +1,14 @@
|
|||
<?xml version="1.0" encoding="UTF-8" standalone="yes" ?>
|
||||
<EmBitz_layout_file>
|
||||
<ActiveTarget name="Release" />
|
||||
<File name="grbl\Config.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<File name="grbl\Config.h" open="1" top="0" tabpos="2" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="1831" topLine="36" />
|
||||
<Cursor1 position="1922" topLine="21" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="grbl\defaults.h" open="1" top="0" tabpos="3" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="0" topLine="0" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="grbl\Nvm.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
|
@ -13,7 +18,7 @@
|
|||
</File>
|
||||
<File name="grbl\Settings.c" open="0" top="0" tabpos="2" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="6104" topLine="204" />
|
||||
<Cursor1 position="2819" topLine="75" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="grbl\SpindleControl.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
|
@ -53,7 +58,7 @@
|
|||
</File>
|
||||
<File name="main.c" open="1" top="1" tabpos="1" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="1190" topLine="0" />
|
||||
<Cursor1 position="0" topLine="0" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="Src\Platform.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
|
|
|
@ -1,11 +1,16 @@
|
|||
<?xml version="1.0" encoding="UTF-8" standalone="yes" ?>
|
||||
<EmBitz_layout_file>
|
||||
<ActiveTarget name="Release" />
|
||||
<File name="grbl\Config.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<File name="grbl\Config.h" open="1" top="0" tabpos="2" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="1842" topLine="12" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="grbl\defaults.h" open="1" top="0" tabpos="3" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="0" topLine="0" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="grbl\Nvm.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="1004" topLine="3" />
|
||||
|
@ -33,12 +38,12 @@
|
|||
</File>
|
||||
<File name="HAL\STM32\stm32f4xx.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="7912" topLine="125" />
|
||||
<Cursor1 position="7911" topLine="125" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="HAL\STM32\system_stm32f4xx.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="8151" topLine="148" />
|
||||
<Cursor1 position="8208" topLine="148" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="HAL\TIM\TIM.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
|
@ -46,39 +51,9 @@
|
|||
<Cursor1 position="844" topLine="24" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="HAL\USART\USART.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="3724" topLine="78" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="main.c" open="1" top="1" tabpos="1" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="2440" topLine="48" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="SPL\inc\stm32f4xx_flash.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="1099" topLine="453" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="SPL\src\stm32f4xx_flash.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="1049" topLine="669" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="SPL\src\stm32f4xx_pwr.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="42659" topLine="1003" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="SPL\src\stm32f4xx_rcc.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="63062" topLine="1319" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="SPL\src\stm32f4xx_usart.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="12891" topLine="290" />
|
||||
<Cursor1 position="2685" topLine="12" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="Src\Platform.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
|
|
|
@ -23,7 +23,11 @@
|
|||
#include "stm32f4xx.h"
|
||||
|
||||
|
||||
#define EEPROM_SIZE 1024
|
||||
#ifdef USE_EXT_EEPROM
|
||||
#define EEPROM_SIZE 1
|
||||
#else
|
||||
#define EEPROM_SIZE 1024
|
||||
#endif
|
||||
|
||||
/* Device voltage range supposed to be [2.7V to 3.6V], the operation will be done by word */
|
||||
#define VOLTAGE_RANGE (uint8_t)VoltageRange_3
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
System32.c - System Implementation
|
||||
Part of STM32F4_HAL
|
||||
|
||||
Copyright (c) 2017 Patrick F.
|
||||
Copyright (c) 2017 Patrick F.
|
||||
|
||||
STM32F4_HAL is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
|
@ -20,32 +20,32 @@
|
|||
|
||||
void SysTick_Init(void)
|
||||
{
|
||||
RCC_ClocksTypeDef RCC_Clocks;
|
||||
RCC_ClocksTypeDef RCC_Clocks;
|
||||
|
||||
/* SysTick end of count event each 1ms */
|
||||
RCC_GetClocksFreq(&RCC_Clocks);
|
||||
SysTick_Config(RCC_Clocks.HCLK_Frequency / 1000);
|
||||
/* SysTick end of count event each 1ms */
|
||||
RCC_GetClocksFreq(&RCC_Clocks);
|
||||
SysTick_Config(RCC_Clocks.HCLK_Frequency / 1000);
|
||||
|
||||
NVIC_SetPriority(SysTick_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 5));
|
||||
NVIC_SetPriority(SysTick_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 5));
|
||||
}
|
||||
|
||||
|
||||
// for 100 MHz STM32F411
|
||||
#define COUNTS_PER_MICROSECOND 33
|
||||
#define COUNTS_PER_MICROSECOND 33
|
||||
void Delay_us(volatile uint32_t us)
|
||||
{
|
||||
volatile uint32_t count = us * COUNTS_PER_MICROSECOND - 2;
|
||||
__asm volatile(" mov r0, %[count] \n\t"
|
||||
"1: subs r0, #1 \n\t"
|
||||
" bhi 1b \n\t"
|
||||
:
|
||||
: [count] "r" (count)
|
||||
: "r0");
|
||||
volatile uint32_t count = us * COUNTS_PER_MICROSECOND - 2;
|
||||
__asm volatile(" mov r0, %[count] \n\t"
|
||||
"1: subs r0, #1 \n\t"
|
||||
" bhi 1b \n\t"
|
||||
:
|
||||
: [count] "r" (count)
|
||||
: "r0");
|
||||
}
|
||||
|
||||
|
||||
void Delay_ms(volatile uint32_t ms)
|
||||
{
|
||||
while(ms--)
|
||||
Delay_us(999);
|
||||
while(ms--)
|
||||
Delay_us(999);
|
||||
}
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
System32.h - System Header
|
||||
Part of STM32F4_HAL
|
||||
|
||||
Copyright (c) 2017 Patrick F.
|
||||
Copyright (c) 2017 Patrick F.
|
||||
|
||||
STM32F4_HAL is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
|
@ -27,16 +27,18 @@ extern "C" {
|
|||
#endif
|
||||
|
||||
|
||||
typedef struct {
|
||||
uint8_t Hours;
|
||||
uint8_t Minutes;
|
||||
uint8_t Seconds;
|
||||
typedef struct
|
||||
{
|
||||
uint8_t Hours;
|
||||
uint8_t Minutes;
|
||||
uint8_t Seconds;
|
||||
} Time_t;
|
||||
|
||||
typedef struct {
|
||||
uint16_t Year;
|
||||
uint8_t Month;
|
||||
uint8_t Day;
|
||||
typedef struct
|
||||
{
|
||||
uint16_t Year;
|
||||
uint8_t Month;
|
||||
uint8_t Day;
|
||||
} Date_t;
|
||||
|
||||
|
||||
|
|
|
@ -97,7 +97,7 @@ void TIM3_Init(void)
|
|||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
|
||||
GPIO_Init(GPIOC, &GPIO_InitStructure);
|
||||
|
||||
/* Connect TIM pins to AF2 */
|
||||
|
|
|
@ -30,162 +30,162 @@ static uint32_t CRC_ReverseBitOrder32(uint32_t value);
|
|||
|
||||
|
||||
#if (CRC_8_MODE == TABLE)
|
||||
static uint8_t CRC8Table[256u];
|
||||
static uint8_t CRC8Table[256u];
|
||||
#endif
|
||||
|
||||
#if (CRC_16_MODE == TABLE)
|
||||
static uint16_t CRC16Table[256u];
|
||||
static uint16_t CRC16Table[256u];
|
||||
#endif
|
||||
|
||||
#if (CRC_32_MODE == TABLE)
|
||||
static uint32_t CRC32Table[256u];
|
||||
static uint32_t CRC32Table[256u];
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
void CRC_Init(void)
|
||||
{
|
||||
CRC_CalculateCRC8Table();
|
||||
CRC_CalculateCRC16Table();
|
||||
CRC_CalculateCRC32Table();
|
||||
CRC_CalculateCRC8Table();
|
||||
CRC_CalculateCRC16Table();
|
||||
CRC_CalculateCRC32Table();
|
||||
}
|
||||
|
||||
|
||||
uint8_t CRC_CalculateCRC8(const uint8_t *Buffer, uint16_t Length)
|
||||
{
|
||||
uint8_t retVal = 0u;
|
||||
uint16_t byteIndex = 0u;
|
||||
uint8_t retVal = 0u;
|
||||
uint16_t byteIndex = 0u;
|
||||
|
||||
|
||||
if(Buffer != NULL)
|
||||
if(Buffer != NULL)
|
||||
{
|
||||
#if (CRC_8_MODE == RUNTTIME)
|
||||
uint8_t bitIndex = 0u;
|
||||
uint8_t bitIndex = 0u;
|
||||
|
||||
retVal = CRC_8_INIT_VALUE;
|
||||
retVal = CRC_8_INIT_VALUE;
|
||||
|
||||
/* Do calculation procedure for each byte */
|
||||
for(byteIndex = 0u; byteIndex < Length; byteIndex++)
|
||||
/* Do calculation procedure for each byte */
|
||||
for(byteIndex = 0u; byteIndex < Length; byteIndex++)
|
||||
{
|
||||
/* XOR new byte with temp result */
|
||||
retVal ^= (Buffer[byteIndex] << (CRC_8_RESULT_WIDTH - 8u));
|
||||
/* XOR new byte with temp result */
|
||||
retVal ^= (Buffer[byteIndex] << (CRC_8_RESULT_WIDTH - 8u));
|
||||
|
||||
/* Do calculation for current data */
|
||||
for(bitIndex = 0u; bitIndex < 8u; bitIndex++)
|
||||
/* Do calculation for current data */
|
||||
for(bitIndex = 0u; bitIndex < 8u; bitIndex++)
|
||||
{
|
||||
if(retVal & (1u << (CRC_8_RESULT_WIDTH - 1u)))
|
||||
if(retVal & (1u << (CRC_8_RESULT_WIDTH - 1u)))
|
||||
{
|
||||
retVal = (retVal << 1u) ^ CRC_8_POLYNOMIAL;
|
||||
}
|
||||
else
|
||||
retVal = (retVal << 1u) ^ CRC_8_POLYNOMIAL;
|
||||
}
|
||||
else
|
||||
{
|
||||
retVal = (retVal << 1u);
|
||||
}
|
||||
}
|
||||
}
|
||||
retVal = (retVal << 1u);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* XOR result with specified value */
|
||||
retVal ^= CRC_8_XOR_VALUE;
|
||||
/* XOR result with specified value */
|
||||
retVal ^= CRC_8_XOR_VALUE;
|
||||
|
||||
#elif (CRC_8_MODE == TABLE)
|
||||
retVal = CRC_8_INIT_VALUE;
|
||||
retVal = CRC_8_INIT_VALUE;
|
||||
|
||||
for(byteIndex = 0u; byteIndex < Length; byteIndex++)
|
||||
for(byteIndex = 0u; byteIndex < Length; byteIndex++)
|
||||
{
|
||||
retVal = CRC8Table[(retVal) ^ Buffer[byteIndex]];
|
||||
}
|
||||
retVal = CRC8Table[(retVal) ^ Buffer[byteIndex]];
|
||||
}
|
||||
|
||||
/* XOR result with specified value */
|
||||
retVal ^= CRC_8_XOR_VALUE;
|
||||
/* XOR result with specified value */
|
||||
retVal ^= CRC_8_XOR_VALUE;
|
||||
|
||||
#else
|
||||
/* Mode not implemented */
|
||||
retVal = 0x00u;
|
||||
/* Mode not implemented */
|
||||
retVal = 0x00u;
|
||||
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
return retVal;
|
||||
return retVal;
|
||||
}
|
||||
|
||||
|
||||
uint16_t CRC_CalculateCRC16(const uint8_t *Buffer, uint16_t Length)
|
||||
{
|
||||
uint16_t retVal = 0u;
|
||||
uint16_t byteIndex = 0u;
|
||||
uint16_t retVal = 0u;
|
||||
uint16_t byteIndex = 0u;
|
||||
|
||||
|
||||
if(Buffer != NULL)
|
||||
{
|
||||
#if (CRC_16_MODE==RUNTTIME)
|
||||
retVal = CRC_16_INIT_VALUE;
|
||||
retVal = CRC_16_INIT_VALUE;
|
||||
|
||||
/* Do calculation procedure for each byte */
|
||||
for(byteIndex = 0u; byteIndex < Length; byteIndex++)
|
||||
/* Do calculation procedure for each byte */
|
||||
for(byteIndex = 0u; byteIndex < Length; byteIndex++)
|
||||
{
|
||||
/* XOR new byte with temp result */
|
||||
retVal ^= (Buffer[byteIndex] << (CRC_16_RESULT_WIDTH - 8u));
|
||||
/* XOR new byte with temp result */
|
||||
retVal ^= (Buffer[byteIndex] << (CRC_16_RESULT_WIDTH - 8u));
|
||||
|
||||
uint8_t bitIndex = 0u;
|
||||
/* Do calculation for current data */
|
||||
for(bitIndex = 0u; bitIndex < 8u; bitIndex++)
|
||||
/* Do calculation for current data */
|
||||
for(bitIndex = 0u; bitIndex < 8u; bitIndex++)
|
||||
{
|
||||
if(retVal & (1u << (CRC_16_RESULT_WIDTH - 1u)))
|
||||
if(retVal & (1u << (CRC_16_RESULT_WIDTH - 1u)))
|
||||
{
|
||||
retVal = (retVal << 1u) ^ CRC_16_POLYNOMIAL;
|
||||
}
|
||||
else
|
||||
retVal = (retVal << 1u) ^ CRC_16_POLYNOMIAL;
|
||||
}
|
||||
else
|
||||
{
|
||||
retVal = (retVal << 1u);
|
||||
}
|
||||
}
|
||||
}
|
||||
retVal = (retVal << 1u);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* XOR result with specified value */
|
||||
retVal ^= CRC_16_XOR_VALUE;
|
||||
/* XOR result with specified value */
|
||||
retVal ^= CRC_16_XOR_VALUE;
|
||||
|
||||
#elif (CRC_16_MODE==TABLE)
|
||||
retVal = CRC_16_INIT_VALUE;
|
||||
retVal = CRC_16_INIT_VALUE;
|
||||
|
||||
/* Update the CRC using the data */
|
||||
for(byteIndex = 0u; byteIndex < Length; byteIndex++)
|
||||
/* Update the CRC using the data */
|
||||
for(byteIndex = 0u; byteIndex < Length; byteIndex++)
|
||||
{
|
||||
retVal = (retVal << 8u) ^ CRC16Table[(retVal >> 8u) ^ Buffer[byteIndex]];
|
||||
}
|
||||
retVal = (retVal << 8u) ^ CRC16Table[(retVal >> 8u) ^ Buffer[byteIndex]];
|
||||
}
|
||||
|
||||
/* XOR result with specified value */
|
||||
retVal ^= CRC_16_XOR_VALUE;
|
||||
/* XOR result with specified value */
|
||||
retVal ^= CRC_16_XOR_VALUE;
|
||||
#else
|
||||
/* Mode not implemented */
|
||||
retVal = 0x0000u;
|
||||
/* Mode not implemented */
|
||||
retVal = 0x0000u;
|
||||
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
return retVal;
|
||||
return retVal;
|
||||
}
|
||||
|
||||
|
||||
uint32_t CRC_CalculateCRC32(const uint8_t *Buffer, uint16_t Length)
|
||||
{
|
||||
uint32_t retVal = 0u;
|
||||
uint16_t byteIndex = 0u;
|
||||
uint32_t retVal = 0u;
|
||||
uint16_t byteIndex = 0u;
|
||||
|
||||
|
||||
if(Buffer != NULL)
|
||||
if(Buffer != NULL)
|
||||
{
|
||||
#if (CRC_32_MODE==RUNTTIME)
|
||||
retVal = CRC_32_INIT_VALUE;
|
||||
retVal = CRC_32_INIT_VALUE;
|
||||
|
||||
/* Do calculation procedure for each byte */
|
||||
for(byteIndex = 0u; byteIndex < Length; byteIndex++)
|
||||
for(byteIndex = 0u; byteIndex < Length; byteIndex++)
|
||||
{
|
||||
/* XOR new byte with temp result */
|
||||
retVal ^= (CRC_ReverseBitOrder8(Buffer[byteIndex]) << (CRC_32_RESULT_WIDTH - 8u));
|
||||
|
||||
uint8_t bitIndex = 0u;
|
||||
/* Do calculation for current data */
|
||||
for(bitIndex = 0u; bitIndex < 8u; bitIndex++)
|
||||
for(bitIndex = 0u; bitIndex < 8u; bitIndex++)
|
||||
{
|
||||
if(retVal & (1u << (CRC_32_RESULT_WIDTH - 1u)))
|
||||
{
|
||||
|
@ -199,59 +199,59 @@ uint32_t CRC_CalculateCRC32(const uint8_t *Buffer, uint16_t Length)
|
|||
}
|
||||
|
||||
/* XOR result with specified value */
|
||||
retVal ^= CRC_32_XOR_VALUE;
|
||||
retVal ^= CRC_32_XOR_VALUE;
|
||||
|
||||
#elif (CRC_32_MODE==TABLE)
|
||||
uint8_t data = 0u;
|
||||
|
||||
retVal = CRC_32_INIT_VALUE;
|
||||
retVal = CRC_32_INIT_VALUE;
|
||||
|
||||
for(byteIndex = 0u; byteIndex < Length; ++byteIndex)
|
||||
for(byteIndex = 0u; byteIndex < Length; ++byteIndex)
|
||||
{
|
||||
data = CRC_ReverseBitOrder8(Buffer[byteIndex]) ^ (retVal >> (CRC_32_RESULT_WIDTH - 8u));
|
||||
retVal = CRC32Table[data] ^ (retVal << 8u);
|
||||
}
|
||||
|
||||
/* XOR result with specified value */
|
||||
retVal ^= CRC_32_XOR_VALUE;
|
||||
/* XOR result with specified value */
|
||||
retVal ^= CRC_32_XOR_VALUE;
|
||||
|
||||
#else
|
||||
/* Mode not implemented */
|
||||
retVal = 0x00000000u;
|
||||
/* Mode not implemented */
|
||||
retVal = 0x00000000u;
|
||||
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
/* Reflect result */
|
||||
retVal = CRC_ReverseBitOrder32(retVal);
|
||||
|
||||
return retVal;
|
||||
return retVal;
|
||||
}
|
||||
|
||||
|
||||
static void CRC_CalculateCRC8Table(void)
|
||||
{
|
||||
#if (CRC_8_MODE==TABLE)
|
||||
uint16_t i = 0u, j = 0u;
|
||||
uint16_t i = 0u, j = 0u;
|
||||
|
||||
for(i = 0u; i < 256u; ++i)
|
||||
{
|
||||
uint8_t curr = i;
|
||||
for(i = 0u; i < 256u; ++i)
|
||||
{
|
||||
uint8_t curr = i;
|
||||
|
||||
for(j = 0u; j < 8u; ++j)
|
||||
{
|
||||
if((curr & 0x80u) != 0u)
|
||||
{
|
||||
curr = (curr << 1u) ^ CRC_8_POLYNOMIAL;
|
||||
}
|
||||
else
|
||||
{
|
||||
curr <<= 1u;
|
||||
}
|
||||
}
|
||||
for(j = 0u; j < 8u; ++j)
|
||||
{
|
||||
if((curr & 0x80u) != 0u)
|
||||
{
|
||||
curr = (curr << 1u) ^ CRC_8_POLYNOMIAL;
|
||||
}
|
||||
else
|
||||
{
|
||||
curr <<= 1u;
|
||||
}
|
||||
}
|
||||
|
||||
CRC8Table[i] = curr;
|
||||
}
|
||||
CRC8Table[i] = curr;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -259,29 +259,29 @@ static void CRC_CalculateCRC8Table(void)
|
|||
static void CRC_CalculateCRC16Table(void)
|
||||
{
|
||||
#if (CRC_16_MODE==TABLE)
|
||||
uint16_t i = 0u, j = 0u;
|
||||
uint16_t result = 0u;
|
||||
uint16_t xor_flag = 0u;
|
||||
uint16_t i = 0u, j = 0u;
|
||||
uint16_t result = 0u;
|
||||
uint16_t xor_flag = 0u;
|
||||
|
||||
for(i = 0u; i < 256u; i++)
|
||||
{
|
||||
result = i << 8u;
|
||||
for(i = 0u; i < 256u; i++)
|
||||
{
|
||||
result = i << 8u;
|
||||
|
||||
for(j = 0u; j < 8u; j++)
|
||||
{
|
||||
/* Flag for XOR if leftmost bit is set */
|
||||
xor_flag = result & 0x8000u;
|
||||
for(j = 0u; j < 8u; j++)
|
||||
{
|
||||
/* Flag for XOR if leftmost bit is set */
|
||||
xor_flag = result & 0x8000u;
|
||||
|
||||
/* Shift CRC */
|
||||
result <<= 1u;
|
||||
/* Shift CRC */
|
||||
result <<= 1u;
|
||||
|
||||
/* Perform the XOR */
|
||||
if(xor_flag != 0u)
|
||||
result ^= CRC_16_POLYNOMIAL;
|
||||
}
|
||||
/* Perform the XOR */
|
||||
if(xor_flag != 0u)
|
||||
result ^= CRC_16_POLYNOMIAL;
|
||||
}
|
||||
|
||||
CRC16Table[i] = result;
|
||||
}
|
||||
CRC16Table[i] = result;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -331,7 +331,7 @@ static uint32_t CRC_ReverseBitOrder32(uint32_t value)
|
|||
{
|
||||
reversed |= (value & 1u) << i;
|
||||
value >>= 1u;
|
||||
-- i;
|
||||
--i;
|
||||
}
|
||||
|
||||
return reversed;
|
||||
|
|
|
@ -27,31 +27,31 @@ extern "C" {
|
|||
#endif
|
||||
|
||||
|
||||
#define RUNTTIME 0
|
||||
#define TABLE 1
|
||||
#define HARDWARE 2
|
||||
#define RUNTTIME 0
|
||||
#define TABLE 1
|
||||
#define HARDWARE 2
|
||||
|
||||
|
||||
/* ---------- Defines for 8-bit SAE J1850 CRC calculation (Not reflected) ------------------------------------------------------- */
|
||||
/* ---------- Defines for 8-bit SAE J1850 CRC calculation (Not reflected) ------------------------------------------------------- */
|
||||
#define CRC_8_RESULT_WIDTH 8u
|
||||
#define CRC_8_POLYNOMIAL 0x1Du
|
||||
#define CRC_8_INIT_VALUE 0xFFu
|
||||
#define CRC_8_XOR_VALUE 0xFFu
|
||||
#define CRC_8_MODE TABLE
|
||||
#define CRC_8_MODE TABLE
|
||||
|
||||
/* ---------- Defines for 16-bit CCITT CRC calculation (Not reflected) ---------------------------------------------------------- */
|
||||
/* ---------- Defines for 16-bit CCITT CRC calculation (Not reflected) ---------------------------------------------------------- */
|
||||
#define CRC_16_RESULT_WIDTH 16u
|
||||
#define CRC_16_POLYNOMIAL 0x1021u
|
||||
#define CRC_16_INIT_VALUE 0xFFFFu
|
||||
#define CRC_16_XOR_VALUE 0x0000u
|
||||
#define CRC_16_MODE RUNTTIME
|
||||
#define CRC_16_MODE RUNTTIME
|
||||
|
||||
/* ---------- Defines for 32-bit CCITT CRC calculation (Reflected) -------------------------------------------------------------- */
|
||||
/* ---------- Defines for 32-bit CCITT CRC calculation (Reflected) -------------------------------------------------------------- */
|
||||
#define CRC_32_RESULT_WIDTH 32u
|
||||
#define CRC_32_POLYNOMIAL 0x04C11DB7u
|
||||
#define CRC_32_INIT_VALUE 0xFFFFFFFFu
|
||||
#define CRC_32_XOR_VALUE 0xFFFFFFFFu
|
||||
#define CRC_32_MODE RUNTTIME
|
||||
#define CRC_32_MODE RUNTTIME
|
||||
|
||||
|
||||
|
||||
|
|
14
Src/M24C0X.c
14
Src/M24C0X.c
|
@ -38,14 +38,14 @@ void M24C0X_Init(void)
|
|||
|
||||
// Initialize write protection pin
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
|
||||
// Enable write protection
|
||||
GPIO_SetBits(GPIOB, GPIO_Pin_12);
|
||||
GPIO_SetBits(GPIOB, GPIO_Pin_12);
|
||||
|
||||
I2C_Mode_t mode = {I2C_SPEED, I2C_Mode_I2C, I2C_Ack_Enable};
|
||||
I2C_Initialize(M24C0X_I2C, &mode);
|
||||
|
@ -170,7 +170,7 @@ uint8_t M24C0X_WriteByteArray(uint16_t addr, uint8_t *pData, uint16_t len)
|
|||
|
||||
static void M24C0X_WriteProtection(uint8_t enable)
|
||||
{
|
||||
__ASM("nop");
|
||||
__ASM("nop");
|
||||
|
||||
if(enable)
|
||||
{
|
||||
|
|
|
@ -6,41 +6,41 @@
|
|||
|
||||
|
||||
//---- I2C ----//
|
||||
#define EEPROM_I2C I2C1
|
||||
#define EEPROM_I2C I2C1
|
||||
|
||||
|
||||
//---- SPI ----//
|
||||
#define SPI_W5500 SPI3
|
||||
#define SPI_W5500 SPI3
|
||||
|
||||
|
||||
//---- USART ----//
|
||||
// Number of used USARTs on this device
|
||||
//#define USART_NUM 2
|
||||
//#define USART_NUM 2
|
||||
|
||||
// Numerate available USARTs in ascending order
|
||||
//#define USART1_NUM 0
|
||||
//#define USART2_NUM 1
|
||||
//#define USART6_NUM 2
|
||||
//#define USART1_NUM 0
|
||||
//#define USART2_NUM 1
|
||||
//#define USART6_NUM 2
|
||||
|
||||
// USART used for Printf(...)
|
||||
#define STDOUT USART2
|
||||
#define STDOUT_NUM USART2_NUM
|
||||
//#define STDOUT_BAUD 115200
|
||||
#define STDOUT USART2
|
||||
#define STDOUT_NUM USART2_NUM
|
||||
//#define STDOUT_BAUD 115200
|
||||
|
||||
|
||||
//---- Defines ----//
|
||||
|
||||
// Direction definitions
|
||||
#define FIFO_DIR_RX 0
|
||||
#define FIFO_DIR_TX 1
|
||||
#define FIFO_DIR_RX 0
|
||||
#define FIFO_DIR_TX 1
|
||||
|
||||
|
||||
// Communication interface
|
||||
// Comment out to use serial interface
|
||||
//#define ETH_IF
|
||||
|
||||
#define ETH_SOCK 0
|
||||
#define ETH_PORT 30501
|
||||
#define ETH_SOCK 0
|
||||
#define ETH_PORT 30501
|
||||
|
||||
|
||||
#endif /* PLATFORM_H_INCLUDED */
|
||||
|
|
131
Src/Print.c
131
Src/Print.c
|
@ -20,20 +20,20 @@ static uint16_t buf_idx = 0;
|
|||
|
||||
void Print_Init(void)
|
||||
{
|
||||
Usart_Init(STDOUT, BAUD_RATE);
|
||||
Usart_Init(STDOUT, BAUD_RATE);
|
||||
}
|
||||
|
||||
|
||||
int Printf(const char *str, ...)
|
||||
{
|
||||
char buffer[MAX_BUFFER_SIZE];
|
||||
uint8_t idx = 0;
|
||||
char buffer[MAX_BUFFER_SIZE];
|
||||
uint8_t idx = 0;
|
||||
|
||||
va_list vl;
|
||||
va_start(vl, str);
|
||||
int i = vsnprintf(buffer, MAX_BUFFER_SIZE, str, vl);
|
||||
va_list vl;
|
||||
va_start(vl, str);
|
||||
int i = vsnprintf(buffer, MAX_BUFFER_SIZE, str, vl);
|
||||
|
||||
if(i > MAX_BUFFER_SIZE)
|
||||
if(i > MAX_BUFFER_SIZE)
|
||||
{
|
||||
i = MAX_BUFFER_SIZE;
|
||||
}
|
||||
|
@ -48,17 +48,18 @@ int Printf(const char *str, ...)
|
|||
va_end(vl);
|
||||
|
||||
// Return number of sent bytes
|
||||
return idx;
|
||||
return idx;
|
||||
}
|
||||
|
||||
|
||||
int8_t Getc(char *c)
|
||||
{
|
||||
if(FifoUsart_Get(STDOUT_NUM, USART_DIR_RX, c) == 0) {
|
||||
return 0;
|
||||
}
|
||||
if(FifoUsart_Get(STDOUT_NUM, USART_DIR_RX, c) == 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
return -1;
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
|
@ -67,7 +68,7 @@ int Putc(const char c)
|
|||
buf[buf_idx++] = c;
|
||||
//Usart_Put(STDOUT, false, c);
|
||||
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
@ -103,48 +104,56 @@ void Print_Flush(void)
|
|||
// techniques are actually just slightly slower. Found this out the hard way.
|
||||
void PrintFloat(float n, uint8_t decimal_places)
|
||||
{
|
||||
if(n < 0) {
|
||||
Putc('-');
|
||||
n = -n;
|
||||
}
|
||||
if(n < 0)
|
||||
{
|
||||
Putc('-');
|
||||
n = -n;
|
||||
}
|
||||
|
||||
uint8_t decimals = decimal_places;
|
||||
uint8_t decimals = decimal_places;
|
||||
|
||||
while(decimals >= 2) { // Quickly convert values expected to be E0 to E-4.
|
||||
n *= 100;
|
||||
decimals -= 2;
|
||||
}
|
||||
while(decimals >= 2) // Quickly convert values expected to be E0 to E-4.
|
||||
{
|
||||
n *= 100;
|
||||
decimals -= 2;
|
||||
}
|
||||
|
||||
if(decimals) {
|
||||
n *= 10;
|
||||
}
|
||||
n += 0.5; // Add rounding factor. Ensures carryover through entire value.
|
||||
if(decimals)
|
||||
{
|
||||
n *= 10;
|
||||
}
|
||||
n += 0.5; // Add rounding factor. Ensures carryover through entire value.
|
||||
|
||||
// Generate digits backwards and store in string.
|
||||
unsigned char buf[13];
|
||||
uint8_t i = 0;
|
||||
uint32_t a = (long)n;
|
||||
// Generate digits backwards and store in string.
|
||||
unsigned char buf[13];
|
||||
uint8_t i = 0;
|
||||
uint32_t a = (long)n;
|
||||
|
||||
while(a > 0) {
|
||||
buf[i++] = (a % 10) + '0'; // Get digit
|
||||
a /= 10;
|
||||
}
|
||||
while(a > 0)
|
||||
{
|
||||
buf[i++] = (a % 10) + '0'; // Get digit
|
||||
a /= 10;
|
||||
}
|
||||
|
||||
while(i < decimal_places) {
|
||||
buf[i++] = '0'; // Fill in zeros to decimal point for (n < 1)
|
||||
}
|
||||
while(i < decimal_places)
|
||||
{
|
||||
buf[i++] = '0'; // Fill in zeros to decimal point for (n < 1)
|
||||
}
|
||||
|
||||
if(i == decimal_places) { // Fill in leading zero, if needed.
|
||||
buf[i++] = '0';
|
||||
}
|
||||
if(i == decimal_places) // Fill in leading zero, if needed.
|
||||
{
|
||||
buf[i++] = '0';
|
||||
}
|
||||
|
||||
// Print the generated string.
|
||||
for(; i > 0; i--) {
|
||||
if(i == decimal_places) {
|
||||
Putc('.');
|
||||
} // Insert decimal point in right place.
|
||||
Putc(buf[i-1]);
|
||||
}
|
||||
// Print the generated string.
|
||||
for(; i > 0; i--)
|
||||
{
|
||||
if(i == decimal_places)
|
||||
{
|
||||
Putc('.');
|
||||
} // Insert decimal point in right place.
|
||||
Putc(buf[i-1]);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
@ -154,21 +163,25 @@ void PrintFloat(float n, uint8_t decimal_places)
|
|||
// - RateValue: Handles feed rate and current velocity in inches or mm reporting.
|
||||
void PrintFloat_CoordValue(float n)
|
||||
{
|
||||
if(BIT_IS_TRUE(settings.flags, BITFLAG_REPORT_INCHES)) {
|
||||
PrintFloat(n*INCH_PER_MM,N_DECIMAL_COORDVALUE_INCH);
|
||||
}
|
||||
else {
|
||||
PrintFloat(n, N_DECIMAL_COORDVALUE_MM);
|
||||
}
|
||||
if(BIT_IS_TRUE(settings.flags, BITFLAG_REPORT_INCHES))
|
||||
{
|
||||
PrintFloat(n*INCH_PER_MM,N_DECIMAL_COORDVALUE_INCH);
|
||||
}
|
||||
else
|
||||
{
|
||||
PrintFloat(n, N_DECIMAL_COORDVALUE_MM);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void PrintFloat_RateValue(float n)
|
||||
{
|
||||
if(BIT_IS_TRUE(settings.flags, BITFLAG_REPORT_INCHES)) {
|
||||
PrintFloat(n*INCH_PER_MM,N_DECIMAL_RATEVALUE_INCH);
|
||||
}
|
||||
else {
|
||||
PrintFloat(n, N_DECIMAL_RATEVALUE_MM);
|
||||
}
|
||||
if(BIT_IS_TRUE(settings.flags, BITFLAG_REPORT_INCHES))
|
||||
{
|
||||
PrintFloat(n*INCH_PER_MM,N_DECIMAL_RATEVALUE_INCH);
|
||||
}
|
||||
else
|
||||
{
|
||||
PrintFloat(n, N_DECIMAL_RATEVALUE_MM);
|
||||
}
|
||||
}
|
||||
|
|
179
grbl/Config.h
179
grbl/Config.h
|
@ -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-2020 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
|
||||
|
@ -28,8 +28,8 @@
|
|||
#define CONFIG_H
|
||||
|
||||
|
||||
#define GRBL_VERSION "1.1"
|
||||
#define GRBL_VERSION_BUILD __DATE__
|
||||
#define GRBL_VERSION "1.1i"
|
||||
#define GRBL_VERSION_BUILD __DATE__
|
||||
|
||||
|
||||
// Define CPU pin map and default settings.
|
||||
|
@ -38,10 +38,9 @@
|
|||
// If doing so, simply comment out these two defines and see instructions below.
|
||||
#define DEFAULTS_GENERIC
|
||||
|
||||
|
||||
// Serial baud rate
|
||||
#define BAUD_RATE 115200
|
||||
//#define BAUD_RATE 230400
|
||||
#define BAUD_RATE 115200
|
||||
//#define BAUD_RATE 230400
|
||||
|
||||
|
||||
// Uncomment to use external I2C EEPROM
|
||||
|
@ -57,12 +56,12 @@
|
|||
// 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_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
|
||||
#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
|
||||
|
@ -73,32 +72,32 @@
|
|||
// #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.
|
||||
#define CMD_FEED_OVR_RESET 0x90 // Restores feed override value to 100%.
|
||||
#define CMD_FEED_OVR_COARSE_PLUS 0x91
|
||||
#define CMD_FEED_OVR_COARSE_MINUS 0x92
|
||||
#define CMD_FEED_OVR_FINE_PLUS 0x93
|
||||
#define CMD_FEED_OVR_FINE_MINUS 0x94
|
||||
#define CMD_RAPID_OVR_RESET 0x95 // Restores rapid override value to 100%.
|
||||
#define CMD_RAPID_OVR_MEDIUM 0x96
|
||||
#define CMD_RAPID_OVR_LOW 0x97
|
||||
//#define CMD_RAPID_OVR_EXTRA_LOW 0x98 // *NOT SUPPORTED*
|
||||
#define CMD_SPINDLE_OVR_RESET 0x99 // Restores spindle override value to 100%.
|
||||
#define CMD_SPINDLE_OVR_COARSE_PLUS 0x9A
|
||||
#define CMD_SPINDLE_OVR_COARSE_MINUS 0x9B
|
||||
#define CMD_SPINDLE_OVR_FINE_PLUS 0x9C
|
||||
#define CMD_SPINDLE_OVR_FINE_MINUS 0x9D
|
||||
#define CMD_SPINDLE_OVR_STOP 0x9E
|
||||
#define CMD_COOLANT_FLOOD_OVR_TOGGLE 0xA0
|
||||
#define CMD_COOLANT_MIST_OVR_TOGGLE 0xA1
|
||||
#define CMD_SAFETY_DOOR 0x84
|
||||
#define CMD_JOG_CANCEL 0x85
|
||||
#define CMD_DEBUG_REPORT 0x86 // Only when DEBUG enabled, sends debug report in '{}' braces.
|
||||
#define CMD_FEED_OVR_RESET 0x90 // Restores feed override value to 100%.
|
||||
#define CMD_FEED_OVR_COARSE_PLUS 0x91
|
||||
#define CMD_FEED_OVR_COARSE_MINUS 0x92
|
||||
#define CMD_FEED_OVR_FINE_PLUS 0x93
|
||||
#define CMD_FEED_OVR_FINE_MINUS 0x94
|
||||
#define CMD_RAPID_OVR_RESET 0x95 // Restores rapid override value to 100%.
|
||||
#define CMD_RAPID_OVR_MEDIUM 0x96
|
||||
#define CMD_RAPID_OVR_LOW 0x97
|
||||
//#define CMD_RAPID_OVR_EXTRA_LOW 0x98 // *NOT SUPPORTED*
|
||||
#define CMD_SPINDLE_OVR_RESET 0x99 // Restores spindle override value to 100%.
|
||||
#define CMD_SPINDLE_OVR_COARSE_PLUS 0x9A
|
||||
#define CMD_SPINDLE_OVR_COARSE_MINUS 0x9B
|
||||
#define CMD_SPINDLE_OVR_FINE_PLUS 0x9C
|
||||
#define CMD_SPINDLE_OVR_FINE_MINUS 0x9D
|
||||
#define CMD_SPINDLE_OVR_STOP 0x9E
|
||||
#define CMD_COOLANT_FLOOD_OVR_TOGGLE 0xA0
|
||||
#define CMD_COOLANT_MIST_OVR_TOGGLE 0xA1
|
||||
|
||||
|
||||
// If homing is enabled, homing init lock sets Grbl into an alarm state upon power up. This forces
|
||||
// the user to perform the homing cycle (or override the locks) before doing anything else. This is
|
||||
// mainly a safety feature to remind the user to home, since position is unknown to Grbl.
|
||||
#define HOMING_INIT_LOCK // Comment to disable
|
||||
#define HOMING_INIT_LOCK // Comment to disable
|
||||
|
||||
|
||||
// Define the homing cycle patterns with bitmasks. The homing cycle first performs a search mode
|
||||
|
@ -116,21 +115,21 @@
|
|||
// 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) // REQUIRED: First move Z to clear workspace.
|
||||
#define HOMING_CYCLE_1 ((1<<X_AXIS)|(1<<Y_AXIS)) // OPTIONAL: Then move X,Y at the same time.
|
||||
#define HOMING_CYCLE_0 (1<<Z_AXIS) // REQUIRED: First move Z to clear workspace.
|
||||
#define HOMING_CYCLE_1 ((1<<X_AXIS)|(1<<Y_AXIS)) // OPTIONAL: Then move X,Y at the same time.
|
||||
// #define HOMING_CYCLE_2 // OPTIONAL: Uncomment and add axes mask to enable
|
||||
|
||||
// NOTE: The following are two examples to setup homing for 2-axis machines.
|
||||
//#define HOMING_CYCLE_0 ((1<<X_AXIS)|(1<<Y_AXIS)) // NOT COMPATIBLE WITH COREXY: Homes both X-Y in one cycle.
|
||||
//#define HOMING_CYCLE_0 ((1<<X_AXIS)|(1<<Y_AXIS)) // NOT COMPATIBLE WITH COREXY: Homes both X-Y in one cycle.
|
||||
|
||||
//#define HOMING_CYCLE_0 (1<<X_AXIS) // COREXY COMPATIBLE: First home X
|
||||
//#define HOMING_CYCLE_1 (1<<Y_AXIS) // COREXY COMPATIBLE: Then home Y
|
||||
//#define HOMING_CYCLE_0 (1<<X_AXIS) // COREXY COMPATIBLE: First home X
|
||||
//#define HOMING_CYCLE_1 (1<<Y_AXIS) // COREXY COMPATIBLE: Then home Y
|
||||
|
||||
|
||||
// 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)
|
||||
#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
|
||||
|
@ -148,8 +147,8 @@
|
|||
// and addresses are defined in settings.h. With the current settings, up to 2 startup blocks may
|
||||
// be stored and executed in order. These startup blocks would typically be used to set the g-code
|
||||
// parser state depending on user preferences.
|
||||
#define N_STARTUP_LINE 0 // Integer (1-2)
|
||||
#define STARTUP_LINE_LEN 80
|
||||
#define N_STARTUP_LINE 0 // Integer (1-2)
|
||||
#define STARTUP_LINE_LEN 80
|
||||
|
||||
|
||||
// Number of floating decimal points printed by Grbl for certain value types. These settings are
|
||||
|
@ -157,12 +156,12 @@
|
|||
// values cannot be less than 0.001mm or 0.0001in, because machines can not be physically more
|
||||
// precise this. So, there is likely no need to change these, but you can if you need to here.
|
||||
// NOTE: Must be an integer value from 0 to ~4. More than 4 may exhibit round-off errors.
|
||||
#define N_DECIMAL_COORDVALUE_INCH 4 // Coordinate or position value in inches
|
||||
#define N_DECIMAL_COORDVALUE_MM 3 // Coordinate or position value in mm
|
||||
#define N_DECIMAL_RATEVALUE_INCH 1 // Rate or velocity value in in/min
|
||||
#define N_DECIMAL_RATEVALUE_MM 0 // Rate or velocity value in mm/min
|
||||
#define N_DECIMAL_SETTINGVALUE 3 // Decimals for floating point setting values
|
||||
#define N_DECIMAL_RPMVALUE 0 // RPM value in rotations per min.
|
||||
#define N_DECIMAL_COORDVALUE_INCH 4 // Coordinate or position value in inches
|
||||
#define N_DECIMAL_COORDVALUE_MM 3 // Coordinate or position value in mm
|
||||
#define N_DECIMAL_RATEVALUE_INCH 1 // Rate or velocity value in in/min
|
||||
#define N_DECIMAL_RATEVALUE_MM 0 // Rate or velocity value in mm/min
|
||||
#define N_DECIMAL_SETTINGVALUE 3 // Decimals for floating point setting values
|
||||
#define N_DECIMAL_RPMVALUE 0 // RPM value in rotations per min.
|
||||
|
||||
|
||||
// If your machine has two limits switches wired in parallel to one axis, you will need to enable
|
||||
|
@ -188,8 +187,8 @@
|
|||
|
||||
// After the safety door switch has been toggled and restored, this setting sets the power-up delay
|
||||
// between restoring the spindle and coolant and resuming the cycle.
|
||||
#define SAFETY_DOOR_SPINDLE_DELAY 2.0 // Float (seconds)
|
||||
#define SAFETY_DOOR_COOLANT_DELAY 1.0 // Float (seconds)
|
||||
#define SAFETY_DOOR_SPINDLE_DELAY 2.0 // Float (seconds)
|
||||
#define SAFETY_DOOR_COOLANT_DELAY 1.0 // Float (seconds)
|
||||
|
||||
|
||||
// Enable CoreXY kinematics. Use ONLY with CoreXY machines.
|
||||
|
@ -208,7 +207,7 @@
|
|||
// will be applied to all of them. This is useful when a user has a mixed set of limit pins with both
|
||||
// normally-open(NO) and normally-closed(NC) switches installed on their machine.
|
||||
// NOTE: PLEASE DO NOT USE THIS, unless you have a situation that needs it.
|
||||
//#define INVERT_LIMIT_PIN_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)) // Default disabled. Uncomment to enable.
|
||||
//#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
|
||||
|
@ -247,22 +246,22 @@
|
|||
// Configure rapid, feed, and spindle override settings. These values define the max and min
|
||||
// allowable override values and the coarse and fine increments per command received. Please
|
||||
// note the allowable values in the descriptions following each define.
|
||||
#define DEFAULT_FEED_OVERRIDE 100 // 100%. Don't change this value.
|
||||
#define MAX_FEED_RATE_OVERRIDE 200 // Percent of programmed feed rate (100-255). Usually 120% or 200%
|
||||
#define MIN_FEED_RATE_OVERRIDE 10 // Percent of programmed feed rate (1-100). Usually 50% or 1%
|
||||
#define FEED_OVERRIDE_COARSE_INCREMENT 10 // (1-99). Usually 10%.
|
||||
#define FEED_OVERRIDE_FINE_INCREMENT 1 // (1-99). Usually 1%.
|
||||
#define DEFAULT_FEED_OVERRIDE 100 // 100%. Don't change this value.
|
||||
#define MAX_FEED_RATE_OVERRIDE 200 // Percent of programmed feed rate (100-255). Usually 120% or 200%
|
||||
#define MIN_FEED_RATE_OVERRIDE 10 // Percent of programmed feed rate (1-100). Usually 50% or 1%
|
||||
#define FEED_OVERRIDE_COARSE_INCREMENT 10 // (1-99). Usually 10%.
|
||||
#define FEED_OVERRIDE_FINE_INCREMENT 1 // (1-99). Usually 1%.
|
||||
|
||||
#define DEFAULT_RAPID_OVERRIDE 100 // 100%. Don't change this value.
|
||||
#define RAPID_OVERRIDE_MEDIUM 50 // Percent of rapid (1-99). Usually 50%.
|
||||
#define RAPID_OVERRIDE_LOW 25 // Percent of rapid (1-99). Usually 25%.
|
||||
//#define RAPID_OVERRIDE_EXTRA_LOW 5 // *NOT SUPPORTED* Percent of rapid (1-99). Usually 5%.
|
||||
#define DEFAULT_RAPID_OVERRIDE 100 // 100%. Don't change this value.
|
||||
#define RAPID_OVERRIDE_MEDIUM 50 // Percent of rapid (1-99). Usually 50%.
|
||||
#define RAPID_OVERRIDE_LOW 25 // Percent of rapid (1-99). Usually 25%.
|
||||
//#define RAPID_OVERRIDE_EXTRA_LOW 5 // *NOT SUPPORTED* Percent of rapid (1-99). Usually 5%.
|
||||
|
||||
#define DEFAULT_SPINDLE_SPEED_OVERRIDE 100 // 100%. Don't change this value.
|
||||
#define MAX_SPINDLE_SPEED_OVERRIDE 200 // Percent of programmed spindle speed (100-255). Usually 200%.
|
||||
#define MIN_SPINDLE_SPEED_OVERRIDE 10 // Percent of programmed spindle speed (1-100). Usually 10%.
|
||||
#define SPINDLE_OVERRIDE_COARSE_INCREMENT 10 // (1-99). Usually 10%.
|
||||
#define SPINDLE_OVERRIDE_FINE_INCREMENT 1 // (1-99). Usually 1%.
|
||||
#define DEFAULT_SPINDLE_SPEED_OVERRIDE 100 // 100%. Don't change this value.
|
||||
#define MAX_SPINDLE_SPEED_OVERRIDE 200 // Percent of programmed spindle speed (100-255). Usually 200%.
|
||||
#define MIN_SPINDLE_SPEED_OVERRIDE 10 // Percent of programmed spindle speed (1-100). Usually 10%.
|
||||
#define SPINDLE_OVERRIDE_COARSE_INCREMENT 10 // (1-99). Usually 10%.
|
||||
#define SPINDLE_OVERRIDE_FINE_INCREMENT 1 // (1-99). Usually 1%.
|
||||
|
||||
|
||||
// When a M2 or M30 program end command is executed, most g-code states are restored to their defaults.
|
||||
|
@ -294,10 +293,10 @@
|
|||
// refreshes more often when its not doing anything important. With a good GUI, this data doesn't need
|
||||
// to be refreshed very often, on the order of a several seconds.
|
||||
// NOTE: WCO refresh must be 2 or greater. OVR refresh must be 1 or greater.
|
||||
#define REPORT_OVR_REFRESH_BUSY_COUNT 20 // (1-255)
|
||||
#define REPORT_OVR_REFRESH_IDLE_COUNT 10 // (1-255) Must be less than or equal to the busy count
|
||||
#define REPORT_WCO_REFRESH_BUSY_COUNT 30 // (2-255)
|
||||
#define REPORT_WCO_REFRESH_IDLE_COUNT 10 // (2-255) Must be less than or equal to the busy count
|
||||
#define REPORT_OVR_REFRESH_BUSY_COUNT 20 // (1-255)
|
||||
#define REPORT_OVR_REFRESH_IDLE_COUNT 10 // (1-255) Must be less than or equal to the busy count
|
||||
#define REPORT_WCO_REFRESH_BUSY_COUNT 30 // (2-255)
|
||||
#define REPORT_WCO_REFRESH_IDLE_COUNT 10 // (2-255) Must be less than or equal to the busy count
|
||||
|
||||
|
||||
// The temporal resolution of the acceleration management subsystem. A higher number gives smoother
|
||||
|
@ -307,14 +306,14 @@
|
|||
// NOTE: Changing this value also changes the execution time of a segment in the step segment buffer.
|
||||
// When increasing this value, this stores less overall time in the segment buffer and vice versa. Make
|
||||
// certain the step segment buffer is increased/decreased to account for these changes.
|
||||
#define ACCELERATION_TICKS_PER_SECOND 210
|
||||
#define ACCELERATION_TICKS_PER_SECOND 210
|
||||
|
||||
|
||||
// Sets the maximum step rate allowed to be written as a Grbl setting. This option enables an error
|
||||
// check in the settings module to prevent settings values that will exceed this limitation. The maximum
|
||||
// step rate is strictly limited by the CPU speed and will change if something other than an AVR running
|
||||
// at 16MHz is used.
|
||||
#define MAX_STEP_RATE_HZ 120000 // Hz
|
||||
#define MAX_STEP_RATE_HZ 120000 // Hz
|
||||
|
||||
|
||||
// By default, Grbl sets all input pins to normal-high operation with their internal pull-up resistors
|
||||
|
@ -338,7 +337,7 @@
|
|||
// Sets which axis the tool length offset is applied. Assumes the spindle is always parallel with
|
||||
// the selected axis with the tool oriented toward the negative direction. In other words, a positive
|
||||
// tool length offset value is subtracted from the current location.
|
||||
#define TOOL_LENGTH_OFFSET_AXIS Z_AXIS // Default z-axis. Valid values are X_AXIS, Y_AXIS, or Z_AXIS.
|
||||
#define TOOL_LENGTH_OFFSET_AXIS Z_AXIS // Default z-axis. Valid values are X_AXIS, Y_AXIS, or Z_AXIS.
|
||||
|
||||
|
||||
// Enables variable spindle output voltage for different RPM values. On the Arduino Uno, the spindle
|
||||
|
@ -385,21 +384,21 @@
|
|||
// limits or angle between neighboring block line move directions. This is useful for machines that can't
|
||||
// tolerate the tool dwelling for a split second, i.e. 3d printers or laser cutters. If used, this value
|
||||
// should not be much greater than zero or to the minimum value necessary for the machine to work.
|
||||
#define MINIMUM_JUNCTION_SPEED 0.0 // (mm/min)
|
||||
#define MINIMUM_JUNCTION_SPEED 0.0 // (mm/min)
|
||||
|
||||
|
||||
// Sets the minimum feed rate the planner will allow. Any value below it will be set to this minimum
|
||||
// value. This also ensures that a planned motion always completes and accounts for any floating-point
|
||||
// round-off errors. Although not recommended, a lower value than 1.0 mm/min will likely work in smaller
|
||||
// machines, perhaps to 0.1mm/min, but your success may vary based on multiple factors.
|
||||
#define MINIMUM_FEED_RATE 1.0 // (mm/min)
|
||||
#define MINIMUM_FEED_RATE 1.0 // (mm/min)
|
||||
|
||||
|
||||
// Number of arc generation iterations by small angle approximation before exact arc trajectory
|
||||
// correction with expensive sin() and cos() calcualtions. This parameter maybe decreased if there
|
||||
// are issues with the accuracy of the arc generations, or increased if arc execution is getting
|
||||
// bogged down by too many trig calculations.
|
||||
#define N_ARC_CORRECTION 4 // Integer (1-255)
|
||||
#define N_ARC_CORRECTION 4 // Integer (1-255)
|
||||
|
||||
|
||||
// The arc G2/3 g-code standard is problematic by definition. Radius-based arcs have horrible numerical
|
||||
|
@ -410,7 +409,7 @@
|
|||
// This define value sets the machine epsilon cutoff to determine if the arc is a full-circle or not.
|
||||
// NOTE: Be very careful when adjusting this value. It should always be greater than 1.2e-7 but not too
|
||||
// much greater than this. The default setting should capture most, if not all, full arc error situations.
|
||||
#define ARC_ANGULAR_TRAVEL_EPSILON 5E-7 // Float (radians)
|
||||
#define ARC_ANGULAR_TRAVEL_EPSILON 5E-7 // Float (radians)
|
||||
|
||||
|
||||
// Time delay increments performed during a dwell. The default value is set at 50ms, which provides
|
||||
|
@ -418,7 +417,7 @@
|
|||
// this delay will increase the maximum dwell time linearly, but also reduces the responsiveness of
|
||||
// run-time command executions, like status reports, since these are performed between each dwell
|
||||
// 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)
|
||||
#define DWELL_TIME_STEP 50 // Integer (1-255) (milliseconds)
|
||||
|
||||
|
||||
// The number of linear motions in the planner buffer to be planned at any give time. The vast
|
||||
|
@ -426,7 +425,7 @@
|
|||
// available RAM, like when re-compiling for a Mega2560. Or decrease if the Arduino begins to
|
||||
// crash due to the lack of available RAM or if the CPU is having trouble keeping up with planning
|
||||
// new incoming motions as they are executed.
|
||||
#define BLOCK_BUFFER_SIZE 64 // Uncomment to override default in planner.h.
|
||||
#define BLOCK_BUFFER_SIZE 64 // Uncomment to override default in planner.h.
|
||||
|
||||
|
||||
// Governs the size of the intermediary step segment buffer between the step execution algorithm
|
||||
|
@ -435,7 +434,7 @@
|
|||
// block velocity profile is traced exactly. The size of this buffer governs how much step
|
||||
// execution lead time there is for other Grbl processes have to compute and do their thing
|
||||
// before having to come back and refill this buffer, currently at ~50msec of step moves.
|
||||
#define SEGMENT_BUFFER_SIZE 32 // Uncomment to override default in stepper.h.
|
||||
#define SEGMENT_BUFFER_SIZE 32 // Uncomment to override default in stepper.h.
|
||||
|
||||
|
||||
// Line buffer size from the serial input stream to be executed. Also, governs the size of
|
||||
|
@ -446,7 +445,7 @@
|
|||
// can be too small and g-code blocks can get truncated. Officially, the g-code standards
|
||||
// support up to 256 characters. In future versions, this default will be increased, when
|
||||
// we know how much extra memory space we can re-invest into this.
|
||||
#define LINE_BUFFER_SIZE 200 // Uncomment to override default in protocol.h
|
||||
#define LINE_BUFFER_SIZE 200 // Uncomment to override default in protocol.h
|
||||
|
||||
|
||||
// Serial send and receive buffer size. The receive buffer is often used as another streaming
|
||||
|
@ -459,8 +458,8 @@
|
|||
// 115200 will take 5 msec to transmit a typical 55 character report. Worst case reports are
|
||||
// around 90-100 characters. As long as the serial TX buffer doesn't get continually maxed, Grbl
|
||||
// will continue operating efficiently. Size the TX buffer around the size of a worst-case report.
|
||||
//#define RX_BUFFER_SIZE 128 // (1-254) Uncomment to override defaults in serial.h
|
||||
//#define TX_BUFFER_SIZE 100 // (1-254)
|
||||
//#define RX_BUFFER_SIZE 128 // (1-254) Uncomment to override defaults in serial.h
|
||||
//#define TX_BUFFER_SIZE 100 // (1-254)
|
||||
|
||||
|
||||
// Configures the position after a probing cycle during Grbl's check mode. Disabled sets
|
||||
|
@ -486,8 +485,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
|
||||
|
@ -505,7 +504,7 @@
|
|||
// written into the Arduino EEPROM via a seperate .INO sketch to contain product data. Altering this
|
||||
// macro to not restore the build info EEPROM will ensure this data is retained after firmware upgrades.
|
||||
// NOTE: Uncomment to override defaults in settings.h
|
||||
//#define SETTINGS_RESTORE_ALL (SETTINGS_RESTORE_DEFAULTS | SETTINGS_RESTORE_PARAMETERS | SETTINGS_RESTORE_STARTUP_LINES | SETTINGS_RESTORE_BUILD_INFO)
|
||||
//#define SETTINGS_RESTORE_ALL (SETTINGS_RESTORE_DEFAULTS | SETTINGS_RESTORE_PARAMETERS | SETTINGS_RESTORE_STARTUP_LINES | SETTINGS_RESTORE_BUILD_INFO)
|
||||
|
||||
|
||||
// Enable the '$I=(string)' build info write command. If disabled, any existing build info data must
|
||||
|
@ -566,12 +565,12 @@
|
|||
|
||||
|
||||
// Configure options for the parking motion, if enabled.
|
||||
#define PARKING_AXIS Z_AXIS // Define which axis that performs the parking motion
|
||||
#define PARKING_TARGET -5.0 // Parking axis target. In mm, as machine coordinate [-max_travel,0].
|
||||
#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.
|
||||
#define PARKING_AXIS Z_AXIS // Define which axis that performs the parking motion
|
||||
#define PARKING_TARGET -5.0 // Parking axis target. In mm, as machine coordinate [-max_travel,0].
|
||||
#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.
|
||||
|
||||
|
||||
// Enables a special set of M-code commands that enables and disables the parking motion.
|
||||
|
|
|
@ -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 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
|
||||
|
@ -28,8 +28,8 @@
|
|||
|
||||
void Coolant_Init(void)
|
||||
{
|
||||
GPIO_InitGPIO(GPIO_COOLANT);
|
||||
Coolant_Stop();
|
||||
GPIO_InitGPIO(GPIO_COOLANT);
|
||||
Coolant_Stop();
|
||||
}
|
||||
|
||||
|
||||
|
@ -38,17 +38,17 @@ void Coolant_Init(void)
|
|||
void Coolant_Stop(void)
|
||||
{
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
GPIO_SetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
|
||||
GPIO_SetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
|
||||
#else
|
||||
GPIO_ResetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
|
||||
GPIO_ResetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
|
||||
#endif
|
||||
|
||||
#ifdef 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
|
||||
#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
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -56,27 +56,32 @@ void Coolant_Stop(void)
|
|||
// Returns current coolant output state. Overrides may alter it from programmed state.
|
||||
uint8_t Coolant_GetState(void)
|
||||
{
|
||||
uint8_t cl_state = COOLANT_STATE_DISABLE;
|
||||
// TODO: Check if reading works
|
||||
uint8_t cl_state = COOLANT_STATE_DISABLE;
|
||||
|
||||
// TODO: Check if reading works
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
if(!GPIO_ReadInputDataBit(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN)) {
|
||||
if(!GPIO_ReadInputDataBit(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN))
|
||||
{
|
||||
#else
|
||||
if(GPIO_ReadInputDataBit(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN)) {
|
||||
if(GPIO_ReadInputDataBit(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN))
|
||||
{
|
||||
#endif
|
||||
cl_state |= COOLANT_STATE_FLOOD;
|
||||
}
|
||||
cl_state |= COOLANT_STATE_FLOOD;
|
||||
}
|
||||
|
||||
#ifdef ENABLE_M7
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
if(!GPIO_ReadInputDataBit(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN)) {
|
||||
#else
|
||||
if(GPIO_ReadInputDataBit(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN)) {
|
||||
#endif
|
||||
cl_state |= COOLANT_STATE_MIST;
|
||||
}
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
if(!GPIO_ReadInputDataBit(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN))
|
||||
{
|
||||
#else
|
||||
if(GPIO_ReadInputDataBit(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN))
|
||||
{
|
||||
#endif
|
||||
cl_state |= COOLANT_STATE_MIST;
|
||||
}
|
||||
#endif
|
||||
|
||||
return cl_state;
|
||||
return cl_state;
|
||||
}
|
||||
|
||||
|
||||
|
@ -86,19 +91,22 @@ uint8_t Coolant_GetState(void)
|
|||
// parser program end, and g-code parser coolant_sync().
|
||||
void Coolant_SetState(uint8_t mode)
|
||||
{
|
||||
if(sys.abort) {
|
||||
// Block during abort.
|
||||
return;
|
||||
}
|
||||
if(sys.abort)
|
||||
{
|
||||
// Block during abort.
|
||||
return;
|
||||
}
|
||||
|
||||
if (mode & COOLANT_FLOOD_ENABLE) {
|
||||
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
|
||||
}
|
||||
else {
|
||||
else
|
||||
{
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
GPIO_SetBits(GPIO_COOL_FLOOD_PORT, GPIO_COOL_FLOOD_PIN);
|
||||
#else
|
||||
|
@ -107,13 +115,16 @@ void Coolant_SetState(uint8_t mode)
|
|||
}
|
||||
|
||||
#ifdef ENABLE_M7
|
||||
if (mode & COOLANT_MIST_ENABLE) {
|
||||
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
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
GPIO_SetBits(GPIO_COOL_MIST_PORT, GPIO_COOL_MIST_PIN);
|
||||
#else
|
||||
|
@ -122,7 +133,7 @@ void Coolant_SetState(uint8_t mode)
|
|||
}
|
||||
#endif
|
||||
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
}
|
||||
|
||||
|
||||
|
@ -130,10 +141,11 @@ void Coolant_SetState(uint8_t mode)
|
|||
// if an abort or check-mode is active.
|
||||
void Coolant_Sync(uint8_t mode)
|
||||
{
|
||||
if(sys.state == STATE_CHECK_MODE) {
|
||||
return;
|
||||
}
|
||||
if(sys.state == STATE_CHECK_MODE)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
Protocol_BufferSynchronize(); // Ensure coolant turns on when specified in program.
|
||||
Coolant_SetState(mode);
|
||||
Protocol_BufferSynchronize(); // Ensure coolant turns on when specified in program.
|
||||
Coolant_SetState(mode);
|
||||
}
|
||||
|
|
|
@ -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 Patrick F.
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
|
@ -25,12 +25,12 @@
|
|||
#include <stdint.h>
|
||||
|
||||
|
||||
#define COOLANT_NO_SYNC false
|
||||
#define COOLANT_FORCE_SYNC true
|
||||
#define COOLANT_NO_SYNC false
|
||||
#define COOLANT_FORCE_SYNC true
|
||||
|
||||
#define COOLANT_STATE_DISABLE 0 // Must be zero
|
||||
#define COOLANT_STATE_FLOOD BIT(0)
|
||||
#define COOLANT_STATE_MIST BIT(1)
|
||||
#define COOLANT_STATE_DISABLE 0 // Must be zero
|
||||
#define COOLANT_STATE_FLOOD BIT(0)
|
||||
#define COOLANT_STATE_MIST BIT(1)
|
||||
|
||||
|
||||
// Initializes coolant control pins.
|
||||
|
|
2809
grbl/GCode.c
2809
grbl/GCode.c
Plik diff jest za duży
Load Diff
248
grbl/GCode.h
248
grbl/GCode.h
|
@ -4,7 +4,7 @@
|
|||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
Copyright (c) 2017-2020 Patrick F.
|
||||
Copyright (c) 2017-2020 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
|
||||
|
@ -33,26 +33,26 @@
|
|||
// a unique motion. These are defined in the NIST RS274-NGC v3 g-code standard, available online,
|
||||
// and are similar/identical to other g-code interpreters by manufacturers (Haas,Fanuc,Mazak,etc).
|
||||
// NOTE: Modal group define values must be sequential and starting from zero.
|
||||
#define MODAL_GROUP_G0 0 // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal
|
||||
#define MODAL_GROUP_G1 1 // [G0,G1,G2,G3,G33,G38.2,G38.3,G38.4,G38.5,G76,G80,G81,G82,G83] Motion
|
||||
#define MODAL_GROUP_G2 2 // [G17,G18,G19] Plane selection
|
||||
#define MODAL_GROUP_G3 3 // [G90,G91] Distance mode
|
||||
#define MODAL_GROUP_G4 4 // [G91.1] Arc IJK distance mode
|
||||
#define MODAL_GROUP_G5 5 // [G93,G94] Feed rate mode
|
||||
#define MODAL_GROUP_G6 6 // [G20,G21] Units
|
||||
#define MODAL_GROUP_G7 7 // [G40] Cutter radius compensation mode. G41/42 NOT SUPPORTED.
|
||||
#define MODAL_GROUP_G8 8 // [G43.1,G49] Tool length offset
|
||||
#define MODAL_GROUP_G12 9 // [G54,G55,G56,G57,G58,G59] Coordinate system selection
|
||||
#define MODAL_GROUP_G13 10 // [G61] Control mode
|
||||
#define MODAL_GROUP_G0 0 // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal
|
||||
#define MODAL_GROUP_G1 1 // [G0,G1,G2,G3,G33,G38.2,G38.3,G38.4,G38.5,G76,G80,G81,G82,G83] Motion
|
||||
#define MODAL_GROUP_G2 2 // [G17,G18,G19] Plane selection
|
||||
#define MODAL_GROUP_G3 3 // [G90,G91] Distance mode
|
||||
#define MODAL_GROUP_G4 4 // [G91.1] Arc IJK distance mode
|
||||
#define MODAL_GROUP_G5 5 // [G93,G94] Feed rate mode
|
||||
#define MODAL_GROUP_G6 6 // [G20,G21] Units
|
||||
#define MODAL_GROUP_G7 7 // [G40] Cutter radius compensation mode. G41/42 NOT SUPPORTED.
|
||||
#define MODAL_GROUP_G8 8 // [G43.1,G49] Tool length offset
|
||||
#define MODAL_GROUP_G12 9 // [G54,G55,G56,G57,G58,G59] Coordinate system selection
|
||||
#define MODAL_GROUP_G13 10 // [G61] Control mode
|
||||
|
||||
#define MODAL_GROUP_G10 11 // [G98, G99] Canned Cycles Return Mode
|
||||
#define MODAL_GROUP_G14 12 // [G96, G97] Spindle Speed Mode
|
||||
#define MODAL_GROUP_G15 13 // [G7, G8] Lathe Diameter Mode
|
||||
|
||||
#define MODAL_GROUP_M4 11 // [M0,M1,M2,M30] Stopping
|
||||
#define MODAL_GROUP_M7 12 // [M3,M4,M5] Spindle turning
|
||||
#define MODAL_GROUP_M8 13 // [M7,M8,M9] Coolant control
|
||||
#define MODAL_GROUP_M9 14 // [M56] Override control
|
||||
#define MODAL_GROUP_M4 11 // [M0,M1,M2,M30] Stopping
|
||||
#define MODAL_GROUP_M7 12 // [M3,M4,M5] Spindle turning
|
||||
#define MODAL_GROUP_M8 13 // [M7,M8,M9] Coolant control
|
||||
#define MODAL_GROUP_M9 14 // [M56] Override control
|
||||
|
||||
|
||||
// Define command actions for within execution-type modal groups (motion, stopping, non-modal). Used
|
||||
|
@ -63,28 +63,28 @@
|
|||
// 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)
|
||||
#define MOTION_MODE_LINEAR 1 // G1 (Do not alter value)
|
||||
#define MOTION_MODE_CW_ARC 2 // G2 (Do not alter value)
|
||||
#define MOTION_MODE_CCW_ARC 3 // G3 (Do not alter value)
|
||||
#define MOTION_MODE_PROBE_TOWARD 140 // G38.2 (Do not alter value)
|
||||
#define MOTION_MODE_PROBE_TOWARD_NO_ERROR 141 // G38.3 (Do not alter value)
|
||||
#define MOTION_MODE_PROBE_AWAY 142 // G38.4 (Do not alter value)
|
||||
#define MOTION_MODE_PROBE_AWAY_NO_ERROR 143 // G38.5 (Do not alter value)
|
||||
#define MOTION_MODE_NONE 80 // G80 (Do not alter value)
|
||||
#define MOTION_MODE_SEEK 0 // G0 (Default: Must be zero)
|
||||
#define MOTION_MODE_LINEAR 1 // G1 (Do not alter value)
|
||||
#define MOTION_MODE_CW_ARC 2 // G2 (Do not alter value)
|
||||
#define MOTION_MODE_CCW_ARC 3 // G3 (Do not alter value)
|
||||
#define MOTION_MODE_PROBE_TOWARD 140 // G38.2 (Do not alter value)
|
||||
#define MOTION_MODE_PROBE_TOWARD_NO_ERROR 141 // G38.3 (Do not alter value)
|
||||
#define MOTION_MODE_PROBE_AWAY 142 // G38.4 (Do not alter value)
|
||||
#define MOTION_MODE_PROBE_AWAY_NO_ERROR 143 // G38.5 (Do not alter value)
|
||||
#define MOTION_MODE_NONE 80 // G80 (Do not alter value)
|
||||
#define MOTION_MODE_DRILL 81 // G81
|
||||
#define MOTION_MODE_DRILL_DWELL 82 // G82
|
||||
#define MOTION_MODE_DRILL_PECK 83 // G83
|
||||
|
@ -92,55 +92,55 @@
|
|||
#define MOTION_MODE_THREADING 76 // G76
|
||||
|
||||
// Modal Group G2: Plane select
|
||||
#define PLANE_SELECT_XY 0 // G17 (Default: Must be zero)
|
||||
#define PLANE_SELECT_ZX 1 // G18 (Do not alter value)
|
||||
#define PLANE_SELECT_YZ 2 // G19 (Do not alter value)
|
||||
#define PLANE_SELECT_XY 0 // G17 (Default: Must be zero)
|
||||
#define PLANE_SELECT_ZX 1 // G18 (Do not alter value)
|
||||
#define PLANE_SELECT_YZ 2 // G19 (Do not alter value)
|
||||
|
||||
// Modal Group G3: Distance mode
|
||||
#define DISTANCE_MODE_ABSOLUTE 0 // G90 (Default: Must be zero)
|
||||
#define DISTANCE_MODE_INCREMENTAL 1 // G91 (Do not alter value)
|
||||
#define DISTANCE_MODE_ABSOLUTE 0 // G90 (Default: Must be zero)
|
||||
#define DISTANCE_MODE_INCREMENTAL 1 // G91 (Do not alter value)
|
||||
|
||||
// Modal Group G4: Arc IJK distance mode
|
||||
#define DISTANCE_ARC_MODE_INCREMENTAL 0 // G91.1 (Default: Must be zero)
|
||||
#define DISTANCE_ARC_MODE_INCREMENTAL 0 // G91.1 (Default: Must be zero)
|
||||
|
||||
// Modal Group M4: Program flow
|
||||
#define PROGRAM_FLOW_RUNNING 0 // (Default: Must be zero)
|
||||
#define PROGRAM_FLOW_PAUSED 3 // M0
|
||||
#define PROGRAM_FLOW_OPTIONAL_STOP 1 // M1 NOTE: Not supported, but valid and ignored.
|
||||
#define PROGRAM_FLOW_COMPLETED_M2 2 // M2 (Do not alter value)
|
||||
#define PROGRAM_FLOW_COMPLETED_M30 30 // M30 (Do not alter value)
|
||||
#define PROGRAM_FLOW_RUNNING 0 // (Default: Must be zero)
|
||||
#define PROGRAM_FLOW_PAUSED 3 // M0
|
||||
#define PROGRAM_FLOW_OPTIONAL_STOP 1 // M1 NOTE: Not supported, but valid and ignored.
|
||||
#define PROGRAM_FLOW_COMPLETED_M2 2 // M2 (Do not alter value)
|
||||
#define PROGRAM_FLOW_COMPLETED_M30 30 // M30 (Do not alter value)
|
||||
|
||||
// Modal Group G5: Feed rate mode
|
||||
#define FEED_RATE_MODE_UNITS_PER_MIN 0 // G94 (Default: Must be zero)
|
||||
#define FEED_RATE_MODE_INVERSE_TIME 1 // G93 (Do not alter value)
|
||||
#define FEED_RATE_MODE_UNITS_PER_MIN 0 // G94 (Default: Must be zero)
|
||||
#define FEED_RATE_MODE_INVERSE_TIME 1 // G93 (Do not alter value)
|
||||
|
||||
// Modal Group G6: Units mode
|
||||
#define UNITS_MODE_MM 0 // G21 (Default: Must be zero)
|
||||
#define UNITS_MODE_INCHES 1 // G20 (Do not alter value)
|
||||
#define UNITS_MODE_MM 0 // G21 (Default: Must be zero)
|
||||
#define UNITS_MODE_INCHES 1 // G20 (Do not alter value)
|
||||
|
||||
// Modal Group G7: Cutter radius compensation mode
|
||||
#define CUTTER_COMP_DISABLE 0 // G40 (Default: Must be zero)
|
||||
#define CUTTER_COMP_DISABLE 0 // G40 (Default: Must be zero)
|
||||
|
||||
// Modal Group G10: Canned Cycle Return Level
|
||||
#define RETRACT_OLD_Z 0 // G98 (Default: Must be zero)
|
||||
#define RETRACT_SPECIFIED_R 1
|
||||
|
||||
// Modal Group G13: Control mode
|
||||
#define CONTROL_MODE_EXACT_PATH 0 // G61 (Default: Must be zero)
|
||||
#define CONTROL_MODE_EXACT_PATH 0 // G61 (Default: Must be zero)
|
||||
|
||||
// Modal Group M7: Spindle control
|
||||
#define SPINDLE_DISABLE 0 // M5 (Default: Must be zero)
|
||||
#define SPINDLE_ENABLE_CW PL_COND_FLAG_SPINDLE_CW // M3 (NOTE: Uses planner condition bit flag)
|
||||
#define SPINDLE_ENABLE_CCW PL_COND_FLAG_SPINDLE_CCW // M4 (NOTE: Uses planner condition bit flag)
|
||||
#define SPINDLE_DISABLE 0 // M5 (Default: Must be zero)
|
||||
#define SPINDLE_ENABLE_CW PL_COND_FLAG_SPINDLE_CW // M3 (NOTE: Uses planner condition bit flag)
|
||||
#define SPINDLE_ENABLE_CCW PL_COND_FLAG_SPINDLE_CCW // M4 (NOTE: Uses planner condition bit flag)
|
||||
|
||||
// Modal Group M8: Coolant control
|
||||
#define COOLANT_DISABLE 0 // M9 (Default: Must be zero)
|
||||
#define COOLANT_FLOOD_ENABLE PL_COND_FLAG_COOLANT_FLOOD // M8 (NOTE: Uses planner condition bit flag)
|
||||
#define COOLANT_MIST_ENABLE PL_COND_FLAG_COOLANT_MIST // M7 (NOTE: Uses planner condition bit flag)
|
||||
#define COOLANT_DISABLE 0 // M9 (Default: Must be zero)
|
||||
#define COOLANT_FLOOD_ENABLE PL_COND_FLAG_COOLANT_FLOOD // M8 (NOTE: Uses planner condition bit flag)
|
||||
#define COOLANT_MIST_ENABLE PL_COND_FLAG_COOLANT_MIST // M7 (NOTE: Uses planner condition bit flag)
|
||||
|
||||
// Modal Group G8: Tool length offset
|
||||
#define TOOL_LENGTH_OFFSET_CANCEL 0 // G49 (Default: Must be zero)
|
||||
#define TOOL_LENGTH_OFFSET_ENABLE_DYNAMIC 1 // G43.1
|
||||
#define TOOL_LENGTH_OFFSET_CANCEL 0 // G49 (Default: Must be zero)
|
||||
#define TOOL_LENGTH_OFFSET_ENABLE_DYNAMIC 1 // G43.1
|
||||
|
||||
// Modal Group G12: Active work coordinate system
|
||||
// N/A: Stores coordinate system value (54-59) to change to.
|
||||
|
@ -155,19 +155,19 @@
|
|||
|
||||
|
||||
// Define parameter word mapping.
|
||||
#define WORD_F 0
|
||||
#define WORD_I 1
|
||||
#define WORD_J 2
|
||||
#define WORD_K 3
|
||||
#define WORD_L 4
|
||||
#define WORD_N 5
|
||||
#define WORD_P 6
|
||||
#define WORD_R 7
|
||||
#define WORD_S 8
|
||||
#define WORD_T 9
|
||||
#define WORD_X 10
|
||||
#define WORD_Y 11
|
||||
#define WORD_Z 12
|
||||
#define WORD_F 0
|
||||
#define WORD_I 1
|
||||
#define WORD_J 2
|
||||
#define WORD_K 3
|
||||
#define WORD_L 4
|
||||
#define WORD_N 5
|
||||
#define WORD_P 6
|
||||
#define WORD_R 7
|
||||
#define WORD_S 8
|
||||
#define WORD_T 9
|
||||
#define WORD_X 10
|
||||
#define WORD_Y 11
|
||||
#define WORD_Z 12
|
||||
#define WORD_Q 13
|
||||
#define WORD_A 14
|
||||
#define WORD_B 15
|
||||
|
@ -176,20 +176,20 @@
|
|||
#define WORD_E 18
|
||||
|
||||
// Define g-code parser position updating flags
|
||||
#define GC_UPDATE_POS_TARGET 0 // Must be zero
|
||||
#define GC_UPDATE_POS_SYSTEM 1
|
||||
#define GC_UPDATE_POS_NONE 2
|
||||
#define GC_UPDATE_POS_TARGET 0 // Must be zero
|
||||
#define GC_UPDATE_POS_SYSTEM 1
|
||||
#define GC_UPDATE_POS_NONE 2
|
||||
|
||||
// Define probe cycle exit states and assign proper position updating.
|
||||
#define GC_PROBE_FOUND GC_UPDATE_POS_SYSTEM
|
||||
#define GC_PROBE_ABORT GC_UPDATE_POS_NONE
|
||||
#define GC_PROBE_FAIL_INIT GC_UPDATE_POS_NONE
|
||||
#define GC_PROBE_FAIL_END GC_UPDATE_POS_TARGET
|
||||
#define GC_PROBE_FOUND GC_UPDATE_POS_SYSTEM
|
||||
#define GC_PROBE_ABORT GC_UPDATE_POS_NONE
|
||||
#define GC_PROBE_FAIL_INIT GC_UPDATE_POS_NONE
|
||||
#define GC_PROBE_FAIL_END GC_UPDATE_POS_TARGET
|
||||
|
||||
#ifdef SET_CHECK_MODE_PROBE_TO_START
|
||||
#define GC_PROBE_CHECK_MODE GC_UPDATE_POS_NONE
|
||||
#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
|
||||
|
||||
|
||||
|
@ -208,23 +208,23 @@
|
|||
// 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 retract; // {G98,G99}
|
||||
// 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 override; // {M56}
|
||||
uint8_t lathe_mode; // {G7,G8}
|
||||
uint8_t spindle_mode; // {G96,G97}
|
||||
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 retract; // {G98,G99}
|
||||
// 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 override; // {M56}
|
||||
uint8_t lathe_mode; // {G7,G8}
|
||||
uint8_t spindle_mode; // {G96,G97}
|
||||
} GC_Modal_t;
|
||||
|
||||
|
||||
|
@ -233,43 +233,43 @@ typedef struct
|
|||
uint16_t d;
|
||||
uint8_t h;
|
||||
float e;
|
||||
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.
|
||||
int32_t line_number; // Last line number sent
|
||||
float spindle_limit;
|
||||
float spindle_speed; // RPM
|
||||
float feed_rate; // Millimeters/min
|
||||
uint8_t tool; // Tracks tool number.
|
||||
int32_t line_number; // Last line number sent
|
||||
float spindle_limit;
|
||||
|
||||
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 position[N_AXIS]; // Where the interpreter considers the tool to be at this point in the code
|
||||
float coord_system[N_AXIS]; // Current work coordinate system (G54+). Stores offset from absolute machine
|
||||
// position in mm. Loaded from EEPROM when called.
|
||||
float coord_offset[N_AXIS]; // Retains the G92 coordinate offset (work coordinates) relative to
|
||||
// machine zero in mm. Non-persistent. Cleared upon reset and boot.
|
||||
float tool_length_offset; // Tracks tool length offset value when enabled.
|
||||
} Parser_State_t;
|
||||
|
||||
|
||||
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;
|
||||
|
||||
extern Parser_State_t gc_state;
|
||||
|
|
46
grbl/Jog.c
46
grbl/Jog.c
|
@ -3,7 +3,7 @@
|
|||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2017 Patrick F.
|
||||
Copyright (c) 2017 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
|
||||
|
@ -30,27 +30,31 @@
|
|||
// Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog.
|
||||
uint8_t Jog_Execute(Planner_LineData_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;
|
||||
pl_data->line_number = gc_block->values.n;
|
||||
// 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;
|
||||
pl_data->line_number = gc_block->values.n;
|
||||
|
||||
if(BIT_IS_TRUE(settings.flags, BITFLAG_SOFT_LIMIT_ENABLE)) {
|
||||
if(System_CheckTravelLimits(gc_block->values.xyz)) {
|
||||
return STATUS_TRAVEL_EXCEEDED;
|
||||
}
|
||||
}
|
||||
if(BIT_IS_TRUE(settings.flags, BITFLAG_SOFT_LIMIT_ENABLE))
|
||||
{
|
||||
if(System_CheckTravelLimits(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 (Planner_GetCurrentBlock() != 0) { // Check if there is a block to execute.
|
||||
sys.state = STATE_JOG;
|
||||
Stepper_PrepareBuffer();
|
||||
Stepper_WakeUp(); // NOTE: Manual start. No state machine required.
|
||||
}
|
||||
}
|
||||
// Valid jog command. Plan, set state, and execute.
|
||||
MC_Line(gc_block->values.xyz, pl_data);
|
||||
if(sys.state == STATE_IDLE)
|
||||
{
|
||||
if (Planner_GetCurrentBlock() != 0) // Check if there is a block to execute.
|
||||
{
|
||||
sys.state = STATE_JOG;
|
||||
Stepper_PrepareBuffer();
|
||||
Stepper_WakeUp(); // NOTE: Manual start. No state machine required.
|
||||
}
|
||||
}
|
||||
|
||||
return STATUS_OK;
|
||||
return STATUS_OK;
|
||||
}
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2017 Patrick F.
|
||||
Copyright (c) 2017 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
|
||||
|
@ -27,7 +27,7 @@
|
|||
|
||||
|
||||
// System motion line numbers must be zero.
|
||||
#define JOG_LINE_NUMBER 0
|
||||
#define JOG_LINE_NUMBER 0
|
||||
|
||||
|
||||
// Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog.
|
||||
|
|
529
grbl/Limits.c
529
grbl/Limits.c
|
@ -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-2020 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
|
||||
|
@ -35,31 +35,33 @@
|
|||
|
||||
// Homing axis search distance multiplier. Computed by this value times the cycle travel.
|
||||
#ifndef HOMING_AXIS_SEARCH_SCALAR
|
||||
#define HOMING_AXIS_SEARCH_SCALAR 1.5 // Must be > 1 to ensure limit switch will be engaged.
|
||||
#define HOMING_AXIS_SEARCH_SCALAR 1.5 // 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 Limits_Init(void)
|
||||
{
|
||||
GPIO_InitGPIO(GPIO_LIMIT);
|
||||
GPIO_InitGPIO(GPIO_LIMIT);
|
||||
|
||||
// TODO: Hard limits via interrupt
|
||||
if(BIT_IS_TRUE(settings.flags, BITFLAG_HARD_LIMIT_ENABLE)) {
|
||||
settings.system_flags |= BITFLAG_ENABLE_LIMITS;
|
||||
}
|
||||
else {
|
||||
Limits_Disable();
|
||||
}
|
||||
// TODO: Hard limits via interrupt
|
||||
if(BIT_IS_TRUE(settings.flags, BITFLAG_HARD_LIMIT_ENABLE))
|
||||
{
|
||||
settings.system_flags |= BITFLAG_ENABLE_LIMITS;
|
||||
}
|
||||
else
|
||||
{
|
||||
Limits_Disable();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Disables hard limits.
|
||||
void Limits_Disable(void)
|
||||
{
|
||||
settings.system_flags &= ~BITFLAG_ENABLE_LIMITS;
|
||||
settings.system_flags &= ~BITFLAG_ENABLE_LIMITS;
|
||||
}
|
||||
|
||||
|
||||
|
@ -68,17 +70,18 @@ void Limits_Disable(void)
|
|||
// 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 limit_state = 0;
|
||||
uint8_t limit_state = 0;
|
||||
|
||||
limit_state = (GPIO_ReadInputDataBit(GPIO_LIM_X_PORT, GPIO_LIM_X_PIN)<<X_LIMIT_BIT);
|
||||
limit_state |= (GPIO_ReadInputDataBit(GPIO_LIM_Y_PORT, GPIO_LIM_Y_PIN)<<Y_LIMIT_BIT);
|
||||
limit_state |= (GPIO_ReadInputDataBit(GPIO_LIM_Z_PORT, GPIO_LIM_Z_PIN)<<Z_LIMIT_BIT);
|
||||
limit_state = (GPIO_ReadInputDataBit(GPIO_LIM_X_PORT, GPIO_LIM_X_PIN)<<X1_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);
|
||||
|
||||
if(BIT_IS_FALSE(settings.flags, BITFLAG_INVERT_LIMIT_PINS)) {
|
||||
limit_state ^= LIMIT_MASK;
|
||||
}
|
||||
if(BIT_IS_FALSE(settings.flags, BITFLAG_INVERT_LIMIT_PINS))
|
||||
{
|
||||
limit_state ^= LIMIT_MASK;
|
||||
}
|
||||
|
||||
return limit_state;
|
||||
return limit_state;
|
||||
}
|
||||
|
||||
|
||||
|
@ -100,20 +103,25 @@ void Limit_PinChangeISR(void) // DEFAULT: Limit pin change interrupt process.
|
|||
// 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) {
|
||||
if(!(sys_rt_exec_alarm)) {
|
||||
if(settings.system_flags & BITFLAG_FORCE_HARD_LIMIT_CHECK) {
|
||||
// Check limit pin state.
|
||||
if(Limits_GetState()) {
|
||||
MC_Reset(); // Initiate system kill.
|
||||
System_SetExecAlarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
|
||||
}
|
||||
}
|
||||
else {
|
||||
MC_Reset(); // Initiate system kill.
|
||||
System_SetExecAlarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
|
||||
}
|
||||
}
|
||||
if(sys.state != STATE_ALARM)
|
||||
{
|
||||
if(!(sys_rt_exec_alarm))
|
||||
{
|
||||
if(settings.system_flags & BITFLAG_FORCE_HARD_LIMIT_CHECK)
|
||||
{
|
||||
// Check limit pin state.
|
||||
if(Limits_GetState())
|
||||
{
|
||||
MC_Reset(); // Initiate system kill.
|
||||
System_SetExecAlarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
MC_Reset(); // Initiate system kill.
|
||||
System_SetExecAlarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -127,231 +135,275 @@ void Limit_PinChangeISR(void) // DEFAULT: Limit pin change interrupt process.
|
|||
// TODO: Move limit pin-specific calls to a general function for portability.
|
||||
void Limits_GoHome(uint8_t cycle_mask)
|
||||
{
|
||||
if(sys.abort)
|
||||
if(sys.abort)
|
||||
{
|
||||
// Block if system reset has been issued.
|
||||
return;
|
||||
}
|
||||
// Block if system reset has been issued.
|
||||
return;
|
||||
}
|
||||
|
||||
// Initialize plan data struct for homing motion. Spindle and coolant are disabled.
|
||||
Planner_LineData_t plan_data;
|
||||
Planner_LineData_t *pl_data = &plan_data;
|
||||
memset(pl_data,0,sizeof(Planner_LineData_t));
|
||||
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION|PL_COND_FLAG_NO_FEED_OVERRIDE);
|
||||
pl_data->line_number = HOMING_CYCLE_LINE_NUMBER;
|
||||
// Initialize plan data struct for homing motion. Spindle and coolant are disabled.
|
||||
Planner_LineData_t plan_data;
|
||||
Planner_LineData_t *pl_data = &plan_data;
|
||||
memset(pl_data,0,sizeof(Planner_LineData_t));
|
||||
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION|PL_COND_FLAG_NO_FEED_OVERRIDE);
|
||||
pl_data->line_number = HOMING_CYCLE_LINE_NUMBER;
|
||||
|
||||
// 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] = Settings_GetStepPinMask(idx);
|
||||
// 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] = Settings_GetStepPinMask(idx);
|
||||
|
||||
#ifdef COREXY
|
||||
if((idx == A_MOTOR) || (idx == B_MOTOR)) {
|
||||
step_pin[idx] = (Settings_GetStepPinMask(X_AXIS) | Settings_GetStepPinMask(Y_AXIS));
|
||||
}
|
||||
if((idx == A_MOTOR) || (idx == B_MOTOR))
|
||||
{
|
||||
step_pin[idx] = (Settings_GetStepPinMask(X_AXIS) | Settings_GetStepPinMask(Y_AXIS));
|
||||
}
|
||||
#endif
|
||||
|
||||
if(BIT_IS_TRUE(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]);
|
||||
}
|
||||
}
|
||||
if(BIT_IS_TRUE(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;
|
||||
// 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_ConvertArraySteps2Mpos(target,sys_position);
|
||||
uint8_t limit_state, axislock, n_active_axis;
|
||||
do
|
||||
{
|
||||
System_ConvertArraySteps2Mpos(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_IS_TRUE(cycle_mask,BIT(idx))) {
|
||||
n_active_axis++;
|
||||
// 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_IS_TRUE(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;
|
||||
}
|
||||
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;
|
||||
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_IS_TRUE(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];
|
||||
}
|
||||
// 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_IS_TRUE(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;
|
||||
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.
|
||||
Planner_BufferLine(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
|
||||
// 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.
|
||||
Planner_BufferLine(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.
|
||||
Stepper_PrepareBuffer(); // Prep and fill segment buffer from newly planned block.
|
||||
Stepper_WakeUp(); // Initiate motion
|
||||
sys.step_control = STEP_CONTROL_EXECUTE_SYS_MOTION; // Set to execute homing motion and clear existing flags.
|
||||
Stepper_PrepareBuffer(); // Prep and fill segment buffer from newly planned block.
|
||||
Stepper_WakeUp(); // Initiate motion
|
||||
|
||||
do {
|
||||
if(approach) {
|
||||
// Check limit state. Lock out cycle axes when they change.
|
||||
limit_state = Limits_GetState();
|
||||
for(idx = 0; idx < N_AXIS; idx++) {
|
||||
if(axislock & step_pin[idx]) {
|
||||
if(limit_state & (1 << idx)) {
|
||||
do
|
||||
{
|
||||
if(approach)
|
||||
{
|
||||
// Check limit state. Lock out cycle axes when they change.
|
||||
limit_state = Limits_GetState();
|
||||
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]);
|
||||
}
|
||||
if(idx == Z_AXIS)
|
||||
{
|
||||
axislock &= ~(step_pin[Z_AXIS]);
|
||||
}
|
||||
else
|
||||
{
|
||||
axislock &= ~(step_pin[A_MOTOR]|step_pin[B_MOTOR]);
|
||||
}
|
||||
#else
|
||||
axislock &= ~(step_pin[idx]);
|
||||
axislock &= ~(step_pin[idx]);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
sys.homing_axis_lock = axislock;
|
||||
}
|
||||
sys.homing_axis_lock = axislock;
|
||||
}
|
||||
|
||||
Stepper_PrepareBuffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us.
|
||||
Stepper_PrepareBuffer(); // 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)) {
|
||||
uint16_t rt_exec = sys_rt_exec_state;
|
||||
// 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))
|
||||
{
|
||||
uint16_t rt_exec = sys_rt_exec_state;
|
||||
|
||||
// Homing failure condition: Reset issued during cycle.
|
||||
if(rt_exec & EXEC_RESET) {
|
||||
System_SetExecAlarm(EXEC_ALARM_HOMING_FAIL_RESET);
|
||||
}
|
||||
// Homing failure condition: Safety door was opened.
|
||||
if(rt_exec & EXEC_SAFETY_DOOR) {
|
||||
System_SetExecAlarm(EXEC_ALARM_HOMING_FAIL_DOOR);
|
||||
}
|
||||
// Homing failure condition: Limit switch still engaged after pull-off motion
|
||||
if(!approach && (Limits_GetState() & cycle_mask)) {
|
||||
System_SetExecAlarm(EXEC_ALARM_HOMING_FAIL_PULLOFF);
|
||||
}
|
||||
// Homing failure condition: Limit switch not found during approach.
|
||||
if(approach && (rt_exec & EXEC_CYCLE_STOP)) {
|
||||
System_SetExecAlarm(EXEC_ALARM_HOMING_FAIL_APPROACH);
|
||||
}
|
||||
if(sys_rt_exec_alarm) {
|
||||
MC_Reset(); // Stop motors, if they are running.
|
||||
Protocol_ExecuteRealtime();
|
||||
// Homing failure condition: Reset issued during cycle.
|
||||
if(rt_exec & EXEC_RESET)
|
||||
{
|
||||
System_SetExecAlarm(EXEC_ALARM_HOMING_FAIL_RESET);
|
||||
}
|
||||
// Homing failure condition: Safety door was opened.
|
||||
if(rt_exec & EXEC_SAFETY_DOOR)
|
||||
{
|
||||
System_SetExecAlarm(EXEC_ALARM_HOMING_FAIL_DOOR);
|
||||
}
|
||||
// Homing failure condition: Limit switch still engaged after pull-off motion
|
||||
if(!approach && (Limits_GetState() & cycle_mask))
|
||||
{
|
||||
System_SetExecAlarm(EXEC_ALARM_HOMING_FAIL_PULLOFF);
|
||||
}
|
||||
// Homing failure condition: Limit switch not found during approach.
|
||||
if(approach && (rt_exec & EXEC_CYCLE_STOP))
|
||||
{
|
||||
System_SetExecAlarm(EXEC_ALARM_HOMING_FAIL_APPROACH);
|
||||
}
|
||||
if(sys_rt_exec_alarm)
|
||||
{
|
||||
MC_Reset(); // Stop motors, if they are running.
|
||||
Protocol_ExecuteRealtime();
|
||||
|
||||
return;
|
||||
}
|
||||
else {
|
||||
// Pull-off motion complete. Disable CYCLE_STOP from executing.
|
||||
System_ClearExecStateFlag(EXEC_CYCLE_STOP);
|
||||
break;
|
||||
}
|
||||
}
|
||||
// TODO:
|
||||
} while(0x07 & axislock);
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
// Pull-off motion complete. Disable CYCLE_STOP from executing.
|
||||
System_ClearExecStateFlag(EXEC_CYCLE_STOP);
|
||||
break;
|
||||
}
|
||||
}
|
||||
// TODO:
|
||||
}
|
||||
while(0x3F & axislock);
|
||||
|
||||
Stepper_Reset(); // Immediately force kill steppers and reset step segment buffer.
|
||||
Delay_ms(settings.homing_debounce_delay); // Delay to allow transient dynamics to dissipate.
|
||||
Stepper_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;
|
||||
// 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;
|
||||
}
|
||||
// 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);
|
||||
}
|
||||
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)) {
|
||||
// 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;
|
||||
set_axis_position = 0;
|
||||
#else
|
||||
if(BIT_IS_TRUE(settings.homing_dir_mask, BIT(idx))) {
|
||||
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]);
|
||||
}
|
||||
if(BIT_IS_TRUE(settings.homing_dir_mask, BIT(idx)))
|
||||
{
|
||||
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
|
||||
|
||||
#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;
|
||||
}
|
||||
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;
|
||||
sys_position[idx] = set_axis_position;
|
||||
#endif
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Necessary for backlash compensation
|
||||
MC_Init();
|
||||
MC_Init();
|
||||
|
||||
sys.step_control = STEP_CONTROL_NORMAL_OP; // Return step control to normal operation.
|
||||
sys.is_homed = 1; // Machine is homed and knows its position
|
||||
sys.step_control = STEP_CONTROL_NORMAL_OP; // Return step control to normal operation.
|
||||
sys.is_homed = 1; // Machine is homed and knows its position
|
||||
}
|
||||
|
||||
|
||||
|
@ -360,27 +412,32 @@ void Limits_GoHome(uint8_t cycle_mask)
|
|||
// NOTE: Used by jogging to limit travel within soft-limit volume.
|
||||
void Limits_SoftCheck(float *target)
|
||||
{
|
||||
if(System_CheckTravelLimits(target)) {
|
||||
sys.soft_limit = true;
|
||||
if(System_CheckTravelLimits(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_SetExecStateFlag(EXEC_FEED_HOLD);
|
||||
do {
|
||||
Protocol_ExecuteRealtime();
|
||||
// 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_SetExecStateFlag(EXEC_FEED_HOLD);
|
||||
do
|
||||
{
|
||||
Protocol_ExecuteRealtime();
|
||||
|
||||
if(sys.abort) {
|
||||
return;
|
||||
}
|
||||
} while(sys.state != STATE_IDLE);
|
||||
}
|
||||
if(sys.abort)
|
||||
{
|
||||
return;
|
||||
}
|
||||
}
|
||||
while(sys.state != STATE_IDLE);
|
||||
}
|
||||
|
||||
MC_Reset(); // Issue system reset and ensure spindle and coolant are shutdown.
|
||||
System_SetExecAlarm(EXEC_ALARM_SOFT_LIMIT); // Indicate soft limit critical event
|
||||
Protocol_ExecuteRealtime(); // Execute to enter critical event loop and system abort
|
||||
MC_Reset(); // Issue system reset and ensure spindle and coolant are shutdown.
|
||||
System_SetExecAlarm(EXEC_ALARM_SOFT_LIMIT); // Indicate soft limit critical event
|
||||
Protocol_ExecuteRealtime(); // Execute to enter critical event loop and system abort
|
||||
|
||||
return;
|
||||
}
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -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 Patrick F.
|
||||
Copyright (c) 2017 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
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
Copyright (c) 2017-2020 Patrick F.
|
||||
Copyright (c) 2017-2020 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
|
||||
|
@ -53,21 +53,21 @@ void MC_Init(void)
|
|||
|
||||
MC_SyncBacklashPosition();
|
||||
|
||||
for(uint8_t i = 0; i < N_AXIS; i++)
|
||||
{
|
||||
// Don't do backlash move, if all axis are 0.0
|
||||
if(settings.backlash[i] > 0.0001)
|
||||
{
|
||||
backlash_enable = 1;
|
||||
}
|
||||
}
|
||||
for(uint8_t i = 0; i < N_AXIS; i++)
|
||||
{
|
||||
// Don't do backlash move, if all axis are 0.0
|
||||
if(settings.backlash[i] > 0.0001)
|
||||
{
|
||||
backlash_enable = 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void MC_SyncBacklashPosition(void)
|
||||
{
|
||||
// Update target_prev
|
||||
System_ConvertArraySteps2Mpos(target_prev, sys_position);
|
||||
// Update target_prev
|
||||
System_ConvertArraySteps2Mpos(target_prev, sys_position);
|
||||
}
|
||||
|
||||
|
||||
|
@ -89,59 +89,66 @@ void MC_Line(float *target, Planner_LineData_t *pl_data)
|
|||
pl_backlash.feed_rate = pl_data->feed_rate;
|
||||
|
||||
|
||||
// If enabled, check for soft limit violations. Placed here all line motions are picked up
|
||||
// from everywhere in Grbl.
|
||||
if(BIT_IS_TRUE(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_SoftCheck(target);
|
||||
}
|
||||
}
|
||||
// If enabled, check for soft limit violations. Placed here all line motions are picked up
|
||||
// from everywhere in Grbl.
|
||||
if(BIT_IS_TRUE(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_SoftCheck(target);
|
||||
}
|
||||
}
|
||||
|
||||
// If in check gcode mode, prevent motion by blocking planner. Soft limits still work.
|
||||
if(sys.state == STATE_CHECK_MODE) {
|
||||
return;
|
||||
}
|
||||
// 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.
|
||||
// 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_ExecuteRealtime(); // Check for any run-time commands
|
||||
// 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_ExecuteRealtime(); // Check for any run-time commands
|
||||
|
||||
if(sys.abort) {
|
||||
// Bail, if system abort.
|
||||
return;
|
||||
}
|
||||
if(sys.abort)
|
||||
{
|
||||
// Bail, if system abort.
|
||||
return;
|
||||
}
|
||||
|
||||
if(Planner_CheckBufferFull()) {
|
||||
// Auto-cycle start when buffer is full.
|
||||
Protocol_AutoCycleStart();
|
||||
}
|
||||
else {
|
||||
break;
|
||||
}
|
||||
} while(1);
|
||||
if(Planner_CheckBufferFull())
|
||||
{
|
||||
// Auto-cycle start when buffer is full.
|
||||
Protocol_AutoCycleStart();
|
||||
}
|
||||
else
|
||||
{
|
||||
break;
|
||||
}
|
||||
} while(1);
|
||||
|
||||
#ifdef ENABLE_BACKLASH_COMPENSATION
|
||||
pl_backlash.backlash_motion = 1;
|
||||
pl_backlash.condition = PL_COND_FLAG_RAPID_MOTION; // Set rapid motion condition flag.
|
||||
|
||||
// Backlash compensation (not for A & B)
|
||||
// Backlash compensation (not for A & B)
|
||||
for(uint8_t i = 0; i < N_LINEAR_AXIS; i++)
|
||||
{
|
||||
// Move positive?
|
||||
|
@ -179,37 +186,44 @@ void MC_Line(float *target, Planner_LineData_t *pl_data)
|
|||
memcpy(target_prev, target, N_AXIS*sizeof(float));
|
||||
|
||||
// Backlash move needs a slot in planner buffer, so we have to check again, if planner is free
|
||||
do {
|
||||
Protocol_ExecuteRealtime(); // Check for any run-time commands
|
||||
do
|
||||
{
|
||||
Protocol_ExecuteRealtime(); // Check for any run-time commands
|
||||
|
||||
if(sys.abort) {
|
||||
// Bail, if system abort.
|
||||
return;
|
||||
}
|
||||
if(sys.abort)
|
||||
{
|
||||
// Bail, if system abort.
|
||||
return;
|
||||
}
|
||||
|
||||
if(Planner_CheckBufferFull()) {
|
||||
// Auto-cycle start when buffer is full.
|
||||
Protocol_AutoCycleStart();
|
||||
}
|
||||
else {
|
||||
break;
|
||||
}
|
||||
} while(1);
|
||||
if(Planner_CheckBufferFull())
|
||||
{
|
||||
// Auto-cycle start when buffer is full.
|
||||
Protocol_AutoCycleStart();
|
||||
}
|
||||
else
|
||||
{
|
||||
break;
|
||||
}
|
||||
} while(1);
|
||||
#else
|
||||
(void)backlash_update;
|
||||
(void)pl_backlash;
|
||||
(void)backlash_update;
|
||||
(void)pl_backlash;
|
||||
#endif
|
||||
|
||||
// Plan and queue motion into planner buffer
|
||||
if(Planner_BufferLine(target, pl_data) == PLAN_EMPTY_BLOCK) {
|
||||
if(BIT_IS_TRUE(settings.flags, BITFLAG_LASER_MODE)) {
|
||||
// Correctly set spindle state, if there is a coincident position passed. Forces a buffer
|
||||
// sync while in M3 laser mode only.
|
||||
if(pl_data->condition & PL_COND_FLAG_SPINDLE_CW) {
|
||||
Spindle_Sync(PL_COND_FLAG_SPINDLE_CW, pl_data->spindle_speed);
|
||||
}
|
||||
}
|
||||
}
|
||||
// Plan and queue motion into planner buffer
|
||||
if(Planner_BufferLine(target, pl_data) == PLAN_EMPTY_BLOCK)
|
||||
{
|
||||
if(BIT_IS_TRUE(settings.flags, BITFLAG_LASER_MODE))
|
||||
{
|
||||
// Correctly set spindle state, if there is a coincident position passed. Forces a buffer
|
||||
// sync while in M3 laser mode only.
|
||||
if(pl_data->condition & PL_COND_FLAG_SPINDLE_CW)
|
||||
{
|
||||
Spindle_Sync(PL_COND_FLAG_SPINDLE_CW, pl_data->spindle_speed);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Execute an arc in offset mode format. position == current xyz, target == target xyz,
|
||||
|
@ -220,129 +234,140 @@ void MC_Line(float *target, Planner_LineData_t *pl_data)
|
|||
// 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, Planner_LineData_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)
|
||||
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;
|
||||
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;
|
||||
|
||||
// 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;
|
||||
}
|
||||
}
|
||||
// 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)));
|
||||
// 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.
|
||||
}
|
||||
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;
|
||||
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;
|
||||
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;
|
||||
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;
|
||||
}
|
||||
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;
|
||||
// Update arc_target location
|
||||
position[axis_0] = center_axis0 + r_axis0;
|
||||
position[axis_1] = center_axis1 + r_axis1;
|
||||
position[axis_linear] += linear_per_segment;
|
||||
|
||||
MC_Line(position, pl_data);
|
||||
MC_Line(position, pl_data);
|
||||
|
||||
// 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.
|
||||
MC_Line(target, pl_data);
|
||||
// Ensure last segment arrives at target location.
|
||||
MC_Line(target, pl_data);
|
||||
}
|
||||
|
||||
|
||||
// Execute dwell in seconds.
|
||||
void MC_Dwell(float seconds)
|
||||
{
|
||||
if(sys.state == STATE_CHECK_MODE) {
|
||||
return;
|
||||
}
|
||||
if(sys.state == STATE_CHECK_MODE)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
// TODO: DWELL sys.state
|
||||
Protocol_BufferSynchronize();
|
||||
Delay_sec(seconds, DELAY_MODE_DWELL);
|
||||
Protocol_BufferSynchronize();
|
||||
Delay_sec(seconds, DELAY_MODE_DWELL);
|
||||
}
|
||||
|
||||
|
||||
|
@ -353,58 +378,61 @@ void MC_HomigCycle(uint8_t cycle_mask)
|
|||
{
|
||||
Stepper_WakeUp();
|
||||
|
||||
// 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.
|
||||
// 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_GetState()) {
|
||||
MC_Reset(); // Issue system reset and ensure spindle and coolant are shutdown.
|
||||
System_SetExecAlarm(EXEC_ALARM_HARD_LIMIT);
|
||||
if(Limits_GetState())
|
||||
{
|
||||
MC_Reset(); // Issue system reset and ensure spindle and coolant are shutdown.
|
||||
System_SetExecAlarm(EXEC_ALARM_HARD_LIMIT);
|
||||
|
||||
return;
|
||||
}
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
Limits_Disable(); // Disable hard limits pin change register for cycle duration
|
||||
Limits_Disable(); // Disable hard limits pin change register for cycle duration
|
||||
|
||||
// -------------------------------------------------------------------------------------
|
||||
// Perform homing routine. NOTE: Special motion case. Only system reset works.
|
||||
// -------------------------------------------------------------------------------------
|
||||
// Perform homing routine. NOTE: Special motion case. Only system reset works.
|
||||
|
||||
#ifdef HOMING_SINGLE_AXIS_COMMANDS
|
||||
if(cycle_mask) {
|
||||
// Perform homing cycle based on mask.
|
||||
Limits_GoHome(cycle_mask);
|
||||
}
|
||||
else
|
||||
if(cycle_mask)
|
||||
{
|
||||
// Perform homing cycle based on mask.
|
||||
Limits_GoHome(cycle_mask);
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
(void)cycle_mask;
|
||||
// Search to engage all axes limit switches at faster homing seek rate.
|
||||
Limits_GoHome(HOMING_CYCLE_0); // Homing cycle 0
|
||||
{
|
||||
(void)cycle_mask;
|
||||
// Search to engage all axes limit switches at faster homing seek rate.
|
||||
Limits_GoHome(HOMING_CYCLE_0); // Homing cycle 0
|
||||
#ifdef HOMING_CYCLE_1
|
||||
Limits_GoHome(HOMING_CYCLE_1); // Homing cycle 1
|
||||
Limits_GoHome(HOMING_CYCLE_1); // Homing cycle 1
|
||||
#endif
|
||||
|
||||
#ifdef HOMING_CYCLE_2
|
||||
Limits_GoHome(HOMING_CYCLE_2); // Homing cycle 2
|
||||
Limits_GoHome(HOMING_CYCLE_2); // Homing cycle 2
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
Protocol_ExecuteRealtime(); // Check for reset and set system abort.
|
||||
if(sys.abort) {
|
||||
// Did not complete. Alarm state set by mc_alarm.
|
||||
return;
|
||||
}
|
||||
Protocol_ExecuteRealtime(); // Check for reset and set system abort.
|
||||
if(sys.abort)
|
||||
{
|
||||
// Did not complete. Alarm state set by mc_alarm.
|
||||
return;
|
||||
}
|
||||
|
||||
// Homing cycle complete! Setup system for normal operation.
|
||||
// -------------------------------------------------------------------------------------
|
||||
// Homing cycle complete! Setup system for normal operation.
|
||||
// -------------------------------------------------------------------------------------
|
||||
|
||||
// Sync gcode parser and planner positions to homed position.
|
||||
GC_SyncPosition();
|
||||
Planner_SyncPosition();
|
||||
// Sync gcode parser and planner positions to homed position.
|
||||
GC_SyncPosition();
|
||||
Planner_SyncPosition();
|
||||
|
||||
// If hard limits feature enabled, re-enable hard limits pin change register after homing cycle.
|
||||
Limits_Init();
|
||||
// If hard limits feature enabled, re-enable hard limits pin change register after homing cycle.
|
||||
Limits_Init();
|
||||
}
|
||||
|
||||
|
||||
|
@ -412,89 +440,100 @@ void MC_HomigCycle(uint8_t cycle_mask)
|
|||
// NOTE: Upon probe failure, the program will be stopped and placed into ALARM state.
|
||||
uint8_t MC_ProbeCycle(float *target, Planner_LineData_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;
|
||||
}
|
||||
// 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_BufferSynchronize();
|
||||
if(sys.abort) {
|
||||
// Return if system reset has been issued.
|
||||
return GC_PROBE_ABORT;
|
||||
}
|
||||
// Finish all queued commands and empty planner buffer before starting probe cycle.
|
||||
Protocol_BufferSynchronize();
|
||||
if(sys.abort)
|
||||
{
|
||||
// Return if system reset has been issued.
|
||||
return GC_PROBE_ABORT;
|
||||
}
|
||||
|
||||
// Initialize probing control variables
|
||||
uint8_t is_probe_away = BIT_IS_TRUE(parser_flags,GC_PARSER_PROBE_IS_AWAY);
|
||||
uint8_t is_no_error = BIT_IS_TRUE(parser_flags,GC_PARSER_PROBE_IS_NO_ERROR);
|
||||
// Initialize probing control variables
|
||||
uint8_t is_probe_away = BIT_IS_TRUE(parser_flags,GC_PARSER_PROBE_IS_AWAY);
|
||||
uint8_t is_no_error = BIT_IS_TRUE(parser_flags,GC_PARSER_PROBE_IS_NO_ERROR);
|
||||
|
||||
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
|
||||
Probe_ConfigureInvertMask(is_probe_away);
|
||||
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
|
||||
Probe_ConfigureInvertMask(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_GetState()) { // Check probe pin state.
|
||||
System_SetExecAlarm(EXEC_ALARM_PROBE_FAIL_INITIAL);
|
||||
Protocol_ExecuteRealtime();
|
||||
Probe_ConfigureInvertMask(false); // Re-initialize invert mask before returning.
|
||||
// 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_GetState()) // Check probe pin state.
|
||||
{
|
||||
System_SetExecAlarm(EXEC_ALARM_PROBE_FAIL_INITIAL);
|
||||
Protocol_ExecuteRealtime();
|
||||
Probe_ConfigureInvertMask(false); // Re-initialize invert mask before returning.
|
||||
|
||||
return GC_PROBE_FAIL_INIT; // Nothing else to do but bail.
|
||||
}
|
||||
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);
|
||||
// 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;
|
||||
// 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_SetExecStateFlag(EXEC_CYCLE_START);
|
||||
do {
|
||||
Protocol_ExecuteRealtime();
|
||||
// Perform probing cycle. Wait here until probe is triggered or motion completes.
|
||||
System_SetExecStateFlag(EXEC_CYCLE_START);
|
||||
do
|
||||
{
|
||||
Protocol_ExecuteRealtime();
|
||||
|
||||
if(sys.abort) {
|
||||
// Check for system abort
|
||||
return(GC_PROBE_ABORT);
|
||||
}
|
||||
} while(sys.state != STATE_IDLE);
|
||||
if(sys.abort)
|
||||
{
|
||||
// Check for system abort
|
||||
return(GC_PROBE_ABORT);
|
||||
}
|
||||
} while(sys.state != STATE_IDLE);
|
||||
|
||||
// Probing cycle complete!
|
||||
// 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_SetExecAlarm(EXEC_ALARM_PROBE_FAIL_CONTACT);
|
||||
}
|
||||
}
|
||||
else {
|
||||
sys.probe_succeeded = true; // Indicate to system the probing cycle completed successfully.
|
||||
}
|
||||
// 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_SetExecAlarm(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_ConfigureInvertMask(false); // Re-initialize invert mask.
|
||||
Protocol_ExecuteRealtime(); // Check and execute run-time commands
|
||||
sys_probe_state = PROBE_OFF; // Ensure probe state monitor is disabled.
|
||||
Probe_ConfigureInvertMask(false); // Re-initialize invert mask.
|
||||
Protocol_ExecuteRealtime(); // Check and execute run-time commands
|
||||
|
||||
// Reset the stepper and planner buffers to remove the remainder of the probe motion.
|
||||
Stepper_Reset(); // Reset step segment buffer.
|
||||
Planner_Reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
|
||||
Planner_SyncPosition(); // Sync planner position to current machine position.
|
||||
MC_SyncBacklashPosition();
|
||||
// Reset the stepper and planner buffers to remove the remainder of the probe motion.
|
||||
Stepper_Reset(); // Reset step segment buffer.
|
||||
Planner_Reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
|
||||
Planner_SyncPosition(); // Sync planner position to current machine position.
|
||||
MC_SyncBacklashPosition();
|
||||
|
||||
#ifdef MESSAGE_PROBE_COORDINATES
|
||||
// All done! Output the probe position as message.
|
||||
Report_ProbeParams();
|
||||
// All done! Output the probe position as message.
|
||||
Report_ProbeParams();
|
||||
#endif
|
||||
|
||||
if(sys.probe_succeeded) {
|
||||
// Successful probe cycle.
|
||||
return GC_PROBE_FOUND;
|
||||
}
|
||||
else {
|
||||
return GC_PROBE_FAIL_END;
|
||||
} // Failed to trigger probe within travel. With or without error.
|
||||
if(sys.probe_succeeded)
|
||||
{
|
||||
// Successful probe cycle.
|
||||
return GC_PROBE_FOUND;
|
||||
}
|
||||
else
|
||||
{
|
||||
return GC_PROBE_FAIL_END;
|
||||
} // Failed to trigger probe within travel. With or without error.
|
||||
}
|
||||
|
||||
|
||||
|
@ -504,9 +543,10 @@ void MC_OverrideCtrlUpdate(uint8_t override_state)
|
|||
// Finish all queued commands before altering override control state
|
||||
Protocol_BufferSynchronize();
|
||||
|
||||
if(sys.abort) {
|
||||
return;
|
||||
}
|
||||
if(sys.abort)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
sys.override_ctrl = override_state;
|
||||
}
|
||||
|
@ -518,33 +558,39 @@ void MC_OverrideCtrlUpdate(uint8_t override_state)
|
|||
#ifdef PARKING_ENABLE
|
||||
void MC_ParkingMotion(float *parking_target, Planner_LineData_t *pl_data)
|
||||
{
|
||||
if(sys.abort) {
|
||||
// Block during abort.
|
||||
return;
|
||||
}
|
||||
if(sys.abort)
|
||||
{
|
||||
// Block during abort.
|
||||
return;
|
||||
}
|
||||
|
||||
uint8_t plan_status = Planner_BufferLine(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.
|
||||
Stepper_ParkingSetupBuffer(); // Setup step segment buffer for special parking motion case
|
||||
Stepper_PrepareBuffer();
|
||||
Stepper_WakeUp();
|
||||
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.
|
||||
Stepper_ParkingSetupBuffer(); // Setup step segment buffer for special parking motion case
|
||||
Stepper_PrepareBuffer();
|
||||
Stepper_WakeUp();
|
||||
|
||||
do {
|
||||
Protocol_ExecRtSystem();
|
||||
do
|
||||
{
|
||||
Protocol_ExecRtSystem();
|
||||
|
||||
if(sys.abort) {
|
||||
return;
|
||||
}
|
||||
} while (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||
if(sys.abort)
|
||||
{
|
||||
return;
|
||||
}
|
||||
}
|
||||
while (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||
|
||||
Stepper_ParkingRestoreBuffer(); // Restore step segment buffer to normal run state.
|
||||
Stepper_ParkingRestoreBuffer(); // Restore step segment buffer to normal run state.
|
||||
}
|
||||
else {
|
||||
BIT_FALSE(sys.step_control, STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||
Protocol_ExecRtSystem();
|
||||
else
|
||||
{
|
||||
BIT_FALSE(sys.step_control, STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||
Protocol_ExecRtSystem();
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -558,29 +604,34 @@ void MC_ParkingMotion(float *parking_target, Planner_LineData_t *pl_data)
|
|||
// realtime abort command and hard limits. So, keep to a minimum.
|
||||
void MC_Reset(void)
|
||||
{
|
||||
// Only this function can set the system reset. Helps prevent multiple kill calls.
|
||||
if(BIT_IS_FALSE(sys_rt_exec_state, EXEC_RESET)) {
|
||||
System_SetExecStateFlag(EXEC_RESET);
|
||||
// Only this function can set the system reset. Helps prevent multiple kill calls.
|
||||
if(BIT_IS_FALSE(sys_rt_exec_state, EXEC_RESET))
|
||||
{
|
||||
System_SetExecStateFlag(EXEC_RESET);
|
||||
|
||||
// Kill spindle and coolant.
|
||||
Spindle_Stop();
|
||||
Coolant_Stop();
|
||||
// Kill spindle and coolant.
|
||||
Spindle_Stop();
|
||||
Coolant_Stop();
|
||||
|
||||
// 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_SetExecAlarm(EXEC_ALARM_HOMING_FAIL_RESET);
|
||||
}
|
||||
}
|
||||
else {
|
||||
System_SetExecAlarm(EXEC_ALARM_ABORT_CYCLE);
|
||||
}
|
||||
// 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_SetExecAlarm(EXEC_ALARM_HOMING_FAIL_RESET);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
System_SetExecAlarm(EXEC_ALARM_ABORT_CYCLE);
|
||||
}
|
||||
|
||||
Stepper_Disable(0); // Force kill steppers. Position has likely been lost.
|
||||
}
|
||||
}
|
||||
Stepper_Disable(0); // Force kill steppers. Position has likely been lost.
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
Copyright (c) 2017-2020 Patrick F.
|
||||
Copyright (c) 2017-2020 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
|
||||
|
@ -26,22 +26,21 @@
|
|||
#include "Planner.h"
|
||||
|
||||
// System motion commands must have a line number of zero.
|
||||
#define HOMING_CYCLE_LINE_NUMBER 0
|
||||
#define PARKING_MOTION_LINE_NUMBER 0
|
||||
#define HOMING_CYCLE_LINE_NUMBER 0
|
||||
#define PARKING_MOTION_LINE_NUMBER 0
|
||||
|
||||
#define HOMING_CYCLE_ALL 0 // Must be zero.
|
||||
#define HOMING_CYCLE_X BIT(X_AXIS)
|
||||
#define HOMING_CYCLE_Y BIT(Y_AXIS)
|
||||
#define HOMING_CYCLE_Z BIT(Z_AXIS)
|
||||
#define HOMING_CYCLE_A BIT(A_AXIS)
|
||||
#define HOMING_CYCLE_B BIT(B_AXIS)
|
||||
#define HOMING_CYCLE_ALL 0 // Must be zero.
|
||||
#define HOMING_CYCLE_X BIT(X_AXIS)
|
||||
#define HOMING_CYCLE_Y BIT(Y_AXIS)
|
||||
#define HOMING_CYCLE_Z BIT(Z_AXIS)
|
||||
#define HOMING_CYCLE_A BIT(A_AXIS)
|
||||
#define HOMING_CYCLE_B BIT(B_AXIS)
|
||||
|
||||
|
||||
void MC_Init(void);
|
||||
|
||||
void MC_SyncBacklashPosition(void);
|
||||
|
||||
|
||||
// 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.
|
||||
|
@ -52,7 +51,7 @@ void MC_Line(float *target, Planner_LineData_t *pl_data);
|
|||
// the direction of helical travel, radius == circle radius, is_clockwise_arc boolean. Used
|
||||
// for vector transformation direction.
|
||||
void MC_Arc(float *target, Planner_LineData_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);
|
||||
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);
|
||||
|
|
28
grbl/Nvm.c
28
grbl/Nvm.c
|
@ -4,7 +4,7 @@
|
|||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
Copyright (c) 2019-2020 Patrick F.
|
||||
Copyright (c) 2019-2020 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
|
||||
|
@ -28,54 +28,54 @@
|
|||
void Nvm_Init(void)
|
||||
{
|
||||
#ifdef USE_EXT_EEPROM
|
||||
M24C0X_Init();
|
||||
M24C0X_Init();
|
||||
#else
|
||||
EE_Init();
|
||||
EE_Init();
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t Nvm_ReadByte(uint16_t Address)
|
||||
{
|
||||
#ifdef USE_EXT_EEPROM
|
||||
return M24C0X_ReadByte(Address);
|
||||
return M24C0X_ReadByte(Address);
|
||||
#else
|
||||
return EE_ReadByte(Address);
|
||||
return EE_ReadByte(Address);
|
||||
#endif
|
||||
}
|
||||
|
||||
void Nvm_WriteByte(uint16_t Address, uint8_t Data)
|
||||
{
|
||||
#ifdef USE_EXT_EEPROM
|
||||
M24C0X_WriteByte(Address, Data);
|
||||
M24C0X_WriteByte(Address, Data);
|
||||
#else
|
||||
EE_WriteByte(Address, Data);
|
||||
EE_WriteByte(Address, Data);
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t Nvm_Read(uint8_t *DataOut, uint16_t Address, uint16_t size)
|
||||
{
|
||||
#ifdef USE_EXT_EEPROM
|
||||
return M24C0X_ReadByteArray(Address, DataOut, size);
|
||||
return M24C0X_ReadByteArray(Address, DataOut, size);
|
||||
#else
|
||||
return EE_ReadByteArray(DataOut, Address, size);
|
||||
return EE_ReadByteArray(DataOut, Address, size);
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t Nvm_Write(uint16_t Address, uint8_t *DataIn, uint16_t size)
|
||||
{
|
||||
#ifdef USE_EXT_EEPROM
|
||||
return M24C0X_WriteByteArray(Address, DataIn, size);
|
||||
return M24C0X_WriteByteArray(Address, DataIn, size);
|
||||
#else
|
||||
EE_WriteByteArray(Address, DataIn, size);
|
||||
return 0;
|
||||
EE_WriteByteArray(Address, DataIn, size);
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
void Nvm_Update(void)
|
||||
{
|
||||
#ifdef USE_EXT_EEPROM
|
||||
// Do nothing
|
||||
// Do nothing
|
||||
#else
|
||||
EE_Program();
|
||||
EE_Program();
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
Copyright (c) 2019-2020 Patrick F.
|
||||
Copyright (c) 2019-2020 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
|
||||
|
@ -26,7 +26,8 @@
|
|||
#include <stdint.h>
|
||||
|
||||
|
||||
#define NVM_SIZE 1024
|
||||
// EEPROM size in bytes
|
||||
#define NVM_SIZE 1024
|
||||
|
||||
|
||||
void Nvm_Init(void);
|
||||
|
|
702
grbl/Planner.c
702
grbl/Planner.c
|
@ -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
|
||||
Copyright (c) 2017 Patrick F.
|
||||
Copyright (c) 2017 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
|
||||
|
@ -31,12 +31,13 @@
|
|||
|
||||
|
||||
// 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
|
||||
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
|
||||
} Planner_t;
|
||||
|
||||
|
||||
|
@ -53,26 +54,25 @@ static uint8_t next_buffer_head; // Index of the next buffer head
|
|||
static uint8_t block_buffer_planned; // Index of the optimally planned block
|
||||
|
||||
|
||||
|
||||
void Planner_Init(void)
|
||||
{
|
||||
Planner_Reset();
|
||||
Planner_Reset();
|
||||
}
|
||||
|
||||
|
||||
void Planner_Reset(void)
|
||||
{
|
||||
memset(&planner, 0, sizeof(Planner_t)); // Clear planner struct
|
||||
Planner_ResetBuffer();
|
||||
memset(&planner, 0, sizeof(Planner_t)); // Clear planner struct
|
||||
Planner_ResetBuffer();
|
||||
}
|
||||
|
||||
|
||||
void Planner_ResetBuffer(void)
|
||||
{
|
||||
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;
|
||||
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;
|
||||
}
|
||||
|
||||
|
||||
|
@ -92,237 +92,263 @@ void Planner_ResetBuffer(void)
|
|||
to execute the special system motion. */
|
||||
uint8_t Planner_BufferLine(float *target, Planner_LineData_t *pl_data)
|
||||
{
|
||||
// Prepare and initialize new block. Copy relevant pl_data for block execution.
|
||||
Planner_Block_t *block = &block_buffer[block_buffer_head];
|
||||
memset(block, 0, sizeof(Planner_Block_t)); // Zero all block values.
|
||||
block->condition = pl_data->condition;
|
||||
block->spindle_speed = pl_data->spindle_speed;
|
||||
block->line_number = pl_data->line_number;
|
||||
block->backlash_motion = pl_data->backlash_motion;
|
||||
// Prepare and initialize new block. Copy relevant pl_data for block execution.
|
||||
Planner_Block_t *block = &block_buffer[block_buffer_head];
|
||||
memset(block, 0, sizeof(Planner_Block_t)); // Zero all block values.
|
||||
block->condition = pl_data->condition;
|
||||
block->spindle_speed = pl_data->spindle_speed;
|
||||
block->line_number = pl_data->line_number;
|
||||
block->backlash_motion = pl_data->backlash_motion;
|
||||
|
||||
// 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;
|
||||
// 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) {
|
||||
// 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];
|
||||
position_steps[A_AXIS] = sys_position[A_AXIS];
|
||||
position_steps[B_AXIS] = sys_position[B_AXIS];
|
||||
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];
|
||||
position_steps[A_AXIS] = sys_position[A_AXIS];
|
||||
position_steps[B_AXIS] = sys_position[B_AXIS];
|
||||
#else
|
||||
memcpy(position_steps, sys_position, sizeof(sys_position));
|
||||
memcpy(position_steps, sys_position, sizeof(sys_position));
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
memcpy(position_steps, planner.position, sizeof(planner.position));
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
memcpy(position_steps, planner.position, sizeof(planner.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]));
|
||||
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.
|
||||
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]);
|
||||
}
|
||||
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]);
|
||||
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];
|
||||
}
|
||||
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];
|
||||
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
|
||||
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 |= Settings_GetDirectionPinMask(idx);
|
||||
}
|
||||
}
|
||||
// Set direction bits. Bit enabled always means direction is negative.
|
||||
if(delta_mm < 0.0)
|
||||
{
|
||||
block->direction_bits |= Settings_GetDirectionPinMask(idx);
|
||||
}
|
||||
}
|
||||
|
||||
// Bail if this is a zero-length block. Highly unlikely to occur.
|
||||
if(block->step_event_count == 0) {
|
||||
return PLAN_EMPTY_BLOCK;
|
||||
}
|
||||
// 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);
|
||||
// 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;
|
||||
}
|
||||
}
|
||||
// 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;
|
||||
// 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 -= planner.previous_unit_vec[idx]*unit_vec[idx];
|
||||
junction_unit_vec[idx] = unit_vec[idx]-planner.previous_unit_vec[idx];
|
||||
}
|
||||
for(idx = 0; idx < N_AXIS; idx++)
|
||||
{
|
||||
junction_cos_theta -= planner.previous_unit_vec[idx]*unit_vec[idx];
|
||||
junction_unit_vec[idx] = unit_vec[idx]-planner.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.
|
||||
// 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->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 = Planner_ComputeProfileNominalSpeed(block);
|
||||
// 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 = Planner_ComputeProfileNominalSpeed(block);
|
||||
|
||||
Planner_ComputeProfileParams(block, nominal_speed, planner.previous_nominal_speed);
|
||||
planner.previous_nominal_speed = nominal_speed;
|
||||
Planner_ComputeProfileParams(block, nominal_speed, planner.previous_nominal_speed);
|
||||
planner.previous_nominal_speed = nominal_speed;
|
||||
|
||||
if(block->backlash_motion == 0)
|
||||
{
|
||||
// Update previous path unit_vector and planner position.
|
||||
memcpy(planner.previous_unit_vec, unit_vec, sizeof(unit_vec)); // pl.previous_unit_vec[] = unit_vec[]
|
||||
memcpy(planner.position, target_steps, sizeof(target_steps)); // pl.position[] = target_steps[]
|
||||
memcpy(planner.previous_unit_vec, unit_vec, sizeof(unit_vec)); // pl.previous_unit_vec[] = unit_vec[]
|
||||
memcpy(planner.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 = Planner_NextBlockIndex(block_buffer_head);
|
||||
// New block is all set. Update buffer head and next buffer head indices.
|
||||
block_buffer_head = next_buffer_head;
|
||||
next_buffer_head = Planner_NextBlockIndex(block_buffer_head);
|
||||
|
||||
// Finish up by recalculating the plan with the new block.
|
||||
Planner_Recalculate();
|
||||
}
|
||||
// Finish up by recalculating the plan with the new block.
|
||||
Planner_Recalculate();
|
||||
}
|
||||
|
||||
return PLAN_OK;
|
||||
return PLAN_OK;
|
||||
}
|
||||
|
||||
|
||||
void Planner_DiscardCurrentBlock(void)
|
||||
{
|
||||
if(block_buffer_head != block_buffer_tail) { // Discard non-empty buffer.
|
||||
uint8_t block_index = Planner_NextBlockIndex(block_buffer_tail);
|
||||
if(block_buffer_head != block_buffer_tail) // Discard non-empty buffer.
|
||||
{
|
||||
uint8_t block_index = Planner_NextBlockIndex(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;
|
||||
}
|
||||
// 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.
|
||||
Planner_Block_t *Planner_GetSystemMotionBlock(void)
|
||||
{
|
||||
return &block_buffer[block_buffer_head];
|
||||
return &block_buffer[block_buffer_head];
|
||||
}
|
||||
|
||||
|
||||
// Returns address of first planner block, if available. Called by various main program functions.
|
||||
Planner_Block_t *Planner_GetCurrentBlock(void)
|
||||
{
|
||||
if(block_buffer_head == block_buffer_tail) {
|
||||
// Buffer empty
|
||||
return 0;
|
||||
}
|
||||
if(block_buffer_head == block_buffer_tail)
|
||||
{
|
||||
// Buffer empty
|
||||
return 0;
|
||||
}
|
||||
|
||||
return &block_buffer[block_buffer_tail];
|
||||
return &block_buffer[block_buffer_tail];
|
||||
}
|
||||
|
||||
|
||||
// Returns the index of the next block in the ring buffer. Also called by stepper segment buffer.
|
||||
uint8_t Planner_NextBlockIndex(uint8_t block_index)
|
||||
{
|
||||
block_index++;
|
||||
if(block_index == BLOCK_BUFFER_SIZE) {
|
||||
block_index = 0;
|
||||
}
|
||||
block_index++;
|
||||
if(block_index == BLOCK_BUFFER_SIZE)
|
||||
{
|
||||
block_index = 0;
|
||||
}
|
||||
|
||||
return block_index;
|
||||
return block_index;
|
||||
}
|
||||
|
||||
|
||||
float Planner_GetExecBlockExitSpeedSqr(void)
|
||||
{
|
||||
uint8_t block_index = Planner_NextBlockIndex(block_buffer_tail);
|
||||
uint8_t block_index = Planner_NextBlockIndex(block_buffer_tail);
|
||||
|
||||
if(block_index == block_buffer_head) {
|
||||
return( 0.0 );
|
||||
}
|
||||
if(block_index == block_buffer_head)
|
||||
{
|
||||
return (0.0);
|
||||
}
|
||||
|
||||
return block_buffer[block_index].entry_speed_sqr;
|
||||
return block_buffer[block_index].entry_speed_sqr;
|
||||
}
|
||||
|
||||
|
||||
|
@ -330,68 +356,78 @@ float Planner_GetExecBlockExitSpeedSqr(void)
|
|||
// NOTE: All system motion commands, such as homing/parking, are not subject to overrides.
|
||||
float Planner_ComputeProfileNominalSpeed(Planner_Block_t *block)
|
||||
{
|
||||
float nominal_speed = block->programmed_rate;
|
||||
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;
|
||||
}
|
||||
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;
|
||||
return MINIMUM_FEED_RATE;
|
||||
}
|
||||
|
||||
|
||||
// Re-calculates buffered motions profile parameters upon a motion-based override change.
|
||||
void Planner_UpdateVelocityProfileParams(void)
|
||||
{
|
||||
uint8_t block_index = block_buffer_tail;
|
||||
Planner_Block_t *block;
|
||||
float nominal_speed;
|
||||
float prev_nominal_speed = SOME_LARGE_VALUE; // Set high for first block nominal speed calculation.
|
||||
uint8_t block_index = block_buffer_tail;
|
||||
Planner_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 = Planner_ComputeProfileNominalSpeed(block);
|
||||
Planner_ComputeProfileParams(block, nominal_speed, prev_nominal_speed);
|
||||
prev_nominal_speed = nominal_speed;
|
||||
block_index = Planner_NextBlockIndex(block_index);
|
||||
}
|
||||
while(block_index != block_buffer_head)
|
||||
{
|
||||
block = &block_buffer[block_index];
|
||||
nominal_speed = Planner_ComputeProfileNominalSpeed(block);
|
||||
Planner_ComputeProfileParams(block, nominal_speed, prev_nominal_speed);
|
||||
prev_nominal_speed = nominal_speed;
|
||||
block_index = Planner_NextBlockIndex(block_index);
|
||||
}
|
||||
|
||||
planner.previous_nominal_speed = prev_nominal_speed; // Update prev nominal speed for next incoming block.
|
||||
planner.previous_nominal_speed = prev_nominal_speed; // Update prev nominal speed for next incoming block.
|
||||
}
|
||||
|
||||
|
||||
// Reset the planner position vectors. Called by the system abort/initialization routine.
|
||||
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++) {
|
||||
// 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) {
|
||||
planner.position[X_AXIS] = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||
}
|
||||
else if(idx==Y_AXIS) {
|
||||
planner.position[Y_AXIS] = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||
}
|
||||
else {
|
||||
planner.position[idx] = sys_position[idx];
|
||||
}
|
||||
if(idx==X_AXIS)
|
||||
{
|
||||
planner.position[X_AXIS] = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||
}
|
||||
else if(idx==Y_AXIS)
|
||||
{
|
||||
planner.position[Y_AXIS] = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||
}
|
||||
else
|
||||
{
|
||||
planner.position[idx] = sys_position[idx];
|
||||
}
|
||||
#else
|
||||
planner.position[idx] = sys_position[idx];
|
||||
planner.position[idx] = sys_position[idx];
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
@ -399,21 +435,22 @@ void Planner_SyncPosition(void)
|
|||
// Called after a steppers have come to a complete stop for a feed hold and the cycle is stopped.
|
||||
void Planner_CycleReinitialize(void)
|
||||
{
|
||||
// Re-plan from a complete stop. Reset planner entry speeds and buffer planned pointer.
|
||||
Stepper_UpdatePlannerBlockParams();
|
||||
block_buffer_planned = block_buffer_tail;
|
||||
Planner_Recalculate();
|
||||
// Re-plan from a complete stop. Reset planner entry speeds and buffer planned pointer.
|
||||
Stepper_UpdatePlannerBlockParams();
|
||||
block_buffer_planned = block_buffer_tail;
|
||||
Planner_Recalculate();
|
||||
}
|
||||
|
||||
|
||||
// Returns the number of available blocks are in the planner buffer.
|
||||
uint8_t Planner_GetBlockBufferAvailable(void)
|
||||
{
|
||||
if(block_buffer_head >= block_buffer_tail) {
|
||||
return (BLOCK_BUFFER_SIZE-1)-(block_buffer_head-block_buffer_tail);
|
||||
}
|
||||
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);
|
||||
return (block_buffer_tail-block_buffer_head-1);
|
||||
}
|
||||
|
||||
|
||||
|
@ -421,34 +458,37 @@ uint8_t Planner_GetBlockBufferAvailable(void)
|
|||
// NOTE: Deprecated. Not used unless classic status reports are enabled in config.h
|
||||
uint8_t Planner_GetBlockBufferCount(void)
|
||||
{
|
||||
if(block_buffer_head >= block_buffer_tail) {
|
||||
return block_buffer_head-block_buffer_tail;
|
||||
}
|
||||
if(block_buffer_head >= block_buffer_tail)
|
||||
{
|
||||
return block_buffer_head-block_buffer_tail;
|
||||
}
|
||||
|
||||
return BLOCK_BUFFER_SIZE - (block_buffer_tail-block_buffer_head);
|
||||
return BLOCK_BUFFER_SIZE - (block_buffer_tail-block_buffer_head);
|
||||
}
|
||||
|
||||
|
||||
// Returns the availability status of the block ring buffer. True, if full.
|
||||
uint8_t Planner_CheckBufferFull(void)
|
||||
{
|
||||
if(block_buffer_tail == next_buffer_head) {
|
||||
return true;
|
||||
}
|
||||
if(block_buffer_tail == next_buffer_head)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
// Returns the index of the previous block in the ring buffer
|
||||
static uint8_t Planner_PrevBlockIndex(uint8_t block_index)
|
||||
{
|
||||
if(block_index == 0) {
|
||||
block_index = BLOCK_BUFFER_SIZE;
|
||||
}
|
||||
block_index--;
|
||||
if(block_index == 0)
|
||||
{
|
||||
block_index = BLOCK_BUFFER_SIZE;
|
||||
}
|
||||
block_index--;
|
||||
|
||||
return block_index;
|
||||
return block_index;
|
||||
}
|
||||
|
||||
|
||||
|
@ -519,83 +559,98 @@ static uint8_t Planner_PrevBlockIndex(uint8_t block_index)
|
|||
*/
|
||||
static void Planner_Recalculate(void)
|
||||
{
|
||||
// Initialize block index to the last block in the planner buffer.
|
||||
uint8_t block_index = Planner_PrevBlockIndex(block_buffer_head);
|
||||
// Initialize block index to the last block in the planner buffer.
|
||||
uint8_t block_index = Planner_PrevBlockIndex(block_buffer_head);
|
||||
|
||||
// Bail. Can't do anything with only one plan-able block.
|
||||
if(block_index == block_buffer_planned) {
|
||||
return;
|
||||
}
|
||||
// Bail. Can't do anything with 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;
|
||||
Planner_Block_t *next;
|
||||
Planner_Block_t *current = &block_buffer[block_index];
|
||||
// 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;
|
||||
Planner_Block_t *next;
|
||||
Planner_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);
|
||||
// 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 = Planner_PrevBlockIndex(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) { Stepper_UpdatePlannerBlockParams(); }
|
||||
}
|
||||
else { // Three or more plan-able blocks
|
||||
while (block_index != block_buffer_planned) {
|
||||
next = current;
|
||||
current = &block_buffer[block_index];
|
||||
block_index = Planner_PrevBlockIndex(block_index);
|
||||
block_index = Planner_PrevBlockIndex(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)
|
||||
{
|
||||
Stepper_UpdatePlannerBlockParams();
|
||||
}
|
||||
}
|
||||
else // Three or more plan-able blocks
|
||||
{
|
||||
while (block_index != block_buffer_planned)
|
||||
{
|
||||
next = current;
|
||||
current = &block_buffer[block_index];
|
||||
block_index = Planner_PrevBlockIndex(block_index);
|
||||
|
||||
// Check if next block is the tail block(=planned block). If so, update current stepper parameters.
|
||||
if(block_index == block_buffer_tail) {
|
||||
Stepper_UpdatePlannerBlockParams();
|
||||
}
|
||||
// Check if next block is the tail block(=planned block). If so, update current stepper parameters.
|
||||
if(block_index == block_buffer_tail)
|
||||
{
|
||||
Stepper_UpdatePlannerBlockParams();
|
||||
}
|
||||
|
||||
// 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;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
// 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 = Planner_NextBlockIndex(block_buffer_planned);
|
||||
while(block_index != block_buffer_head) {
|
||||
current = next;
|
||||
next = &block_buffer[block_index];
|
||||
// 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 = Planner_NextBlockIndex(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;
|
||||
// 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.
|
||||
}
|
||||
}
|
||||
// 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 = Planner_NextBlockIndex( 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 = Planner_NextBlockIndex( block_index );
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
@ -603,15 +658,18 @@ static void Planner_Recalculate(void)
|
|||
// previous and current nominal speeds and max junction speed.
|
||||
static void Planner_ComputeProfileParams(Planner_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;
|
||||
}
|
||||
// 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;
|
||||
}
|
||||
if(block->max_entry_speed_sqr > block->max_junction_speed_sqr)
|
||||
{
|
||||
block->max_entry_speed_sqr = block->max_junction_speed_sqr;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
Copyright (c) 2017 Patrick F.
|
||||
Copyright (c) 2017 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
|
||||
|
@ -27,71 +27,73 @@
|
|||
|
||||
|
||||
// Returned status message from planner.
|
||||
#define PLAN_OK true
|
||||
#define PLAN_EMPTY_BLOCK false
|
||||
#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.
|
||||
#define PL_COND_FLAG_NO_FEED_OVERRIDE BIT(2) // Motion does not honor feed override.
|
||||
#define PL_COND_FLAG_INVERSE_TIME BIT(3) // Interprets feed rate value as inverse time when set.
|
||||
#define PL_COND_FLAG_SPINDLE_CW BIT(4)
|
||||
#define PL_COND_FLAG_SPINDLE_CCW BIT(5)
|
||||
#define PL_COND_FLAG_COOLANT_FLOOD BIT(6)
|
||||
#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_SPINDLE_MASK (PL_COND_FLAG_SPINDLE_CW|PL_COND_FLAG_SPINDLE_CCW)
|
||||
#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)
|
||||
#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.
|
||||
#define PL_COND_FLAG_NO_FEED_OVERRIDE BIT(2) // Motion does not honor feed override.
|
||||
#define PL_COND_FLAG_INVERSE_TIME BIT(3) // Interprets feed rate value as inverse time when set.
|
||||
#define PL_COND_FLAG_SPINDLE_CW BIT(4)
|
||||
#define PL_COND_FLAG_SPINDLE_CCW BIT(5)
|
||||
#define PL_COND_FLAG_COOLANT_FLOOD BIT(6)
|
||||
#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_SPINDLE_MASK (PL_COND_FLAG_SPINDLE_CW|PL_COND_FLAG_SPINDLE_CCW)
|
||||
#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)
|
||||
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.
|
||||
int32_t line_number; // Block line number for real-time reporting. Copied from pl_line_data.
|
||||
// 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.
|
||||
int32_t line_number; // Block line number for real-time reporting. Copied from pl_line_data.
|
||||
|
||||
// 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.
|
||||
// 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).
|
||||
// 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).
|
||||
|
||||
// Stored spindle speed data used by spindle overrides and resuming methods.
|
||||
float spindle_speed; // Block spindle speed. Copied from pl_line_data.
|
||||
// Stored spindle speed data used by spindle overrides and resuming methods.
|
||||
float spindle_speed; // Block spindle speed. Copied from pl_line_data.
|
||||
|
||||
uint8_t backlash_motion;
|
||||
uint8_t backlash_motion;
|
||||
} Planner_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.
|
||||
int32_t line_number; // Desired line number to report when executing.
|
||||
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.
|
||||
int32_t line_number; // Desired line number to report when executing.
|
||||
|
||||
uint8_t backlash_motion;
|
||||
uint8_t backlash_motion;
|
||||
} Planner_LineData_t;
|
||||
|
||||
|
||||
// Initialize and reset the motion plan subsystem
|
||||
void Planner_Init(void);
|
||||
void Planner_Reset(void); // Reset all
|
||||
void Planner_Reset(void); // Reset all
|
||||
void Planner_ResetBuffer(void); // Reset buffer only.
|
||||
|
||||
// Add a new linear movement to the buffer. target[N_AXIS] is the signed, absolute target position
|
||||
|
|
42
grbl/Probe.c
42
grbl/Probe.c
|
@ -3,7 +3,7 @@
|
|||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2017 Patrick F.
|
||||
Copyright (c) 2017 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
|
||||
|
@ -32,16 +32,16 @@ static uint8_t probe_invert_mask;
|
|||
// Probe pin initialization routine.
|
||||
void Probe_Init(void)
|
||||
{
|
||||
GPIO_InitGPIO(GPIO_PROBE);
|
||||
GPIO_InitGPIO(GPIO_PROBE);
|
||||
|
||||
Probe_ConfigureInvertMask(false); // Initialize invert mask.*/
|
||||
Probe_ConfigureInvertMask(false); // Initialize invert mask.*/
|
||||
}
|
||||
|
||||
|
||||
void Probe_Reset(void)
|
||||
{
|
||||
// Clear probe position.
|
||||
memset(sys_probe_position, 0 , sizeof(sys_probe_position));
|
||||
// Clear probe position.
|
||||
memset(sys_probe_position, 0 , sizeof(sys_probe_position));
|
||||
}
|
||||
|
||||
|
||||
|
@ -50,20 +50,23 @@ void Probe_Reset(void)
|
|||
// and the probing cycle modes for toward-workpiece/away-from-workpiece.
|
||||
void Probe_ConfigureInvertMask(uint8_t is_probe_away)
|
||||
{
|
||||
probe_invert_mask = 0; // Initialize as zero.
|
||||
probe_invert_mask = 0; // Initialize as zero.
|
||||
|
||||
if(BIT_IS_FALSE(settings.flags, BITFLAG_INVERT_PROBE_PIN)) {
|
||||
probe_invert_mask ^= 1;
|
||||
}
|
||||
if(is_probe_away) {
|
||||
probe_invert_mask ^= 1;
|
||||
}
|
||||
if(BIT_IS_FALSE(settings.flags, BITFLAG_INVERT_PROBE_PIN))
|
||||
{
|
||||
probe_invert_mask ^= 1;
|
||||
}
|
||||
if(is_probe_away)
|
||||
{
|
||||
probe_invert_mask ^= 1;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Returns the probe pin state. Triggered = true. Called by gcode parser and probe state monitor.
|
||||
uint8_t Probe_GetState(void) {
|
||||
return (GPIO_ReadInputDataBit(GPIO_PROBE_PORT, GPIO_PROBE_PIN) ^ probe_invert_mask);
|
||||
uint8_t Probe_GetState(void)
|
||||
{
|
||||
return (GPIO_ReadInputDataBit(GPIO_PROBE_PORT, GPIO_PROBE_PIN) ^ probe_invert_mask);
|
||||
}
|
||||
|
||||
|
||||
|
@ -72,9 +75,10 @@ uint8_t Probe_GetState(void) {
|
|||
// NOTE: This function must be extremely efficient as to not bog down the stepper ISR.
|
||||
void Probe_StateMonitor(void)
|
||||
{
|
||||
if(Probe_GetState()) {
|
||||
sys_probe_state = PROBE_OFF;
|
||||
memcpy(sys_probe_position, sys_position, sizeof(sys_position));
|
||||
BIT_TRUE(sys_rt_exec_state, EXEC_MOTION_CANCEL);
|
||||
}
|
||||
if(Probe_GetState())
|
||||
{
|
||||
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-Advanced
|
||||
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2017 Patrick F.
|
||||
Copyright (c) 2017 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
|
||||
|
@ -25,8 +25,8 @@
|
|||
|
||||
|
||||
// Values that define the probing state machine.
|
||||
#define PROBE_OFF 0 // Probing disabled or not in use. (Must be zero.)
|
||||
#define PROBE_ACTIVE 1 // Actively watching the input pin.
|
||||
#define PROBE_OFF 0 // Probing disabled or not in use. (Must be zero.)
|
||||
#define PROBE_ACTIVE 1 // Actively watching the input pin.
|
||||
|
||||
// Probe pin initialization routine.
|
||||
void Probe_Init(void);
|
||||
|
|
1491
grbl/Protocol.c
1491
grbl/Protocol.c
Plik diff jest za duży
Load Diff
|
@ -4,7 +4,7 @@
|
|||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
Copyright (c) 2017 Patrick F.
|
||||
Copyright (c) 2017 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
|
||||
|
|
1064
grbl/Report.c
1064
grbl/Report.c
Plik diff jest za duży
Load Diff
118
grbl/Report.h
118
grbl/Report.h
|
@ -3,7 +3,7 @@
|
|||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2017-2020 Patrick F.
|
||||
Copyright (c) 2017-2020 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
|
||||
|
@ -25,70 +25,70 @@
|
|||
|
||||
|
||||
// Define Grbl status codes. Valid values (0-255)
|
||||
#define STATUS_OK 0
|
||||
#define STATUS_EXPECTED_COMMAND_LETTER 1
|
||||
#define STATUS_BAD_NUMBER_FORMAT 2
|
||||
#define STATUS_INVALID_STATEMENT 3
|
||||
#define STATUS_NEGATIVE_VALUE 4
|
||||
#define STATUS_SETTING_DISABLED 5
|
||||
#define STATUS_SETTING_STEP_PULSE_MIN 6
|
||||
#define STATUS_SETTING_READ_FAIL 7
|
||||
#define STATUS_IDLE_ERROR 8
|
||||
#define STATUS_SYSTEM_GC_LOCK 9
|
||||
#define STATUS_SOFT_LIMIT_ERROR 10
|
||||
#define STATUS_OVERFLOW 11
|
||||
#define STATUS_MAX_STEP_RATE_EXCEEDED 12
|
||||
#define STATUS_CHECK_DOOR 13
|
||||
#define STATUS_LINE_LENGTH_EXCEEDED 14
|
||||
#define STATUS_TRAVEL_EXCEEDED 15
|
||||
#define STATUS_INVALID_JOG_COMMAND 16
|
||||
#define STATUS_SETTING_DISABLED_LASER 17
|
||||
#define STATUS_MACHINE_NOT_HOMED 18
|
||||
#define STATUS_OK 0
|
||||
#define STATUS_EXPECTED_COMMAND_LETTER 1
|
||||
#define STATUS_BAD_NUMBER_FORMAT 2
|
||||
#define STATUS_INVALID_STATEMENT 3
|
||||
#define STATUS_NEGATIVE_VALUE 4
|
||||
#define STATUS_SETTING_DISABLED 5
|
||||
#define STATUS_SETTING_STEP_PULSE_MIN 6
|
||||
#define STATUS_SETTING_READ_FAIL 7
|
||||
#define STATUS_IDLE_ERROR 8
|
||||
#define STATUS_SYSTEM_GC_LOCK 9
|
||||
#define STATUS_SOFT_LIMIT_ERROR 10
|
||||
#define STATUS_OVERFLOW 11
|
||||
#define STATUS_MAX_STEP_RATE_EXCEEDED 12
|
||||
#define STATUS_CHECK_DOOR 13
|
||||
#define STATUS_LINE_LENGTH_EXCEEDED 14
|
||||
#define STATUS_TRAVEL_EXCEEDED 15
|
||||
#define STATUS_INVALID_JOG_COMMAND 16
|
||||
#define STATUS_SETTING_DISABLED_LASER 17
|
||||
#define STATUS_MACHINE_NOT_HOMED 18
|
||||
#define STATUS_TLS_NOT_SET 19
|
||||
|
||||
#define STATUS_GCODE_UNSUPPORTED_COMMAND 20
|
||||
#define STATUS_GCODE_MODAL_GROUP_VIOLATION 21
|
||||
#define STATUS_GCODE_UNDEFINED_FEED_RATE 22
|
||||
#define STATUS_GCODE_COMMAND_VALUE_NOT_INTEGER 23
|
||||
#define STATUS_GCODE_AXIS_COMMAND_CONFLICT 24
|
||||
#define STATUS_GCODE_WORD_REPEATED 25
|
||||
#define STATUS_GCODE_NO_AXIS_WORDS 26
|
||||
#define STATUS_GCODE_INVALID_LINE_NUMBER 27
|
||||
#define STATUS_GCODE_VALUE_WORD_MISSING 28
|
||||
#define STATUS_GCODE_UNSUPPORTED_COORD_SYS 29
|
||||
#define STATUS_GCODE_G53_INVALID_MOTION_MODE 30
|
||||
#define STATUS_GCODE_AXIS_WORDS_EXIST 31
|
||||
#define STATUS_GCODE_NO_AXIS_WORDS_IN_PLANE 32
|
||||
#define STATUS_GCODE_INVALID_TARGET 33
|
||||
#define STATUS_GCODE_ARC_RADIUS_ERROR 34
|
||||
#define STATUS_GCODE_NO_OFFSETS_IN_PLANE 35
|
||||
#define STATUS_GCODE_UNUSED_WORDS 36
|
||||
#define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37
|
||||
#define STATUS_GCODE_MAX_VALUE_EXCEEDED 38
|
||||
#define STATUS_GCODE_UNSUPPORTED_COMMAND 20
|
||||
#define STATUS_GCODE_MODAL_GROUP_VIOLATION 21
|
||||
#define STATUS_GCODE_UNDEFINED_FEED_RATE 22
|
||||
#define STATUS_GCODE_COMMAND_VALUE_NOT_INTEGER 23
|
||||
#define STATUS_GCODE_AXIS_COMMAND_CONFLICT 24
|
||||
#define STATUS_GCODE_WORD_REPEATED 25
|
||||
#define STATUS_GCODE_NO_AXIS_WORDS 26
|
||||
#define STATUS_GCODE_INVALID_LINE_NUMBER 27
|
||||
#define STATUS_GCODE_VALUE_WORD_MISSING 28
|
||||
#define STATUS_GCODE_UNSUPPORTED_COORD_SYS 29
|
||||
#define STATUS_GCODE_G53_INVALID_MOTION_MODE 30
|
||||
#define STATUS_GCODE_AXIS_WORDS_EXIST 31
|
||||
#define STATUS_GCODE_NO_AXIS_WORDS_IN_PLANE 32
|
||||
#define STATUS_GCODE_INVALID_TARGET 33
|
||||
#define STATUS_GCODE_ARC_RADIUS_ERROR 34
|
||||
#define STATUS_GCODE_NO_OFFSETS_IN_PLANE 35
|
||||
#define STATUS_GCODE_UNUSED_WORDS 36
|
||||
#define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37
|
||||
#define STATUS_GCODE_MAX_VALUE_EXCEEDED 38
|
||||
|
||||
// Define Grbl alarm codes. Valid values (1-255). 0 is reserved.
|
||||
#define ALARM_HARD_LIMIT_ERROR EXEC_ALARM_HARD_LIMIT
|
||||
#define ALARM_SOFT_LIMIT_ERROR EXEC_ALARM_SOFT_LIMIT
|
||||
#define ALARM_ABORT_CYCLE EXEC_ALARM_ABORT_CYCLE
|
||||
#define ALARM_PROBE_FAIL_INITIAL EXEC_ALARM_PROBE_FAIL_INITIAL
|
||||
#define ALARM_PROBE_FAIL_CONTACT EXEC_ALARM_PROBE_FAIL_CONTACT
|
||||
#define ALARM_HOMING_FAIL_RESET EXEC_ALARM_HOMING_FAIL_RESET
|
||||
#define ALARM_HOMING_FAIL_DOOR EXEC_ALARM_HOMING_FAIL_DOOR
|
||||
#define ALARM_HOMING_FAIL_PULLOFF EXEC_ALARM_HOMING_FAIL_PULLOFF
|
||||
#define ALARM_HOMING_FAIL_APPROACH EXEC_ALARM_HOMING_FAIL_APPROACH
|
||||
#define ALARM_HARD_LIMIT_ERROR EXEC_ALARM_HARD_LIMIT
|
||||
#define ALARM_SOFT_LIMIT_ERROR EXEC_ALARM_SOFT_LIMIT
|
||||
#define ALARM_ABORT_CYCLE EXEC_ALARM_ABORT_CYCLE
|
||||
#define ALARM_PROBE_FAIL_INITIAL EXEC_ALARM_PROBE_FAIL_INITIAL
|
||||
#define ALARM_PROBE_FAIL_CONTACT EXEC_ALARM_PROBE_FAIL_CONTACT
|
||||
#define ALARM_HOMING_FAIL_RESET EXEC_ALARM_HOMING_FAIL_RESET
|
||||
#define ALARM_HOMING_FAIL_DOOR EXEC_ALARM_HOMING_FAIL_DOOR
|
||||
#define ALARM_HOMING_FAIL_PULLOFF EXEC_ALARM_HOMING_FAIL_PULLOFF
|
||||
#define ALARM_HOMING_FAIL_APPROACH EXEC_ALARM_HOMING_FAIL_APPROACH
|
||||
|
||||
// Define Grbl feedback message codes. Valid values (0-255).
|
||||
#define MESSAGE_CRITICAL_EVENT 1
|
||||
#define MESSAGE_ALARM_LOCK 2
|
||||
#define MESSAGE_ALARM_UNLOCK 3
|
||||
#define MESSAGE_ENABLED 4
|
||||
#define MESSAGE_DISABLED 5
|
||||
#define MESSAGE_SAFETY_DOOR_AJAR 6
|
||||
#define MESSAGE_CHECK_LIMITS 7
|
||||
#define MESSAGE_PROGRAM_END 8
|
||||
#define MESSAGE_RESTORE_DEFAULTS 9
|
||||
#define MESSAGE_SPINDLE_RESTORE 10
|
||||
#define MESSAGE_SLEEP_MODE 11
|
||||
#define MESSAGE_CRITICAL_EVENT 1
|
||||
#define MESSAGE_ALARM_LOCK 2
|
||||
#define MESSAGE_ALARM_UNLOCK 3
|
||||
#define MESSAGE_ENABLED 4
|
||||
#define MESSAGE_DISABLED 5
|
||||
#define MESSAGE_SAFETY_DOOR_AJAR 6
|
||||
#define MESSAGE_CHECK_LIMITS 7
|
||||
#define MESSAGE_PROGRAM_END 8
|
||||
#define MESSAGE_RESTORE_DEFAULTS 9
|
||||
#define MESSAGE_SPINDLE_RESTORE 10
|
||||
#define MESSAGE_SLEEP_MODE 11
|
||||
#define MESSAGE_INVALID_TOOL 12
|
||||
|
||||
|
||||
|
|
733
grbl/Settings.c
733
grbl/Settings.c
|
@ -4,7 +4,7 @@
|
|||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
Copyright (c) 2017-2020 Patrick F.
|
||||
Copyright (c) 2017-2020 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
|
||||
|
@ -42,12 +42,12 @@ Settings_t settings;
|
|||
void Settings_StoreStartupLine(uint8_t n, char *line)
|
||||
{
|
||||
#ifdef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE
|
||||
Protocol_BufferSynchronize(); // A startup line may contain a motion and be executing.
|
||||
Protocol_BufferSynchronize(); // A startup line may contain a motion and be executing.
|
||||
#endif
|
||||
|
||||
uint32_t addr = n*(STARTUP_LINE_LEN+1)+EEPROM_ADDR_STARTUP_BLOCK;
|
||||
Nvm_Write(addr, (uint8_t*)line, STARTUP_LINE_LEN);
|
||||
Nvm_Update();
|
||||
uint32_t addr = n*(STARTUP_LINE_LEN+1)+EEPROM_ADDR_STARTUP_BLOCK;
|
||||
Nvm_Write(addr, (uint8_t*)line, STARTUP_LINE_LEN);
|
||||
Nvm_Update();
|
||||
}
|
||||
|
||||
|
||||
|
@ -55,9 +55,9 @@ void Settings_StoreStartupLine(uint8_t n, char *line)
|
|||
// NOTE: This function can only be called in IDLE state.
|
||||
void Settings_StoreBuildInfo(char *line)
|
||||
{
|
||||
// Build info can only be stored when state is IDLE.
|
||||
Nvm_Write(EEPROM_ADDR_BUILD_INFO, (uint8_t*)line, STARTUP_LINE_LEN);
|
||||
Nvm_Update();
|
||||
// Build info can only be stored when state is IDLE.
|
||||
Nvm_Write(EEPROM_ADDR_BUILD_INFO, (uint8_t*)line, STARTUP_LINE_LEN);
|
||||
Nvm_Update();
|
||||
}
|
||||
|
||||
|
||||
|
@ -68,10 +68,10 @@ void Settings_WriteCoordData(uint8_t coord_select, float *coord_data)
|
|||
Protocol_BufferSynchronize();
|
||||
#endif
|
||||
|
||||
uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS;
|
||||
Nvm_Write(addr, (uint8_t*)coord_data, sizeof(float)*N_AXIS);
|
||||
uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS;
|
||||
Nvm_Write(addr, (uint8_t*)coord_data, sizeof(float)*N_AXIS);
|
||||
|
||||
Nvm_Update();
|
||||
Nvm_Update();
|
||||
}
|
||||
|
||||
|
||||
|
@ -79,111 +79,141 @@ void Settings_WriteCoordData(uint8_t coord_select, float *coord_data)
|
|||
// NOTE: This function can only be called in IDLE state.
|
||||
void WriteGlobalSettings(void)
|
||||
{
|
||||
Nvm_WriteByte(0, SETTINGS_VERSION);
|
||||
Nvm_Write(EEPROM_ADDR_GLOBAL, (uint8_t*)&settings, sizeof(Settings_t));
|
||||
Nvm_WriteByte(0, SETTINGS_VERSION);
|
||||
Nvm_Write(EEPROM_ADDR_GLOBAL, (uint8_t*)&settings, sizeof(Settings_t));
|
||||
|
||||
Nvm_Update();
|
||||
Nvm_Update();
|
||||
}
|
||||
|
||||
|
||||
// Method to restore EEPROM-saved Grbl global settings back to defaults.
|
||||
void Settings_Restore(uint8_t restore_flag) {
|
||||
if(restore_flag & SETTINGS_RESTORE_DEFAULTS) {
|
||||
settings.system_flags = DEFAULT_SYSTEM_INVERT_MASK;
|
||||
settings.flags2 = DEFAULT_LATHE_MODE;
|
||||
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;
|
||||
void Settings_Restore(uint8_t restore_flag)
|
||||
{
|
||||
if(restore_flag & SETTINGS_RESTORE_DEFAULTS)
|
||||
{
|
||||
settings.system_flags = DEFAULT_SYSTEM_INVERT_MASK;
|
||||
settings.flags2 = DEFAULT_LATHE_MODE;
|
||||
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.rpm_max = DEFAULT_SPINDLE_RPM_MAX;
|
||||
settings.rpm_min = DEFAULT_SPINDLE_RPM_MIN;
|
||||
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.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.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.steps_per_mm[A_AXIS] = DEFAULT_A_STEPS_PER_DEG;
|
||||
settings.steps_per_mm[B_AXIS] = DEFAULT_B_STEPS_PER_DEG;
|
||||
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.steps_per_mm[A_AXIS] = DEFAULT_A_STEPS_PER_DEG;
|
||||
settings.steps_per_mm[B_AXIS] = DEFAULT_B_STEPS_PER_DEG;
|
||||
|
||||
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.max_rate[A_AXIS] = DEFAULT_A_MAX_RATE;
|
||||
settings.max_rate[B_AXIS] = DEFAULT_B_MAX_RATE;
|
||||
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.max_rate[A_AXIS] = DEFAULT_A_MAX_RATE;
|
||||
settings.max_rate[B_AXIS] = DEFAULT_B_MAX_RATE;
|
||||
|
||||
settings.acceleration[X_AXIS] = DEFAULT_X_ACCELERATION;
|
||||
settings.acceleration[Y_AXIS] = DEFAULT_Y_ACCELERATION;
|
||||
settings.acceleration[Z_AXIS] = DEFAULT_Z_ACCELERATION;
|
||||
settings.acceleration[A_AXIS] = DEFAULT_A_ACCELERATION;
|
||||
settings.acceleration[B_AXIS] = DEFAULT_B_ACCELERATION;
|
||||
settings.acceleration[X_AXIS] = DEFAULT_X_ACCELERATION;
|
||||
settings.acceleration[Y_AXIS] = DEFAULT_Y_ACCELERATION;
|
||||
settings.acceleration[Z_AXIS] = DEFAULT_Z_ACCELERATION;
|
||||
settings.acceleration[A_AXIS] = DEFAULT_A_ACCELERATION;
|
||||
settings.acceleration[B_AXIS] = DEFAULT_B_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.max_travel[A_AXIS] = (-DEFAULT_A_MAX_TRAVEL);
|
||||
settings.max_travel[B_AXIS] = (-DEFAULT_B_MAX_TRAVEL);
|
||||
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.max_travel[A_AXIS] = (-DEFAULT_A_MAX_TRAVEL);
|
||||
settings.max_travel[B_AXIS] = (-DEFAULT_B_MAX_TRAVEL);
|
||||
|
||||
settings.backlash[X_AXIS] = DEFAULT_X_BACKLASH;
|
||||
settings.backlash[Y_AXIS] = DEFAULT_Y_BACKLASH;
|
||||
settings.backlash[Z_AXIS] = DEFAULT_Z_BACKLASH;
|
||||
settings.backlash[X_AXIS] = DEFAULT_X_BACKLASH;
|
||||
settings.backlash[Y_AXIS] = DEFAULT_Y_BACKLASH;
|
||||
settings.backlash[Z_AXIS] = DEFAULT_Z_BACKLASH;
|
||||
|
||||
settings.tool_change = DEFAULT_TOOL_CHANGE_MODE;
|
||||
settings.tls_valid = 0;
|
||||
settings.tls_position[X_AXIS] = 0;
|
||||
settings.tls_position[Y_AXIS] = 0;
|
||||
settings.tls_position[Z_AXIS] = 0;
|
||||
settings.tool_change = DEFAULT_TOOL_CHANGE_MODE;
|
||||
settings.tls_valid = 0;
|
||||
settings.tls_position[X_AXIS] = 0;
|
||||
settings.tls_position[Y_AXIS] = 0;
|
||||
settings.tls_position[Z_AXIS] = 0;
|
||||
|
||||
WriteGlobalSettings();
|
||||
}
|
||||
WriteGlobalSettings();
|
||||
}
|
||||
|
||||
if(restore_flag & SETTINGS_RESTORE_PARAMETERS) {
|
||||
uint8_t idx;
|
||||
float coord_data[N_AXIS];
|
||||
if(restore_flag & SETTINGS_RESTORE_PARAMETERS)
|
||||
{
|
||||
uint8_t idx;
|
||||
float coord_data[N_AXIS];
|
||||
|
||||
memset(&coord_data, 0, sizeof(coord_data));
|
||||
memset(&coord_data, 0, sizeof(coord_data));
|
||||
|
||||
for(idx = 0; idx <= SETTING_INDEX_NCOORD; idx++) {
|
||||
Settings_WriteCoordData(idx, coord_data);
|
||||
}
|
||||
}
|
||||
for(idx = 0; idx <= SETTING_INDEX_NCOORD; idx++)
|
||||
{
|
||||
Settings_WriteCoordData(idx, coord_data);
|
||||
}
|
||||
}
|
||||
|
||||
if(restore_flag & SETTINGS_RESTORE_STARTUP_LINES) {
|
||||
if(restore_flag & SETTINGS_RESTORE_STARTUP_LINES)
|
||||
{
|
||||
#if N_STARTUP_LINE > 0
|
||||
Nvm_WriteByte(EEPROM_ADDR_STARTUP_BLOCK, 0);
|
||||
Nvm_WriteByte(EEPROM_ADDR_STARTUP_BLOCK+1, 0); // Checksum
|
||||
Nvm_WriteByte(EEPROM_ADDR_STARTUP_BLOCK, 0);
|
||||
Nvm_WriteByte(EEPROM_ADDR_STARTUP_BLOCK+1, 0); // Checksum
|
||||
#endif
|
||||
#if N_STARTUP_LINE > 1
|
||||
Nvm_WriteByte(EEPROM_ADDR_STARTUP_BLOCK+(STARTUP_LINE_LEN+1), 0);
|
||||
Nvm_WriteByte(EEPROM_ADDR_STARTUP_BLOCK+(STARTUP_LINE_LEN+2), 0); // Checksum
|
||||
Nvm_WriteByte(EEPROM_ADDR_STARTUP_BLOCK+(STARTUP_LINE_LEN+1), 0);
|
||||
Nvm_WriteByte(EEPROM_ADDR_STARTUP_BLOCK+(STARTUP_LINE_LEN+2), 0); // Checksum
|
||||
#endif
|
||||
Nvm_Update();
|
||||
}
|
||||
Nvm_Update();
|
||||
}
|
||||
|
||||
if(restore_flag & SETTINGS_RESTORE_BUILD_INFO) {
|
||||
Nvm_WriteByte(EEPROM_ADDR_BUILD_INFO , 0);
|
||||
Nvm_WriteByte(EEPROM_ADDR_BUILD_INFO+1 , 0); // Checksum
|
||||
Nvm_Update();
|
||||
}
|
||||
if(restore_flag & SETTINGS_RESTORE_BUILD_INFO)
|
||||
{
|
||||
Nvm_WriteByte(EEPROM_ADDR_BUILD_INFO , 0);
|
||||
Nvm_WriteByte(EEPROM_ADDR_BUILD_INFO+1 , 0); // Checksum
|
||||
Nvm_Update();
|
||||
}
|
||||
|
||||
if(restore_flag & SETTINGS_RESTORE_TOOLS)
|
||||
if(restore_flag & SETTINGS_RESTORE_TOOLS)
|
||||
{
|
||||
TT_Reset();
|
||||
}
|
||||
|
@ -193,16 +223,17 @@ void Settings_Restore(uint8_t restore_flag) {
|
|||
// Reads startup line from EEPROM. Updated pointed line string data.
|
||||
uint8_t Settings_ReadStartupLine(uint8_t n, char *line)
|
||||
{
|
||||
uint32_t addr = n*(STARTUP_LINE_LEN+1)+EEPROM_ADDR_STARTUP_BLOCK;
|
||||
if (!(Nvm_Read((uint8_t*)line, addr, STARTUP_LINE_LEN))) {
|
||||
// Reset line with default value
|
||||
line[0] = 0; // Empty line
|
||||
Settings_StoreStartupLine(n, line);
|
||||
uint32_t addr = n*(STARTUP_LINE_LEN+1)+EEPROM_ADDR_STARTUP_BLOCK;
|
||||
if(!(Nvm_Read((uint8_t*)line, addr, STARTUP_LINE_LEN)))
|
||||
{
|
||||
// Reset line with default value
|
||||
line[0] = 0; // Empty line
|
||||
Settings_StoreStartupLine(n, line);
|
||||
|
||||
return false;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
|
@ -220,7 +251,8 @@ void Settings_StoreToolParams(uint8_t tool_nr, ToolParams_t *params)
|
|||
|
||||
uint8_t Settings_ReadToolTable(ToolTable_t *table)
|
||||
{
|
||||
if(!(Nvm_Read((uint8_t*)table, EEPROM_ADDR_TOOLTABLE, sizeof(ToolTable_t)))) {
|
||||
if(!(Nvm_Read((uint8_t*)table, EEPROM_ADDR_TOOLTABLE, sizeof(ToolTable_t))))
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -231,194 +263,304 @@ uint8_t Settings_ReadToolTable(ToolTable_t *table)
|
|||
// Reads startup line from EEPROM. Updated pointed line string data.
|
||||
uint8_t Settings_ReadBuildInfo(char *line)
|
||||
{
|
||||
if(!(Nvm_Read((uint8_t*)line, EEPROM_ADDR_BUILD_INFO, STARTUP_LINE_LEN))) {
|
||||
// Reset line with default value
|
||||
line[0] = 0; // Empty line
|
||||
Settings_StoreBuildInfo(line);
|
||||
if(!(Nvm_Read((uint8_t*)line, EEPROM_ADDR_BUILD_INFO, STARTUP_LINE_LEN)))
|
||||
{
|
||||
// Reset line with default value
|
||||
line[0] = 0; // Empty line
|
||||
Settings_StoreBuildInfo(line);
|
||||
|
||||
return false;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
// Read selected coordinate data from EEPROM. Updates pointed coord_data value.
|
||||
uint8_t Settings_ReadCoordData(uint8_t coord_select, float *coord_data)
|
||||
{
|
||||
uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS;
|
||||
if(!(Nvm_Read((uint8_t*)coord_data, addr, sizeof(float)*N_AXIS))) {
|
||||
// Reset with default zero vector
|
||||
memset(&coord_data, 0.0, sizeof(coord_data));
|
||||
Settings_WriteCoordData(coord_select, coord_data);
|
||||
uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS;
|
||||
if(!(Nvm_Read((uint8_t*)coord_data, addr, sizeof(float)*N_AXIS)))
|
||||
{
|
||||
// Reset with default zero vector
|
||||
memset(&coord_data, 0.0, sizeof(coord_data));
|
||||
Settings_WriteCoordData(coord_select, coord_data);
|
||||
|
||||
return false;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
// Reads Grbl global settings struct from EEPROM.
|
||||
uint8_t ReadGlobalSettings() {
|
||||
// Check version-byte of eeprom
|
||||
uint8_t version = Nvm_ReadByte(0);
|
||||
uint8_t ReadGlobalSettings()
|
||||
{
|
||||
// Check version-byte of eeprom
|
||||
uint8_t version = Nvm_ReadByte(0);
|
||||
|
||||
if(version == SETTINGS_VERSION) {
|
||||
// Read settings-record and check checksum
|
||||
if(!(Nvm_Read((uint8_t*)&settings, EEPROM_ADDR_GLOBAL, sizeof(Settings_t)))) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else {
|
||||
return false;
|
||||
}
|
||||
if(version == SETTINGS_VERSION)
|
||||
{
|
||||
// Read settings-record and check checksum
|
||||
if(!(Nvm_Read((uint8_t*)&settings, EEPROM_ADDR_GLOBAL, sizeof(Settings_t))))
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
// A helper method to set settings from command line
|
||||
uint8_t Settings_StoreGlobalSetting(uint8_t parameter, float value) {
|
||||
if(value < 0.0) {
|
||||
return STATUS_NEGATIVE_VALUE;
|
||||
}
|
||||
uint8_t Settings_StoreGlobalSetting(uint8_t parameter, float value)
|
||||
{
|
||||
if(value < 0.0)
|
||||
{
|
||||
return STATUS_NEGATIVE_VALUE;
|
||||
}
|
||||
|
||||
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;
|
||||
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:
|
||||
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); }
|
||||
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;
|
||||
settings.steps_per_mm[parameter] = value;
|
||||
break;
|
||||
|
||||
case 1:
|
||||
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); }
|
||||
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;
|
||||
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: settings.backlash[parameter] = value; 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;
|
||||
}
|
||||
}
|
||||
}
|
||||
else {
|
||||
// Store non-axis Grbl settings
|
||||
uint8_t int_value = trunc(value);
|
||||
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:
|
||||
settings.backlash[parameter] = value;
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// Store non-axis Grbl settings
|
||||
uint8_t int_value = trunc(value);
|
||||
|
||||
switch(parameter)
|
||||
{
|
||||
case 0:
|
||||
//settings.system_flags = int_value;
|
||||
break;
|
||||
|
||||
case 1:
|
||||
settings.stepper_idle_lock_time = int_value;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
settings.step_invert_mask = int_value;
|
||||
Stepper_GenerateStepDirInvertMasks(); // Regenerate step and direction port invert masks.
|
||||
break;
|
||||
|
||||
case 3:
|
||||
settings.dir_invert_mask = int_value;
|
||||
Stepper_GenerateStepDirInvertMasks(); // 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_ConfigureInvertMask(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_FlagWcoChange(); // Make sure WCO is immediately updated.
|
||||
break;
|
||||
|
||||
case 14: settings.tool_change = int_value; break; // Check for range?
|
||||
|
||||
case 20:
|
||||
if (int_value) {
|
||||
if (BIT_IS_FALSE(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:
|
||||
if (int_value) { settings.flags |= BITFLAG_LASER_MODE; }
|
||||
else { settings.flags &= ~BITFLAG_LASER_MODE; }
|
||||
break;
|
||||
|
||||
case 33:
|
||||
if (int_value) { settings.flags2 |= BITFLAG_LATHE_MODE; }
|
||||
else { settings.flags2 &= ~BITFLAG_LATHE_MODE; }
|
||||
switch(parameter)
|
||||
{
|
||||
case 0:
|
||||
//settings.system_flags = int_value;
|
||||
break;
|
||||
|
||||
default:
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
}
|
||||
case 1:
|
||||
settings.stepper_idle_lock_time = int_value;
|
||||
break;
|
||||
|
||||
WriteGlobalSettings();
|
||||
case 2:
|
||||
settings.step_invert_mask = int_value;
|
||||
Stepper_GenerateStepDirInvertMasks(); // Regenerate step and direction port invert masks.
|
||||
break;
|
||||
|
||||
return 0;
|
||||
case 3:
|
||||
settings.dir_invert_mask = int_value;
|
||||
Stepper_GenerateStepDirInvertMasks(); // 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_ConfigureInvertMask(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_FlagWcoChange(); // Make sure WCO is immediately updated.
|
||||
break;
|
||||
|
||||
case 14:
|
||||
settings.tool_change = int_value;
|
||||
break; // Check for range?
|
||||
|
||||
case 20:
|
||||
if (int_value)
|
||||
{
|
||||
if (BIT_IS_FALSE(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:
|
||||
if (int_value)
|
||||
{
|
||||
settings.flags |= BITFLAG_LASER_MODE;
|
||||
}
|
||||
else
|
||||
{
|
||||
settings.flags &= ~BITFLAG_LASER_MODE;
|
||||
}
|
||||
break;
|
||||
|
||||
case 33:
|
||||
if (int_value)
|
||||
{
|
||||
settings.flags2 |= BITFLAG_LATHE_MODE;
|
||||
}
|
||||
else
|
||||
{
|
||||
settings.flags2 &= ~BITFLAG_LATHE_MODE;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
}
|
||||
|
||||
WriteGlobalSettings();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
@ -434,50 +576,87 @@ void Settings_StoreTlsPosition(void)
|
|||
// Initialize the config subsystem
|
||||
void Settings_Init(void)
|
||||
{
|
||||
Nvm_Init();
|
||||
Nvm_Init();
|
||||
|
||||
if(!ReadGlobalSettings()) {
|
||||
Report_StatusMessage(STATUS_SETTING_READ_FAIL);
|
||||
Settings_Restore(SETTINGS_RESTORE_ALL); // Force restore all EEPROM data.
|
||||
Report_GrblSettings();
|
||||
}
|
||||
if(!ReadGlobalSettings())
|
||||
{
|
||||
Report_StatusMessage(STATUS_SETTING_READ_FAIL);
|
||||
Settings_Restore(SETTINGS_RESTORE_ALL); // Force restore all EEPROM data.
|
||||
Report_GrblSettings();
|
||||
}
|
||||
|
||||
// Read tool table
|
||||
TT_Init();
|
||||
TT_Init();
|
||||
}
|
||||
|
||||
|
||||
// Returns step pin mask according to Grbl internal axis indexing.
|
||||
uint8_t Settings_GetStepPinMask(uint8_t axis_idx)
|
||||
{
|
||||
if(axis_idx == X_AXIS) { return (1<<X_STEP_BIT); }
|
||||
if(axis_idx == Y_AXIS) { return (1<<Y_STEP_BIT); }
|
||||
if(axis_idx == Z_AXIS) { return (1<<Z_STEP_BIT); }
|
||||
if(axis_idx == A_AXIS) { return (1<<A_STEP_BIT); }
|
||||
if(axis_idx == X_AXIS)
|
||||
{
|
||||
return (1<<X_STEP_BIT);
|
||||
}
|
||||
if(axis_idx == Y_AXIS)
|
||||
{
|
||||
return (1<<Y_STEP_BIT);
|
||||
}
|
||||
if(axis_idx == Z_AXIS)
|
||||
{
|
||||
return (1<<Z_STEP_BIT);
|
||||
}
|
||||
if(axis_idx == A_AXIS)
|
||||
{
|
||||
return (1<<A_STEP_BIT);
|
||||
}
|
||||
|
||||
return (1<<B_STEP_BIT);
|
||||
return (1<<B_STEP_BIT);
|
||||
}
|
||||
|
||||
|
||||
// Returns direction pin mask according to Grbl internal axis indexing.
|
||||
uint8_t Settings_GetDirectionPinMask(uint8_t axis_idx)
|
||||
{
|
||||
if(axis_idx == X_AXIS) { return (1<<X_DIRECTION_BIT); }
|
||||
if(axis_idx == Y_AXIS) { return (1<<Y_DIRECTION_BIT); }
|
||||
if(axis_idx == Z_AXIS) { return (1<<Z_DIRECTION_BIT); }
|
||||
if(axis_idx == A_AXIS) { return (1<<A_DIRECTION_BIT); }
|
||||
if(axis_idx == X_AXIS)
|
||||
{
|
||||
return (1<<X_DIRECTION_BIT);
|
||||
}
|
||||
if(axis_idx == Y_AXIS)
|
||||
{
|
||||
return (1<<Y_DIRECTION_BIT);
|
||||
}
|
||||
if(axis_idx == Z_AXIS)
|
||||
{
|
||||
return (1<<Z_DIRECTION_BIT);
|
||||
}
|
||||
if(axis_idx == A_AXIS)
|
||||
{
|
||||
return (1<<A_DIRECTION_BIT);
|
||||
}
|
||||
|
||||
return (1<<B_DIRECTION_BIT);
|
||||
return (1<<B_DIRECTION_BIT);
|
||||
}
|
||||
|
||||
|
||||
// Returns limit pin mask according to Grbl internal axis indexing.
|
||||
uint8_t Settings_GetLimitPinMask(uint8_t axis_idx)
|
||||
{
|
||||
if(axis_idx == X_AXIS) { return (1<<X_STEP_BIT); }
|
||||
if(axis_idx == Y_AXIS) { return (1<<Y_STEP_BIT); }
|
||||
if(axis_idx == Z_AXIS) { return (1<<Z_STEP_BIT); }
|
||||
if(axis_idx == A_AXIS) { return (1<<A_STEP_BIT); }
|
||||
if(axis_idx == X_AXIS)
|
||||
{
|
||||
return (1<<X_STEP_BIT);
|
||||
}
|
||||
if(axis_idx == Y_AXIS)
|
||||
{
|
||||
return (1<<Y_STEP_BIT);
|
||||
}
|
||||
if(axis_idx == Z_AXIS)
|
||||
{
|
||||
return (1<<Z_STEP_BIT);
|
||||
}
|
||||
if(axis_idx == A_AXIS)
|
||||
{
|
||||
return (1<<A_STEP_BIT);
|
||||
}
|
||||
|
||||
return (1<<B_STEP_BIT);
|
||||
return (1<<B_STEP_BIT);
|
||||
}
|
||||
|
|
122
grbl/Settings.h
122
grbl/Settings.h
|
@ -4,7 +4,7 @@
|
|||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
Copyright (c) 2017-2020 Patrick F.
|
||||
Copyright (c) 2017-2020 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
|
||||
|
@ -29,67 +29,67 @@
|
|||
|
||||
// Version of the EEPROM data. Will be used to migrate existing data from older versions of Grbl
|
||||
// when firmware is upgraded. Always stored in byte 0 of eeprom
|
||||
#define SETTINGS_VERSION 7 // NOTE: Check settings_reset() when moving to next version.
|
||||
#define SETTINGS_VERSION 7 // NOTE: Check settings_reset() when moving to next version.
|
||||
|
||||
|
||||
// Define bit flag masks for the boolean settings in settings.system_flags
|
||||
#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_FORCE_HARD_LIMIT_CHECK BIT(5)
|
||||
#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_FORCE_HARD_LIMIT_CHECK BIT(5)
|
||||
|
||||
// Define bit flag masks for the boolean settings in settings.flag.
|
||||
#define BITFLAG_REPORT_INCHES BIT(0)
|
||||
#define BITFLAG_LASER_MODE BIT(1)
|
||||
#define BITFLAG_INVERT_ST_ENABLE BIT(2)
|
||||
#define BITFLAG_HARD_LIMIT_ENABLE BIT(3)
|
||||
#define BITFLAG_HOMING_ENABLE BIT(4)
|
||||
#define BITFLAG_SOFT_LIMIT_ENABLE BIT(5)
|
||||
#define BITFLAG_INVERT_LIMIT_PINS BIT(6)
|
||||
#define BITFLAG_INVERT_PROBE_PIN BIT(7)
|
||||
#define BITFLAG_REPORT_INCHES BIT(0)
|
||||
#define BITFLAG_LASER_MODE BIT(1)
|
||||
#define BITFLAG_INVERT_ST_ENABLE BIT(2)
|
||||
#define BITFLAG_HARD_LIMIT_ENABLE BIT(3)
|
||||
#define BITFLAG_HOMING_ENABLE BIT(4)
|
||||
#define BITFLAG_SOFT_LIMIT_ENABLE BIT(5)
|
||||
#define BITFLAG_INVERT_LIMIT_PINS BIT(6)
|
||||
#define BITFLAG_INVERT_PROBE_PIN BIT(7)
|
||||
|
||||
// Define bit flag masks for the boolean settings in settings.flag2.
|
||||
#define BITFLAG_LATHE_MODE BIT(0)
|
||||
#define BITFLAG_LATHE_MODE BIT(0)
|
||||
|
||||
// Define status reporting boolean enable bit flags in settings.status_report_mask
|
||||
#define BITFLAG_RT_STATUS_POSITION_TYPE BIT(0)
|
||||
#define BITFLAG_RT_STATUS_BUFFER_STATE BIT(1)
|
||||
|
||||
// Define settings restore bitflags.
|
||||
#define SETTINGS_RESTORE_DEFAULTS BIT(0)
|
||||
#define SETTINGS_RESTORE_PARAMETERS BIT(1)
|
||||
#define SETTINGS_RESTORE_STARTUP_LINES BIT(2)
|
||||
#define SETTINGS_RESTORE_BUILD_INFO BIT(3)
|
||||
#define SETTINGS_RESTORE_TOOLS BIT(4)
|
||||
#define SETTINGS_RESTORE_DEFAULTS BIT(0)
|
||||
#define SETTINGS_RESTORE_PARAMETERS BIT(1)
|
||||
#define SETTINGS_RESTORE_STARTUP_LINES BIT(2)
|
||||
#define SETTINGS_RESTORE_BUILD_INFO BIT(3)
|
||||
#define SETTINGS_RESTORE_TOOLS BIT(4)
|
||||
|
||||
// Define EEPROM memory address location values for Grbl settings and parameters
|
||||
// NOTE: The Atmega328p has 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_GLOBAL 1U
|
||||
#define EEPROM_ADDR_GLOBAL 1U
|
||||
#define EEPROM_ADDR_TOOLTABLE 180U
|
||||
#define EEPROM_ADDR_PARAMETERS 512U
|
||||
#define EEPROM_ADDR_STARTUP_BLOCK 768U
|
||||
#define EEPROM_ADDR_BUILD_INFO 942U
|
||||
#define EEPROM_ADDR_PARAMETERS 512U
|
||||
#define EEPROM_ADDR_STARTUP_BLOCK 768U
|
||||
#define EEPROM_ADDR_BUILD_INFO 942U
|
||||
|
||||
// Define EEPROM address indexing for coordinate parameters
|
||||
#define N_COORDINATE_SYSTEM 6 // Number of supported work coordinate systems (from index 1)
|
||||
#define SETTING_INDEX_NCOORD N_COORDINATE_SYSTEM+1 // Total number of system stored (from index 0)
|
||||
#define N_COORDINATE_SYSTEM 6 // Number of supported work coordinate systems (from index 1)
|
||||
#define SETTING_INDEX_NCOORD N_COORDINATE_SYSTEM+1 // Total number of system stored (from index 0)
|
||||
|
||||
// NOTE: Work coordinate indices are (0=G54, 1=G55, ... , 6=G59)
|
||||
#define SETTING_INDEX_G28 N_COORDINATE_SYSTEM // Home position 1
|
||||
#define SETTING_INDEX_G30 N_COORDINATE_SYSTEM+1 // Home position 2
|
||||
#define SETTING_INDEX_G28 N_COORDINATE_SYSTEM // Home position 1
|
||||
#define SETTING_INDEX_G30 N_COORDINATE_SYSTEM+1 // Home position 2
|
||||
// #define SETTING_INDEX_G92 N_COORDINATE_SYSTEM+2 // Coordinate offset (G92.2,G92.3 not supported)
|
||||
|
||||
// Define Grbl axis settings numbering scheme. Starts at START_VAL, every INCREMENT, over N_SETTINGS.
|
||||
#define AXIS_N_SETTINGS 5
|
||||
#define AXIS_SETTINGS_START_VAL 100 // NOTE: Reserving settings values >= 100 for axis settings. Up to 255.
|
||||
#define AXIS_SETTINGS_INCREMENT 10 // Must be greater than the number of axis settings
|
||||
#define AXIS_N_SETTINGS 5
|
||||
#define AXIS_SETTINGS_START_VAL 100 // NOTE: Reserving settings values >= 100 for axis settings. Up to 255.
|
||||
#define AXIS_SETTINGS_INCREMENT 10 // Must be greater than the number of axis settings
|
||||
|
||||
#ifndef SETTINGS_RESTORE_ALL
|
||||
#define SETTINGS_RESTORE_ALL 0xFF // All bitflags
|
||||
#define SETTINGS_RESTORE_ALL 0xFF // All bitflags
|
||||
#endif
|
||||
|
||||
|
||||
|
@ -97,42 +97,42 @@
|
|||
// Global persistent settings (Stored from byte EEPROM_ADDR_GLOBAL onwards); 111 Bytes
|
||||
typedef struct
|
||||
{
|
||||
// Axis settings
|
||||
float steps_per_mm[N_AXIS];
|
||||
float max_rate[N_AXIS];
|
||||
float acceleration[N_AXIS];
|
||||
float max_travel[N_AXIS];
|
||||
// Axis settings
|
||||
float steps_per_mm[N_AXIS];
|
||||
float max_rate[N_AXIS];
|
||||
float acceleration[N_AXIS];
|
||||
float max_travel[N_AXIS];
|
||||
|
||||
float backlash[N_AXIS];
|
||||
float backlash[N_AXIS];
|
||||
|
||||
// Tool change mode
|
||||
uint8_t tool_change;
|
||||
|
||||
// Position of tool length sensor (only XYZ axis)
|
||||
int32_t tls_position[N_AXIS];
|
||||
uint8_t tls_valid;
|
||||
// Position of tool length sensor (only XYZ axis)
|
||||
int32_t tls_position[N_AXIS];
|
||||
uint8_t tls_valid;
|
||||
|
||||
// Remaining Grbl settings
|
||||
// TODO: document system_flags
|
||||
uint8_t system_flags;
|
||||
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;
|
||||
// Remaining Grbl settings
|
||||
// TODO: document system_flags
|
||||
uint8_t system_flags;
|
||||
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 rpm_max;
|
||||
float rpm_min;
|
||||
float rpm_max;
|
||||
float rpm_min;
|
||||
|
||||
uint8_t flags; // Contains default boolean settings
|
||||
uint8_t flags2;
|
||||
uint8_t flags; // Contains default boolean settings
|
||||
uint8_t flags2;
|
||||
|
||||
uint8_t homing_dir_mask;
|
||||
float homing_feed_rate;
|
||||
float homing_seek_rate;
|
||||
uint16_t homing_debounce_delay;
|
||||
float homing_pulloff;
|
||||
uint8_t homing_dir_mask;
|
||||
float homing_feed_rate;
|
||||
float homing_seek_rate;
|
||||
uint16_t homing_debounce_delay;
|
||||
float homing_pulloff;
|
||||
} Settings_t;
|
||||
#pragma pack(pop)
|
||||
|
||||
|
|
|
@ -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-2020 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
|
||||
|
@ -33,6 +33,8 @@ static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversi
|
|||
static uint8_t spindle_enabled = 0;
|
||||
static uint8_t spindle_dir_cw = 1;
|
||||
|
||||
extern uint32_t uwTIM3Freq;
|
||||
|
||||
|
||||
void Spindle_Init(void)
|
||||
{
|
||||
|
@ -45,7 +47,7 @@ void Spindle_Init(void)
|
|||
pwm_gradient = SPINDLE_PWM_RANGE/(settings.rpm_max-settings.rpm_min);
|
||||
spindle_dir_cw = 1;
|
||||
|
||||
Spindle_Stop();
|
||||
Spindle_Stop();
|
||||
}
|
||||
|
||||
|
||||
|
@ -54,8 +56,8 @@ void Spindle_Init(void)
|
|||
// Called by spindle_init(), spindle_set_speed(), spindle_set_state(), and mc_reset().
|
||||
void Spindle_Stop(void)
|
||||
{
|
||||
TIM1->CCR1 = TIM1_INIT; // Disable PWM. Output voltage is zero.
|
||||
spindle_enabled = 0;
|
||||
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);
|
||||
|
@ -68,19 +70,19 @@ void Spindle_Stop(void)
|
|||
uint8_t Spindle_GetState(void)
|
||||
{
|
||||
// Check if PWM is enabled.
|
||||
if(spindle_enabled)
|
||||
if(spindle_enabled)
|
||||
{
|
||||
if(spindle_dir_cw == 0)
|
||||
{
|
||||
return SPINDLE_STATE_CCW;
|
||||
}
|
||||
else
|
||||
if(spindle_dir_cw == 0)
|
||||
{
|
||||
return SPINDLE_STATE_CW;
|
||||
}
|
||||
}
|
||||
return SPINDLE_STATE_CCW;
|
||||
}
|
||||
else
|
||||
{
|
||||
return SPINDLE_STATE_CW;
|
||||
}
|
||||
}
|
||||
|
||||
return SPINDLE_STATE_DISABLE;
|
||||
return SPINDLE_STATE_DISABLE;
|
||||
}
|
||||
|
||||
|
||||
|
@ -88,69 +90,81 @@ uint8_t Spindle_GetState(void)
|
|||
// and stepper ISR. Keep routine small and efficient.
|
||||
void Spindle_SetSpeed(uint8_t pwm_value)
|
||||
{
|
||||
TIM1->CCR1 = TIM1_INIT - pwm_value; // Set PWM output level.
|
||||
TIM1->CCR1 = TIM1_INIT - pwm_value; // Set PWM output level.
|
||||
#ifdef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
||||
if (pwm_value == SPINDLE_PWM_OFF_VALUE)
|
||||
if (pwm_value == SPINDLE_PWM_OFF_VALUE)
|
||||
{
|
||||
Spindle_Stop();
|
||||
}
|
||||
else
|
||||
Spindle_Stop();
|
||||
}
|
||||
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
|
||||
spindle_enabled = 1;
|
||||
}
|
||||
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
|
||||
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.
|
||||
spindle_enabled = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
TIM_Cmd(TIM1, ENABLE); // Ensure PWM output is enabled.
|
||||
spindle_enabled = 1;
|
||||
}
|
||||
GPIO_SetBits(GPIO_SPINDLE_ENA_PORT, GPIO_SPINDLE_ENA_PIN);
|
||||
#endif
|
||||
spindle_enabled = 1;
|
||||
}
|
||||
#else
|
||||
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.
|
||||
spindle_enabled = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
TIM_Cmd(TIM1, ENABLE); // Ensure PWM output is enabled.
|
||||
spindle_enabled = 1;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
uint16_t Spindle_GetRPM(void)
|
||||
{
|
||||
// 4 impulses per revolution
|
||||
return (uint16_t)(uwTIM3Freq / 4);
|
||||
}
|
||||
|
||||
|
||||
// Called by spindle_set_state() and step segment generator. Keep routine small and efficient.
|
||||
uint8_t Spindle_ComputePwmValue(float rpm) // 328p PWM register is 8-bit.
|
||||
{
|
||||
uint8_t pwm_value;
|
||||
uint8_t pwm_value;
|
||||
|
||||
rpm *= (0.010*sys.spindle_speed_ovr); // Scale by spindle speed override 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;
|
||||
pwm_value = floor((rpm-settings.rpm_min)*pwm_gradient) + SPINDLE_PWM_MIN_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;
|
||||
pwm_value = floor((rpm-settings.rpm_min)*pwm_gradient) + SPINDLE_PWM_MIN_VALUE;
|
||||
}
|
||||
|
||||
return pwm_value;
|
||||
return pwm_value;
|
||||
}
|
||||
|
||||
|
||||
|
@ -159,43 +173,50 @@ uint8_t Spindle_ComputePwmValue(float rpm) // 328p PWM register is 8-bit.
|
|||
// sleep, and spindle stop override.
|
||||
void Spindle_SetState(uint8_t state, float rpm)
|
||||
{
|
||||
if(sys.abort) {
|
||||
// Block during abort.
|
||||
return;
|
||||
}
|
||||
if(sys.abort)
|
||||
{
|
||||
// Block during abort.
|
||||
return;
|
||||
}
|
||||
|
||||
if(state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
|
||||
sys.spindle_speed = 0.0;
|
||||
Spindle_Stop();
|
||||
}
|
||||
else {
|
||||
if(state == SPINDLE_ENABLE_CW) {
|
||||
GPIO_ResetBits(GPIO_SPINDLE_DIR_PORT, GPIO_SPINDLE_DIR_PIN);
|
||||
spindle_dir_cw = 1;
|
||||
}
|
||||
else {
|
||||
GPIO_SetBits(GPIO_SPINDLE_DIR_PORT, GPIO_SPINDLE_DIR_PIN);
|
||||
spindle_dir_cw = 0;
|
||||
}
|
||||
if(state == SPINDLE_DISABLE) // Halt or set spindle direction and rpm.
|
||||
{
|
||||
sys.spindle_speed = 0.0;
|
||||
Spindle_Stop();
|
||||
}
|
||||
else
|
||||
{
|
||||
if(state == SPINDLE_ENABLE_CW)
|
||||
{
|
||||
GPIO_ResetBits(GPIO_SPINDLE_DIR_PORT, GPIO_SPINDLE_DIR_PIN);
|
||||
spindle_dir_cw = 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
GPIO_SetBits(GPIO_SPINDLE_DIR_PORT, GPIO_SPINDLE_DIR_PIN);
|
||||
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
|
||||
#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
|
||||
|
||||
// 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) {
|
||||
// TODO: May need to be rpm_min*(100/MAX_SPINDLE_SPEED_OVERRIDE);
|
||||
rpm = 0.0;
|
||||
}
|
||||
}
|
||||
// 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)
|
||||
{
|
||||
// TODO: May need to be rpm_min*(100/MAX_SPINDLE_SPEED_OVERRIDE);
|
||||
rpm = 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
Spindle_SetSpeed(Spindle_ComputePwmValue(rpm));
|
||||
}
|
||||
Spindle_SetSpeed(Spindle_ComputePwmValue(rpm));
|
||||
}
|
||||
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
}
|
||||
|
||||
|
||||
|
@ -203,11 +224,12 @@ void Spindle_SetState(uint8_t state, float rpm)
|
|||
// if an abort or check-mode is active.
|
||||
void Spindle_Sync(uint8_t state, float rpm)
|
||||
{
|
||||
if(sys.state == STATE_CHECK_MODE) {
|
||||
return;
|
||||
}
|
||||
if(sys.state == STATE_CHECK_MODE)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
Protocol_BufferSynchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
||||
Spindle_SetState(state, rpm);
|
||||
Protocol_BufferSynchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
||||
Spindle_SetState(state, rpm);
|
||||
}
|
||||
|
||||
|
|
|
@ -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 Patrick F.
|
||||
Copyright (c) 2017 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
|
||||
|
@ -25,19 +25,19 @@
|
|||
#include <stdint.h>
|
||||
|
||||
|
||||
#define SPINDLE_NO_SYNC false
|
||||
#define SPINDLE_FORCE_SYNC true
|
||||
#define SPINDLE_NO_SYNC false
|
||||
#define SPINDLE_FORCE_SYNC true
|
||||
|
||||
#define SPINDLE_STATE_DISABLE 0 // Must be zero.
|
||||
#define SPINDLE_STATE_CW BIT(0)
|
||||
#define SPINDLE_STATE_CCW BIT(1)
|
||||
#define SPINDLE_STATE_DISABLE 0 // Must be zero.
|
||||
#define SPINDLE_STATE_CW BIT(0)
|
||||
#define SPINDLE_STATE_CCW BIT(1)
|
||||
|
||||
#define SPINDLE_PWM_MAX_VALUE 200 // Don't change.
|
||||
#define SPINDLE_PWM_MAX_VALUE 200 // Don't change.
|
||||
#ifndef SPINDLE_PWM_MIN_VALUE
|
||||
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
|
||||
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
|
||||
#endif
|
||||
#define SPINDLE_PWM_OFF_VALUE 1
|
||||
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
|
||||
#define SPINDLE_PWM_OFF_VALUE 1
|
||||
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
|
||||
|
||||
|
||||
// Initializes spindle pins and hardware PWM, if enabled.
|
||||
|
|
1693
grbl/Stepper.c
1693
grbl/Stepper.c
Plik diff jest za duży
Load Diff
|
@ -4,7 +4,7 @@
|
|||
|
||||
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||
Copyright (c) 2017 Patrick F.
|
||||
Copyright (c) 2017 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
|
||||
|
|
774
grbl/System.c
774
grbl/System.c
|
@ -3,7 +3,7 @@
|
|||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2017-2020 Patrick F.
|
||||
Copyright (c) 2017-2020 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
|
||||
|
@ -37,24 +37,24 @@
|
|||
|
||||
void System_Init(void)
|
||||
{
|
||||
GPIO_InitGPIO(GPIO_SYSTEM);
|
||||
GPIO_InitGPIO(GPIO_SYSTEM);
|
||||
}
|
||||
|
||||
|
||||
void System_Clear(void)
|
||||
{
|
||||
memset(&sys, 0, sizeof(System_t)); // Clear system struct variable.
|
||||
memset(&sys, 0, sizeof(System_t)); // Clear system struct variable.
|
||||
|
||||
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%
|
||||
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%
|
||||
}
|
||||
|
||||
|
||||
void System_ResetPosition(void)
|
||||
{
|
||||
// Clear machine position.
|
||||
memset(sys_position, 0 , sizeof(sys_position));
|
||||
// Clear machine position.
|
||||
memset(sys_position, 0 , sizeof(sys_position));
|
||||
}
|
||||
|
||||
|
||||
|
@ -63,31 +63,35 @@ void System_ResetPosition(void)
|
|||
// defined by the CONTROL_PIN_INDEX in the header file.
|
||||
uint8_t System_GetControlState(void)
|
||||
{
|
||||
uint8_t control_state = 0;
|
||||
uint8_t pin = ((GPIO_ReadInputDataBit(GPIOA, GPIO_Pin_0)<<CONTROL_RESET_BIT) |
|
||||
(GPIO_ReadInputDataBit(GPIOA, GPIO_Pin_1)<<CONTROL_FEED_HOLD_BIT) |
|
||||
(GPIO_ReadInputDataBit(GPIOA, GPIO_Pin_4)<<CONTROL_CYCLE_START_BIT) |
|
||||
(GPIO_ReadInputDataBit(GPIOB, GPIO_Pin_8)<<CONTROL_SAFETY_DOOR_BIT));
|
||||
uint8_t control_state = 0;
|
||||
uint8_t pin = ((GPIO_ReadInputDataBit(GPIOA, GPIO_Pin_0)<<CONTROL_RESET_BIT) |
|
||||
(GPIO_ReadInputDataBit(GPIOA, GPIO_Pin_1)<<CONTROL_FEED_HOLD_BIT) |
|
||||
(GPIO_ReadInputDataBit(GPIOA, GPIO_Pin_4)<<CONTROL_CYCLE_START_BIT) |
|
||||
(GPIO_ReadInputDataBit(GPIOB, GPIO_Pin_8)<<CONTROL_SAFETY_DOOR_BIT));
|
||||
|
||||
// Invert control pins if necessary
|
||||
pin ^= CONTROL_MASK & settings.system_flags;
|
||||
// Invert control pins if necessary
|
||||
pin ^= CONTROL_MASK & settings.system_flags;
|
||||
|
||||
if(pin) {
|
||||
if(BIT_IS_FALSE(pin, (1<<CONTROL_RESET_BIT))) {
|
||||
control_state |= CONTROL_PIN_INDEX_RESET;
|
||||
}
|
||||
if(BIT_IS_FALSE(pin, (1<<CONTROL_FEED_HOLD_BIT))) {
|
||||
control_state |= CONTROL_PIN_INDEX_FEED_HOLD;
|
||||
}
|
||||
if(BIT_IS_FALSE(pin, (1<<CONTROL_CYCLE_START_BIT))) {
|
||||
control_state |= CONTROL_PIN_INDEX_CYCLE_START;
|
||||
}
|
||||
/*if(BIT_IS_FALSE(pin, (1<<CONTROL_SAFETY_DOOR_BIT))) {
|
||||
control_state |= CONTROL_PIN_INDEX_SAFETY_DOOR;
|
||||
}*/
|
||||
}
|
||||
if(pin)
|
||||
{
|
||||
if(BIT_IS_TRUE(pin, (1<<CONTROL_RESET_BIT)))
|
||||
{
|
||||
control_state |= CONTROL_PIN_INDEX_RESET;
|
||||
}
|
||||
if(BIT_IS_TRUE(pin, (1<<CONTROL_FEED_HOLD_BIT)))
|
||||
{
|
||||
control_state |= CONTROL_PIN_INDEX_FEED_HOLD;
|
||||
}
|
||||
if(BIT_IS_TRUE(pin, (1<<CONTROL_CYCLE_START_BIT)))
|
||||
{
|
||||
control_state |= CONTROL_PIN_INDEX_CYCLE_START;
|
||||
}
|
||||
/*if(BIT_IS_TRUE(pin, (1<<CONTROL_SAFETY_DOOR_BIT))) {
|
||||
control_state |= CONTROL_PIN_INDEX_SAFETY_DOOR;
|
||||
}*/
|
||||
}
|
||||
|
||||
return control_state;
|
||||
return control_state;
|
||||
}
|
||||
|
||||
|
||||
|
@ -97,22 +101,27 @@ 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();
|
||||
|
||||
if(pin) {
|
||||
if(BIT_IS_TRUE(pin, CONTROL_PIN_INDEX_RESET)) {
|
||||
MC_Reset();
|
||||
}
|
||||
else if(BIT_IS_TRUE(pin, CONTROL_PIN_INDEX_CYCLE_START)) {
|
||||
BIT_TRUE(sys_rt_exec_state, EXEC_CYCLE_START);
|
||||
}
|
||||
if(BIT_IS_TRUE(pin, CONTROL_PIN_INDEX_FEED_HOLD)) {
|
||||
BIT_TRUE(sys_rt_exec_state, EXEC_FEED_HOLD);
|
||||
}
|
||||
if(BIT_IS_TRUE(pin, CONTROL_PIN_INDEX_SAFETY_DOOR)) {
|
||||
BIT_TRUE(sys_rt_exec_state, EXEC_SAFETY_DOOR);
|
||||
}
|
||||
}
|
||||
if(pin)
|
||||
{
|
||||
if(BIT_IS_TRUE(pin, CONTROL_PIN_INDEX_RESET))
|
||||
{
|
||||
MC_Reset();
|
||||
}
|
||||
else if(BIT_IS_TRUE(pin, CONTROL_PIN_INDEX_CYCLE_START))
|
||||
{
|
||||
BIT_TRUE(sys_rt_exec_state, EXEC_CYCLE_START);
|
||||
}
|
||||
if(BIT_IS_TRUE(pin, CONTROL_PIN_INDEX_FEED_HOLD))
|
||||
{
|
||||
BIT_TRUE(sys_rt_exec_state, EXEC_FEED_HOLD);
|
||||
}
|
||||
if(BIT_IS_TRUE(pin, CONTROL_PIN_INDEX_SAFETY_DOOR))
|
||||
{
|
||||
BIT_TRUE(sys_rt_exec_state, EXEC_SAFETY_DOOR);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
@ -127,23 +136,27 @@ uint8_t System_CheckSafetyDoorAjar(void)
|
|||
void System_ExecuteStartup(char *line)
|
||||
{
|
||||
#if (N_STARTUP_LINE > 0)
|
||||
uint8_t n;
|
||||
uint8_t n;
|
||||
|
||||
for(n = 0; n < N_STARTUP_LINE; n++) {
|
||||
if(!(Settings_ReadStartupLine(n, line))) {
|
||||
line[0] = 0;
|
||||
Report_ExecuteStartupMessage(line, STATUS_SETTING_READ_FAIL);
|
||||
}
|
||||
else {
|
||||
if(line[0] != 0) {
|
||||
uint8_t status_code = GC_ExecuteLine(line);
|
||||
for(n = 0; n < N_STARTUP_LINE; n++)
|
||||
{
|
||||
if(!(Settings_ReadStartupLine(n, line)))
|
||||
{
|
||||
line[0] = 0;
|
||||
Report_ExecuteStartupMessage(line, STATUS_SETTING_READ_FAIL);
|
||||
}
|
||||
else
|
||||
{
|
||||
if(line[0] != 0)
|
||||
{
|
||||
uint8_t status_code = GC_ExecuteLine(line);
|
||||
|
||||
Report_ExecuteStartupMessage(line,status_code);
|
||||
}
|
||||
}
|
||||
}
|
||||
Report_ExecuteStartupMessage(line,status_code);
|
||||
}
|
||||
}
|
||||
}
|
||||
#else
|
||||
(void)line;
|
||||
(void)line;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -158,84 +171,95 @@ void System_ExecuteStartup(char *line)
|
|||
// be an issue, since these commands are not typically used during a cycle.
|
||||
uint8_t System_ExecuteLine(char *line)
|
||||
{
|
||||
uint8_t char_counter = 1;
|
||||
uint8_t helper_var = 0; // Helper variable
|
||||
float parameter, value;
|
||||
uint8_t char_counter = 1;
|
||||
uint8_t helper_var = 0; // Helper variable
|
||||
float parameter, value;
|
||||
|
||||
switch(line[char_counter])
|
||||
{
|
||||
case 0:
|
||||
Report_GrblHelp();
|
||||
break;
|
||||
switch(line[char_counter])
|
||||
{
|
||||
case 0:
|
||||
Report_GrblHelp();
|
||||
break;
|
||||
|
||||
case 'J': // Jogging
|
||||
// Execute only if in IDLE or JOG states.
|
||||
if(sys.state != STATE_IDLE && sys.state != STATE_JOG) {
|
||||
return STATUS_IDLE_ERROR;
|
||||
}
|
||||
if(line[2] != '=') {
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
return GC_ExecuteLine(line); // NOTE: $J= is ignored inside g-code parser and used to detect jog motions.
|
||||
break;
|
||||
case 'J': // Jogging
|
||||
// Execute only if in IDLE or JOG states.
|
||||
if(sys.state != STATE_IDLE && sys.state != STATE_JOG)
|
||||
{
|
||||
return STATUS_IDLE_ERROR;
|
||||
}
|
||||
if(line[2] != '=')
|
||||
{
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
return GC_ExecuteLine(line); // NOTE: $J= is ignored inside g-code parser and used to detect jog motions.
|
||||
break;
|
||||
|
||||
case '$':
|
||||
case 'G':
|
||||
case 'C':
|
||||
case 'X':
|
||||
if(line[2] != 0) {
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
case '$':
|
||||
case 'G':
|
||||
case 'C':
|
||||
case 'X':
|
||||
if(line[2] != 0)
|
||||
{
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
|
||||
switch(line[1])
|
||||
{
|
||||
case '$': // Prints Grbl settings
|
||||
if(sys.state & (STATE_CYCLE | STATE_HOLD)) {
|
||||
return(STATUS_IDLE_ERROR);
|
||||
} // Block during cycle. Takes too long to print.
|
||||
else {
|
||||
Report_GrblSettings();
|
||||
}
|
||||
break;
|
||||
switch(line[1])
|
||||
{
|
||||
case '$': // Prints Grbl settings
|
||||
if(sys.state & (STATE_CYCLE | STATE_HOLD))
|
||||
{
|
||||
return(STATUS_IDLE_ERROR);
|
||||
} // Block during cycle. Takes too long to print.
|
||||
else
|
||||
{
|
||||
Report_GrblSettings();
|
||||
}
|
||||
break;
|
||||
|
||||
case 'G': // Prints gcode parser state
|
||||
// TODO: Move this to realtime commands for GUIs to request this data during suspend-state.
|
||||
Report_GCodeModes();
|
||||
break;
|
||||
case 'G': // Prints gcode parser state
|
||||
// TODO: Move this to realtime commands for GUIs to request this data during suspend-state.
|
||||
Report_GCodeModes();
|
||||
break;
|
||||
|
||||
case 'C': // Set check g-code mode [IDLE/CHECK]
|
||||
// Perform reset when toggling off. Check g-code mode should only work if Grbl
|
||||
// is idle and ready, regardless of alarm locks. This is mainly to keep things
|
||||
// simple and consistent.
|
||||
if(sys.state == STATE_CHECK_MODE ) {
|
||||
MC_Reset();
|
||||
Report_FeedbackMessage(MESSAGE_DISABLED);
|
||||
}
|
||||
else {
|
||||
if(sys.state) {
|
||||
// Requires no alarm mode.
|
||||
return STATUS_IDLE_ERROR;
|
||||
}
|
||||
case 'C': // Set check g-code mode [IDLE/CHECK]
|
||||
// Perform reset when toggling off. Check g-code mode should only work if Grbl
|
||||
// is idle and ready, regardless of alarm locks. This is mainly to keep things
|
||||
// simple and consistent.
|
||||
if(sys.state == STATE_CHECK_MODE )
|
||||
{
|
||||
MC_Reset();
|
||||
Report_FeedbackMessage(MESSAGE_DISABLED);
|
||||
}
|
||||
else
|
||||
{
|
||||
if(sys.state)
|
||||
{
|
||||
// Requires no alarm mode.
|
||||
return STATUS_IDLE_ERROR;
|
||||
}
|
||||
|
||||
sys.state = STATE_CHECK_MODE;
|
||||
Report_FeedbackMessage(MESSAGE_ENABLED);
|
||||
}
|
||||
break;
|
||||
sys.state = STATE_CHECK_MODE;
|
||||
Report_FeedbackMessage(MESSAGE_ENABLED);
|
||||
}
|
||||
break;
|
||||
|
||||
case 'X': // Disable alarm lock [ALARM]
|
||||
if(sys.state == STATE_ALARM) {
|
||||
// Block if safety door is ajar.
|
||||
if(System_CheckSafetyDoorAjar()) {
|
||||
return(STATUS_CHECK_DOOR);
|
||||
}
|
||||
case 'X': // Disable alarm lock [ALARM]
|
||||
if(sys.state == STATE_ALARM)
|
||||
{
|
||||
// Block if safety door is ajar.
|
||||
if(System_CheckSafetyDoorAjar())
|
||||
{
|
||||
return(STATUS_CHECK_DOOR);
|
||||
}
|
||||
|
||||
Report_FeedbackMessage(MESSAGE_ALARM_UNLOCK);
|
||||
sys.state = STATE_IDLE;
|
||||
// Don't run startup script. Prevents stored moves in startup from causing accidents.
|
||||
} // Otherwise, no effect.
|
||||
break;
|
||||
}
|
||||
break;
|
||||
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.
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
case 'T':
|
||||
if(line[++char_counter] == 0)
|
||||
|
@ -288,7 +312,8 @@ uint8_t System_ExecuteLine(char *line)
|
|||
{
|
||||
c = line[char_counter++];
|
||||
num[idx++] = c;
|
||||
} while(isdigit(c) && idx < 3);
|
||||
}
|
||||
while(isdigit(c) && idx < 3);
|
||||
num[idx] = '\0';
|
||||
|
||||
if(c == '=')
|
||||
|
@ -344,205 +369,238 @@ uint8_t System_ExecuteLine(char *line)
|
|||
|
||||
break;
|
||||
|
||||
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) ) {
|
||||
return(STATUS_IDLE_ERROR);
|
||||
}
|
||||
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) )
|
||||
{
|
||||
return(STATUS_IDLE_ERROR);
|
||||
}
|
||||
|
||||
switch(line[1])
|
||||
{
|
||||
case '#': // Print Grbl NGC parameters
|
||||
if(line[2] != 0) {
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
else {
|
||||
Report_NgcParams();
|
||||
}
|
||||
break;
|
||||
switch(line[1])
|
||||
{
|
||||
case '#': // Print Grbl NGC parameters
|
||||
if(line[2] != 0)
|
||||
{
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
else
|
||||
{
|
||||
Report_NgcParams();
|
||||
}
|
||||
break;
|
||||
|
||||
case 'H': // Perform homing cycle [IDLE/ALARM]
|
||||
if(BIT_IS_FALSE(settings.flags, BITFLAG_HOMING_ENABLE)) {
|
||||
return(STATUS_SETTING_DISABLED);
|
||||
}
|
||||
if(System_CheckSafetyDoorAjar()) {
|
||||
// Block if safety door is ajar.
|
||||
return STATUS_CHECK_DOOR;
|
||||
}
|
||||
case 'H': // Perform homing cycle [IDLE/ALARM]
|
||||
if(BIT_IS_FALSE(settings.flags, BITFLAG_HOMING_ENABLE))
|
||||
{
|
||||
return(STATUS_SETTING_DISABLED);
|
||||
}
|
||||
if(System_CheckSafetyDoorAjar())
|
||||
{
|
||||
// Block if safety door is ajar.
|
||||
return STATUS_CHECK_DOOR;
|
||||
}
|
||||
|
||||
sys.state = STATE_HOMING; // Set system state variable
|
||||
sys.state = STATE_HOMING; // Set system state variable
|
||||
|
||||
if(line[2] == 0) {
|
||||
MC_HomigCycle(HOMING_CYCLE_ALL);
|
||||
if(line[2] == 0)
|
||||
{
|
||||
MC_HomigCycle(HOMING_CYCLE_ALL);
|
||||
#ifdef HOMING_SINGLE_AXIS_COMMANDS
|
||||
}
|
||||
else if(line[3] == 0) {
|
||||
switch(line[2])
|
||||
{
|
||||
case 'X':
|
||||
MC_HomigCycle(HOMING_CYCLE_X);
|
||||
break;
|
||||
}
|
||||
else if(line[3] == 0)
|
||||
{
|
||||
switch(line[2])
|
||||
{
|
||||
case 'X':
|
||||
MC_HomigCycle(HOMING_CYCLE_X);
|
||||
break;
|
||||
|
||||
case 'Y':
|
||||
MC_HomigCycle(HOMING_CYCLE_Y);
|
||||
break;
|
||||
case 'Y':
|
||||
MC_HomigCycle(HOMING_CYCLE_Y);
|
||||
break;
|
||||
|
||||
case 'Z':
|
||||
MC_HomigCycle(HOMING_CYCLE_Z);
|
||||
break;
|
||||
case 'Z':
|
||||
MC_HomigCycle(HOMING_CYCLE_Z);
|
||||
break;
|
||||
|
||||
case 'A':
|
||||
MC_HomigCycle(HOMING_CYCLE_A);
|
||||
break;
|
||||
MC_HomigCycle(HOMING_CYCLE_A);
|
||||
break;
|
||||
|
||||
case 'B':
|
||||
MC_HomigCycle(HOMING_CYCLE_B);
|
||||
break;
|
||||
MC_HomigCycle(HOMING_CYCLE_B);
|
||||
break;
|
||||
|
||||
default:
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
default:
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
|
||||
if(!sys.abort) { // Execute startup scripts after successful homing.
|
||||
sys.state = STATE_IDLE; // Set to IDLE when complete.
|
||||
Stepper_Disable(0); // Set steppers to the settings idle state before returning.
|
||||
if(!sys.abort) // Execute startup scripts after successful homing.
|
||||
{
|
||||
sys.state = STATE_IDLE; // Set to IDLE when complete.
|
||||
Stepper_Disable(0); // Set steppers to the settings idle state before returning.
|
||||
|
||||
if(line[2] == 0) {
|
||||
System_ExecuteStartup(line);
|
||||
}
|
||||
}
|
||||
break;
|
||||
if(line[2] == 0)
|
||||
{
|
||||
System_ExecuteStartup(line);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case 'S': // Puts Grbl to sleep [IDLE/ALARM]
|
||||
if((line[2] != 'L') || (line[3] != 'P') || (line[4] != 0)) {
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
System_SetExecStateFlag(EXEC_SLEEP); // Set to execute sleep mode immediately
|
||||
break;
|
||||
case 'S': // Puts Grbl to sleep [IDLE/ALARM]
|
||||
if((line[2] != 'L') || (line[3] != 'P') || (line[4] != 0))
|
||||
{
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
System_SetExecStateFlag(EXEC_SLEEP); // Set to execute sleep mode immediately
|
||||
break;
|
||||
|
||||
case 'I': // Print or store build info. [IDLE/ALARM]
|
||||
if(line[++char_counter] == 0 ) {
|
||||
Settings_ReadBuildInfo(line);
|
||||
Report_BuildInfo(line);
|
||||
case 'I': // Print or store build info. [IDLE/ALARM]
|
||||
if(line[++char_counter] == 0 )
|
||||
{
|
||||
Settings_ReadBuildInfo(line);
|
||||
Report_BuildInfo(line);
|
||||
#ifdef ENABLE_BUILD_INFO_WRITE_COMMAND
|
||||
}
|
||||
else { // Store startup line [IDLE/ALARM]
|
||||
if(line[char_counter++] != '=') {
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
}
|
||||
else // Store startup line [IDLE/ALARM]
|
||||
{
|
||||
if(line[char_counter++] != '=')
|
||||
{
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
|
||||
helper_var = char_counter; // Set helper variable as counter to start of user info line.
|
||||
helper_var = char_counter; // Set helper variable as counter to start of user info line.
|
||||
|
||||
do {
|
||||
line[char_counter-helper_var] = line[char_counter];
|
||||
} while(line[char_counter++] != 0);
|
||||
do
|
||||
{
|
||||
line[char_counter-helper_var] = line[char_counter];
|
||||
}
|
||||
while(line[char_counter++] != 0);
|
||||
|
||||
Settings_StoreBuildInfo(line);
|
||||
Settings_StoreBuildInfo(line);
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
case 'R': // Restore defaults [IDLE/ALARM]
|
||||
if((line[2] != 'S') || (line[3] != 'T') || (line[4] != '=') || (line[6] != 0)) {
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
switch(line[5])
|
||||
{
|
||||
case 'R': // Restore defaults [IDLE/ALARM]
|
||||
if((line[2] != 'S') || (line[3] != 'T') || (line[4] != '=') || (line[6] != 0))
|
||||
{
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
switch(line[5])
|
||||
{
|
||||
#ifdef ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS
|
||||
case '$':
|
||||
Settings_Restore(SETTINGS_RESTORE_DEFAULTS);
|
||||
break;
|
||||
case '$':
|
||||
Settings_Restore(SETTINGS_RESTORE_DEFAULTS);
|
||||
break;
|
||||
#endif
|
||||
#ifdef ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS
|
||||
case '#':
|
||||
Settings_Restore(SETTINGS_RESTORE_PARAMETERS);
|
||||
case '#':
|
||||
Settings_Restore(SETTINGS_RESTORE_PARAMETERS);
|
||||
break;
|
||||
#endif
|
||||
#ifdef ENABLE_RESTORE_EEPROM_WIPE_ALL
|
||||
case '*':
|
||||
Settings_Restore(SETTINGS_RESTORE_ALL);
|
||||
case '*':
|
||||
Settings_Restore(SETTINGS_RESTORE_ALL);
|
||||
break;
|
||||
#endif
|
||||
case 'T':
|
||||
TT_Reset();
|
||||
break;
|
||||
|
||||
default:
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
default:
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
|
||||
Report_FeedbackMessage(MESSAGE_RESTORE_DEFAULTS);
|
||||
MC_Reset(); // Force reset to ensure settings are initialized correctly.
|
||||
break;
|
||||
Report_FeedbackMessage(MESSAGE_RESTORE_DEFAULTS);
|
||||
MC_Reset(); // Force reset to ensure settings are initialized correctly.
|
||||
break;
|
||||
|
||||
case 'N': // Startup lines. [IDLE/ALARM]
|
||||
case 'N': // Startup lines. [IDLE/ALARM]
|
||||
#if (N_STARTUP_LINE > 0)
|
||||
if(line[++char_counter] == 0 ) { // Print startup lines
|
||||
for(helper_var = 0; helper_var < N_STARTUP_LINE; helper_var++) {
|
||||
if (!(Settings_ReadStartupLine(helper_var, line))) {
|
||||
Report_StatusMessage(STATUS_SETTING_READ_FAIL);
|
||||
}
|
||||
else {
|
||||
Report_StartupLine(helper_var,line);
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
else { // Store startup line [IDLE Only] Prevents motion during ALARM.
|
||||
if(sys.state != STATE_IDLE) {
|
||||
// Store only when idle.
|
||||
return STATUS_IDLE_ERROR;
|
||||
}
|
||||
helper_var = true; // Set helper_var to flag storing method.
|
||||
// No break. Continues into default: to read remaining command characters.
|
||||
}
|
||||
if(line[++char_counter] == 0 ) // Print startup lines
|
||||
{
|
||||
for(helper_var = 0; helper_var < N_STARTUP_LINE; helper_var++)
|
||||
{
|
||||
if (!(Settings_ReadStartupLine(helper_var, line)))
|
||||
{
|
||||
Report_StatusMessage(STATUS_SETTING_READ_FAIL);
|
||||
}
|
||||
else
|
||||
{
|
||||
Report_StartupLine(helper_var,line);
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
else // Store startup line [IDLE Only] Prevents motion during ALARM.
|
||||
{
|
||||
if(sys.state != STATE_IDLE)
|
||||
{
|
||||
// Store only when idle.
|
||||
return STATUS_IDLE_ERROR;
|
||||
}
|
||||
helper_var = true; // Set helper_var to flag storing method.
|
||||
// No break. Continues into default: to read remaining command characters.
|
||||
}
|
||||
#endif
|
||||
|
||||
default: // Storing setting methods [IDLE/ALARM]
|
||||
if(!Read_Float(line, &char_counter, ¶meter)) {
|
||||
return(STATUS_BAD_NUMBER_FORMAT);
|
||||
}
|
||||
if(line[char_counter++] != '=') {
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
if(helper_var) { // Store startup line
|
||||
// Prepare sending gcode block to gcode parser by shifting all characters
|
||||
helper_var = char_counter; // Set helper variable as counter to start of gcode block
|
||||
default: // Storing setting methods [IDLE/ALARM]
|
||||
if(!Read_Float(line, &char_counter, ¶meter))
|
||||
{
|
||||
return(STATUS_BAD_NUMBER_FORMAT);
|
||||
}
|
||||
if(line[char_counter++] != '=')
|
||||
{
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
if(helper_var) // Store startup line
|
||||
{
|
||||
// Prepare sending gcode block to gcode parser by shifting all characters
|
||||
helper_var = char_counter; // Set helper variable as counter to start of gcode block
|
||||
|
||||
do {
|
||||
line[char_counter-helper_var] = line[char_counter];
|
||||
} while(line[char_counter++] != 0);
|
||||
do
|
||||
{
|
||||
line[char_counter-helper_var] = line[char_counter];
|
||||
}
|
||||
while(line[char_counter++] != 0);
|
||||
|
||||
// Execute gcode block to ensure block is valid.
|
||||
helper_var = GC_ExecuteLine(line); // Set helper_var to returned status code.
|
||||
// Execute gcode block to ensure block is valid.
|
||||
helper_var = GC_ExecuteLine(line); // Set helper_var to returned status code.
|
||||
|
||||
if(helper_var) {
|
||||
return(helper_var);
|
||||
}
|
||||
else {
|
||||
helper_var = trunc(parameter); // Set helper_var to int value of parameter
|
||||
Settings_StoreStartupLine(helper_var, line);
|
||||
}
|
||||
}
|
||||
else { // Store global setting.
|
||||
if(!Read_Float(line, &char_counter, &value)) {
|
||||
return STATUS_BAD_NUMBER_FORMAT;
|
||||
}
|
||||
if((line[char_counter] != 0) || (parameter > 255)) {
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
if(helper_var)
|
||||
{
|
||||
return(helper_var);
|
||||
}
|
||||
else
|
||||
{
|
||||
helper_var = trunc(parameter); // Set helper_var to int value of parameter
|
||||
Settings_StoreStartupLine(helper_var, line);
|
||||
}
|
||||
}
|
||||
else // Store global setting.
|
||||
{
|
||||
if(!Read_Float(line, &char_counter, &value))
|
||||
{
|
||||
return STATUS_BAD_NUMBER_FORMAT;
|
||||
}
|
||||
if((line[char_counter] != 0) || (parameter > 255))
|
||||
{
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
|
||||
return Settings_StoreGlobalSetting((uint8_t)parameter, value);
|
||||
}
|
||||
}
|
||||
}
|
||||
return Settings_StoreGlobalSetting((uint8_t)parameter, value);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return STATUS_OK; // If '$' command makes it to here, then everything's ok.
|
||||
return STATUS_OK; // If '$' command makes it to here, then everything's ok.
|
||||
}
|
||||
|
||||
|
||||
|
@ -552,7 +610,7 @@ void System_FlagWcoChange(void)
|
|||
#ifdef FORCE_BUFFER_SYNC_DURING_WCO_CHANGE
|
||||
Protocol_BufferSynchronize();
|
||||
#endif
|
||||
sys.report_wco_counter = 0;
|
||||
sys.report_wco_counter = 0;
|
||||
}
|
||||
|
||||
|
||||
|
@ -561,39 +619,43 @@ void System_FlagWcoChange(void)
|
|||
// serves as a central place to compute the transformation.
|
||||
float System_ConvertAxisSteps2Mpos(const int32_t *steps, const uint8_t idx)
|
||||
{
|
||||
float pos = 0.0;
|
||||
float pos = 0.0;
|
||||
|
||||
#ifdef COREXY
|
||||
if(idx == X_AXIS) {
|
||||
pos = (float)system_convert_corexy_to_x_axis_steps(steps) / settings.steps_per_mm[idx];
|
||||
}
|
||||
else if (idx == Y_AXIS) {
|
||||
pos = (float)system_convert_corexy_to_y_axis_steps(steps) / settings.steps_per_mm[idx];
|
||||
}
|
||||
else {
|
||||
pos = steps[idx]/settings.steps_per_mm[idx];
|
||||
}
|
||||
if(idx == X_AXIS)
|
||||
{
|
||||
pos = (float)system_convert_corexy_to_x_axis_steps(steps) / settings.steps_per_mm[idx];
|
||||
}
|
||||
else if (idx == Y_AXIS)
|
||||
{
|
||||
pos = (float)system_convert_corexy_to_y_axis_steps(steps) / settings.steps_per_mm[idx];
|
||||
}
|
||||
else
|
||||
{
|
||||
pos = steps[idx]/settings.steps_per_mm[idx];
|
||||
}
|
||||
#else
|
||||
if(settings.steps_per_mm[idx] != 0)
|
||||
if(settings.steps_per_mm[idx] != 0)
|
||||
{
|
||||
pos = steps[idx] / settings.steps_per_mm[idx];
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
return pos;
|
||||
return pos;
|
||||
}
|
||||
|
||||
|
||||
void System_ConvertArraySteps2Mpos(float *position, const int32_t *steps)
|
||||
{
|
||||
uint8_t idx;
|
||||
uint8_t idx;
|
||||
|
||||
for(idx = 0; idx < N_AXIS; idx++) {
|
||||
position[idx] = System_ConvertAxisSteps2Mpos(steps, idx);
|
||||
}
|
||||
for(idx = 0; idx < N_AXIS; idx++)
|
||||
{
|
||||
position[idx] = System_ConvertAxisSteps2Mpos(steps, idx);
|
||||
}
|
||||
|
||||
return;
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
|
@ -614,118 +676,124 @@ int32_t system_convert_corexy_to_y_axis_steps(int32_t *steps)
|
|||
// Checks and reports if target array exceeds machine travel limits.
|
||||
uint8_t System_CheckTravelLimits(float *target)
|
||||
{
|
||||
uint8_t idx;
|
||||
uint8_t idx;
|
||||
|
||||
for(idx = 0; idx < N_AXIS; idx++) {
|
||||
for(idx = 0; idx < N_AXIS; idx++)
|
||||
{
|
||||
#ifdef HOMING_FORCE_SET_ORIGIN
|
||||
// When homing forced set origin is enabled, soft limits checks need to account for directionality.
|
||||
// NOTE: max_travel is stored as negative
|
||||
if(BIT_IS_TRUE(settings.homing_dir_mask, BIT(idx))) {
|
||||
if(target[idx] < 0 || target[idx] > -settings.max_travel[idx]) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
else {
|
||||
if(target[idx] > 0 || target[idx] < settings.max_travel[idx]) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
// When homing forced set origin is enabled, soft limits checks need to account for directionality.
|
||||
// NOTE: max_travel is stored as negative
|
||||
if(BIT_IS_TRUE(settings.homing_dir_mask, BIT(idx)))
|
||||
{
|
||||
if(target[idx] < 0 || target[idx] > -settings.max_travel[idx])
|
||||
{
|
||||
return true;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if(target[idx] > 0 || target[idx] < settings.max_travel[idx])
|
||||
{
|
||||
return true;
|
||||
}
|
||||
}
|
||||
#else
|
||||
// NOTE: max_travel is stored as negative
|
||||
if(target[idx] > 0 || target[idx] < settings.max_travel[idx]) {
|
||||
return true;
|
||||
}
|
||||
// NOTE: max_travel is stored as negative
|
||||
if(target[idx] > 0 || target[idx] < settings.max_travel[idx])
|
||||
{
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
// Special handlers for setting and clearing Grbl's real-time execution flags.
|
||||
void System_SetExecStateFlag(uint16_t mask)
|
||||
{
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
|
||||
sys_rt_exec_state |= (mask);
|
||||
sys_rt_exec_state |= (mask);
|
||||
|
||||
__set_PRIMASK(primask);
|
||||
__set_PRIMASK(primask);
|
||||
}
|
||||
|
||||
|
||||
void System_ClearExecStateFlag(uint16_t mask)
|
||||
{
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
|
||||
sys_rt_exec_state &= ~(mask);
|
||||
sys_rt_exec_state &= ~(mask);
|
||||
|
||||
__set_PRIMASK(primask);
|
||||
__set_PRIMASK(primask);
|
||||
}
|
||||
|
||||
|
||||
void System_SetExecAlarm(uint8_t code)
|
||||
{
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
|
||||
sys_rt_exec_alarm = code;
|
||||
sys_rt_exec_alarm = code;
|
||||
|
||||
__set_PRIMASK(primask);
|
||||
__set_PRIMASK(primask);
|
||||
}
|
||||
|
||||
|
||||
void System_ClearExecAlarm(void)
|
||||
{
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
|
||||
sys_rt_exec_alarm = 0;
|
||||
sys_rt_exec_alarm = 0;
|
||||
|
||||
__set_PRIMASK(primask);
|
||||
__set_PRIMASK(primask);
|
||||
}
|
||||
|
||||
|
||||
void System_SetExecMotionOverrideFlag(uint8_t mask)
|
||||
{
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
|
||||
sys_rt_exec_motion_override |= (mask);
|
||||
sys_rt_exec_motion_override |= (mask);
|
||||
|
||||
__set_PRIMASK(primask);
|
||||
__set_PRIMASK(primask);
|
||||
}
|
||||
|
||||
|
||||
void System_SetExecAccessoryOverrideFlag(uint8_t mask)
|
||||
{
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
|
||||
sys_rt_exec_accessory_override |= (mask);
|
||||
sys_rt_exec_accessory_override |= (mask);
|
||||
|
||||
__set_PRIMASK(primask);
|
||||
__set_PRIMASK(primask);
|
||||
}
|
||||
|
||||
|
||||
void System_ClearExecMotionOverride(void)
|
||||
{
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
|
||||
sys_rt_exec_motion_override = 0;
|
||||
sys_rt_exec_motion_override = 0;
|
||||
|
||||
__set_PRIMASK(primask);
|
||||
__set_PRIMASK(primask);
|
||||
}
|
||||
|
||||
|
||||
void System_ClearExecAccessoryOverrides(void)
|
||||
{
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
uint32_t primask = __get_PRIMASK();
|
||||
__disable_irq();
|
||||
|
||||
sys_rt_exec_accessory_override = 0;
|
||||
sys_rt_exec_accessory_override = 0;
|
||||
|
||||
__set_PRIMASK(primask);
|
||||
__set_PRIMASK(primask);
|
||||
}
|
||||
|
|
176
grbl/System.h
176
grbl/System.h
|
@ -3,7 +3,7 @@
|
|||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2017-2020 Patrick F.
|
||||
Copyright (c) 2017-2020 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
|
||||
|
@ -30,120 +30,128 @@
|
|||
// NOTE: The system executor uses an unsigned 8-bit volatile variable (8 flag limit.) The default
|
||||
// flags are always false, so the realtime protocol only needs to check for a non-zero value to
|
||||
// know when there is a realtime command to execute.
|
||||
#define EXEC_STATUS_REPORT BIT(0)
|
||||
#define EXEC_CYCLE_START BIT(1)
|
||||
#define EXEC_CYCLE_STOP BIT(2)
|
||||
#define EXEC_FEED_HOLD BIT(3)
|
||||
#define EXEC_RESET BIT(4)
|
||||
#define EXEC_SAFETY_DOOR BIT(5)
|
||||
#define EXEC_MOTION_CANCEL BIT(6)
|
||||
#define EXEC_SLEEP BIT(7)
|
||||
#define EXEC_STATUS_REPORT BIT(0)
|
||||
#define EXEC_CYCLE_START BIT(1)
|
||||
#define EXEC_CYCLE_STOP BIT(2)
|
||||
#define EXEC_FEED_HOLD BIT(3)
|
||||
#define EXEC_RESET BIT(4)
|
||||
#define EXEC_SAFETY_DOOR BIT(5)
|
||||
#define EXEC_MOTION_CANCEL BIT(6)
|
||||
#define EXEC_SLEEP BIT(7)
|
||||
|
||||
#define EXEC_FEED_DWELL BIT(8)
|
||||
#define EXEC_TOOL_CHANGE BIT(9)
|
||||
|
||||
// Alarm executor codes. Valid values (1-255). Zero is reserved.
|
||||
#define EXEC_ALARM_HARD_LIMIT 1
|
||||
#define EXEC_ALARM_SOFT_LIMIT 2
|
||||
#define EXEC_ALARM_ABORT_CYCLE 3
|
||||
#define EXEC_ALARM_PROBE_FAIL_INITIAL 4
|
||||
#define EXEC_ALARM_PROBE_FAIL_CONTACT 5
|
||||
#define EXEC_ALARM_HOMING_FAIL_RESET 6
|
||||
#define EXEC_ALARM_HOMING_FAIL_DOOR 7
|
||||
#define EXEC_ALARM_HOMING_FAIL_PULLOFF 8
|
||||
#define EXEC_ALARM_HOMING_FAIL_APPROACH 9
|
||||
#define EXEC_ALARM_HARD_LIMIT 1
|
||||
#define EXEC_ALARM_SOFT_LIMIT 2
|
||||
#define EXEC_ALARM_ABORT_CYCLE 3
|
||||
#define EXEC_ALARM_PROBE_FAIL_INITIAL 4
|
||||
#define EXEC_ALARM_PROBE_FAIL_CONTACT 5
|
||||
#define EXEC_ALARM_HOMING_FAIL_RESET 6
|
||||
#define EXEC_ALARM_HOMING_FAIL_DOOR 7
|
||||
#define EXEC_ALARM_HOMING_FAIL_PULLOFF 8
|
||||
#define EXEC_ALARM_HOMING_FAIL_APPROACH 9
|
||||
|
||||
#define EXEC_ALARM_HARD_LIMIT_X1 21
|
||||
#define EXEC_ALARM_HARD_LIMIT_X2 22
|
||||
#define EXEC_ALARM_HARD_LIMIT_Y1 23
|
||||
#define EXEC_ALARM_HARD_LIMIT_Y2 24
|
||||
#define EXEC_ALARM_HARD_LIMIT_Z1 25
|
||||
#define EXEC_ALARM_HARD_LIMIT_Z2 26
|
||||
|
||||
// Override bit maps. Realtime bitflags to control feed, rapid, spindle, and coolant overrides.
|
||||
// Spindle/coolant and feed/rapids are separated into two controlling flag variables.
|
||||
#define EXEC_FEED_OVR_RESET BIT(0)
|
||||
#define EXEC_FEED_OVR_COARSE_PLUS BIT(1)
|
||||
#define EXEC_FEED_OVR_COARSE_MINUS BIT(2)
|
||||
#define EXEC_FEED_OVR_FINE_PLUS BIT(3)
|
||||
#define EXEC_FEED_OVR_FINE_MINUS BIT(4)
|
||||
#define EXEC_RAPID_OVR_RESET BIT(5)
|
||||
#define EXEC_RAPID_OVR_MEDIUM BIT(6)
|
||||
#define EXEC_RAPID_OVR_LOW BIT(7)
|
||||
//#define EXEC_RAPID_OVR_EXTRA_LOW BIT(*) // *NOT SUPPORTED*
|
||||
#define EXEC_FEED_OVR_RESET BIT(0)
|
||||
#define EXEC_FEED_OVR_COARSE_PLUS BIT(1)
|
||||
#define EXEC_FEED_OVR_COARSE_MINUS BIT(2)
|
||||
#define EXEC_FEED_OVR_FINE_PLUS BIT(3)
|
||||
#define EXEC_FEED_OVR_FINE_MINUS BIT(4)
|
||||
#define EXEC_RAPID_OVR_RESET BIT(5)
|
||||
#define EXEC_RAPID_OVR_MEDIUM BIT(6)
|
||||
#define EXEC_RAPID_OVR_LOW BIT(7)
|
||||
//#define EXEC_RAPID_OVR_EXTRA_LOW BIT(*) // *NOT SUPPORTED*
|
||||
|
||||
#define EXEC_SPINDLE_OVR_RESET BIT(0)
|
||||
#define EXEC_SPINDLE_OVR_COARSE_PLUS BIT(1)
|
||||
#define EXEC_SPINDLE_OVR_COARSE_MINUS BIT(2)
|
||||
#define EXEC_SPINDLE_OVR_FINE_PLUS BIT(3)
|
||||
#define EXEC_SPINDLE_OVR_FINE_MINUS BIT(4)
|
||||
#define EXEC_SPINDLE_OVR_STOP BIT(5)
|
||||
#define EXEC_COOLANT_FLOOD_OVR_TOGGLE BIT(6)
|
||||
#define EXEC_COOLANT_MIST_OVR_TOGGLE BIT(7)
|
||||
#define EXEC_SPINDLE_OVR_RESET BIT(0)
|
||||
#define EXEC_SPINDLE_OVR_COARSE_PLUS BIT(1)
|
||||
#define EXEC_SPINDLE_OVR_COARSE_MINUS BIT(2)
|
||||
#define EXEC_SPINDLE_OVR_FINE_PLUS BIT(3)
|
||||
#define EXEC_SPINDLE_OVR_FINE_MINUS BIT(4)
|
||||
#define EXEC_SPINDLE_OVR_STOP BIT(5)
|
||||
#define EXEC_COOLANT_FLOOD_OVR_TOGGLE BIT(6)
|
||||
#define EXEC_COOLANT_MIST_OVR_TOGGLE BIT(7)
|
||||
|
||||
// Define system state bit map. The state variable primarily tracks the individual functions
|
||||
// of Grbl to manage each without overlapping. It is also used as a messaging flag for
|
||||
// critical events.
|
||||
#define STATE_IDLE 0 // Must be zero. No flags.
|
||||
#define STATE_ALARM BIT(0) // In alarm state. Locks out all g-code processes. Allows settings access.
|
||||
#define STATE_CHECK_MODE BIT(1) // G-code check mode. Locks out planner and motion only.
|
||||
#define STATE_HOMING BIT(2) // Performing homing cycle
|
||||
#define STATE_CYCLE BIT(3) // Cycle is running or motions are being executed.
|
||||
#define STATE_HOLD BIT(4) // Active feed hold
|
||||
#define STATE_JOG BIT(5) // Jogging mode.
|
||||
#define STATE_SAFETY_DOOR BIT(6) // Safety door is ajar. Feed holds and de-energizes system.
|
||||
#define STATE_SLEEP BIT(7) // Sleep state.
|
||||
#define STATE_IDLE 0 // Must be zero. No flags.
|
||||
#define STATE_ALARM BIT(0) // In alarm state. Locks out all g-code processes. Allows settings access.
|
||||
#define STATE_CHECK_MODE BIT(1) // G-code check mode. Locks out planner and motion only.
|
||||
#define STATE_HOMING BIT(2) // Performing homing cycle
|
||||
#define STATE_CYCLE BIT(3) // Cycle is running or motions are being executed.
|
||||
#define STATE_HOLD BIT(4) // Active feed hold
|
||||
#define STATE_JOG BIT(5) // Jogging mode.
|
||||
#define STATE_SAFETY_DOOR BIT(6) // Safety door is ajar. Feed holds and de-energizes system.
|
||||
#define STATE_SLEEP BIT(7) // Sleep state.
|
||||
|
||||
#define STATE_FEED_DWELL BIT(8) // Dwell
|
||||
#define STATE_TOOL_CHANGE BIT(9) // Tool change in progress
|
||||
|
||||
// Define system suspend flags. Used in various ways to manage suspend states and procedures.
|
||||
#define SUSPEND_DISABLE 0 // Must be zero.
|
||||
#define SUSPEND_HOLD_COMPLETE BIT(0) // Indicates initial feed hold is complete.
|
||||
#define SUSPEND_RESTART_RETRACT BIT(1) // Flag to indicate a retract from a restore parking motion.
|
||||
#define SUSPEND_RETRACT_COMPLETE BIT(2) // (Safety door only) Indicates retraction and de-energizing is complete.
|
||||
#define SUSPEND_INITIATE_RESTORE BIT(3) // (Safety door only) Flag to initiate resume procedures from a cycle start.
|
||||
#define SUSPEND_RESTORE_COMPLETE BIT(4) // (Safety door only) Indicates ready to resume normal operation.
|
||||
#define SUSPEND_SAFETY_DOOR_AJAR BIT(5) // Tracks safety door state for resuming.
|
||||
#define SUSPEND_MOTION_CANCEL BIT(6) // Indicates a canceled resume motion. Currently used by probing routine.
|
||||
#define SUSPEND_JOG_CANCEL BIT(7) // Indicates a jog cancel in process and to reset buffers when complete.
|
||||
#define SUSPEND_DISABLE 0 // Must be zero.
|
||||
#define SUSPEND_HOLD_COMPLETE BIT(0) // Indicates initial feed hold is complete.
|
||||
#define SUSPEND_RESTART_RETRACT BIT(1) // Flag to indicate a retract from a restore parking motion.
|
||||
#define SUSPEND_RETRACT_COMPLETE BIT(2) // (Safety door only) Indicates retraction and de-energizing is complete.
|
||||
#define SUSPEND_INITIATE_RESTORE BIT(3) // (Safety door only) Flag to initiate resume procedures from a cycle start.
|
||||
#define SUSPEND_RESTORE_COMPLETE BIT(4) // (Safety door only) Indicates ready to resume normal operation.
|
||||
#define SUSPEND_SAFETY_DOOR_AJAR BIT(5) // Tracks safety door state for resuming.
|
||||
#define SUSPEND_MOTION_CANCEL BIT(6) // Indicates a canceled resume motion. Currently used by probing routine.
|
||||
#define SUSPEND_JOG_CANCEL BIT(7) // Indicates a jog cancel in process and to reset buffers when complete.
|
||||
|
||||
// Define step segment generator state flags.
|
||||
#define STEP_CONTROL_NORMAL_OP 0 // Must be zero.
|
||||
#define STEP_CONTROL_END_MOTION BIT(0)
|
||||
#define STEP_CONTROL_EXECUTE_HOLD BIT(1)
|
||||
#define STEP_CONTROL_EXECUTE_SYS_MOTION BIT(2)
|
||||
#define STEP_CONTROL_UPDATE_SPINDLE_PWM BIT(3)
|
||||
#define STEP_CONTROL_NORMAL_OP 0 // Must be zero.
|
||||
#define STEP_CONTROL_END_MOTION BIT(0)
|
||||
#define STEP_CONTROL_EXECUTE_HOLD BIT(1)
|
||||
#define STEP_CONTROL_EXECUTE_SYS_MOTION BIT(2)
|
||||
#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 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_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 spindle stop override control states.
|
||||
#define SPINDLE_STOP_OVR_DISABLED 0 // Must be zero.
|
||||
#define SPINDLE_STOP_OVR_ENABLED BIT(0)
|
||||
#define SPINDLE_STOP_OVR_INITIATE BIT(1)
|
||||
#define SPINDLE_STOP_OVR_RESTORE BIT(2)
|
||||
#define SPINDLE_STOP_OVR_RESTORE_CYCLE BIT(3)
|
||||
#define SPINDLE_STOP_OVR_DISABLED 0 // Must be zero.
|
||||
#define SPINDLE_STOP_OVR_ENABLED BIT(0)
|
||||
#define SPINDLE_STOP_OVR_INITIATE BIT(1)
|
||||
#define SPINDLE_STOP_OVR_RESTORE BIT(2)
|
||||
#define SPINDLE_STOP_OVR_RESTORE_CYCLE BIT(3)
|
||||
|
||||
|
||||
|
||||
// Define global system variables
|
||||
typedef struct {
|
||||
uint16_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.
|
||||
typedef struct
|
||||
{
|
||||
uint16_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.
|
||||
uint8_t override_ctrl; // Tracks override control states.
|
||||
#endif
|
||||
float spindle_speed;
|
||||
uint8_t is_homed;
|
||||
float spindle_speed;
|
||||
uint8_t is_homed;
|
||||
} System_t;
|
||||
|
||||
extern System_t sys;
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
ToolChange.c - Changing tool
|
||||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2018-2020 Patrick F.
|
||||
Copyright (c) 2018-2020 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
|
||||
|
@ -49,7 +49,7 @@ void TC_Init(void)
|
|||
memset(tc_pos, 0, sizeof(float)*N_AXIS);
|
||||
|
||||
gc_state.modal.tool_length = TOOL_LENGTH_OFFSET_CANCEL;
|
||||
gc_state.tool_length_offset = 0.0;
|
||||
gc_state.tool_length_offset = 0.0;
|
||||
}
|
||||
|
||||
|
||||
|
@ -61,16 +61,16 @@ void TC_ChangeCurrentTool(void)
|
|||
|
||||
if(sys.state == STATE_CHECK_MODE)
|
||||
{
|
||||
return;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
// Wait until queue is processed
|
||||
Protocol_BufferSynchronize();
|
||||
|
||||
// Move TOOL_LENGTH_OFFSET_AXIS to 0
|
||||
System_ConvertArraySteps2Mpos(position, sys_position);
|
||||
position[TOOL_LENGTH_OFFSET_AXIS] = 0.0;
|
||||
memcpy(tc_pos, position, sizeof(float)*N_AXIS);
|
||||
System_ConvertArraySteps2Mpos(position, sys_position);
|
||||
position[TOOL_LENGTH_OFFSET_AXIS] = 0.0;
|
||||
memcpy(tc_pos, position, sizeof(float)*N_AXIS);
|
||||
|
||||
//System_SetExecStateFlag(EXEC_TOOL_CHANGE);
|
||||
|
||||
|
@ -80,12 +80,12 @@ void TC_ChangeCurrentTool(void)
|
|||
pl_data.spindle_speed = 0;
|
||||
pl_data.line_number = gc_state.line_number;
|
||||
|
||||
MC_Line(position, &pl_data);
|
||||
Delay_ms(20);
|
||||
MC_Line(position, &pl_data);
|
||||
Delay_ms(20);
|
||||
|
||||
Spindle_Stop();
|
||||
Spindle_Stop();
|
||||
|
||||
// Wait until queue is processed
|
||||
// Wait until queue is processed
|
||||
Protocol_BufferSynchronize();
|
||||
|
||||
// Wait until move is finished
|
||||
|
@ -106,33 +106,33 @@ void TC_ProbeTLS(void)
|
|||
|
||||
if(sys.state == STATE_CHECK_MODE || settings.tls_valid == 0)
|
||||
{
|
||||
return;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
// Move to XY position of TLS
|
||||
System_ConvertArraySteps2Mpos(position, settings.tls_position);
|
||||
position[TOOL_LENGTH_OFFSET_AXIS] = 0.0;
|
||||
// Move to XY position of TLS
|
||||
System_ConvertArraySteps2Mpos(position, settings.tls_position);
|
||||
position[TOOL_LENGTH_OFFSET_AXIS] = 0.0;
|
||||
|
||||
// Set-up planer
|
||||
pl_data.feed_rate = 0.0;
|
||||
pl_data.condition |= PL_COND_FLAG_RAPID_MOTION; // Set rapid motion condition flag.
|
||||
pl_data.condition |= PL_COND_FLAG_RAPID_MOTION; // Set rapid motion condition flag.
|
||||
pl_data.backlash_motion = 0;
|
||||
pl_data.spindle_speed = 0;
|
||||
pl_data.line_number = gc_state.line_number;
|
||||
|
||||
// Move to X/Y position of TLS
|
||||
MC_Line(position, &pl_data);
|
||||
MC_Line(position, &pl_data);
|
||||
|
||||
// Move down with offset (for tool)
|
||||
position[TOOL_LENGTH_OFFSET_AXIS] = (settings.tls_position[TOOL_LENGTH_OFFSET_AXIS] / settings.steps_per_mm[TOOL_LENGTH_OFFSET_AXIS]) + TOOL_SENSOR_OFFSET;
|
||||
MC_Line(position, &pl_data);
|
||||
position[TOOL_LENGTH_OFFSET_AXIS] = (settings.tls_position[TOOL_LENGTH_OFFSET_AXIS] / settings.steps_per_mm[TOOL_LENGTH_OFFSET_AXIS]) + TOOL_SENSOR_OFFSET;
|
||||
MC_Line(position, &pl_data);
|
||||
|
||||
// Wait until queue is processed
|
||||
// Wait until queue is processed
|
||||
Protocol_BufferSynchronize();
|
||||
|
||||
// Set up fast probing
|
||||
pl_data.feed_rate = 200.0;
|
||||
pl_data.condition = 0; // Reset rapid motion condition flag.
|
||||
pl_data.condition = 0; // Reset rapid motion condition flag.
|
||||
|
||||
// Probe TLS fast
|
||||
position[TOOL_LENGTH_OFFSET_AXIS] -= 200.0;
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
ToolChange.h - Changing tool
|
||||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2018-2020 Patrick F.
|
||||
Copyright (c) 2018-2020 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
ToolTable.c - Tool Table Library
|
||||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2020 Patrick F.
|
||||
Copyright (c) 2020 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
ToolTable.h - Tool Table Library
|
||||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2020 Patrick F.
|
||||
Copyright (c) 2020 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
|
||||
|
|
|
@ -3,6 +3,7 @@
|
|||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2017-2020 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
|
||||
|
@ -29,56 +30,56 @@
|
|||
|
||||
|
||||
#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
|
||||
// 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_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
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 50 // msec (0-254, 255 keeps steppers enabled)
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||
#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_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 1 // false
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||
#define DEFAULT_LASER_MODE 0 // false
|
||||
#define DEFAULT_LATHE_MODE 0 // false
|
||||
#define DEFAULT_HOMING_ENABLE 1 // false
|
||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
||||
#define DEFAULT_HOMING_FEED_RATE 50.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 500.0 // mm/min
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
||||
#define DEFAULT_TOOL_CHANGE_MODE 0 // 0 = Ignore M6; 1 = Manual tool change; 2 = Manual tool change + TLS
|
||||
#define DEFAULT_SYSTEM_INVERT_MASK 0
|
||||
#define DEFAULT_STEPPING_INVERT_MASK 0
|
||||
#define DEFAULT_DIRECTION_INVERT_MASK 0
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 50 // msec (0-254, 255 keeps steppers enabled)
|
||||
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||
#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_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 1 // false
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||
#define DEFAULT_LASER_MODE 0 // false
|
||||
#define DEFAULT_LATHE_MODE 0 // false
|
||||
#define DEFAULT_HOMING_ENABLE 1 // false
|
||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
||||
#define DEFAULT_HOMING_FEED_RATE 50.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 500.0 // mm/min
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
||||
#define DEFAULT_TOOL_CHANGE_MODE 0 // 0 = Ignore M6; 1 = Manual tool change; 2 = Manual tool change + TLS
|
||||
#endif
|
||||
|
||||
|
||||
|
|
265
grbl/util.c
265
grbl/util.c
|
@ -3,7 +3,7 @@
|
|||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2017-2020 Patrick F.
|
||||
Copyright (c) 2017-2020 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
|
||||
|
@ -40,85 +40,110 @@
|
|||
// 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;
|
||||
char *ptr = line + *char_counter;
|
||||
unsigned char c;
|
||||
|
||||
// Grab first character and increment pointer. No spaces assumed in line.
|
||||
c = *ptr++;
|
||||
// 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;
|
||||
c = *ptr++;
|
||||
}
|
||||
else if(c == '+') {
|
||||
c = *ptr++;
|
||||
}
|
||||
// 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;
|
||||
// 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';
|
||||
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++;
|
||||
}
|
||||
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++;
|
||||
}
|
||||
|
||||
// Return if no digits have been read.
|
||||
if(!ndigit) { return(false); };
|
||||
// Return if no digits have been read.
|
||||
if(!ndigit)
|
||||
{
|
||||
return(false);
|
||||
};
|
||||
|
||||
// Convert integer into floating point.
|
||||
float fval;
|
||||
fval = (float)intval;
|
||||
// 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);
|
||||
}
|
||||
}
|
||||
// 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);
|
||||
}
|
||||
}
|
||||
|
||||
// Assign floating point value with correct sign.
|
||||
if(isnegative) {
|
||||
*float_ptr = -fval;
|
||||
}
|
||||
else {
|
||||
*float_ptr = fval;
|
||||
}
|
||||
// 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
|
||||
*char_counter = ptr - line - 1; // Set char_counter to next statement
|
||||
|
||||
return(true);
|
||||
return(true);
|
||||
}
|
||||
|
||||
// Search a float in a string and return it as string
|
||||
|
@ -141,7 +166,8 @@ uint8_t ExtractFloat(char *line, int start_idx, char *float_char)
|
|||
do
|
||||
{
|
||||
float_char[j++] = line[i++];
|
||||
} while(isdigit((unsigned char)line[i]) || line[i] == '.'); // Read float
|
||||
}
|
||||
while(isdigit((unsigned char)line[i]) || line[i] == '.'); // Read float
|
||||
|
||||
float_char[j] = '\0';
|
||||
|
||||
|
@ -156,76 +182,87 @@ uint8_t ExtractFloat(char *line, int start_idx, char *float_char)
|
|||
// 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);
|
||||
uint16_t i = ceil(1000/DWELL_TIME_STEP*seconds);
|
||||
|
||||
while(i-- > 0) {
|
||||
if(sys.abort) {
|
||||
return;
|
||||
}
|
||||
while(i-- > 0)
|
||||
{
|
||||
if(sys.abort)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
if(mode == DELAY_MODE_DWELL) {
|
||||
Protocol_ExecuteRealtime();
|
||||
}
|
||||
else { // DELAY_MODE_SYS_SUSPEND
|
||||
// Execute rt_system() only to avoid nesting suspend loops.
|
||||
Protocol_ExecRtSystem();
|
||||
if(mode == DELAY_MODE_DWELL)
|
||||
{
|
||||
Protocol_ExecuteRealtime();
|
||||
}
|
||||
else // DELAY_MODE_SYS_SUSPEND
|
||||
{
|
||||
// Execute rt_system() only to avoid nesting suspend loops.
|
||||
Protocol_ExecRtSystem();
|
||||
|
||||
if(sys.suspend & SUSPEND_RESTART_RETRACT) {
|
||||
// Bail, if safety door reopens.
|
||||
return;
|
||||
}
|
||||
}
|
||||
if(sys.suspend & SUSPEND_RESTART_RETRACT)
|
||||
{
|
||||
// Bail, if safety door reopens.
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
Delay_ms(DWELL_TIME_STEP); // Delay DWELL_TIME_STEP increment
|
||||
}
|
||||
Delay_ms(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);
|
||||
return sqrt(x*x + y*y);
|
||||
}
|
||||
|
||||
bool isEqual_f(float a, float b)
|
||||
{
|
||||
if(fabs(a-b) < 0.00001) {
|
||||
return true;
|
||||
}
|
||||
if(fabs(a-b) < 0.00001)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
return false;
|
||||
}
|
||||
|
||||
float convert_delta_vector_to_unit_vector(float *vector)
|
||||
{
|
||||
uint8_t idx;
|
||||
float magnitude = 0.0;
|
||||
uint8_t idx;
|
||||
float magnitude = 0.0;
|
||||
|
||||
for(idx = 0; idx < N_AXIS; idx++) {
|
||||
if(vector[idx] != 0.0) {
|
||||
magnitude += vector[idx]*vector[idx];
|
||||
}
|
||||
}
|
||||
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;
|
||||
magnitude = sqrt(magnitude);
|
||||
float inv_magnitude = 1.0/magnitude;
|
||||
|
||||
for(idx = 0; idx < N_AXIS; idx++) {
|
||||
vector[idx] *= inv_magnitude;
|
||||
}
|
||||
for(idx = 0; idx < N_AXIS; idx++)
|
||||
{
|
||||
vector[idx] *= inv_magnitude;
|
||||
}
|
||||
|
||||
return magnitude;
|
||||
return magnitude;
|
||||
}
|
||||
|
||||
float limit_value_by_axis_maximum(float *max_value, float *unit_vec)
|
||||
{
|
||||
uint8_t idx;
|
||||
float limit_value = SOME_LARGE_VALUE;
|
||||
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]));
|
||||
}
|
||||
}
|
||||
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;
|
||||
}
|
||||
|
|
101
grbl/util.h
101
grbl/util.h
|
@ -3,7 +3,7 @@
|
|||
Part of Grbl-Advanced
|
||||
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
Copyright (c) 2017-2020 Patrick F.
|
||||
Copyright (c) 2017-2020 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
|
||||
|
@ -27,93 +27,96 @@
|
|||
|
||||
|
||||
#ifndef M_PI
|
||||
#define M_PI 3.14159265358979323846
|
||||
#define M_PI 3.14159265358979323846
|
||||
#endif // M_PI
|
||||
|
||||
|
||||
// Bit field and masking macros
|
||||
#define BIT(n) (1 << n)
|
||||
#define BIT_TRUE_ATOMIC(x,mask) BIT_TRUE(x,mask)
|
||||
#define BIT_FALSE_ATOMIC(x,mask) BIT_FALSE(x,mask)
|
||||
#define BIT_TOGGLE_ATOMIC(x,mask) (x) ^= (mask)
|
||||
#define BIT_TRUE(x,mask) (x) |= (mask)
|
||||
#define BIT_FALSE(x,mask) (x) &= ~(mask)
|
||||
#define BIT_IS_TRUE(x,mask) ((x & mask) != 0)
|
||||
#define BIT_IS_FALSE(x,mask) ((x & mask) == 0)
|
||||
#define BIT(n) (1 << n)
|
||||
#define BIT_TRUE_ATOMIC(x,mask) BIT_TRUE(x,mask)
|
||||
#define BIT_FALSE_ATOMIC(x,mask) BIT_FALSE(x,mask)
|
||||
#define BIT_TOGGLE_ATOMIC(x,mask) (x) ^= (mask)
|
||||
#define BIT_TRUE(x,mask) (x) |= (mask)
|
||||
#define BIT_FALSE(x,mask) (x) &= ~(mask)
|
||||
#define BIT_IS_TRUE(x,mask) ((x & mask) != 0)
|
||||
#define BIT_IS_FALSE(x,mask) ((x & mask) == 0)
|
||||
|
||||
|
||||
#define F_CPU 96000000UL
|
||||
#define F_CPU 96000000UL
|
||||
#define F_TIMER_STEPPER 24000000UL
|
||||
|
||||
#define N_AXIS 5
|
||||
#define N_AXIS 5
|
||||
#define N_LINEAR_AXIS 3
|
||||
|
||||
#define X_AXIS 0 // Axis indexing value.
|
||||
#define Y_AXIS 1
|
||||
#define Z_AXIS 2
|
||||
#define A_AXIS 3
|
||||
#define B_AXIS 4
|
||||
#define X_AXIS 0 // Axis indexing value.
|
||||
#define Y_AXIS 1
|
||||
#define Z_AXIS 2
|
||||
#define A_AXIS 3
|
||||
#define B_AXIS 4
|
||||
|
||||
#define X_STEP_BIT 0
|
||||
#define Y_STEP_BIT 1
|
||||
#define Z_STEP_BIT 2
|
||||
#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 X_DIRECTION_BIT 0
|
||||
#define Y_DIRECTION_BIT 1
|
||||
#define Z_DIRECTION_BIT 2
|
||||
#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 X_LIMIT_BIT 0
|
||||
#define Y_LIMIT_BIT 1
|
||||
#define Z_LIMIT_BIT 2
|
||||
#define LIMIT_MASK ((1<<X_LIMIT_BIT) | (1<<Y_LIMIT_BIT) | (1<<Z_LIMIT_BIT))
|
||||
#define X1_LIMIT_BIT 0
|
||||
#define Y1_LIMIT_BIT 1
|
||||
#define Z1_LIMIT_BIT 2
|
||||
#define X2_LIMIT_BIT 3
|
||||
#define Y2_LIMIT_BIT 4
|
||||
#define Z2_LIMIT_BIT 5
|
||||
#define LIMIT_MASK ((1<<X1_LIMIT_BIT) | (1<<Y1_LIMIT_BIT) | (1<<Z1_LIMIT_BIT) | (1<<X2_LIMIT_BIT) | (1<<Y2_LIMIT_BIT) | (1<<Z2_LIMIT_BIT))
|
||||
|
||||
#define SPINDLE_ENABLE_BIT 0
|
||||
#define SPINDLE_DIRECTION_BIT 1
|
||||
#define SPINDLE_ENABLE_BIT 0
|
||||
#define SPINDLE_DIRECTION_BIT 1
|
||||
|
||||
#define CONTROL_RESET_BIT 0
|
||||
#define CONTROL_FEED_HOLD_BIT 1
|
||||
#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_RESET_BIT 0
|
||||
#define CONTROL_FEED_HOLD_BIT 1
|
||||
#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 DELAY_MODE_DWELL 0
|
||||
#define DELAY_MODE_SYS_SUSPEND 1
|
||||
#define DELAY_MODE_DWELL 0
|
||||
#define DELAY_MODE_SYS_SUSPEND 1
|
||||
|
||||
|
||||
// CoreXY motor assignments. DO NOT ALTER.
|
||||
// NOTE: If the A and B motor axis bindings are changed, this effects the CoreXY equations.
|
||||
#ifdef COREXY
|
||||
#define A_MOTOR X_AXIS // Must be X_AXIS
|
||||
#define B_MOTOR Y_AXIS // Must be Y_AXIS
|
||||
#define A_MOTOR X_AXIS // Must be X_AXIS
|
||||
#define B_MOTOR Y_AXIS // Must be Y_AXIS
|
||||
#endif
|
||||
|
||||
|
||||
// Conversions
|
||||
#define MM_PER_INCH (25.40)
|
||||
#define INCH_PER_MM (0.0393701)
|
||||
#define TICKS_PER_MICROSECOND (24UL)
|
||||
#define MM_PER_INCH (25.40)
|
||||
#define INCH_PER_MM (0.0393701)
|
||||
#define TICKS_PER_MICROSECOND (24UL)
|
||||
|
||||
|
||||
#define SOME_LARGE_VALUE 1.0E+38
|
||||
#define SOME_LARGE_VALUE 1.0E+38
|
||||
|
||||
|
||||
#define ACCEL_TICKS_PER_SECOND 100
|
||||
#define ACCEL_TICKS_PER_SECOND 100
|
||||
|
||||
|
||||
#define max(a,b) (((a) > (b)) ? (a) : (b))
|
||||
#define min(a,b) (((a) < (b)) ? (a) : (b))
|
||||
#define max(a,b) (((a) > (b)) ? (a) : (b))
|
||||
#define min(a,b) (((a) < (b)) ? (a) : (b))
|
||||
|
||||
|
||||
#define clear_vector(a) (memset(a,0,sizeof(a)))
|
||||
#define clear_vector_f(a) (memset(a, 0.0, sizeof(a)))
|
||||
#define copy_vector(d,s) (memcpy(d,s,sizeof(d)))
|
||||
#define clear_vector(a) (memset(a,0,sizeof(a)))
|
||||
#define clear_vector_f(a) (memset(a, 0.0, sizeof(a)))
|
||||
#define copy_vector(d,s) (memcpy(d,s,sizeof(d)))
|
||||
|
||||
#define isequal_position_vector(a,b) !(memcmp(a, b, sizeof(float)*N_AXIS))
|
||||
#define isequal_position_vector(a,b) !(memcmp(a, b, sizeof(float)*N_AXIS))
|
||||
|
||||
|
||||
// Read a floating point value from a string. Line points to the input buffer, char_counter
|
||||
|
|
80
main.c
80
main.c
|
@ -57,8 +57,8 @@ volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bit
|
|||
|
||||
int main(void)
|
||||
{
|
||||
// Init formatted output
|
||||
Print_Init();
|
||||
// Init formatted output
|
||||
Print_Init();
|
||||
System_Init();
|
||||
Stepper_Init();
|
||||
Settings_Init();
|
||||
|
@ -77,63 +77,63 @@ int main(void)
|
|||
GrIP_Init();
|
||||
|
||||
// Init SysTick 1ms
|
||||
SysTick_Init();
|
||||
SysTick_Init();
|
||||
|
||||
if(BIT_IS_TRUE(settings.flags, BITFLAG_HOMING_ENABLE))
|
||||
{
|
||||
sys.state = STATE_ALARM;
|
||||
sys.state = STATE_ALARM;
|
||||
}
|
||||
else
|
||||
{
|
||||
sys.state = STATE_IDLE;
|
||||
sys.state = STATE_IDLE;
|
||||
}
|
||||
|
||||
// Grbl-Advanced initialization loop upon power-up or a system abort. For the latter, all processes
|
||||
// will return to this loop to be cleanly re-initialized.
|
||||
while(1)
|
||||
// Grbl-Advanced initialization loop upon power-up or a system abort. For the latter, all processes
|
||||
// will return to this loop to be cleanly re-initialized.
|
||||
while(1)
|
||||
{
|
||||
// Reset system variables.
|
||||
uint16_t prior_state = sys.state;
|
||||
uint8_t home_state = sys.is_homed;
|
||||
// Reset system variables.
|
||||
uint16_t prior_state = sys.state;
|
||||
uint8_t home_state = sys.is_homed;
|
||||
|
||||
System_Clear();
|
||||
sys.state = prior_state;
|
||||
sys.is_homed = home_state;
|
||||
System_Clear();
|
||||
sys.state = prior_state;
|
||||
sys.is_homed = home_state;
|
||||
|
||||
Probe_Reset();
|
||||
Probe_Reset();
|
||||
|
||||
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;
|
||||
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-Advanced primary systems.
|
||||
GC_Init();
|
||||
Planner_Init();
|
||||
MC_Init();
|
||||
TC_Init();
|
||||
// Reset Grbl-Advanced primary systems.
|
||||
GC_Init();
|
||||
Planner_Init();
|
||||
MC_Init();
|
||||
TC_Init();
|
||||
|
||||
Coolant_Init();
|
||||
Limits_Init();
|
||||
Probe_Init();
|
||||
Spindle_Init();
|
||||
Stepper_Reset();
|
||||
Coolant_Init();
|
||||
Limits_Init();
|
||||
Probe_Init();
|
||||
Spindle_Init();
|
||||
Stepper_Reset();
|
||||
|
||||
// Sync cleared gcode and planner positions to current system position.
|
||||
Planner_SyncPosition();
|
||||
GC_SyncPosition();
|
||||
// Sync cleared gcode and planner positions to current system position.
|
||||
Planner_SyncPosition();
|
||||
GC_SyncPosition();
|
||||
|
||||
// Print welcome message. Indicates an initialization has occured at power-up or with a reset.
|
||||
Report_InitMessage();
|
||||
// Print welcome message. Indicates an initialization has occured at power-up or with a reset.
|
||||
Report_InitMessage();
|
||||
|
||||
//-- Start Grbl-Advanced main loop. Processes program inputs and executes them. --//
|
||||
Protocol_MainLoop();
|
||||
//--------------------------------------------------------------------------------//
|
||||
//-- Start Grbl-Advanced main loop. Processes program inputs and executes them. --//
|
||||
Protocol_MainLoop();
|
||||
//--------------------------------------------------------------------------------//
|
||||
|
||||
// Clear serial buffer after soft reset to prevent undefined behavior
|
||||
FifoUsart_Init();
|
||||
}
|
||||
FifoUsart_Init();
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
Ładowanie…
Reference in New Issue