Merge branch 'master-corexy'
This commit is contained in:
@@ -72,8 +72,8 @@
|
|||||||
// on separate pin, but homed in one cycle. Also, it should be noted that the function of hard limits
|
// 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.
|
// 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.
|
// 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_0 (1<<X_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_1 (1<<Y_AXIS) // OPTIONAL: Then move X,Y at the same time.
|
||||||
// #define HOMING_CYCLE_2 // OPTIONAL: Uncomment and add axes mask to enable
|
// #define HOMING_CYCLE_2 // OPTIONAL: Uncomment and add axes mask to enable
|
||||||
|
|
||||||
// Number of homing cycles performed after when the machine initially jogs to limit switches.
|
// Number of homing cycles performed after when the machine initially jogs to limit switches.
|
||||||
@@ -149,7 +149,7 @@
|
|||||||
// defined at (http://corexy.com/theory.html). Motors are assumed to positioned and wired exactly as
|
// defined at (http://corexy.com/theory.html). Motors are assumed to positioned and wired exactly as
|
||||||
// described, if not, motions may move in strange directions. Grbl assumes the CoreXY A and B motors
|
// described, if not, motions may move in strange directions. Grbl assumes the CoreXY A and B motors
|
||||||
// have the same steps per mm internally.
|
// have the same steps per mm internally.
|
||||||
// #define COREXY // Default disabled. Uncomment to enable.
|
#define COREXY // Default disabled. Uncomment to enable.
|
||||||
|
|
||||||
// Inverts pin logic of the control command pins. This essentially means when this option is enabled
|
// Inverts pin logic of the control command pins. This essentially means when this option is enabled
|
||||||
// you can use normally-closed switches, rather than the default normally-open switches.
|
// you can use normally-closed switches, rather than the default normally-open switches.
|
||||||
|
|||||||
@@ -184,7 +184,20 @@ void limits_go_home(uint8_t cycle_mask)
|
|||||||
// Set target location for active axes and setup computation for homing rate.
|
// Set target location for active axes and setup computation for homing rate.
|
||||||
if (bit_istrue(cycle_mask,bit(idx))) {
|
if (bit_istrue(cycle_mask,bit(idx))) {
|
||||||
n_active_axis++;
|
n_active_axis++;
|
||||||
sys.position[idx] = 0;
|
#ifdef COREXY
|
||||||
|
if (idx == X_AXIS) {
|
||||||
|
int32_t axis_position = system_convert_corexy_to_y_axis_steps(sys.position);
|
||||||
|
sys.position[A_MOTOR] = axis_position;
|
||||||
|
sys.position[B_MOTOR] = -axis_position;
|
||||||
|
} else if (idx == Y_AXIS) {
|
||||||
|
int32_t axis_position = system_convert_corexy_to_x_axis_steps(sys.position);
|
||||||
|
sys.position[A_MOTOR] = sys.position[B_MOTOR] = axis_position;
|
||||||
|
} else {
|
||||||
|
sys.position[Z_AXIS] = 0;
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
sys.position[idx] = 0;
|
||||||
|
#endif
|
||||||
// Set target direction based on cycle mask and homing cycle approach state.
|
// Set target direction based on cycle mask and homing cycle approach state.
|
||||||
// NOTE: This happens to compile smaller than any other implementation tried.
|
// NOTE: This happens to compile smaller than any other implementation tried.
|
||||||
if (bit_istrue(settings.homing_dir_mask,bit(idx))) {
|
if (bit_istrue(settings.homing_dir_mask,bit(idx))) {
|
||||||
@@ -219,7 +232,14 @@ void limits_go_home(uint8_t cycle_mask)
|
|||||||
limit_state = limits_get_state();
|
limit_state = limits_get_state();
|
||||||
for (idx=0; idx<N_AXIS; idx++) {
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
if (axislock & step_pin[idx]) {
|
if (axislock & step_pin[idx]) {
|
||||||
if (limit_state & (1 << idx)) { axislock &= ~(step_pin[idx]); }
|
if (limit_state & (1 << idx)) {
|
||||||
|
#ifdef COREXY
|
||||||
|
if (idx==Z_AXIS) { axislock &= ~(step_pin[Z_AXIS]); }
|
||||||
|
else { axislock &= ~(step_pin[A_MOTOR]|step_pin[B_MOTOR]); }
|
||||||
|
#else
|
||||||
|
axislock &= ~(step_pin[idx]);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
sys.homing_axis_lock = axislock;
|
sys.homing_axis_lock = axislock;
|
||||||
@@ -270,9 +290,6 @@ void limits_go_home(uint8_t cycle_mask)
|
|||||||
// set up pull-off maneuver from axes limit switches that have been homed. This provides
|
// 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
|
// 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.
|
// triggering when hard limits are enabled or when more than one axes shares a limit pin.
|
||||||
#ifdef COREXY
|
|
||||||
int32_t off_axis_position = 0;
|
|
||||||
#endif
|
|
||||||
int32_t set_axis_position;
|
int32_t set_axis_position;
|
||||||
// Set machine positions for homed limit switches. Don't update non-homed axes.
|
// Set machine positions for homed limit switches. Don't update non-homed axes.
|
||||||
for (idx=0; idx<N_AXIS; idx++) {
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
@@ -290,13 +307,13 @@ void limits_go_home(uint8_t cycle_mask)
|
|||||||
|
|
||||||
#ifdef COREXY
|
#ifdef COREXY
|
||||||
if (idx==X_AXIS) {
|
if (idx==X_AXIS) {
|
||||||
off_axis_position = (sys.position[B_MOTOR] - sys.position[A_MOTOR])/2;
|
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[A_MOTOR] = set_axis_position + off_axis_position;
|
||||||
sys.position[B_MOTOR] = set_axis_position + off_axis_position;
|
sys.position[B_MOTOR] = set_axis_position - off_axis_position;
|
||||||
} else if (idx==Y_AXIS) {
|
} else if (idx==Y_AXIS) {
|
||||||
off_axis_position = (sys.position[A_MOTOR] + sys.position[B_MOTOR])/2;
|
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[A_MOTOR] = off_axis_position + set_axis_position;
|
||||||
sys.position[B_MOTOR] = off_axis_position + set_axis_position;
|
sys.position[B_MOTOR] = off_axis_position - set_axis_position;
|
||||||
} else {
|
} else {
|
||||||
sys.position[idx] = set_axis_position;
|
sys.position[idx] = set_axis_position;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -292,9 +292,9 @@ uint8_t plan_check_full_buffer()
|
|||||||
}
|
}
|
||||||
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) {
|
if (idx == A_MOTOR) {
|
||||||
delta_mm = ((target_steps[X_AXIS]-pl.position[X_AXIS]) + (target_steps[Y_AXIS]-pl.position[Y_AXIS]))/settings.steps_per_mm[idx];
|
delta_mm = (target_steps[X_AXIS]-pl.position[X_AXIS] + target_steps[Y_AXIS]-pl.position[Y_AXIS])/settings.steps_per_mm[idx];
|
||||||
} else if (idx == B_MOTOR) {
|
} else if (idx == B_MOTOR) {
|
||||||
delta_mm = ((target_steps[X_AXIS]-pl.position[X_AXIS]) - (target_steps[Y_AXIS]-pl.position[Y_AXIS]))/settings.steps_per_mm[idx];
|
delta_mm = (target_steps[X_AXIS]-pl.position[X_AXIS] - target_steps[Y_AXIS]+pl.position[Y_AXIS])/settings.steps_per_mm[idx];
|
||||||
} else {
|
} else {
|
||||||
delta_mm = (target_steps[idx] - pl.position[idx])/settings.steps_per_mm[idx];
|
delta_mm = (target_steps[idx] - pl.position[idx])/settings.steps_per_mm[idx];
|
||||||
}
|
}
|
||||||
@@ -424,10 +424,10 @@ void plan_sync_position()
|
|||||||
uint8_t idx;
|
uint8_t idx;
|
||||||
for (idx=0; idx<N_AXIS; idx++) {
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
#ifdef COREXY
|
#ifdef COREXY
|
||||||
if (idx==A_MOTOR) {
|
if (idx==X_AXIS) {
|
||||||
pl.position[idx] = (sys.position[A_MOTOR] + sys.position[B_MOTOR])/2;
|
pl.position[X_AXIS] = system_convert_corexy_to_x_axis_steps(sys.position);
|
||||||
} else if (idx==B_MOTOR) {
|
} else if (idx==Y_AXIS) {
|
||||||
pl.position[idx] = (sys.position[A_MOTOR] - sys.position[B_MOTOR])/2;
|
pl.position[Y_AXIS] = system_convert_corexy_to_y_axis_steps(sys.position);
|
||||||
} else {
|
} else {
|
||||||
pl.position[idx] = sys.position[idx];
|
pl.position[idx] = sys.position[idx];
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -264,10 +264,10 @@ float system_convert_axis_steps_to_mpos(int32_t *steps, uint8_t idx)
|
|||||||
{
|
{
|
||||||
float pos;
|
float pos;
|
||||||
#ifdef COREXY
|
#ifdef COREXY
|
||||||
if (idx==A_MOTOR) {
|
if (idx==X_AXIS) {
|
||||||
pos = 0.5*((steps[A_MOTOR] + steps[B_MOTOR])/settings.steps_per_mm[idx]);
|
pos = (float)system_convert_corexy_to_x_axis_steps(steps) / settings.steps_per_mm[idx];
|
||||||
} else if (idx==B_MOTOR) {
|
} else if (idx==Y_AXIS) {
|
||||||
pos = 0.5*((steps[A_MOTOR] - steps[B_MOTOR])/settings.steps_per_mm[idx]);
|
pos = (float)system_convert_corexy_to_y_axis_steps(steps) / settings.steps_per_mm[idx];
|
||||||
} else {
|
} else {
|
||||||
pos = steps[idx]/settings.steps_per_mm[idx];
|
pos = steps[idx]/settings.steps_per_mm[idx];
|
||||||
}
|
}
|
||||||
@@ -286,3 +286,15 @@ void system_convert_array_steps_to_mpos(float *position, int32_t *steps)
|
|||||||
}
|
}
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// CoreXY calculation only. Returns x or y-axis "steps" based on CoreXY motor steps.
|
||||||
|
int32_t system_convert_corexy_to_x_axis_steps(int32_t *steps)
|
||||||
|
{
|
||||||
|
return( (steps[A_MOTOR] + steps[B_MOTOR])/2 );
|
||||||
|
}
|
||||||
|
int32_t system_convert_corexy_to_y_axis_steps(int32_t *steps)
|
||||||
|
{
|
||||||
|
return( (steps[A_MOTOR] - steps[B_MOTOR])/2 );
|
||||||
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -106,4 +106,8 @@ float system_convert_axis_steps_to_mpos(int32_t *steps, uint8_t idx);
|
|||||||
// Updates a machine 'position' array based on the 'step' array sent.
|
// Updates a machine 'position' array based on the 'step' array sent.
|
||||||
void system_convert_array_steps_to_mpos(float *position, int32_t *steps);
|
void system_convert_array_steps_to_mpos(float *position, int32_t *steps);
|
||||||
|
|
||||||
|
// CoreXY calculation only. Returns x or y-axis "steps" based on CoreXY motor steps.
|
||||||
|
int32_t system_convert_corexy_to_x_axis_steps(int32_t *steps);
|
||||||
|
int32_t system_convert_corexy_to_y_axis_steps(int32_t *steps);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
Reference in New Issue
Block a user