Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
  • Loading branch information
timschmidt committed May 15, 2015
1 parent 105851a commit 6276056
Show file tree
Hide file tree
Showing 12 changed files with 200 additions and 142 deletions.
2 changes: 1 addition & 1 deletion Marlin/Base64.cpp
Expand Up @@ -47,7 +47,7 @@ int base64_encode(char *output, char *input, int inputLen) {
return encLen;
}

int base64_decode(char * output, char * input, int inputLen) {
int base64_decode(unsigned char * output, char * input, int inputLen) {
int i = 0, j = 0;
int decLen = 0;
unsigned char a3[3];
Expand Down
2 changes: 1 addition & 1 deletion Marlin/Base64.h
Expand Up @@ -44,7 +44,7 @@ int base64_encode(char *output, char *input, int inputLen);
* 2. input must not be null
* 3. inputLen must be greater than or equal to 0
*/
int base64_decode(char *output, char *input, int inputLen);
int base64_decode(unsigned char *output, char *input, int inputLen);

/* base64_enc_len:
* Description:
Expand Down
19 changes: 15 additions & 4 deletions Marlin/Configuration.h
Expand Up @@ -91,8 +91,8 @@
//// Raster mode enables the laser to etch bitmap data at high speeds. Increases command buffer size substantially.
#define LASER_RASTER
#define LASER_MAX_RASTER_LINE 68 // maximum number of base64 encoded pixels per raster gcode command
#define LASER_RASTER_ASPECT_RATIO 1.33 // pixels aren't square on most displays, 1.33 == 4:3 aspect ratio
#define LASER_RASTER_MM_PER_PULSE 0.2
#define LASER_RASTER_ASPECT_RATIO 1 // pixels aren't square on most displays, 1.33 == 4:3 aspect ratio
#define LASER_RASTER_MM_PER_PULSE 0.2 //Can be overridden by providing an R value in M649 command : M649 S17 B2 D0 R0.1 F4000

//// Uncomment the following if the laser cutter is equipped with a peripheral relay board
//// to control power to an exhaust fan, water pump, laser power supply, etc.
Expand Down Expand Up @@ -145,6 +145,9 @@
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan) (1k pullup)


// changes made in ULTRA_LCD_IMPLEMENTATION_HITACHI_HD44780.H line 473 to allow temperature display
// instead of Z position, set to 1 for temperature, 0 for no temperature.
#define TEMP_SENSOR_0 0
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
Expand Down Expand Up @@ -350,6 +353,14 @@ const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define Z_MAX_POS 95
#define Z_MIN_POS 0

// China Town K40 CO2 Laser Engraver/Cutter
//#define X_MAX_POS 337
//#define X_MIN_POS 0
//#define Y_MAX_POS 230
//#define Y_MIN_POS 0
//#define Z_MAX_POS 75
//#define Z_MIN_POS 0

#define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
Expand All @@ -367,7 +378,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o

//// MOVEMENT SETTINGS
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
#define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0} // set the homing speeds (mm/min)
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)

// default settings

Expand All @@ -380,7 +391,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o

// Lansing Makers Netowork Laser Cutter
#define DEFAULT_AXIS_STEPS_PER_UNIT {157.4802,157.4802,6047.2440} // default steps per unit for Ultimaker
#define DEFAULT_MAX_FEEDRATE {500, 500, 10, 25} // (mm/sec)
#define DEFAULT_MAX_FEEDRATE {3000, 3000, 10, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {2600,2600,2.5,2.5} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.

#define DEFAULT_ACCELERATION 2000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
Expand Down
68 changes: 62 additions & 6 deletions Marlin/Marlin_main.cpp
Expand Up @@ -526,7 +526,14 @@ void get_command()
if(!comment_mode){
comment_mode = false; //for new command
fromsd[bufindw] = false;
if(strchr(cmdbuffer[bufindw], 'N') != NULL)

//Turnkey - Changed <=6 to <=8 to allow up to 999999 lines of raster data to be transmitted per raster node
//This area needs improving for stability.
if( (strstr_P(cmdbuffer[bufindw], PSTR("G7")) == NULL && strchr(cmdbuffer[bufindw], 'N') != NULL) || //For non G7 commands, run as normal.
((strstr_P(cmdbuffer[bufindw], PSTR("G7")) != NULL) &&
((strstr_P(cmdbuffer[bufindw], PSTR("G7")) - strchr(cmdbuffer[bufindw], 'N') <=8 ) &&
(strstr_P(cmdbuffer[bufindw], PSTR("G7")) - strchr(cmdbuffer[bufindw], 'N') >0 )))
)
{
strchr_pointer = strchr(cmdbuffer[bufindw], 'N');
gcode_N = (strtol(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL, 10));
Expand Down Expand Up @@ -907,13 +914,47 @@ void process_commands()
case 2: // G2 - CW ARC
if(Stopped == false) {
get_arc_coordinates();

#ifdef LASER_FIRE_G1
if (code_seen('S') && !IsStopped()) laser.intensity = (float) code_value();
if (code_seen('L') && !IsStopped()) laser.duration = (unsigned long) labs(code_value());
if (code_seen('P') && !IsStopped()) laser.ppm = (float) code_value();
if (code_seen('D') && !IsStopped()) laser.diagnostics = (bool) code_value();
if (code_seen('B') && !IsStopped()) laser_set_mode((int) code_value());

laser.status = LASER_ON;
laser.fired = LASER_FIRE_G1;
#endif // LASER_FIRE_G1

prepare_arc_move(true);

#ifdef LASER_FIRE_G1
laser.status = LASER_OFF;
#endif // LASER_FIRE_G1

return;
}
case 3: // G3 - CCW ARC
if(Stopped == false) {
get_arc_coordinates();

#ifdef LASER_FIRE_G1
if (code_seen('S') && !IsStopped()) laser.intensity = (float) code_value();
if (code_seen('L') && !IsStopped()) laser.duration = (unsigned long) labs(code_value());
if (code_seen('P') && !IsStopped()) laser.ppm = (float) code_value();
if (code_seen('D') && !IsStopped()) laser.diagnostics = (bool) code_value();
if (code_seen('B') && !IsStopped()) laser_set_mode((int) code_value());

laser.status = LASER_ON;
laser.fired = LASER_FIRE_G1;
#endif // LASER_FIRE_G1

prepare_arc_move(false);

#ifdef LASER_FIRE_G1
laser.status = LASER_OFF;
#endif // LASER_FIRE_G1

return;
}
case 4: // G4 dwell
Expand Down Expand Up @@ -1035,7 +1076,7 @@ void process_commands()
#ifdef LASER_RASTER
case 7: //G7 Execute raster line
if (code_seen('L')) laser.raster_raw_length = int(code_value());
if (code_seen('N')) {
if (code_seen('$')) {
laser.raster_direction = (bool)code_value();
destination[Y_AXIS] = current_position[Y_AXIS] + (laser.raster_mm_per_pulse * laser.raster_aspect_ratio); // increment Y axis
}
Expand All @@ -1053,8 +1094,10 @@ void process_commands()
SERIAL_ECHOLN("Positive Raster Line");
}
}
laser.ppm = 1 / laser.raster_mm_per_pulse;
laser.duration = labs(1 / (feedrate * laser.ppm) * 1000000);

laser.ppm = 1 / laser.raster_mm_per_pulse; //number of pulses per millimetre
laser.duration = (1000000 / ( feedrate / 60)) / laser.ppm; // (1 second in microseconds / (time to move 1mm in microseconds)) / (pulses per mm) = Duration of pulse, taking into account feedrate as speed and ppm

laser.mode = RASTER;
laser.status = LASER_ON;
laser.fired = RASTER;
Expand All @@ -1078,7 +1121,7 @@ void process_commands()
}

break;
case 11: // G10 retract_recover
case 11: // G11 retract_recover
if(!retracted)
{
destination[X_AXIS]=current_position[X_AXIS];
Expand Down Expand Up @@ -1319,10 +1362,14 @@ void process_commands()

laser.status = LASER_ON;
laser.fired = LASER_FIRE_SPINDLE;
//*=*=*=*=*=*
lcd_update();

prepare_move();
break;
case 5: //M5 stop firing laser
laser.status = LASER_OFF;
lcd_update();
prepare_move();
break;
#endif // LASER_FIRE_SPINDLE
Expand Down Expand Up @@ -2381,11 +2428,20 @@ void process_commands()
#ifdef LASER
case 649: // M649 set laser options
{
if (code_seen('S') && !IsStopped()) laser.intensity = (float) code_value();
if (code_seen('S') && !IsStopped()) {
laser.intensity = (float) code_value();
laser.rasterlaserpower = laser.intensity;
}
if (code_seen('L') && !IsStopped()) laser.duration = (unsigned long) labs(code_value());
if (code_seen('P') && !IsStopped()) laser.ppm = (float) code_value();
if (code_seen('D') && !IsStopped()) laser.diagnostics = (bool) code_value();
if (code_seen('B') && !IsStopped()) laser_set_mode((int) code_value());
if (code_seen('R') && !IsStopped()) laser.raster_mm_per_pulse = ((float) code_value());
if (code_seen('F')) {
next_feedrate = code_value();
if(next_feedrate > 0.0) feedrate = next_feedrate;
}

}
break;
#endif // LASER
Expand Down
23 changes: 12 additions & 11 deletions Marlin/laser.cpp
Expand Up @@ -76,11 +76,11 @@ void laser_init()
#endif

#ifdef LASER_PERIPHERALS
digitalWrite(LASER_PERIPHERALS_PIN, HIGH); // Laser peripherals are active LOW, so preset the pin
pinMode(LASER_PERIPHERALS_PIN, OUTPUT);
digitalWrite(LASER_PERIPHERALS_PIN, HIGH); // Laser peripherals are active LOW, so preset the pin
pinMode(LASER_PERIPHERALS_PIN, OUTPUT);

digitalWrite(LASER_PERIPHERALS_STATUS_PIN, HIGH); // Set the peripherals status pin to pull-up.
pinMode(LASER_PERIPHERALS_STATUS_PIN, INPUT);
digitalWrite(LASER_PERIPHERALS_STATUS_PIN, HIGH); // Set the peripherals status pin to pull-up.
pinMode(LASER_PERIPHERALS_STATUS_PIN, INPUT);
#endif // LASER_PERIPHERALS

// initialize state to some sane defaults
Expand All @@ -107,22 +107,23 @@ void laser_init()
laser_extinguish();
}
void laser_fire(int intensity = 100.0){
laser.firing = LASER_ON;
laser.last_firing = micros(); // microseconds of last laser firing
if (intensity > 100.0) intensity = 100.0; // restrict intensity between 0 and 100
if (intensity < 0) intensity = 0;
laser.firing = LASER_ON;
laser.last_firing = micros(); // microseconds of last laser firing
if (intensity > 100.0) intensity = 100.0; // restrict intensity between 0 and 100
if (intensity < 0) intensity = 0;

#if LASER_CONTROL == 1
pinMode(LASER_FIRING_PIN, OUTPUT);
#if LASER_CONTROL == 1
analogWrite(LASER_FIRING_PIN, labs((intensity / 100.0)*(F_CPU / LASER_PWM)));
#endif
#if LASER_CONTROL == 2
#if LASER_CONTROL == 2
analogWrite(LASER_INTENSITY_PIN, labs((intensity / 100.0)*(F_CPU / LASER_PWM)));
digitalWrite(LASER_FIRING_PIN, HIGH);
#endif

if (laser.diagnostics) {
SERIAL_ECHOLN("Laser fired");
}
}
}
void laser_extinguish(){
if (laser.firing == LASER_ON) {
Expand Down
4 changes: 3 additions & 1 deletion Marlin/laser.h
Expand Up @@ -38,7 +38,9 @@ typedef struct {
unsigned int time; // temporary counter to limit eeprom writes
unsigned int lifetime; // laser lifetime firing counter in minutes
#ifdef LASER_RASTER
char raster_data[LASER_MAX_RASTER_LINE];
unsigned char raster_data[LASER_MAX_RASTER_LINE];
unsigned char rasterlaserpower;

float raster_aspect_ratio;
float raster_mm_per_pulse;
int raster_raw_length;
Expand Down
27 changes: 21 additions & 6 deletions Marlin/planner.cpp
Expand Up @@ -687,13 +687,28 @@ block->steps_y = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-positi
// When operating in PULSED or RASTER modes, laser pulsing must operate in sync with movement.
// Calculate steps between laser firings (steps_l) and consider that when determining largest
// interval between steps for X, Y, Z, E, L to feed to the motion control code.
if (laser.mode == PULSED or laser.mode == RASTER) {
block->steps_l = labs(block->millimeters*laser.ppm);
for (int i = 0; i < LASER_MAX_RASTER_LINE; i++) {
block->laser_raster_data[i] = laser.raster_data[i];
}
if (laser.mode == RASTER || laser.mode == PULSED) {
block->steps_l = labs(block->millimeters*laser.ppm);
for (int i = 0; i < LASER_MAX_RASTER_LINE; i++) {

//Scale the image intensity based on the raster power.
//100% power on a pixel basis is 255, convert back to 255 = 100.

//http://stackoverflow.com/questions/929103/convert-a-number-range-to-another-range-maintaining-ratio
int OldRange, NewRange;
float NewValue;
OldRange = (255 - 0);
NewRange = (laser.rasterlaserpower - 7); //7% power on my unit outputs hardly any noticable burn at F3000 on paper, so adjust the raster contrast based off 7 being the lower. 7 still produces burns at slower feed rates, but getting less power than this isn't typically needed at slow feed rates.
NewValue = (float)(((((float)laser.raster_data[i] - 0) * NewRange) / OldRange) + 7);

//If less than 7%, turn off the laser tube.
if(NewValue == 7)
NewValue = 0;

block->laser_raster_data[i] = NewValue;
}
} else {
block->steps_l = 0;
block->steps_l = 0;
}
block->step_event_count = max(block->steps_x, max(block->steps_y, max(block->steps_z, max(block->steps_e, block->steps_l))));

Expand Down
2 changes: 1 addition & 1 deletion Marlin/planner.h
Expand Up @@ -76,7 +76,7 @@ typedef struct {
long steps_l; // step count between firings of the laser, for pulsed firing mode
int laser_intensity; // Laser firing instensity in clock cycles for the PWM timer
#ifdef LASER_RASTER
char laser_raster_data[LASER_MAX_RASTER_LINE];
unsigned char laser_raster_data[LASER_MAX_RASTER_LINE];
#endif // LASER_RASTER
#endif // LASER
volatile char busy;
Expand Down
2 changes: 1 addition & 1 deletion Marlin/stepper.cpp
Expand Up @@ -670,7 +670,7 @@ ISR(TIMER1_COMPA_vect)
}
#ifdef LASER_RASTER
if (current_block->laser_mode == RASTER && current_block->laser_status == LASER_ON) { // Raster Firing Mode
laser_fire((float)current_block->laser_raster_data[counter_raster]/255.0*100.0);
laser_fire(current_block->laser_raster_data[counter_raster]); //For some reason, when comparing raster power to ppm line burns the rasters were around 2% more powerful - going from darkened paper to burning through paper.
if (laser.diagnostics) {
SERIAL_ECHOPAIR("Pixel: ", (float)current_block->laser_raster_data[counter_raster]);
}
Expand Down
13 changes: 13 additions & 0 deletions Marlin/ultralcd_implementation_hitachi_HD44780.h
Expand Up @@ -371,6 +371,8 @@ static void lcd_implementation_status_screen()
lcd.setCursor(0, 0);
lcd.print("Laser Power: ");
lcd.print(itostr3(int(laser.intensity)));
lcd.print(itostr3(int(laser.status)));

#else
int tHotend=int(degHotend(0) + 0.5);
int tTarget=int(degTargetHotend(0) + 0.5);
Expand Down Expand Up @@ -463,9 +465,20 @@ static void lcd_implementation_status_screen()
lcd.print(ftostr3(current_position[Y_AXIS]));
# endif//EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
# endif//LCD_WIDTH > 19

//******************************************************=*=*=*=*=*
// If temperature sensor 0 is sset then water displayed, if not Z displayed
lcd.setCursor(LCD_WIDTH - 8, 1);
#if TEMP_SENSOR_0 > 0
lcd.print('T');
lcd.setCursor(LCD_WIDTH - 7, 1);
lcd.print('=');
lcd.print(ftostr32(current_temperature[0]));
#else
lcd.print('Z');
lcd.print(ftostr32(current_position[Z_AXIS]));
#endif

#endif//LCD_HEIGHT > 2

#if LCD_HEIGHT > 3
Expand Down

0 comments on commit 6276056

Please sign in to comment.