|
|
@ -429,7 +429,7 @@ void enquecommand(const char *cmd)
|
|
|
|
//this is dangerous if a mixing of serial and this happens
|
|
|
|
//this is dangerous if a mixing of serial and this happens
|
|
|
|
strcpy(&(cmdbuffer[bufindw][0]),cmd);
|
|
|
|
strcpy(&(cmdbuffer[bufindw][0]),cmd);
|
|
|
|
SERIAL_ECHO_START;
|
|
|
|
SERIAL_ECHO_START;
|
|
|
|
SERIAL_ECHOPGM("enqueing \"");
|
|
|
|
SERIAL_ECHOPGM(MSG_Enqueing);
|
|
|
|
SERIAL_ECHO(cmdbuffer[bufindw]);
|
|
|
|
SERIAL_ECHO(cmdbuffer[bufindw]);
|
|
|
|
SERIAL_ECHOLNPGM("\"");
|
|
|
|
SERIAL_ECHOLNPGM("\"");
|
|
|
|
bufindw= (bufindw + 1)%BUFSIZE;
|
|
|
|
bufindw= (bufindw + 1)%BUFSIZE;
|
|
|
@ -444,7 +444,7 @@ void enquecommand_P(const char *cmd)
|
|
|
|
//this is dangerous if a mixing of serial and this happens
|
|
|
|
//this is dangerous if a mixing of serial and this happens
|
|
|
|
strcpy_P(&(cmdbuffer[bufindw][0]),cmd);
|
|
|
|
strcpy_P(&(cmdbuffer[bufindw][0]),cmd);
|
|
|
|
SERIAL_ECHO_START;
|
|
|
|
SERIAL_ECHO_START;
|
|
|
|
SERIAL_ECHOPGM("enqueing \"");
|
|
|
|
SERIAL_ECHOPGM(MSG_Enqueing);
|
|
|
|
SERIAL_ECHO(cmdbuffer[bufindw]);
|
|
|
|
SERIAL_ECHO(cmdbuffer[bufindw]);
|
|
|
|
SERIAL_ECHOLNPGM("\"");
|
|
|
|
SERIAL_ECHOLNPGM("\"");
|
|
|
|
bufindw= (bufindw + 1)%BUFSIZE;
|
|
|
|
bufindw= (bufindw + 1)%BUFSIZE;
|
|
|
@ -1537,7 +1537,7 @@ void process_commands()
|
|
|
|
#ifdef SCARA
|
|
|
|
#ifdef SCARA
|
|
|
|
current_position[X_AXIS]=code_value();
|
|
|
|
current_position[X_AXIS]=code_value();
|
|
|
|
#else
|
|
|
|
#else
|
|
|
|
current_position[X_AXIS]=code_value()+add_homing[0];
|
|
|
|
current_position[X_AXIS]=code_value()+add_homing[X_AXIS];
|
|
|
|
#endif
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
@ -1547,7 +1547,7 @@ void process_commands()
|
|
|
|
#ifdef SCARA
|
|
|
|
#ifdef SCARA
|
|
|
|
current_position[Y_AXIS]=code_value();
|
|
|
|
current_position[Y_AXIS]=code_value();
|
|
|
|
#else
|
|
|
|
#else
|
|
|
|
current_position[Y_AXIS]=code_value()+add_homing[1];
|
|
|
|
current_position[Y_AXIS]=code_value()+add_homing[Y_AXIS];
|
|
|
|
#endif
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
@ -1612,7 +1612,7 @@ void process_commands()
|
|
|
|
|
|
|
|
|
|
|
|
if(code_seen(axis_codes[Z_AXIS])) {
|
|
|
|
if(code_seen(axis_codes[Z_AXIS])) {
|
|
|
|
if(code_value_long() != 0) {
|
|
|
|
if(code_value_long() != 0) {
|
|
|
|
current_position[Z_AXIS]=code_value()+add_homing[2];
|
|
|
|
current_position[Z_AXIS]=code_value()+add_homing[Z_AXIS];
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#ifdef ENABLE_AUTO_BED_LEVELING
|
|
|
|
#ifdef ENABLE_AUTO_BED_LEVELING
|
|
|
@ -2745,9 +2745,9 @@ Sigma_Exit:
|
|
|
|
SERIAL_PROTOCOLLN("");
|
|
|
|
SERIAL_PROTOCOLLN("");
|
|
|
|
|
|
|
|
|
|
|
|
SERIAL_PROTOCOLPGM("SCARA Cal - Theta:");
|
|
|
|
SERIAL_PROTOCOLPGM("SCARA Cal - Theta:");
|
|
|
|
SERIAL_PROTOCOL(delta[X_AXIS]+add_homing[0]);
|
|
|
|
SERIAL_PROTOCOL(delta[X_AXIS]+add_homing[X_AXIS]);
|
|
|
|
SERIAL_PROTOCOLPGM(" Psi+Theta (90):");
|
|
|
|
SERIAL_PROTOCOLPGM(" Psi+Theta (90):");
|
|
|
|
SERIAL_PROTOCOL(delta[Y_AXIS]-delta[X_AXIS]-90+add_homing[1]);
|
|
|
|
SERIAL_PROTOCOL(delta[Y_AXIS]-delta[X_AXIS]-90+add_homing[Y_AXIS]);
|
|
|
|
SERIAL_PROTOCOLLN("");
|
|
|
|
SERIAL_PROTOCOLLN("");
|
|
|
|
|
|
|
|
|
|
|
|
SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:");
|
|
|
|
SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:");
|
|
|
@ -2883,11 +2883,11 @@ Sigma_Exit:
|
|
|
|
#ifdef SCARA
|
|
|
|
#ifdef SCARA
|
|
|
|
if(code_seen('T')) // Theta
|
|
|
|
if(code_seen('T')) // Theta
|
|
|
|
{
|
|
|
|
{
|
|
|
|
add_homing[0] = code_value() ;
|
|
|
|
add_homing[X_AXIS] = code_value() ;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if(code_seen('P')) // Psi
|
|
|
|
if(code_seen('P')) // Psi
|
|
|
|
{
|
|
|
|
{
|
|
|
|
add_homing[1] = code_value() ;
|
|
|
|
add_homing[Y_AXIS] = code_value() ;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
break;
|
|
|
@ -3275,11 +3275,11 @@ Sigma_Exit:
|
|
|
|
//SERIAL_ECHOLN(" Soft endstops disabled ");
|
|
|
|
//SERIAL_ECHOLN(" Soft endstops disabled ");
|
|
|
|
if(Stopped == false) {
|
|
|
|
if(Stopped == false) {
|
|
|
|
//get_coordinates(); // For X Y Z E F
|
|
|
|
//get_coordinates(); // For X Y Z E F
|
|
|
|
delta[0] = 0;
|
|
|
|
delta[X_AXIS] = 0;
|
|
|
|
delta[1] = 120;
|
|
|
|
delta[Y_AXIS] = 120;
|
|
|
|
calculate_SCARA_forward_Transform(delta);
|
|
|
|
calculate_SCARA_forward_Transform(delta);
|
|
|
|
destination[0] = delta[0]/axis_scaling[X_AXIS];
|
|
|
|
destination[X_AXIS] = delta[X_AXIS]/axis_scaling[X_AXIS];
|
|
|
|
destination[1] = delta[1]/axis_scaling[Y_AXIS];
|
|
|
|
destination[Y_AXIS] = delta[Y_AXIS]/axis_scaling[Y_AXIS];
|
|
|
|
|
|
|
|
|
|
|
|
prepare_move();
|
|
|
|
prepare_move();
|
|
|
|
//ClearToSend();
|
|
|
|
//ClearToSend();
|
|
|
@ -3293,11 +3293,11 @@ Sigma_Exit:
|
|
|
|
//SERIAL_ECHOLN(" Soft endstops disabled ");
|
|
|
|
//SERIAL_ECHOLN(" Soft endstops disabled ");
|
|
|
|
if(Stopped == false) {
|
|
|
|
if(Stopped == false) {
|
|
|
|
//get_coordinates(); // For X Y Z E F
|
|
|
|
//get_coordinates(); // For X Y Z E F
|
|
|
|
delta[0] = 90;
|
|
|
|
delta[X_AXIS] = 90;
|
|
|
|
delta[1] = 130;
|
|
|
|
delta[Y_AXIS] = 130;
|
|
|
|
calculate_SCARA_forward_Transform(delta);
|
|
|
|
calculate_SCARA_forward_Transform(delta);
|
|
|
|
destination[0] = delta[0]/axis_scaling[X_AXIS];
|
|
|
|
destination[X_AXIS] = delta[X_AXIS]/axis_scaling[X_AXIS];
|
|
|
|
destination[1] = delta[1]/axis_scaling[Y_AXIS];
|
|
|
|
destination[Y_AXIS] = delta[Y_AXIS]/axis_scaling[Y_AXIS];
|
|
|
|
|
|
|
|
|
|
|
|
prepare_move();
|
|
|
|
prepare_move();
|
|
|
|
//ClearToSend();
|
|
|
|
//ClearToSend();
|
|
|
@ -3310,11 +3310,11 @@ Sigma_Exit:
|
|
|
|
//SERIAL_ECHOLN(" Soft endstops disabled ");
|
|
|
|
//SERIAL_ECHOLN(" Soft endstops disabled ");
|
|
|
|
if(Stopped == false) {
|
|
|
|
if(Stopped == false) {
|
|
|
|
//get_coordinates(); // For X Y Z E F
|
|
|
|
//get_coordinates(); // For X Y Z E F
|
|
|
|
delta[0] = 60;
|
|
|
|
delta[X_AXIS] = 60;
|
|
|
|
delta[1] = 180;
|
|
|
|
delta[Y_AXIS] = 180;
|
|
|
|
calculate_SCARA_forward_Transform(delta);
|
|
|
|
calculate_SCARA_forward_Transform(delta);
|
|
|
|
destination[0] = delta[0]/axis_scaling[X_AXIS];
|
|
|
|
destination[X_AXIS] = delta[X_AXIS]/axis_scaling[X_AXIS];
|
|
|
|
destination[1] = delta[1]/axis_scaling[Y_AXIS];
|
|
|
|
destination[Y_AXIS] = delta[Y_AXIS]/axis_scaling[Y_AXIS];
|
|
|
|
|
|
|
|
|
|
|
|
prepare_move();
|
|
|
|
prepare_move();
|
|
|
|
//ClearToSend();
|
|
|
|
//ClearToSend();
|
|
|
@ -3327,11 +3327,11 @@ Sigma_Exit:
|
|
|
|
//SERIAL_ECHOLN(" Soft endstops disabled ");
|
|
|
|
//SERIAL_ECHOLN(" Soft endstops disabled ");
|
|
|
|
if(Stopped == false) {
|
|
|
|
if(Stopped == false) {
|
|
|
|
//get_coordinates(); // For X Y Z E F
|
|
|
|
//get_coordinates(); // For X Y Z E F
|
|
|
|
delta[0] = 50;
|
|
|
|
delta[X_AXIS] = 50;
|
|
|
|
delta[1] = 90;
|
|
|
|
delta[Y_AXIS] = 90;
|
|
|
|
calculate_SCARA_forward_Transform(delta);
|
|
|
|
calculate_SCARA_forward_Transform(delta);
|
|
|
|
destination[0] = delta[0]/axis_scaling[X_AXIS];
|
|
|
|
destination[X_AXIS] = delta[X_AXIS]/axis_scaling[X_AXIS];
|
|
|
|
destination[1] = delta[1]/axis_scaling[Y_AXIS];
|
|
|
|
destination[Y_AXIS] = delta[Y_AXIS]/axis_scaling[Y_AXIS];
|
|
|
|
|
|
|
|
|
|
|
|
prepare_move();
|
|
|
|
prepare_move();
|
|
|
|
//ClearToSend();
|
|
|
|
//ClearToSend();
|
|
|
@ -3344,11 +3344,11 @@ Sigma_Exit:
|
|
|
|
//SERIAL_ECHOLN(" Soft endstops disabled ");
|
|
|
|
//SERIAL_ECHOLN(" Soft endstops disabled ");
|
|
|
|
if(Stopped == false) {
|
|
|
|
if(Stopped == false) {
|
|
|
|
//get_coordinates(); // For X Y Z E F
|
|
|
|
//get_coordinates(); // For X Y Z E F
|
|
|
|
delta[0] = 45;
|
|
|
|
delta[X_AXIS] = 45;
|
|
|
|
delta[1] = 135;
|
|
|
|
delta[Y_AXIS] = 135;
|
|
|
|
calculate_SCARA_forward_Transform(delta);
|
|
|
|
calculate_SCARA_forward_Transform(delta);
|
|
|
|
destination[0] = delta[0]/axis_scaling[X_AXIS];
|
|
|
|
destination[X_AXIS] = delta[X_AXIS]/axis_scaling[X_AXIS];
|
|
|
|
destination[1] = delta[1]/axis_scaling[Y_AXIS];
|
|
|
|
destination[Y_AXIS] = delta[Y_AXIS]/axis_scaling[Y_AXIS];
|
|
|
|
|
|
|
|
|
|
|
|
prepare_move();
|
|
|
|
prepare_move();
|
|
|
|
//ClearToSend();
|
|
|
|
//ClearToSend();
|
|
|
@ -4020,9 +4020,9 @@ for (int s = 1; s <= steps; s++) {
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
calculate_delta(destination);
|
|
|
|
calculate_delta(destination);
|
|
|
|
//SERIAL_ECHOPGM("destination[0]="); SERIAL_ECHOLN(destination[0]);
|
|
|
|
//SERIAL_ECHOPGM("destination[X_AXIS]="); SERIAL_ECHOLN(destination[X_AXIS]);
|
|
|
|
//SERIAL_ECHOPGM("destination[1]="); SERIAL_ECHOLN(destination[1]);
|
|
|
|
//SERIAL_ECHOPGM("destination[Y_AXIS]="); SERIAL_ECHOLN(destination[Y_AXIS]);
|
|
|
|
//SERIAL_ECHOPGM("destination[2]="); SERIAL_ECHOLN(destination[2]);
|
|
|
|
//SERIAL_ECHOPGM("destination[Z_AXIS]="); SERIAL_ECHOLN(destination[Z_AXIS]);
|
|
|
|
//SERIAL_ECHOPGM("delta[X_AXIS]="); SERIAL_ECHOLN(delta[X_AXIS]);
|
|
|
|
//SERIAL_ECHOPGM("delta[X_AXIS]="); SERIAL_ECHOLN(delta[X_AXIS]);
|
|
|
|
//SERIAL_ECHOPGM("delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]);
|
|
|
|
//SERIAL_ECHOPGM("delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]);
|
|
|
|
//SERIAL_ECHOPGM("delta[Z_AXIS]="); SERIAL_ECHOLN(delta[Z_AXIS]);
|
|
|
|
//SERIAL_ECHOPGM("delta[Z_AXIS]="); SERIAL_ECHOLN(delta[Z_AXIS]);
|
|
|
|