First port of the LASER support

parent 0e1c4b38
...@@ -1265,6 +1265,19 @@ ...@@ -1265,6 +1265,19 @@
/**************************************************************************/ /**************************************************************************/
/**************************************************************************
******************************* Laser **** *******************************
**************************************************************************
* *
* Support for laser beam *
* Check also Configuration_Laser.h *
* *
**************************************************************************/
//#define LASER
/**************************************************************************/
//=========================================================================== //===========================================================================
//========================= ADVANCED MOTION FEATURES ======================== //========================= ADVANCED MOTION FEATURES ========================
//=========================================================================== //===========================================================================
......
#ifndef CONFIGURATION_LASER
#define CONFIGURATION_LASER
//===========================================================================
//============================= Laser Settings ==============================
//===========================================================================
//
// Laser control is used by the Muve1 3D printer and the Buildlog.net laser cutter
//
//// The following define selects how to control the laser. Please choose the one that matches your setup.
// 1 = Single pin control - LOW when off, HIGH when on, PWM to adjust intensity
// 2 = Two pin control - A firing pin for which LOW = off, HIGH = on, and a seperate intensity pin which carries a constant PWM signal and adjusts duty cycle to control intensity
// mUVe, buildlog.net and K40 chinese machines uses 2, AMRI ablative uses 1, AMRI SLS uses 2
#define LASER_CONTROL 2
// Uncomment the following if your laser firing pin (not the PWM pin) for two pin control requires a HIGH signal to fire rather than a low (eg Red Sail M300 RS 3040)
/// #define HIGH_TO_FIRE
// Uncomment the following to enable the use of the PWM (the one for the extruder 0) to drive a peltier cell or any PWM driven cooler for the laser
#define LASER_WATER_COOLING
//// The following defines select which G codes tell the laser to fire. It's OK to uncomment more than one.
#define LASER_FIRE_G1 10 // fire the laser on a G1 move, extinguish when the move ends
#define LASER_FIRE_SPINDLE 11 // fire the laser on M3, extinguish on M5
#define LASER_FIRE_E 12 // fire the laser when the E axis moves
//// 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 // 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.
//#define LASER_PERIPHERALS
//#define LASER_PERIPHERALS_TIMEOUT 30000 // Number of milliseconds to wait for status signal from peripheral control board
//// Uncomment the following line to enable cubic bezier curve movement with the G5 code
// #define G5_BEZIER
// Uncomment these options for the mUVe 1 3D printer
// #define CUSTOM_MENDEL_NAME "mUVe1 Printer"
// #define LASER_WATTS 0.05
// #define LASER_DIAMETER 0.1 // milimeters
// #define LASER_PWM 8000 // hertz
// #define MUVE_Z_PEEL // The mUVe 1 uses a special peel maneuver between each layer, it requires independent control of each Z motor
// Uncomment these options for the Buildlog.net laser cutter, and other similar models
#define CUSTOM_MENDEL_NAME "Laser Cutter"
#define LASER_WATTS 40.0
#define LASER_DIAMETER 0.1 // milimeters
#define LASER_PWM 50000 // hertz
#define LASER_FOCAL_HEIGHT 74.50 // z axis position at which the laser is focused
//Uncomment for AMRI Ablative or SLS
//#define CUSTOM_MENDEL_NAME "Laser Cutter"
//#define LASER_WATTS 40.0
//#define LASER_DIAMETER 0.1 // milimeters
//#define LASER_PWM 25000 // hertz
//#define LASER_FOCAL_HEIGHT 74.50 // z axis position at which the laser is focused
#endif
...@@ -106,6 +106,24 @@ ...@@ -106,6 +106,24 @@
#define LASER_TTL_PIN -1 #define LASER_TTL_PIN -1
#endif #endif
#if ENABLED(LASER)
#if LASER_CONTROL == 1
#define LASER_FIRING_PIN 5
#endif
#if LASER_CONTROL == 2
#define LASER_INTENSITY_PIN 6 // Digital pins 2, 3, 5, 6, 7, 8 are attached to timers we can use
#define LASER_FIRING_PIN 5
#endif
#ifdef LASER_POWER_DOWN
#define LASER_POWER_PIN 9 // This is currently hard-coded to timer2 which services pins 9, 10
#endif // LASER_POWER_DOWN
#ifdef LASER_PERIPHERALS
#define LASER_PERIPHERALS_PIN 4
#define LASER_PERIPHERALS_STATUS_PIN 11
#endif // LASER_PERIPHERALS
#endif
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FILRUNOUT_PIN -1 #define FILRUNOUT_PIN -1
#endif #endif
......
...@@ -75,4 +75,12 @@ ...@@ -75,4 +75,12 @@
#include "module/mfrc522/MFRC522_serial.h" #include "module/mfrc522/MFRC522_serial.h"
#endif #endif
#if ENABLED(LASER)
#include "Configuration_Laser.h"
#if ENABLED(LASER_RASTER)
#include "module/base64/Base64.h"
#endif
#include "module/laser/laser.h"
#endif
#endif #endif
This diff is collapsed.
#include "Base64.h"
const char b64_alphabet[] = "ABCDEFGHIJKLMNOPQRSTUVWXYZ"
"abcdefghijklmnopqrstuvwxyz"
"0123456789+/";
/* 'Private' declarations */
inline void a3_to_a4(unsigned char * a4, unsigned char * a3);
inline void a4_to_a3(unsigned char * a3, unsigned char * a4);
inline unsigned char b64_lookup(char c);
int base64_encode(char *output, char *input, int inputLen) {
int i = 0, j = 0;
int encLen = 0;
unsigned char a3[3];
unsigned char a4[4];
while(inputLen--) {
a3[i++] = *(input++);
if(i == 3) {
a3_to_a4(a4, a3);
for(i = 0; i < 4; i++) {
output[encLen++] = b64_alphabet[a4[i]];
}
i = 0;
}
}
if(i) {
for(j = i; j < 3; j++) {
a3[j] = '\0';
}
a3_to_a4(a4, a3);
for(j = 0; j < i + 1; j++) {
output[encLen++] = b64_alphabet[a4[j]];
}
while((i++ < 3)) {
output[encLen++] = '=';
}
}
output[encLen] = '\0';
return encLen;
}
int base64_decode(unsigned char * output, char * input, int inputLen) {
int i = 0, j = 0;
int decLen = 0;
unsigned char a3[3];
unsigned char a4[4];
while (inputLen--) {
if(*input == '=') {
break;
}
a4[i++] = *(input++);
if (i == 4) {
for (i = 0; i <4; i++) {
a4[i] = b64_lookup(a4[i]);
}
a4_to_a3(a3,a4);
for (i = 0; i < 3; i++) {
output[decLen++] = a3[i];
}
i = 0;
}
}
if (i) {
for (j = i; j < 4; j++) {
a4[j] = '\0';
}
for (j = 0; j <4; j++) {
a4[j] = b64_lookup(a4[j]);
}
a4_to_a3(a3,a4);
for (j = 0; j < i - 1; j++) {
output[decLen++] = a3[j];
}
}
output[decLen] = '\0';
return decLen;
}
int base64_enc_len(int plainLen) {
int n = plainLen;
return (n + 2 - ((n + 2) % 3)) / 3 * 4;
}
int base64_dec_len(char * input, int inputLen) {
int i = 0;
int numEq = 0;
for(i = inputLen - 1; input[i] == '='; i--) {
numEq++;
}
return ((6 * inputLen) / 8) - numEq;
}
inline void a3_to_a4(unsigned char * a4, unsigned char * a3) {
a4[0] = (a3[0] & 0xfc) >> 2;
a4[1] = ((a3[0] & 0x03) << 4) + ((a3[1] & 0xf0) >> 4);
a4[2] = ((a3[1] & 0x0f) << 2) + ((a3[2] & 0xc0) >> 6);
a4[3] = (a3[2] & 0x3f);
}
inline void a4_to_a3(unsigned char * a3, unsigned char * a4) {
a3[0] = (a4[0] << 2) + ((a4[1] & 0x30) >> 4);
a3[1] = ((a4[1] & 0xf) << 4) + ((a4[2] & 0x3c) >> 2);
a3[2] = ((a4[2] & 0x3) << 6) + a4[3];
}
inline unsigned char b64_lookup(char c) {
if(c >='A' && c <='Z') return c - 'A';
if(c >='a' && c <='z') return c - 71;
if(c >='0' && c <='9') return c + 4;
if(c == '+') return 62;
if(c == '/') return 63;
return -1;
}
/*
* Copyright (c) 2013 Adam Rudd.
* See LICENSE for more information
*/
#ifndef _BASE64_H
#define _BASE64_H
/* b64_alphabet:
* Description: Base64 alphabet table, a mapping between integers
* and base64 digits
* Notes: This is an extern here but is defined in Base64.c
*/
extern const char b64_alphabet[];
/* base64_encode:
* Description:
* Encode a string of characters as base64
* Parameters:
* output: the output buffer for the encoding, stores the encoded string
* input: the input buffer for the encoding, stores the binary to be encoded
* inputLen: the length of the input buffer, in bytes
* Return value:
* Returns the length of the encoded string
* Requirements:
* 1. output must not be null or empty
* 2. input must not be null
* 3. inputLen must be greater than or equal to 0
*/
int base64_encode(char *output, char *input, int inputLen);
/* base64_decode:
* Description:
* Decode a base64 encoded string into bytes
* Parameters:
* output: the output buffer for the decoding,
* stores the decoded binary
* input: the input buffer for the decoding,
* stores the base64 string to be decoded
* inputLen: the length of the input buffer, in bytes
* Return value:
* Returns the length of the decoded string
* Requirements:
* 1. output must not be null or empty
* 2. input must not be null
* 3. inputLen must be greater than or equal to 0
*/
int base64_decode(unsigned char *output, char *input, int inputLen);
/* base64_enc_len:
* Description:
* Returns the length of a base64 encoded string whose decoded
* form is inputLen bytes long
* Parameters:
* inputLen: the length of the decoded string
* Return value:
* The length of a base64 encoded string whose decoded form
* is inputLen bytes long
* Requirements:
* None
*/
int base64_enc_len(int inputLen);
/* base64_dec_len:
* Description:
* Returns the length of the decoded form of a
* base64 encoded string
* Parameters:
* input: the base64 encoded string to be measured
* inputLen: the length of the base64 encoded string
* Return value:
* Returns the length of the decoded form of a
* base64 encoded string
* Requirements:
* 1. input must not be null
* 2. input must be greater than or equal to zero
*/
int base64_dec_len(char *input, int inputLen);
#endif // _BASE64_H
...@@ -74,6 +74,17 @@ ...@@ -74,6 +74,17 @@
#define KILL_PIN -1 // 80 with Smart Controller LCD #define KILL_PIN -1 // 80 with Smart Controller LCD
#define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing. #define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing.
#undef LASER_INTENSITY_PIN
#undef LASER_FIRING_PIN
#if LASER_CONTROL == 1
#define LASER_FIRING_PIN 5
#endif
#if LASER_CONTROL == 2
#define LASER_INTENSITY_PIN 5 // Digital pins 2, 3, 5, 6, 7, 8 are attached to timers we can use
#define LASER_FIRING_PIN 2
#endif
#if ENABLED(ULTRA_LCD) #if ENABLED(ULTRA_LCD)
#define KILL_PIN 80 #define KILL_PIN 80
#if ENABLED(NEWPANEL) #if ENABLED(NEWPANEL)
......
/*
laser.cpp - Laser control library for Arduino using 16 bit timers- Version 1
Copyright (c) 2013 Timothy Schmidt. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 3 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "laser.h"
#include "Configuration.h"
#include "ConfigurationStore.h"
#include "pins.h"
#include <avr/interrupt.h>
#include <Arduino.h>
#include "Marlin.h"
laser_t laser;
void timer3_init(int pin) {
pinMode(pin, OUTPUT);
analogWrite(pin, 1); // let Arduino setup do it's thing to the PWM pin
TCCR3B = 0x00; // stop Timer4 clock for register updates
TCCR3A = 0x82; // Clear OC3A on match, fast PWM mode, lower WGM3x=14
ICR3 = labs(F_CPU / LASER_PWM); // clock cycles per PWM pulse
OCR3A = labs(F_CPU / LASER_PWM) - 1; // ICR3 - 1 force immediate compare on next tick
TCCR3B = 0x18 | 0x01; // upper WGM4x = 14, clock sel = prescaler, start running
noInterrupts();
TCCR3B &= 0xf8; // stop timer, OC3A may be active now
TCNT3 = labs(F_CPU / LASER_PWM); // force immediate compare on next tick
ICR3 = labs(F_CPU / LASER_PWM); // set new PWM period
TCCR3B |= 0x01; // start the timer with proper prescaler value
interrupts();
}
void timer4_init(int pin) {
pinMode(pin, OUTPUT);
analogWrite(pin, 1); // let Arduino setup do it's thing to the PWM pin
TCCR4B = 0x00; // stop Timer4 clock for register updates
TCCR4A = 0x82; // Clear OC4A on match, fast PWM mode, lower WGM4x=14
ICR4 = labs(F_CPU / LASER_PWM); // clock cycles per PWM pulse
OCR4A = labs(F_CPU / LASER_PWM) - 1; // ICR4 - 1 force immediate compare on next tick
TCCR4B = 0x18 | 0x01; // upper WGM4x = 14, clock sel = prescaler, start running
noInterrupts();
TCCR4B &= 0xf8; // stop timer, OC4A may be active now
TCNT4 = labs(F_CPU / LASER_PWM); // force immediate compare on next tick
ICR4 = labs(F_CPU / LASER_PWM); // set new PWM period
TCCR4B |= 0x01; // start the timer with proper prescaler value
interrupts();
}
void laser_init()
{
// Initialize timers for laser intensity control
#if LASER_CONTROL == 1
if (LASER_FIRING_PIN == 2 || LASER_FIRING_PIN == 3 || LASER_FIRING_PIN == 5) timer3_init(LASER_FIRING_PIN);
if (LASER_FIRING_PIN == 6 || LASER_FIRING_PIN == 7 || LASER_FIRING_PIN == 8) timer4_init(LASER_FIRING_PIN);
#endif
#if LASER_CONTROL == 2
if (LASER_INTENSITY_PIN == 2 || LASER_INTENSITY_PIN == 3 || LASER_INTENSITY_PIN == 5) timer3_init(LASER_INTENSITY_PIN);
if (LASER_INTENSITY_PIN == 6 || LASER_INTENSITY_PIN == 7 || LASER_INTENSITY_PIN == 8) timer4_init(LASER_INTENSITY_PIN);
#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_STATUS_PIN, HIGH); // Set the peripherals status pin to pull-up.
pinMode(LASER_PERIPHERALS_STATUS_PIN, INPUT);
#endif // LASER_PERIPHERALS
digitalWrite(LASER_FIRING_PIN, LASER_UNARM); // Laser FIRING is active LOW, so preset the pin
pinMode(LASER_FIRING_PIN, OUTPUT);
// initialize state to some sane defaults
laser.intensity = 100.0;
laser.ppm = 0.0;
laser.duration = 0;
laser.status = LASER_OFF;
laser.firing = LASER_OFF;
laser.mode = CONTINUOUS;
laser.last_firing = 0;
laser.diagnostics = false;
laser.time = 0;
#ifdef LASER_RASTER
laser.raster_aspect_ratio = LASER_RASTER_ASPECT_RATIO;
laser.raster_mm_per_pulse = LASER_RASTER_MM_PER_PULSE;
laser.raster_direction = 1;
#endif // LASER_RASTER
#ifdef MUVE_Z_PEEL
laser.peel_distance = 2.0;
laser.peel_speed = 2.0;
laser.peel_pause = 0.0;
#endif // MUVE_Z_PEEL
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;
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
analogWrite(LASER_INTENSITY_PIN, labs((intensity / 100.0)*(F_CPU / LASER_PWM)));
digitalWrite(LASER_FIRING_PIN, LASER_ARM);
#endif
if (laser.diagnostics) {
SERIAL_ECHOLN("Laser fired");
}
}
void laser_extinguish(){
if (laser.firing == LASER_ON) {
laser.firing = LASER_OFF;
// Engage the pullup resistor for TTL laser controllers which don't turn off entirely without it.
digitalWrite(LASER_FIRING_PIN, LASER_UNARM);
laser.time += millis() - (laser.last_firing / 1000);
if (laser.diagnostics) {
SERIAL_ECHOLN("Laser extinguished");
}
}
}
void laser_set_mode(int mode){
switch(mode){
case 0:
laser.mode = CONTINUOUS;
return;
case 1:
laser.mode = PULSED;
return;
case 2:
laser.mode = RASTER;
return;
}
}
#ifdef LASER_PERIPHERALS
bool laser_peripherals_ok(){
return !digitalRead(LASER_PERIPHERALS_STATUS_PIN);
}
void laser_peripherals_on(){
digitalWrite(LASER_PERIPHERALS_PIN, LOW);
if (laser.diagnostics) {
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Laser Peripherals Enabled");
}
}
void laser_peripherals_off(){
if (!digitalRead(LASER_PERIPHERALS_STATUS_PIN)) {
digitalWrite(LASER_PERIPHERALS_PIN, HIGH);
if (laser.diagnostics) {
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Laser Peripherals Disabled");
}
}
}
void laser_wait_for_peripherals() {
unsigned long timeout = millis() + LASER_PERIPHERALS_TIMEOUT;
if (laser.diagnostics) {
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Waiting for peripheral control board signal...");
}
while(!laser_peripherals_ok()) {
if (millis() > timeout) {
if (laser.diagnostics) {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Peripheral control board failed to respond");
}
Stop();
break;
}
}
}
#endif // LASER_PERIPHERALS
/*
laser.h - Laser cutter control library for Arduino using 16 bit timers- Version 1
Copyright (c) 2013 Timothy Schmidt. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 3 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef LASER_H
#define LASER_H
#include <inttypes.h>
#include "Configuration.h"
// split into planned and status
typedef struct {
int fired; // method used to ask the laser to fire - LASER_FIRE_G1, LASER_FIRE_SPINDLE, LASER_FIRE_E, etc
float intensity; // Laser firing instensity 0.0 - 100.0
float ppm; // pulses per millimeter, for pulsed firing mode
unsigned long duration; // laser firing duration in microseconds, for pulsed firing mode
unsigned long dur; // instantaneous duration
bool status; // LASER_ON / LASER_OFF - buffered
bool firing; // LASER_ON / LASER_OFF - instantaneous
uint8_t mode; // CONTINUOUS, PULSED, RASTER
unsigned long last_firing; // microseconds since last laser firing
bool diagnostics; // Verbose debugging output over serial
unsigned int time; // temporary counter to limit eeprom writes
unsigned int lifetime; // laser lifetime firing counter in minutes
#ifdef LASER_RASTER
unsigned char raster_data[LASER_MAX_RASTER_LINE];
unsigned char rasterlaserpower;
float raster_aspect_ratio;
float raster_mm_per_pulse;
int raster_raw_length;
int raster_num_pixels;
bool raster_direction;
#endif // LASER_RASTER
#ifdef MUVE_Z_PEEL
float peel_distance;
float peel_speed;
float peel_pause;
#endif // MUVE_Z_PEEL
} laser_t;
extern laser_t laser;
void laser_init();
void laser_fire(int intensity);
void laser_extinguish();
void laser_update_lifetime();
void laser_set_mode(int mode);
#ifdef LASER_PERIPHERALS
bool laser_peripherals_ok();
void laser_peripherals_on();
void laser_peripherals_off();
void laser_wait_for_peripherals();
#endif // LASER_PERIPHERALS
#ifdef HIGH_TO_FIRE // Some cutters fire on high, some on low.
#define LASER_ARM HIGH
#define LASER_UNARM LOW
#else
#define LASER_ARM LOW
#define LASER_UNARM HIGH
#endif
// Laser constants
#define LASER_OFF 0
#define LASER_ON 1
#define CONTINUOUS 0
#define PULSED 1
#define RASTER 2
#endif // LASER_H
#define LASERENABLE_HEIGHT 20
#define LASERENABLE_WIDTH 25
#define LASERENABLE_BYTEWIDTH 4
const unsigned char laserenable_bmp[] PROGMEM = {
0x00, 0x1c, 0x00, 0x00,
0x00, 0x3e, 0x00, 0x00,
0x00, 0x77, 0x00, 0x00,
0x00, 0x63, 0x00, 0x00,
0x00, 0xc1, 0x80, 0x00,
0x01, 0xc1, 0xc0, 0x00,
0x01, 0x88, 0xc0, 0x00,
0x03, 0x08, 0x60, 0x00,
0x07, 0x41, 0x70, 0x00,
0x06, 0x2a, 0x30, 0x00,
0x0c, 0x1c, 0x18, 0x00,
0x1d, 0xbf, 0xfc, 0x00,
0x18, 0x1c, 0x0c, 0x00,
0x30, 0x2a, 0x06, 0x00,
0x70, 0x41, 0x07, 0x00,
0x60, 0x88, 0x83, 0x00,
0xc0, 0x08, 0x01, 0x80,
0xc0, 0x00, 0x01, 0x80,
0xff, 0xff, 0xff, 0x80,
0x7f, 0xff, 0xff, 0x00
};
#define ICON_HEIGHT 13
#define ICON_WIDTH 12
#define ICON_BYTEWIDTH 2
const unsigned char laseron_bmp[] PROGMEM = {
0xff, 0xf0,
0x8f, 0x10,
0x8f, 0x10,
0x9f, 0x90,
0x9f, 0x90,
0x80, 0x10,
0x86, 0x10,
0x86, 0x10,
0xc6, 0x30,
0xa6, 0x50,
0x96, 0x90,
0xaf, 0x50,
0xff, 0xf0
};
const unsigned char laseroff_bmp[] PROGMEM = {
0xff, 0xf0,
0x8f, 0x10,
0x8f, 0x10,
0x9f, 0x90,
0x9f, 0x90,
0x80, 0x10,
0x80, 0x10,
0x80, 0x10,
0x80, 0x10,
0x80, 0x10,
0x80, 0x10,
0x80, 0x10,
0xff, 0xf0
};
const unsigned char lockicon_bmp[] PROGMEM = {
0x0f, 0x00,
0x19, 0x80,
0x30, 0xc0,
0x20, 0x40,
0x20, 0x40,
0x20, 0x40,
0x3f, 0xc0,
0x20, 0x40,
0x26, 0x40,
0x26, 0x40,
0x2f, 0x40,
0x20, 0x40,
0x3f, 0xc0
};
const unsigned char vacicon_bmp[] PROGMEM = {
0x06, 0x00,
0x06, 0x00,
0x06, 0x00,
0x0f, 0x00,
0x0f, 0x00,
0x1f, 0x80,
0x3f, 0xc0,
0xff, 0xf0,
0xff, 0xf0,
0xc0, 0x30,
0x16, 0x80,
0x29, 0x40,
0x50, 0xa0
};
const unsigned char airicon_bmp[] PROGMEM = {
0x32, 0xc0,
0x30, 0xc0,
0x34, 0xc0,
0x30, 0xc0,
0x32, 0xc0,
0x30, 0xc0,
0x34, 0xc0,
0x19, 0x80,
0x02, 0x00,
0x00, 0x00,
0x04, 0x00,
0x09, 0x00,
0x22, 0x40
};
const unsigned char watericon_bmp[] PROGMEM = {
0x02, 0x00,
0x07, 0x00,
0x05, 0x00,
0x0d, 0x80,
0x08, 0x80,
0x18, 0xc0,
0x10, 0x40,
0x30, 0x60,
0x38, 0x20,
0x3c, 0x60,
0x3f, 0xe0,
0x1f, 0xc0,
0x0f, 0x80
};
...@@ -44,6 +44,10 @@ ...@@ -44,6 +44,10 @@
#undef USE_BIG_EDIT_FONT #undef USE_BIG_EDIT_FONT
#endif #endif
#if ENABLED(LASER)
#include "../laser/laserbitmaps.h"
#endif
#if ENABLED(USE_SMALL_INFOFONT) #if ENABLED(USE_SMALL_INFOFONT)
#include "dogm_font_data_6x9_marlin.h" #include "dogm_font_data_6x9_marlin.h"
#define FONT_STATUSMENU_NAME u8g_font_6x9 #define FONT_STATUSMENU_NAME u8g_font_6x9
...@@ -318,8 +322,28 @@ static void _draw_heater_status(int x, int heater) { ...@@ -318,8 +322,28 @@ static void _draw_heater_status(int x, int heater) {
static void lcd_implementation_status_screen() { static void lcd_implementation_status_screen() {
u8g.setColorIndex(1); // black on white u8g.setColorIndex(1); // black on white
#if ENABLED(LASER)
#if ENABLED(LASER_PERIPHERALS)
if (laser_peripherals_ok()) {
u8g.drawBitmapP(29,4, LASERENABLE_BYTEWIDTH, LASERENABLE_HEIGHT, laserenable_bmp);
}
#endif
u8g.setFont(FONT_STATUSMENU);
u8g.setColorIndex(1);
u8g.setPrintPos(3,6);
if (current_block->laser_status == LASER_ON) {
u8g.drawBitmapP(5,14, ICON_BYTEWIDTH, ICON_HEIGHT, laseron_bmp);
u8g.print(itostr3(current_block->laser_intensity));
lcd_printPGM(PSTR("%"));
} else {
u8g.drawBitmapP(5,14, ICON_BYTEWIDTH, ICON_HEIGHT, laseroff_bmp);
lcd_printPGM(PSTR("---%"));
}
#else
// Symbols menu graphics, animated fan // Symbols menu graphics, animated fan
u8g.drawBitmapP(9, 1, STATUS_SCREENBYTEWIDTH, STATUS_SCREENHEIGHT, (blink % 2) && fanSpeed ? status_screen0_bmp : status_screen1_bmp); u8g.drawBitmapP(9, 1, STATUS_SCREENBYTEWIDTH, STATUS_SCREENHEIGHT, (blink % 2) && fanSpeed ? status_screen0_bmp : status_screen1_bmp);
#endif
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
// SD Card Symbol // SD Card Symbol
...@@ -392,12 +416,13 @@ static void lcd_implementation_status_screen() { ...@@ -392,12 +416,13 @@ static void lcd_implementation_status_screen() {
} }
#endif #endif
#if DISABLED(LASER)
// Hotends // Hotends
for (int i = 0; i < HOTENDS; i++) _draw_heater_status(6 + i * 25, i); for (int i = 0; i < HOTENDS; i++) _draw_heater_status(6 + i * 25, i);
// Heatbed // Heatbed
if (HOTENDS < 4) _draw_heater_status(81, -1); if (HOTENDS < 4) _draw_heater_status(81, -1);
#endif // DISABLED LASER
// Fan // Fan
lcd_setFont(FONT_STATUSMENU); lcd_setFont(FONT_STATUSMENU);
u8g.setPrintPos(104, 27); u8g.setPrintPos(104, 27);
......
...@@ -48,6 +48,30 @@ char lcd_status_message[3 * LCD_WIDTH + 1] = WELCOME_MSG; // worst case is kana ...@@ -48,6 +48,30 @@ char lcd_status_message[3 * LCD_WIDTH + 1] = WELCOME_MSG; // worst case is kana
#define LCD_Printpos(x, y) lcd.setCursor(x, y) #define LCD_Printpos(x, y) lcd.setCursor(x, y)
#endif #endif
#if ENABLED(LASER)
static void lcd_laser_focus_menu();
static void lcd_laser_menu();
static void lcd_laser_test_fire_menu();
static void laser_test_fire(uint8_t power, uint8_t dwell);
static void laser_set_focus(float f_length);
static void action_laser_focus_custom();
static void action_laser_focus_1mm();
static void action_laser_focus_2mm();
static void action_laser_focus_3mm();
static void action_laser_focus_4mm();
static void action_laser_focus_5mm();
static void action_laser_focus_6mm();
static void action_laser_focus_7mm();
static void action_laser_test_20_50ms();
static void action_laser_test_20_100ms();
static void action_laser_test_100_50ms();
static void action_laser_test_100_100ms();
static void action_laser_test_warm();
static void action_laser_acc_on();
static void action_laser_acc_off();
#endif
// The main status screen // The main status screen
static void lcd_status_screen(); static void lcd_status_screen();
...@@ -441,6 +465,11 @@ static void lcd_return_to_status() { lcd_goto_menu(lcd_status_screen); } ...@@ -441,6 +465,11 @@ static void lcd_return_to_status() { lcd_goto_menu(lcd_status_screen); }
static void lcd_main_menu() { static void lcd_main_menu() {
START_MENU(lcd_status_screen); START_MENU(lcd_status_screen);
MENU_ITEM(back, MSG_WATCH, lcd_status_screen); MENU_ITEM(back, MSG_WATCH, lcd_status_screen);
#if ENABLED(LASER)
if (!(movesplanned() || IS_SD_PRINTING)) {
MENU_ITEM(submenu, "Laser Functions", lcd_laser_menu);
}
#endif
if (movesplanned() || IS_SD_PRINTING) { if (movesplanned() || IS_SD_PRINTING) {
MENU_ITEM(submenu, MSG_TUNE, lcd_tune_menu); MENU_ITEM(submenu, MSG_TUNE, lcd_tune_menu);
} }
...@@ -568,6 +597,13 @@ static void lcd_tune_menu() { ...@@ -568,6 +597,13 @@ static void lcd_tune_menu() {
// //
MENU_ITEM_EDIT(int3, MSG_SPEED, &feedrate_multiplier, 10, 999); MENU_ITEM_EDIT(int3, MSG_SPEED, &feedrate_multiplier, 10, 999);
//
// Laser:
//
#if ENABLED(LASER)
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15);
#endif
// //
// Nozzle: // Nozzle:
// //
...@@ -826,7 +862,11 @@ static void lcd_prepare_menu() { ...@@ -826,7 +862,11 @@ static void lcd_prepare_menu() {
// //
// Auto Home // Auto Home
// //
#if ENABLED(LASER)
MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28 X Y F2000"));
#else
MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28")); MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28"));
#endif
// //
// Set Home Offsets // Set Home Offsets
...@@ -859,7 +899,7 @@ static void lcd_prepare_menu() { ...@@ -859,7 +899,7 @@ static void lcd_prepare_menu() {
// Preheat ABS // Preheat ABS
// Preheat GUM // Preheat GUM
// //
#if TEMP_SENSOR_0 != 0 #if TEMP_SENSOR_0 != 0 && DISABLED(LASER)
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_BED != 0 #if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_BED != 0
MENU_ITEM(submenu, MSG_PREHEAT_PLA, lcd_preheat_pla_menu); MENU_ITEM(submenu, MSG_PREHEAT_PLA, lcd_preheat_pla_menu);
MENU_ITEM(submenu, MSG_PREHEAT_ABS, lcd_preheat_abs_menu); MENU_ITEM(submenu, MSG_PREHEAT_ABS, lcd_preheat_abs_menu);
...@@ -1096,8 +1136,12 @@ static void lcd_control_menu() { ...@@ -1096,8 +1136,12 @@ static void lcd_control_menu() {
START_MENU(lcd_main_menu); START_MENU(lcd_main_menu);
MENU_ITEM(back, MSG_MAIN, lcd_main_menu); MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
MENU_ITEM(submenu, MSG_TEMPERATURE, lcd_control_temperature_menu); MENU_ITEM(submenu, MSG_TEMPERATURE, lcd_control_temperature_menu);
#if ENABLED(LASER)
MENU_ITEM(submenu, MSG_TEMPERATURE, lcd_control_temperature_menu);
#else
MENU_ITEM(submenu, MSG_MOTION, lcd_control_motion_menu); MENU_ITEM(submenu, MSG_MOTION, lcd_control_motion_menu);
MENU_ITEM(submenu, MSG_FILAMENT, lcd_control_volumetric_menu); MENU_ITEM(submenu, MSG_FILAMENT, lcd_control_volumetric_menu);
#endif
#if HAS(LCD_CONTRAST) #if HAS(LCD_CONTRAST)
//MENU_ITEM_EDIT(int3, MSG_CONTRAST, &lcd_contrast, 0, 63); //MENU_ITEM_EDIT(int3, MSG_CONTRAST, &lcd_contrast, 0, 63);
...@@ -1178,6 +1222,7 @@ static void lcd_stats_menu() { ...@@ -1178,6 +1222,7 @@ static void lcd_stats_menu() {
* "Control" > "Temperature" submenu * "Control" > "Temperature" submenu
* *
*/ */
#if DISABLED(LASER)
static void lcd_control_temperature_menu() { static void lcd_control_temperature_menu() {
START_MENU(lcd_control_menu); START_MENU(lcd_control_menu);
...@@ -1297,12 +1342,15 @@ static void lcd_control_temperature_menu() { ...@@ -1297,12 +1342,15 @@ static void lcd_control_temperature_menu() {
MENU_ITEM(submenu, MSG_PREHEAT_GUM_SETTINGS, lcd_control_temperature_preheat_gum_settings_menu); MENU_ITEM(submenu, MSG_PREHEAT_GUM_SETTINGS, lcd_control_temperature_preheat_gum_settings_menu);
END_MENU(); END_MENU();
} }
#endif
/** /**
* *
* "Temperature" > "Preheat PLA conf" submenu * "Temperature" > "Preheat PLA conf" submenu
* *
*/ */
#if DISABLED(LASER)
static void lcd_control_temperature_preheat_pla_settings_menu() { static void lcd_control_temperature_preheat_pla_settings_menu() {
START_MENU(lcd_control_temperature_menu); START_MENU(lcd_control_temperature_menu);
MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu); MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu);
...@@ -1318,12 +1366,14 @@ static void lcd_control_temperature_preheat_pla_settings_menu() { ...@@ -1318,12 +1366,14 @@ static void lcd_control_temperature_preheat_pla_settings_menu() {
#endif #endif
END_MENU(); END_MENU();
} }
#endif
/** /**
* *
* "Temperature" > "Preheat ABS conf" submenu * "Temperature" > "Preheat ABS conf" submenu
* *
*/ */
#if DISABLED(LASER)
static void lcd_control_temperature_preheat_abs_settings_menu() { static void lcd_control_temperature_preheat_abs_settings_menu() {
START_MENU(lcd_control_temperature_menu); START_MENU(lcd_control_temperature_menu);
MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu); MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu);
...@@ -1339,12 +1389,13 @@ static void lcd_control_temperature_preheat_abs_settings_menu() { ...@@ -1339,12 +1389,13 @@ static void lcd_control_temperature_preheat_abs_settings_menu() {
#endif #endif
END_MENU(); END_MENU();
} }
#endif
/** /**
* *
* "Temperature" > "Preheat GUM conf" submenu * "Temperature" > "Preheat GUM conf" submenu
* *
*/ */
#if DISABLED(LASER)
static void lcd_control_temperature_preheat_gum_settings_menu() { static void lcd_control_temperature_preheat_gum_settings_menu() {
START_MENU(lcd_control_temperature_menu); START_MENU(lcd_control_temperature_menu);
MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu); MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu);
...@@ -1360,7 +1411,7 @@ static void lcd_control_temperature_preheat_gum_settings_menu() { ...@@ -1360,7 +1411,7 @@ static void lcd_control_temperature_preheat_gum_settings_menu() {
#endif #endif
END_MENU(); END_MENU();
} }
#endif
/** /**
* *
* "Control" > "Motion" submenu * "Control" > "Motion" submenu
...@@ -1431,6 +1482,7 @@ static void lcd_control_motion_menu() { ...@@ -1431,6 +1482,7 @@ static void lcd_control_motion_menu() {
* "Control" > "Filament" submenu * "Control" > "Filament" submenu
* *
*/ */
#if DISABLED(LASER)
static void lcd_control_volumetric_menu() { static void lcd_control_volumetric_menu() {
START_MENU(lcd_control_menu); START_MENU(lcd_control_menu);
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu); MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
...@@ -1454,6 +1506,7 @@ static void lcd_control_volumetric_menu() { ...@@ -1454,6 +1506,7 @@ static void lcd_control_volumetric_menu() {
END_MENU(); END_MENU();
} }
#endif
/** /**
* *
...@@ -1510,6 +1563,127 @@ static void lcd_control_volumetric_menu() { ...@@ -1510,6 +1563,127 @@ static void lcd_control_volumetric_menu() {
} }
#endif // FWRETRACT #endif // FWRETRACT
#if ENABLED(LASER)
static void lcd_laser_menu()
{
START_MENU();
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
MENU_ITEM(submenu, "Set Focus", lcd_laser_focus_menu);
MENU_ITEM(submenu, "Test Fire", lcd_laser_test_fire_menu);
#ifdef LASER_PERIPHERALS
if (laser_peripherals_ok()) {
MENU_ITEM(function, "Turn On Pumps/Fans", action_laser_acc_on);
} else if (!(movesplanned() || IS_SD_PRINTING)) {
MENU_ITEM(function, "Turn Off Pumps/Fans", action_laser_acc_off);
}
#endif // LASER_PERIPHERALS
END_MENU();
}
static void lcd_laser_test_fire_menu() {
START_MENU();
MENU_ITEM(back, "Laser Functions", lcd_laser_menu);
MENU_ITEM(function, " 20% 50ms", action_laser_test_20_50ms);
MENU_ITEM(function, " 20% 100ms", action_laser_test_20_100ms);
MENU_ITEM(function, "100% 50ms", action_laser_test_100_50ms);
MENU_ITEM(function, "100% 100ms", action_laser_test_100_100ms);
MENU_ITEM(function, "Warm-up Laser 2sec", action_laser_test_warm);
END_MENU();
}
static void action_laser_acc_on() {
enquecommand_P(PSTR("M80"));
}
static void action_laser_acc_off() {
enquecommand_P(PSTR("M81"));
}
static void action_laser_test_20_50ms() {
laser_test_fire(20, 50);
}
static void action_laser_test_20_100ms() {
laser_test_fire(20, 100);
}
static void action_laser_test_100_50ms() {
laser_test_fire(100, 50);
}
static void action_laser_test_100_100ms() {
laser_test_fire(100, 100);
}
static void action_laser_test_warm() {
laser_test_fire(15, 2000);
}
static void laser_test_fire(uint8_t power, uint8_t dwell) {
enquecommand_P(PSTR("M80")); // Enable laser accessories since we don't know if its been done (and there's no penalty for doing it again).
laser_fire(power);
delay(dwell);
laser_extinguish();
}
float focalLength = 0;
static void lcd_laser_focus_menu() {
START_MENU();
MENU_ITEM(back, "Laser Functions", lcd_laser_menu);
MENU_ITEM(function, "1mm", action_laser_focus_1mm);
MENU_ITEM(function, "2mm", action_laser_focus_2mm);
MENU_ITEM(function, "3mm - 1/8in", action_laser_focus_3mm);
MENU_ITEM(function, "4mm", action_laser_focus_4mm);
MENU_ITEM(function, "5mm", action_laser_focus_5mm);
MENU_ITEM(function, "6mm - 1/4in", action_laser_focus_6mm);
MENU_ITEM(function, "7mm", action_laser_focus_7mm);
MENU_ITEM_EDIT_CALLBACK(float32, "Custom", &focalLength, 0, LASER_FOCAL_HEIGHT, action_laser_focus_custom);
END_MENU();
}
static void action_laser_focus_custom() {
laser_set_focus(focalLength);
}
static void action_laser_focus_1mm() {
laser_set_focus(1);
}
static void action_laser_focus_2mm() {
laser_set_focus(2);
}
static void action_laser_focus_3mm() {
laser_set_focus(3);
}
static void action_laser_focus_4mm() {
laser_set_focus(4);
}
static void action_laser_focus_5mm() {
laser_set_focus(5);
}
static void action_laser_focus_6mm() {
laser_set_focus(6);
}
static void action_laser_focus_7mm() {
laser_set_focus(7);
}
static void laser_set_focus(float f_length) {
if (!has_axis_homed[Z_AXIS]) {
enquecommand_P(PSTR("G28 Z F150"));
}
focalLength = f_length;
float focus = LASER_FOCAL_HEIGHT - f_length;
char cmd[20];
sprintf_P(cmd, PSTR("G0 Z%s F150"), ftostr52(focus));
enquecommand(cmd);
}
#endif // LASER
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
#if !PIN_EXISTS(SD_DETECT) #if !PIN_EXISTS(SD_DETECT)
......
...@@ -601,8 +601,10 @@ float junction_deviation = 0.1; ...@@ -601,8 +601,10 @@ float junction_deviation = 0.1;
block->steps[E_AXIS] /= 100; block->steps[E_AXIS] /= 100;
block->step_event_count = max(block->steps[X_AXIS], max(block->steps[Y_AXIS], max(block->steps[Z_AXIS], block->steps[E_AXIS]))); block->step_event_count = max(block->steps[X_AXIS], max(block->steps[Y_AXIS], max(block->steps[Z_AXIS], block->steps[E_AXIS])));
#if DISABLED(LASER)
// Bail if this is a zero-length block // Bail if this is a zero-length block
if (block->step_event_count <= DROP_SEGMENTS) return; if (block->step_event_count <= DROP_SEGMENTS) return;
#endif
block->fan_speed = fanSpeed; block->fan_speed = fanSpeed;
...@@ -851,6 +853,49 @@ float junction_deviation = 0.1; ...@@ -851,6 +853,49 @@ float junction_deviation = 0.1;
#endif #endif
); );
} }
#if ENABLED(LASER)
block->laser_intensity = laser.intensity;
block->laser_duration = laser.duration;
block->laser_status = laser.status;
block->laser_mode = laser.mode;
// 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 == 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->step_event_count = max(block->steps_x, max(block->steps_y, max(block->steps_z, max(block->steps_e, block->steps_l))));
if (laser.diagnostics) {
if (block->laser_status == LASER_ON) {
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Laser firing enabled");
}
}
#endif // LASER
float inverse_millimeters = 1.0 / block->millimeters; // Inverse millimeters to remove multiple divides float inverse_millimeters = 1.0 / block->millimeters; // Inverse millimeters to remove multiple divides
// Calculate speed in mm/second for each axis. No divide by zero due to previous checks. // Calculate speed in mm/second for each axis. No divide by zero due to previous checks.
......
...@@ -70,6 +70,18 @@ typedef struct { ...@@ -70,6 +70,18 @@ typedef struct {
unsigned long e_to_p_pressure; unsigned long e_to_p_pressure;
#endif #endif
#if ENABLED(LASER)
uint8_t laser_mode; // CONTINUOUS, PULSED, RASTER
bool laser_status; // LASER_OFF, LASER_ON
float laser_ppm; // pulses per millimeter, for pulsed and raster firing modes
unsigned long laser_duration; // laser firing duration in microseconds, for pulsed and raster firing modes
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
#if ENABLED(LASER_RASTER)
unsigned char laser_raster_data[LASER_MAX_RASTER_LINE];
#endif
#endif
#if ENABLED(LASERBEAM) #if ENABLED(LASERBEAM)
unsigned long laser_ttlmodulation; unsigned long laser_ttlmodulation;
#endif #endif
......
...@@ -45,6 +45,16 @@ block_t* current_block; // A pointer to the block currently being traced ...@@ -45,6 +45,16 @@ block_t* current_block; // A pointer to the block currently being traced
static unsigned char out_bits = 0; // The next stepping-bits to be output static unsigned char out_bits = 0; // The next stepping-bits to be output
static unsigned int cleaning_buffer_counter; static unsigned int cleaning_buffer_counter;
#ifdef LASER
static long counter_l;
#endif // LASER
#ifdef LASER_RASTER
static int counter_raster;
#endif // LASER_RASTER
#if ENABLED(Z_DUAL_ENDSTOPS) #if ENABLED(Z_DUAL_ENDSTOPS)
static bool performing_homing = false, static bool performing_homing = false,
locked_z_motor = false, locked_z_motor = false,
...@@ -643,6 +653,12 @@ ISR(TIMER1_COMPA_vect) { ...@@ -643,6 +653,12 @@ ISR(TIMER1_COMPA_vect) {
return; return;
} }
#if ENABLED(LASER)
if (laser.dur != 0 && (laser.last_firing + laser.dur < micros())) {
if (laser.diagnostics) SERIAL_ECHOLN("Laser firing duration elapsed, in interrupt handler");
laser_extinguish();
#endif
// If there is no current block, attempt to pop one from the buffer // If there is no current block, attempt to pop one from the buffer
if (!current_block) { if (!current_block) {
// Anything in the buffer? // Anything in the buffer?
...@@ -654,6 +670,10 @@ ISR(TIMER1_COMPA_vect) { ...@@ -654,6 +670,10 @@ ISR(TIMER1_COMPA_vect) {
// Initialize Bresenham counters to 1/2 the ceiling // Initialize Bresenham counters to 1/2 the ceiling
long new_count = -(current_block->step_event_count >> 1); long new_count = -(current_block->step_event_count >> 1);
counter_x = counter_y = counter_z = counter_e = new_count; counter_x = counter_y = counter_z = counter_e = new_count;
#if ENABLED(LASER)
counter_l = counter_x;
laser.dur = current_block->laser_duration;
#endif
#if ENABLED(COLOR_MIXING_EXTRUDER) #if ENABLED(COLOR_MIXING_EXTRUDER)
for (uint8_t i = 0; i < DRIVER_EXTRUDERS; i++) for (uint8_t i = 0; i < DRIVER_EXTRUDERS; i++)
...@@ -665,11 +685,18 @@ ISR(TIMER1_COMPA_vect) { ...@@ -665,11 +685,18 @@ ISR(TIMER1_COMPA_vect) {
#if ENABLED(Z_LATE_ENABLE) #if ENABLED(Z_LATE_ENABLE)
if (current_block->steps[Z_AXIS] > 0) { if (current_block->steps[Z_AXIS] > 0) {
enable_z(); enable_z();
#if ENABLED(MUVE)
enable_e();
#endif
OCR1A = 2000; // 1ms wait OCR1A = 2000; // 1ms wait
return; return;
} }
#endif #endif
#if ENABLED(LASER_RASTER)
if (current_block->laser_mode == RASTER) counter_raster = 0;
#endif
// #if ENABLED(ADVANCE) // #if ENABLED(ADVANCE)
// e_steps[current_block->active_driver] = 0; // e_steps[current_block->active_driver] = 0;
// #endif // #endif
...@@ -684,6 +711,17 @@ ISR(TIMER1_COMPA_vect) { ...@@ -684,6 +711,17 @@ ISR(TIMER1_COMPA_vect) {
// Update endstops state, if enabled // Update endstops state, if enabled
if (check_endstops) update_endstops(); if (check_endstops) update_endstops();
// Continuous firing of the laser during a move happens here, PPM and raster happen further down
#if ENABLED(LASER)
if (current_block->laser_mode == CONTINUOUS && current_block->laser_status == LASER_ON) {
laser_fire(current_block->laser_intensity);
}
if (current_block->laser_status == LASER_OFF) {
if (laser.diagnostics) SERIAL_ECHOLN("Laser status set to off, in interrupt handler");
laser_extinguish();
}
#endif
// Take multiple steps per interrupt (For high speed moves) // Take multiple steps per interrupt (For high speed moves)
for (uint8_t i = 0; i < step_loops; i++) { for (uint8_t i = 0; i < step_loops; i++) {
...@@ -764,6 +802,37 @@ ISR(TIMER1_COMPA_vect) { ...@@ -764,6 +802,37 @@ ISR(TIMER1_COMPA_vect) {
#endif #endif
#endif #endif
#if ENABLED(LASER)
counter_l += current_block->steps_l;
if (counter_l > 0) {
if (current_block->laser_mode == PULSED && current_block->laser_status == LASER_ON) { // Pulsed Firing Mode
laser_fire(current_block->laser_intensity);
if (laser.diagnostics) {
SERIAL_ECHOPAIR("X: ", counter_x);
SERIAL_ECHOPAIR("Y: ", counter_y);
SERIAL_ECHOPAIR("L: ", counter_l);
}
}
#if ENABLED(LASER_RASTER)
if (current_block->laser_mode == RASTER && current_block->laser_status == LASER_ON) { // Raster Firing Mode
// 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.
laser_fire(current_block->laser_raster_data[counter_raster]);
if (laser.diagnostics) {
SERIAL_ECHOPAIR("Pixel: ", (float)current_block->laser_raster_data[counter_raster]);
}
counter_raster++;
}
#endif // LASER_RASTER
counter_l -= current_block->step_event_count;
}
if (current_block->laser_duration != 0 && (laser.last_firing + current_block->laser_duration < micros())) {
if (laser.diagnostics) SERIAL_ECHOLN("Laser firing duration elapsed, in interrupt fast loop");
laser_extinguish();
}
#endif // LASER
step_events_completed++; step_events_completed++;
if (step_events_completed >= current_block->step_event_count) break; if (step_events_completed >= current_block->step_event_count) break;
} }
......
...@@ -1721,6 +1721,10 @@ ...@@ -1721,6 +1721,10 @@
#error DEPENDENCY ERROR: You have to set LASER_PWR_PIN and LASER_TTL_PIN to a valid pin if you enable LASERBEAM #error DEPENDENCY ERROR: You have to set LASER_PWR_PIN and LASER_TTL_PIN to a valid pin if you enable LASERBEAM
#endif #endif
#if ENABLED(LASERBEAM) && ENABLED(LASER)
#error DEPENDENCY ERROR: You must enable only one of LASERBEAM or LASER, not both!
#endif
#if ENABLED(FILAMENT_RUNOUT_SENSOR) && !PIN_EXISTS(FILRUNOUT) #if ENABLED(FILAMENT_RUNOUT_SENSOR) && !PIN_EXISTS(FILRUNOUT)
#error DEPENDENCY ERROR: You have to set FILRUNOUT_PIN to a valid pin if you enable FILAMENT_RUNOUT_SENSOR #error DEPENDENCY ERROR: You have to set FILRUNOUT_PIN to a valid pin if you enable FILAMENT_RUNOUT_SENSOR
#endif #endif
...@@ -1761,4 +1765,8 @@ ...@@ -1761,4 +1765,8 @@
#error DEPENDENCY ERROR: You have to set SLED_PIN to a valid pin if you enable Z_PROBE_SLED #error DEPENDENCY ERROR: You have to set SLED_PIN to a valid pin if you enable Z_PROBE_SLED
#endif #endif
#if ENABLED(LASERBEAM) && ENABLED(LASER)
#error DEPENDENCY ERROR: You have to select only one of LASER or LASERBEAM
#endif
#endif //SANITYCHECK_H #endif //SANITYCHECK_H
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment