kopia lustrzana https://github.com/Schildkroet/GRBL-Advanced
ATTENTION: New config version!! Save your settings, before updating!!
Added experimental support for rotary axis (5 axis)pull/89/head
rodzic
3b2d351f68
commit
48cd2aa655
|
@ -21,9 +21,9 @@
|
|||
<Cursor1 position="1639" topLine="32" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="grbl\Config.h" open="1" top="0" tabpos="4" 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="36781" topLine="531" />
|
||||
<Cursor1 position="1123" topLine="21" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="grbl\CoolantControl.c" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
|
@ -36,7 +36,7 @@
|
|||
<Cursor1 position="873" topLine="13" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="grbl\defaults.h" open="1" top="0" tabpos="5" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<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="2407" topLine="10" />
|
||||
</Cursor>
|
||||
|
@ -116,12 +116,12 @@
|
|||
<Cursor1 position="842" topLine="3" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="grbl\Report.c" open="1" top="0" tabpos="2" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<File name="grbl\Report.c" open="0" top="0" tabpos="2" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="7135" topLine="235" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="grbl\Report.h" open="1" top="0" tabpos="3" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<File name="grbl\Report.h" open="0" top="0" tabpos="3" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="1483" topLine="9" />
|
||||
</Cursor>
|
||||
|
@ -296,9 +296,9 @@
|
|||
<Cursor1 position="781" topLine="12" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="main.c" open="1" top="1" tabpos="6" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<File name="main.c" open="1" top="1" tabpos="4" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
<Cursor>
|
||||
<Cursor1 position="2509" topLine="62" />
|
||||
<Cursor1 position="240" topLine="0" />
|
||||
</Cursor>
|
||||
</File>
|
||||
<File name="SPL\inc\stm32f4xx_cryp.h" open="0" top="0" tabpos="0" split="0" active="1" splitpos="0" zoom_1="0" zoom_2="0">
|
||||
|
|
|
@ -83,7 +83,7 @@ static void GPIO_InitStepper(void)
|
|||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
|
||||
/* GPIO Configuration: A3, D3, D5, D4, D6 */
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3 | GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_10;
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3 | GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_10;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
}
|
||||
|
||||
|
|
|
@ -26,17 +26,25 @@
|
|||
#define GPIO_STEP_X_PORT GPIOA
|
||||
#define GPIO_STEP_Y_PORT GPIOB
|
||||
#define GPIO_STEP_Z_PORT GPIOB
|
||||
#define GPIO_STEP_A_PORT GPIOB
|
||||
#define GPIO_STEP_B_PORT GPIOB
|
||||
#define GPIO_STEP_X_PIN GPIO_Pin_10
|
||||
#define GPIO_STEP_Y_PIN GPIO_Pin_3
|
||||
#define GPIO_STEP_Z_PIN GPIO_Pin_5
|
||||
#define GPIO_STEP_A_PIN GPIO_Pin_1
|
||||
#define GPIO_STEP_B_PIN GPIO_Pin_14
|
||||
|
||||
// Direction Pins
|
||||
#define GPIO_DIR_X_PORT GPIOB
|
||||
#define GPIO_DIR_Y_PORT GPIOB
|
||||
#define GPIO_DIR_Z_PORT GPIOA
|
||||
#define GPIO_DIR_A_PORT GPIOB
|
||||
#define GPIO_DIR_B_PORT GPIOB
|
||||
#define GPIO_DIR_X_PIN GPIO_Pin_4
|
||||
#define GPIO_DIR_Y_PIN GPIO_Pin_10
|
||||
#define GPIO_DIR_Z_PIN GPIO_Pin_8
|
||||
#define GPIO_DIR_A_PIN GPIO_Pin_2
|
||||
#define GPIO_DIR_B_PIN GPIO_Pin_15
|
||||
|
||||
// Stepper Enable
|
||||
#define GPIO_ENABLE_PORT GPIOA
|
||||
|
|
|
@ -47,6 +47,9 @@
|
|||
// Uncomment to use external I2C EEPROM
|
||||
//#define USE_EXT_EEPROM
|
||||
|
||||
// Uncomment to use 4th/5th axis
|
||||
//#define USE_MULTI_AXIS
|
||||
|
||||
|
||||
// Define realtime command special characters. These characters are 'picked-off' directly from the
|
||||
// serial read data stream and are not passed to the grbl line execution parser. Select characters
|
||||
|
@ -113,8 +116,8 @@
|
|||
// 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.
|
||||
|
|
11
grbl/GCode.c
11
grbl/GCode.c
|
@ -461,8 +461,10 @@ uint8_t GC_ExecuteLine(char *line)
|
|||
words (I,J,K,L,P,R) have multiple connotations and/or depend on the issued commands. */
|
||||
switch(letter)
|
||||
{
|
||||
// case 'A': // Not supported
|
||||
// case 'B': // Not supported
|
||||
#ifdef USE_MULTI_AXIS
|
||||
case 'A': word_bit = WORD_A; gc_block.values.xyz[A_AXIS] = value; axis_words |= (1<<A_AXIS); break;
|
||||
case 'B': word_bit = WORD_B; gc_block.values.xyz[B_AXIS] = value; axis_words |= (1<<B_AXIS); break;
|
||||
#endif
|
||||
// case 'C': // Not supported
|
||||
// case 'D': // Not supported
|
||||
case 'F': word_bit = WORD_F; gc_block.values.f = value; break;
|
||||
|
@ -1199,7 +1201,7 @@ uint8_t GC_ExecuteLine(char *line)
|
|||
|
||||
// Convert IJK values to proper units.
|
||||
if(gc_block.modal.units == UNITS_MODE_INCHES) {
|
||||
for(idx = 0; idx < N_AXIS; idx++) { // Axes indices are consistent, so loop may be used to save flash space.
|
||||
for(idx = 0; idx < N_LINEAR_AXIS; idx++) { // Axes indices are consistent, so loop may be used to save flash space.
|
||||
if(ijk_words & BIT(idx)) {
|
||||
gc_block.values.ijk[idx] *= MM_PER_INCH;
|
||||
}
|
||||
|
@ -1283,7 +1285,7 @@ uint8_t GC_ExecuteLine(char *line)
|
|||
if(axis_command)
|
||||
{
|
||||
// Remove axis words.
|
||||
BIT_FALSE(value_words, (BIT(WORD_X)|BIT(WORD_Y)|BIT(WORD_Z)));
|
||||
BIT_FALSE(value_words, (BIT(WORD_X)|BIT(WORD_Y)|BIT(WORD_Z)|BIT(WORD_A)|BIT(WORD_B)));
|
||||
}
|
||||
|
||||
if(value_words)
|
||||
|
@ -1807,7 +1809,6 @@ uint8_t GC_ExecuteLine(char *line)
|
|||
|
||||
- Canned cycles
|
||||
- Tool radius compensation
|
||||
- A,B,C-axes
|
||||
- Evaluation of expressions
|
||||
- Variables
|
||||
- Override control (TBD)
|
||||
|
|
|
@ -157,6 +157,8 @@
|
|||
#define WORD_Y 11
|
||||
#define WORD_Z 12
|
||||
#define WORD_Q 13
|
||||
#define WORD_A 14
|
||||
#define WORD_B 15
|
||||
|
||||
// Define g-code parser position updating flags
|
||||
#define GC_UPDATE_POS_TARGET 0 // Must be zero
|
||||
|
@ -209,7 +211,7 @@ typedef struct {
|
|||
|
||||
typedef struct {
|
||||
float f; // Feed
|
||||
float ijk[3]; // I,J,K Axis arc offsets
|
||||
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
|
||||
|
|
|
@ -141,8 +141,8 @@ void MC_Line(float *target, Planner_LineData_t *pl_data)
|
|||
pl_backlash.backlash_motion = 1;
|
||||
pl_backlash.condition = PL_COND_FLAG_RAPID_MOTION; // Set rapid motion condition flag.
|
||||
|
||||
// Backlash compensation
|
||||
for(uint8_t i = 0; i < N_AXIS; i++)
|
||||
// Backlash compensation (not for A & B)
|
||||
for(uint8_t i = 0; i < N_LINEAR_AXIS; i++)
|
||||
{
|
||||
// Move positive?
|
||||
if(target[i] > target_prev[i])
|
||||
|
|
|
@ -33,6 +33,8 @@
|
|||
#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);
|
||||
|
|
|
@ -111,6 +111,8 @@ uint8_t Planner_BufferLine(float *target, Planner_LineData_t *pl_data)
|
|||
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));
|
||||
#endif
|
||||
|
|
|
@ -83,11 +83,16 @@ static void report_util_gcode_modes_M(void)
|
|||
static void Report_AxisValue(float *axis_value)
|
||||
{
|
||||
uint8_t idx;
|
||||
uint8_t axis_num = N_LINEAR_AXIS;
|
||||
|
||||
for(idx = 0; idx < N_AXIS; idx++) {
|
||||
#ifdef USE_MULTI_AXIS
|
||||
axis_num = N_AXIS;
|
||||
#endif
|
||||
|
||||
for(idx = 0; idx < axis_num; idx++) {
|
||||
PrintFloat_CoordValue(axis_value[idx]);
|
||||
|
||||
if(idx < (N_AXIS-1)) {
|
||||
if(idx < (axis_num-1)) {
|
||||
Putc(',');
|
||||
}
|
||||
}
|
||||
|
@ -574,6 +579,9 @@ void Report_BuildInfo(char *line)
|
|||
#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
|
||||
Putc('+');
|
||||
#endif
|
||||
#ifdef USE_MULTI_AXIS
|
||||
Putc('A');
|
||||
#endif
|
||||
|
||||
// NOTE: Compiled values, like override increments/max/min values, may be added at some point later.
|
||||
Putc(',');
|
||||
|
|
|
@ -119,15 +119,26 @@ void Settings_Restore(uint8_t restore_flag) {
|
|||
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.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.backlash[X_AXIS] = DEFAULT_X_BACKLASH;
|
||||
settings.backlash[Y_AXIS] = DEFAULT_Y_BACKLASH;
|
||||
|
@ -405,8 +416,10 @@ 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); }
|
||||
|
||||
return (1<<Z_STEP_BIT);
|
||||
return (1<<B_STEP_BIT);
|
||||
}
|
||||
|
||||
|
||||
|
@ -415,8 +428,10 @@ 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); }
|
||||
|
||||
return (1<<Z_DIRECTION_BIT);
|
||||
return (1<<B_DIRECTION_BIT);
|
||||
}
|
||||
|
||||
|
||||
|
@ -425,6 +440,8 @@ 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); }
|
||||
|
||||
return (1<<Z_STEP_BIT);
|
||||
return (1<<B_STEP_BIT);
|
||||
}
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
|
||||
// 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 4 // NOTE: Check settings_reset() when moving to next version.
|
||||
#define SETTINGS_VERSION 5 // NOTE: Check settings_reset() when moving to next version.
|
||||
|
||||
|
||||
// Define bit flag masks for the boolean settings in settings.system_flags
|
||||
|
|
|
@ -106,7 +106,7 @@ typedef struct {
|
|||
typedef struct {
|
||||
// Used by the bresenham line algorithm
|
||||
// Counter variables for the bresenham line tracer
|
||||
uint32_t counter_x, counter_y, counter_z;
|
||||
uint32_t counter_x, counter_y, counter_z, counter_a, counter_b;
|
||||
|
||||
uint8_t execute_step; // Flags step execution for each interrupt.
|
||||
uint8_t step_pulse_time; // Step pulse reset time after step rise
|
||||
|
@ -366,6 +366,26 @@ void Stepper_MainISR(void)
|
|||
GPIO_SetBits(GPIO_STEP_Z_PORT, GPIO_STEP_Z_PIN);
|
||||
}
|
||||
}
|
||||
if(st.step_outbits & (1<<A_STEP_BIT)) {
|
||||
if(step_port_invert_mask & (1<<A_STEP_BIT)) {
|
||||
// Low pulse
|
||||
GPIO_ResetBits(GPIO_STEP_A_PORT, GPIO_STEP_A_PIN);
|
||||
}
|
||||
else {
|
||||
// High pulse
|
||||
GPIO_SetBits(GPIO_STEP_A_PORT, GPIO_STEP_A_PIN);
|
||||
}
|
||||
}
|
||||
if(st.step_outbits & (1<<B_STEP_BIT)) {
|
||||
if(step_port_invert_mask & (1<<B_STEP_BIT)) {
|
||||
// Low pulse
|
||||
//GPIO_ResetBits(GPIO_STEP_B_PORT, GPIO_STEP_B_PIN);
|
||||
}
|
||||
else {
|
||||
// High pulse
|
||||
//GPIO_SetBits(GPIO_STEP_B_PORT, GPIO_STEP_B_PIN);
|
||||
}
|
||||
}
|
||||
|
||||
// If there is no step segment, attempt to pop one from the stepper buffer
|
||||
if(st.exec_segment == 0) {
|
||||
|
@ -391,7 +411,7 @@ void Stepper_MainISR(void)
|
|||
st.exec_block = &st_block_buffer[st.exec_block_index];
|
||||
|
||||
// Initialize Bresenham line and distance counters
|
||||
st.counter_x = st.counter_y = st.counter_z = (st.exec_block->step_event_count >> 1);
|
||||
st.counter_x = st.counter_y = st.counter_z = st.counter_a = st.counter_b = (st.exec_block->step_event_count >> 1);
|
||||
}
|
||||
|
||||
st.dir_outbits = st.exec_block->direction_bits ^ dir_port_invert_mask;
|
||||
|
@ -416,11 +436,25 @@ void Stepper_MainISR(void)
|
|||
else {
|
||||
GPIO_ResetBits(GPIO_DIR_Z_PORT, GPIO_DIR_Z_PIN);
|
||||
}
|
||||
if(st.dir_outbits & (1<<A_DIRECTION_BIT)) {
|
||||
GPIO_SetBits(GPIO_DIR_A_PORT, GPIO_DIR_A_PIN);
|
||||
}
|
||||
else {
|
||||
GPIO_ResetBits(GPIO_DIR_A_PORT, GPIO_DIR_A_PIN);
|
||||
}
|
||||
if(st.dir_outbits & (1<<B_DIRECTION_BIT)) {
|
||||
//GPIO_SetBits(GPIO_DIR_B_PORT, GPIO_DIR_B_PIN);
|
||||
}
|
||||
else {
|
||||
//GPIO_ResetBits(GPIO_DIR_B_PORT, GPIO_DIR_B_PIN);
|
||||
}
|
||||
|
||||
// With AMASS enabled, adjust Bresenham axis increment counters according to AMASS level.
|
||||
st.steps[X_AXIS] = st.exec_block->steps[X_AXIS] >> st.exec_segment->amass_level;
|
||||
st.steps[Y_AXIS] = st.exec_block->steps[Y_AXIS] >> st.exec_segment->amass_level;
|
||||
st.steps[Z_AXIS] = st.exec_block->steps[Z_AXIS] >> st.exec_segment->amass_level;
|
||||
st.steps[A_AXIS] = st.exec_block->steps[A_AXIS] >> st.exec_segment->amass_level;
|
||||
st.steps[B_AXIS] = st.exec_block->steps[B_AXIS] >> st.exec_segment->amass_level;
|
||||
|
||||
// Set real-time spindle output as segment is loaded, just prior to the first step.
|
||||
Spindle_SetSpeed(st.exec_segment->spindle_pwm);
|
||||
|
@ -501,6 +535,40 @@ void Stepper_MainISR(void)
|
|||
}
|
||||
}
|
||||
|
||||
st.counter_a += st.steps[A_AXIS];
|
||||
|
||||
if(st.counter_a > st.exec_block->step_event_count) {
|
||||
st.step_outbits |= (1<<A_STEP_BIT);
|
||||
st.counter_a -= st.exec_block->step_event_count;
|
||||
|
||||
//if(st.exec_segment->backlash_motion == 0)
|
||||
{
|
||||
if(st.exec_block->direction_bits & (1<<A_DIRECTION_BIT)) {
|
||||
sys_position[A_AXIS]--;
|
||||
}
|
||||
else {
|
||||
sys_position[A_AXIS]++;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
st.counter_b += st.steps[B_AXIS];
|
||||
|
||||
if(st.counter_b > st.exec_block->step_event_count) {
|
||||
st.step_outbits |= (1<<B_STEP_BIT);
|
||||
st.counter_b -= st.exec_block->step_event_count;
|
||||
|
||||
//if(st.exec_segment->backlash_motion == 0)
|
||||
{
|
||||
if(st.exec_block->direction_bits & (1<<B_DIRECTION_BIT)) {
|
||||
sys_position[B_AXIS]--;
|
||||
}
|
||||
else {
|
||||
sys_position[B_AXIS]++;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// During a homing cycle, lock out and prevent desired axes from moving.
|
||||
if(sys.state == STATE_HOMING) {
|
||||
st.step_outbits &= sys.homing_axis_lock;
|
||||
|
@ -552,6 +620,22 @@ void Stepper_PortResetISR(void)
|
|||
else {
|
||||
GPIO_ResetBits(GPIO_STEP_Z_PORT, GPIO_STEP_Z_PIN);
|
||||
}
|
||||
|
||||
// A
|
||||
if(step_port_invert_mask & (1<<A_STEP_BIT)) {
|
||||
GPIO_SetBits(GPIO_STEP_A_PORT, GPIO_STEP_A_PIN);
|
||||
}
|
||||
else {
|
||||
GPIO_ResetBits(GPIO_STEP_A_PORT, GPIO_STEP_A_PIN);
|
||||
}
|
||||
|
||||
// B
|
||||
if(step_port_invert_mask & (1<<B_STEP_BIT)) {
|
||||
//GPIO_SetBits(GPIO_STEP_B_PORT, GPIO_STEP_B_PIN);
|
||||
}
|
||||
else {
|
||||
//GPIO_ResetBits(GPIO_STEP_B_PORT, GPIO_STEP_B_PIN);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
@ -600,11 +684,15 @@ void Stepper_Reset(void)
|
|||
GPIO_ResetBits(GPIO_STEP_X_PORT, GPIO_STEP_X_PIN);
|
||||
GPIO_ResetBits(GPIO_STEP_Y_PORT, GPIO_STEP_Y_PIN);
|
||||
GPIO_ResetBits(GPIO_STEP_Z_PORT, GPIO_STEP_Z_PIN);
|
||||
GPIO_ResetBits(GPIO_STEP_A_PORT, GPIO_STEP_A_PIN);
|
||||
//GPIO_ResetBits(GPIO_STEP_B_PORT, GPIO_STEP_B_PIN);
|
||||
|
||||
// Reset Direction Pins
|
||||
GPIO_ResetBits(GPIO_DIR_X_PORT, GPIO_DIR_X_PIN);
|
||||
GPIO_ResetBits(GPIO_DIR_Y_PORT, GPIO_DIR_Y_PIN);
|
||||
GPIO_ResetBits(GPIO_DIR_Z_PORT, GPIO_DIR_Z_PIN);
|
||||
GPIO_ResetBits(GPIO_DIR_A_PORT, GPIO_DIR_A_PIN);
|
||||
//GPIO_ResetBits(GPIO_DIR_B_PORT, GPIO_DIR_B_PIN);
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -324,6 +324,14 @@ uint8_t System_ExecuteLine(char *line)
|
|||
MC_HomigCycle(HOMING_CYCLE_Z);
|
||||
break;
|
||||
|
||||
case 'A':
|
||||
MC_HomigCycle(HOMING_CYCLE_A);
|
||||
break;
|
||||
|
||||
case 'B':
|
||||
MC_HomigCycle(HOMING_CYCLE_B);
|
||||
break;
|
||||
|
||||
default:
|
||||
return STATUS_INVALID_STATEMENT;
|
||||
}
|
||||
|
|
|
@ -33,15 +33,23 @@
|
|||
#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 1000.0 // °/min
|
||||
#define DEFAULT_B_MAX_RATE 1000.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 (50.0*60*60) // 100*60*60 mm/min^2 = 100 mm/sec^2
|
||||
#define DEFAULT_B_ACCELERATION (50.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
|
||||
|
||||
|
|
|
@ -45,22 +45,26 @@
|
|||
#define F_CPU 96000000UL
|
||||
#define F_TIMER_STEPPER 24000000UL
|
||||
|
||||
#define N_AXIS 3
|
||||
#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_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 A_DIRECTION_BIT 3
|
||||
#define B_DIRECTION_BIT 4
|
||||
|
||||
#define X_LIMIT_BIT 0
|
||||
#define Y_LIMIT_BIT 1
|
||||
|
|
2
main.c
2
main.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) 2018-2019 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
|
||||
|
|
Ładowanie…
Reference in New Issue