22 Commits

Author SHA1 Message Date
96ad0afdda Set coolant pins for all supported boards in cpu-map.h 2017-08-03 16:00:15 +02:00
4252f75a84 Merge branch 'more-axis' 2017-08-03 15:07:11 +02:00
dc92bf565e Support coolant flood and mist for remix board 2017-08-03 15:01:34 +02:00
436615095f Always use MIN endstop pins (independant of board!) 2017-07-12 19:01:01 +02:00
a661778252 Made board switchable in config.h 2017-07-12 18:34:50 +02:00
54ae403094 Made A-Axis switchable in config.h 2017-07-12 17:56:46 +02:00
06e9bf8f82 Made CPU-MAP per Board instead of MCU 2017-07-12 17:45:06 +02:00
f904fff7ba Highlight make as command. 2017-06-21 09:06:55 +02:00
b24e01d588 Merge branch 'master' of https://github.com/cprezzi/grbl-LPC 2017-06-21 09:04:30 +02:00
ba4e83723f Added Links for Make Tool and ARM Toolchain. 2017-06-21 09:01:12 +02:00
14983881ee Added Links for Make and ARM Toolchain. 2017-06-21 08:58:57 +02:00
eeb206ec97 Adjusted config.h 2017-06-21 08:32:02 +02:00
83c1b57c41 Merge branch 'master' into more-axis 2017-05-26 20:23:51 +02:00
50c13a1868 Moved homing origin to bottom/left instead of top/right 2017-05-18 23:10:44 +02:00
8856b3fef4 Corrected K40 defaults 2017-05-18 16:45:59 +02:00
73cdb2f722 Corrected stepper invert mask for K40 2017-05-18 14:47:53 +02:00
b28fd39e7d Merge branch 'master' into more-axis 2017-05-18 12:51:28 +02:00
1f0ab33787 Merged new $ params 2017-05-18 12:47:37 +02:00
d85bfa8c83 Added default settings for PWM_OFF_VALUE, PWM_MIN_VALUE and PMW_MAX_VALUE 2017-05-18 11:51:16 +02:00
da946353c8 Merge remote-tracking branch 'upstream/master' 2017-05-16 15:03:18 +02:00
b1ecb47bec #4: PWM $ settings 2017-05-13 13:54:50 -04:00
f7083b9491 Added 4.axes (A) and moved default settings to defaults.h and cpu-map.h 2017-05-11 19:58:41 +02:00
23 changed files with 862 additions and 304 deletions

View File

@ -1,7 +1,8 @@
![GitHub Logo](https://github.com/gnea/gnea-Media/blob/master/Grbl%20Logo/Grbl%20Logo%20250px.png?raw=true)
***
_Click the `Release` tab to download pre-compiled `.bin` files or just [click here](https://github.com/cprezzi/grbl-LPC/releases)_
Old releases are in the `Release` tab. See [cprezzi's branch](https://github.com/cprezzi/grbl-LPC) for more recent releases.
Note: cprezzi's branch disables current control and has defaults more suitable for other boards.
***
This is GRBL 1.1 ported to the LPC1769. It can run on Smoothieboard.
@ -10,30 +11,30 @@ Usage notes:
If it doesn't, try installing VCOM_lib/usbser.inf.
* This doesn't pass the sdcard to the host. Once installed you need to use a micro sdcard adaptor to replace or change it.
* Only tested with lasers with PWM. Non-PWM spindle control not ported.
* This special version supports setting PWM frequency by $33. Default is 5000 Hz. Pin can only be changes in config.h.
* Pin 2.5
* 5 kHz
* PWM off value: 0%
* Mimimum PWM value: 0%
* Maximum PWM value: 100%
* These are defaults for easy-to-change config values.
* Maximum S value: 1000.0 ($30)
* WPos enabled for LaserWeb compatability ($10=0)
* Laser mode: ON ($32)
* Minimum S value: 0.0 ($31)
* Laser mode: 1 ($32)
* Laser PWM frequency: 5000 ($33)
* Maximum S value: 1.0 ($30)
* Hard limits not yet ported
* Control inputs not yet ported (e.g. Cycle Start and Safety Door switches)
New configuration settings
* $33 is PWM frequency in Hz
* $34 is PWM off value in %
* $35 is PWM min value in %
* $36 is PWM max value in %
* $140, $141, $142 are X, Y, Z current (amps)
* Default to 0.0 A to avoid burning out your motors
* Your motors will likely stall if you don't set these!
* Default to 0.0 A to avoid burning out your motors
* Your motors will likely stall if you don't set these!
Build notes:
* You should use virtual machines, if you use multiple toolchains on the same PC.
* Install make if not already there (for Windows see http://gnuwin32.sourceforge.net/packages/make.htm)
* Install the ARM embeded toolchain (see https://developer.arm.com/open-source/gnu-toolchain/gnu-rm/downloads)
* Include ```make``` and the ```arm-none-eabi-*``` tools in your path.
* Run ```git submodule init``` and ```git submodule update``` before building.
* Make produces 2 files:
* ```make``` produces 2 files:
* ```build/firmware.bin```: this is compatible with the sdcard bootloader.
* ```build/grbl.hex```: this is not compatible with the sdcard bootloader. It loads using Flash Magic
and is primarilly for developers who don't want to keep swapping sdcards. If you flash this,

View File

@ -51,6 +51,7 @@ $27=1.000
$30=1000.
$31=0.
$32=0
$33=5000
$100=250.000
$101=250.000
$102=250.000
@ -63,6 +64,9 @@ $122=10.000
$130=200.000
$131=200.000
$132=200.000
$140=0.000
$141=0.000
$142=0.000
```
#### $x=val - Save Grbl setting
@ -227,6 +231,10 @@ When enabled, Grbl will move continuously through consecutive `G1`, `G2`, or `G3
When disabled, Grbl will operate as it always has, stopping motion with every `S` spindle speed command. This is the default operation of a milling machine to allow a pause to let the spindle change speeds.
#### $33 - Spindle/Laser PWM frequency
This sets the PWM frequency.
#### $100, $101 and $102 [X,Y,Z] steps/mm
Grbl needs to know how far each step will take the tool in reality. To calculate steps/mm for an axis of your machine you need to know:

BIN
doc/media/Thumbs.db Normal file

Binary file not shown.

View File

@ -55,7 +55,7 @@ void current_init()
set_current(0, settings.current[0]);
set_current(1, settings.current[1]);
set_current(2, settings.current[2]);
set_current(3, DEFAULT_A_CURRENT);
set_current(3, settings.current[3]);
#endif
}

View File

@ -31,12 +31,17 @@
#include "LPC17xx.h"
// Define CPU pin map and default settings.
// NOTE: OEMs can avoid the need to maintain/update the defaults.h and cpu_map.h files and use only
// one configuration file by placing their specific defaults and pin map at the bottom of this file.
// If doing so, simply comment out these two defines and see instructions below.
// #define DEFAULTS_GENERIC
// #define CPU_MAP_ATMEGA328P // Arduino Uno CPU
// Define board type for pin map and default settings.
#define CPU_MAP_SMOOTHIEBOARD // Smoothieboard (NXP LPC1769 MCU)
//#define CPU_MAP_C3D_REMIX // Cohesion3D Remix (NXP LPC1769 MCU)
//#define CPU_MAP_C3D_MINI // Cohesion3D Mini (NXP LPC1769 MCU)
//#define CPU_MAP_MKS_SBASE // MKS SBASE Board (NXP LPC1768 MCU)
//#define CPU_MAP_AZTEEG_X5 // Azteeg X5 Board (NXP LPC1769 MCU)
// Define machine type for machine specific defaults
//#define DEFAULTS_GENERIC
#define DEFAULTS_K40
//#define DEFAULTS_FABKIT
// Serial baud rate
// #define BAUD_RATE 230400
@ -108,10 +113,11 @@
// #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.
#define HOMING_CYCLE_0 ((1<<X_AXIS)|(1<<Y_AXIS)) // NOT COMPATIBLE WITH COREXY: Homes both X-Y in one cycle.
//#define HOMING_CYCLE_0 ((1<<X_AXIS)|(1<<Y_AXIS)) // NOT COMPATIBLE WITH COREXY: Homes both X-Y in one cycle.
// #define HOMING_CYCLE_0 (1<<X_AXIS) // COREXY COMPATIBLE: First home X
// #define HOMING_CYCLE_1 (1<<Y_AXIS) // COREXY COMPATIBLE: Then home Y
// Homing cycle pattern is defined in Machine defaults!!!
// Number of homing cycles performed after when the machine initially jogs to limit switches.
// This help in preventing overshoot and should improve repeatability. This value should be one or
@ -129,6 +135,9 @@
// define to force Grbl to always set the machine origin at the homed location despite switch orientation.
// #define HOMING_FORCE_SET_ORIGIN // Uncomment to enable.
// Uncomment this define to force Grbl to always set the machine origin at bottom left.
//#define HOMING_FORCE_POSITIVE_SPACE // Uncomment to enable.
// Number of blocks Grbl executes upon startup. These blocks are stored in EEPROM, where the size
// and addresses are defined in settings.h. With the current settings, up to 2 startup blocks may
// be stored and executed in order. These startup blocks would typically be used to set the g-code
@ -167,7 +176,7 @@
// Enables a second coolant control pin via the mist coolant g-code command M7 on the Arduino Uno
// analog pin 4. Only use this option if you require a second coolant control pin.
// NOTE: The M8 flood coolant control pin on analog pin 3 will still be functional regardless.
// #define ENABLE_M7 // Disabled by default. Uncomment to enable.
//#define ENABLE_M7 // Disabled by default. Uncomment to enable.
// This option causes the feed hold input to act as a safety door switch. A safety door, when triggered,
// immediately forces a feed hold and then safely de-energizes the machine. Resuming is blocked until
@ -187,7 +196,7 @@
// 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 requires the CoreXY A and B motors
// 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 based on a mask. This essentially means you can use
// normally-closed switches on the specified pins, rather than the default normally-open switches.
@ -359,11 +368,6 @@
// pwm = scaled value. settings.rpm_min scales to SPINDLE_PWM_MIN_VALUE. settings.rpm_max
// scales to SPINDLE_PWM_MAX_VALUE.
//#define SPINDLE_PWM_PERIOD (SystemCoreClock / 40000) // SystemCoreClock / frequency
#define SPINDLE_PWM_OFF_VALUE 0.0 // SPINDLE_PWM_PERIOD * fraction
//#define SPINDLE_PWM_MIN_VALUE (SPINDLE_PWM_PERIOD * 0.0) // SPINDLE_PWM_PERIOD * fraction
//#define SPINDLE_PWM_MAX_VALUE (SPINDLE_PWM_PERIOD * 1.0) // SPINDLE_PWM_PERIOD * fraction
// Used by variable spindle output only. This forces the PWM output to a minimum duty cycle when enabled.
// The PWM pin will still read 0V when the spindle is disabled. Most users will not need this option, but
// it may be useful in certain scenarios. This minimum PWM settings coincides with the spindle rpm minimum
@ -565,7 +569,7 @@
// LPC176x flash blocks have a rating of 10,000 write cycles. To prevent excess wear, we don't
// write G10, G28.1, and G30.1. Uncomment to enable these writes.
// #define STORE_COORD_DATA // Default disabled. Uncomment to enable.
#define STORE_COORD_DATA // Default disabled. Uncomment to enable.
// In Grbl v0.9 and prior, there is an old outstanding bug where the `WPos:` work position reported
// may not correlate to what is executing, because `WPos:` is based on the g-code parser state, which
@ -629,154 +633,5 @@
below.
*/
// Paste CPU_MAP definitions here.
// Define serial port pins and interrupt vectors.
#define SERIAL_RX USART_RX_vect
#define SERIAL_UDRE USART_UDRE_vect
// Define step pulse output pins. NOTE: All step bit pins must be on the same port.
#define STEP_DDR LPC_GPIO2->FIODIR
#define STEP_PORT LPC_GPIO2->FIOPIN
#define X_STEP_BIT 0
#define Y_STEP_BIT 1
#define Z_STEP_BIT 2
#define STEP_MASK ((1<<X_STEP_BIT)|(1<<Y_STEP_BIT)|(1<<Z_STEP_BIT)) // All step bits
// Define step direction output pins. NOTE: All direction pins must be on the same port.
#define DIRECTION_DDR LPC_GPIO0->FIODIR
#define DIRECTION_PORT LPC_GPIO0->FIOPIN
#define X_DIRECTION_BIT 5
#define Y_DIRECTION_BIT 11
#define Z_DIRECTION_BIT 20
#define DIRECTION_MASK ((1<<X_DIRECTION_BIT)|(1<<Y_DIRECTION_BIT)|(1<<Z_DIRECTION_BIT)) // All direction bits
// Define stepper driver enable/disable output pin.
#define STEPPERS_DISABLE_DDR LPC_GPIO0->FIODIR
#define STEPPERS_DISABLE_PORT LPC_GPIO0->FIOPIN
#define X_DISABLE_BIT 4
#define Y_DISABLE_BIT 10
#define Z_DISABLE_BIT 19
#define STEPPERS_DISABLE_MASK ((1<<X_DISABLE_BIT)|(1<<Y_DISABLE_BIT)|(1<<Z_DISABLE_BIT))
// Define homing/hard limit switch input pins and limit interrupt vectors.
// NOTE: All limit bit pins must be on the same port, but not on a port with other input pins (CONTROL).
#define LIMIT_DDR LPC_GPIO1->FIODIR
#define LIMIT_PIN LPC_GPIO1->FIOPIN
#define LIMIT_PORT LPC_GPIO1->FIOPIN
#define X_LIMIT_BIT 24 // X-MIN=24, X-MAX=25
#define Y_LIMIT_BIT 27 // Y-MIN=26, Y-MAX=27
#define Z_LIMIT_BIT 29 // Z-MIN=28, Z-MAX=29
#define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)) //|(1<<Z_LIMIT_BIT)) // All limit bits
// hard limits not ported #define LIMIT_INT PCIE0 // Pin change interrupt enable pin
// hard limits not ported #define LIMIT_INT_vect PCINT0_vect
// hard limits not ported #define LIMIT_PCMSK PCMSK0 // Pin change interrupt register
// Define spindle enable and spindle direction output pins.
/* not ported
#define SPINDLE_ENABLE_DDR DDRB
#define SPINDLE_ENABLE_PORT PORTB
// Z Limit pin and spindle PWM/enable pin swapped to access hardware PWM on Pin 11.
#ifdef VARIABLE_SPINDLE
#ifdef USE_SPINDLE_DIR_AS_ENABLE_PIN
// If enabled, spindle direction pin now used as spindle enable, while PWM remains on D11.
#define SPINDLE_ENABLE_BIT 5 // Uno Digital Pin 13 (NOTE: D13 can't be pulled-high input due to LED.)
#else
#define SPINDLE_ENABLE_BIT 3 // Uno Digital Pin 11
#endif
#else
#define SPINDLE_ENABLE_BIT 4 // Uno Digital Pin 12
#endif
#ifndef USE_SPINDLE_DIR_AS_ENABLE_PIN
#define SPINDLE_DIRECTION_DDR DDRB
#define SPINDLE_DIRECTION_PORT PORTB
#define SPINDLE_DIRECTION_BIT 5 // Uno Digital Pin 13 (NOTE: D13 can't be pulled-high input due to LED.)
#endif
*/
// Define flood and mist coolant enable output pins.
#define COOLANT_FLOOD_DDR NotUsed
#define COOLANT_FLOOD_PORT NotUsed
#define COOLANT_FLOOD_BIT 3 // Uno Analog Pin 3
#define COOLANT_MIST_DDR NotUsed
#define COOLANT_MIST_PORT NotUsed
#define COOLANT_MIST_BIT 4 // Uno Analog Pin 3
// Define user-control controls (cycle start, reset, feed hold) input pins.
// NOTE: All CONTROLs pins must be on the same port and not on a port with other input pins (limits).
#define CONTROL_DDR NotUsed
#define CONTROL_PIN NotUsed
#define CONTROL_PORT NotUsed
#define CONTROL_RESET_BIT 0 // Uno Analog Pin 0
#define CONTROL_FEED_HOLD_BIT 1 // Uno Analog Pin 1
#define CONTROL_CYCLE_START_BIT 2 // Uno Analog Pin 2
#define CONTROL_SAFETY_DOOR_BIT 1 // Uno Analog Pin 1 NOTE: Safety door is shared with feed hold. Enabled by config define.
#define CONTROL_INT PCIE1 // Pin change interrupt enable pin
#define CONTROL_INT_vect PCINT1_vect
#define CONTROL_PCMSK NotUsed // Pin change interrupt register
#define CONTROL_MASK ((1<<CONTROL_RESET_BIT)|(1<<CONTROL_FEED_HOLD_BIT)|(1<<CONTROL_CYCLE_START_BIT)|(1<<CONTROL_SAFETY_DOOR_BIT))
#define CONTROL_INVERT_MASK CONTROL_MASK // May be re-defined to only invert certain control pins.
// Define probe switch input pin.
#define PROBE_DDR NotUsed
#define PROBE_PIN NotUsed
#define PROBE_PORT NotUsed
#define PROBE_BIT 5 // Uno Analog Pin 5
#define PROBE_MASK (1<<PROBE_BIT)
// The LPC17xx has 6 PWM channels. Each channel has 2 pins. It can drive both pins simultaneously to the same value.
//
// PWM Channel PWM1_CH1 PWM1_CH2 PWM1_CH3 PWM1_CH4 PWM1_CH5 PWM1_CH6
// Primary pin P1.18 P1.20 P1.21 P1.23 P1.24 P1.26
// Secondary pin P2.0 P2.1 P2.2 P2.3 P2.4 P2.5
#define SPINDLE_PWM_CHANNEL PWM1_CH6
#define SPINDLE_PWM_USE_PRIMARY_PIN false
#define SPINDLE_PWM_USE_SECONDARY_PIN true
// Stepper current control
//#define CURRENT_I2C Driver_I2C1 // I2C driver for current control. Comment out to disable.
#define CURRENT_MCP44XX_ADDR 0b0101100 // Address of MCP44XX
#define CURRENT_WIPERS {0, 1, 6, 7}; // Wiper registers (X, Y, Z, A)
#define CURRENT_FACTOR 113.33 // Convert amps to digipot value
// Paste default settings definitions here.
#define DEFAULT_X_STEPS_PER_MM 160.0
#define DEFAULT_Y_STEPS_PER_MM 160.0
#define DEFAULT_Z_STEPS_PER_MM 160.0
#define DEFAULT_X_MAX_RATE 24000 // mm/min
#define DEFAULT_Y_MAX_RATE 24000 // mm/min
#define DEFAULT_Z_MAX_RATE 24000 // mm/min
#define DEFAULT_X_ACCELERATION (2500.0*60*60) // 5000*60*60 mm/min^2 = 5000 mm/sec^2
#define DEFAULT_Y_ACCELERATION (2500.0*60*60) // 5000*60*60 mm/min^2 = 5000 mm/sec^2
#define DEFAULT_Z_ACCELERATION (2500.0*60*60) // 5000*60*60 mm/min^2 = 5000 mm/sec^2
#define DEFAULT_X_CURRENT 0.0 // amps
#define DEFAULT_Y_CURRENT 0.0 // amps
#define DEFAULT_Z_CURRENT 0.0 // amps
#define DEFAULT_A_CURRENT 0.0 // amps
#define DEFAULT_X_MAX_TRAVEL 300.0 // mm
#define DEFAULT_Y_MAX_TRAVEL 200.0 // mm
#define DEFAULT_Z_MAX_TRAVEL 50.0 // mm
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
#define DEFAULT_STEPPING_INVERT_MASK 0
#define DEFAULT_DIRECTION_INVERT_MASK 0
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
#define DEFAULT_STATUS_REPORT_MASK 0 // WPos enabled
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
#define DEFAULT_REPORT_INCHES 0 // false
#define DEFAULT_INVERT_ST_ENABLE 0 // false
#define DEFAULT_INVERT_LIMIT_PINS 1 // false
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
#define DEFAULT_INVERT_PROBE_PIN 0 // false
#define DEFAULT_LASER_MODE 1 // true
#define DEFAULT_HOMING_ENABLE 0 // false
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
#define DEFAULT_HOMING_FEED_RATE 50.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 6000.0 // mm/min
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
#endif

View File

@ -144,11 +144,521 @@
// NOTE: On the 328p, these must be the same as the SPINDLE_ENABLE settings.
#define SPINDLE_PWM_DDR DDRB
#define SPINDLE_PWM_PORT PORTB
#define SPINDLE_PWM_PORT PORTB
#define SPINDLE_PWM_BIT 3 // Uno Digital Pin 11
#endif
#ifdef CPU_MAP_SMOOTHIEBOARD // (Smoothieboards)
// Define serial port pins and interrupt vectors.
#define SERIAL_RX USART_RX_vect
#define SERIAL_UDRE USART_UDRE_vect
// Define step pulse output pins. NOTE: All step bit pins must be on the same port.
#define STEP_DDR LPC_GPIO2->FIODIR
#define STEP_PORT LPC_GPIO2->FIOPIN
#define X_STEP_BIT 0
#define Y_STEP_BIT 1
#define Z_STEP_BIT 2
#define A_STEP_BIT 3
#define STEP_MASK ((1<<X_STEP_BIT)|(1<<Y_STEP_BIT)|(1<<Z_STEP_BIT)|(1<<A_STEP_BIT)) // All step bits
// Define step direction output pins. NOTE: All direction pins must be on the same port.
#define DIRECTION_DDR LPC_GPIO0->FIODIR
#define DIRECTION_PORT LPC_GPIO0->FIOPIN
#define X_DIRECTION_BIT 5
#define Y_DIRECTION_BIT 11
#define Z_DIRECTION_BIT 20
#define A_DIRECTION_BIT 22
#define DIRECTION_MASK ((1<<X_DIRECTION_BIT)|(1<<Y_DIRECTION_BIT)|(1<<Z_DIRECTION_BIT)|(1<<A_DIRECTION_BIT)) // All direction bits
// Define stepper driver enable/disable output pin.
#define STEPPERS_DISABLE_DDR LPC_GPIO0->FIODIR
#define STEPPERS_DISABLE_PORT LPC_GPIO0->FIOPIN
#define X_DISABLE_BIT 4
#define Y_DISABLE_BIT 10
#define Z_DISABLE_BIT 19
#define A_DISABLE_BIT 21
#define STEPPERS_DISABLE_MASK ((1<<X_DISABLE_BIT)|(1<<Y_DISABLE_BIT)|(1<<Z_DISABLE_BIT)|(1<<A_DISABLE_BIT))
// Define homing/hard limit switch input pins and limit interrupt vectors.
// NOTE: All limit bit pins must be on the same port, but not on a port with other input pins (CONTROL).
#define LIMIT_DDR LPC_GPIO1->FIODIR
#define LIMIT_PIN LPC_GPIO1->FIOPIN
#define LIMIT_PORT LPC_GPIO1->FIOPIN
#define X_LIMIT_BIT 24 // X-MIN=24, X-MAX=25
#define Y_LIMIT_BIT 26 // Y-MIN=26, Y-MAX=27
#define Z_LIMIT_BIT 28 // Z-MIN=28, Z-MAX=29
#define A_LIMIT_BIT 29 // reuse p1.29
#define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)|(1<<Z_LIMIT_BIT)|(1<<A_LIMIT_BIT)) // All limit bits
// Define flood and mist coolant enable output pins.
#define COOLANT_FLOOD_DDR LPC_GPIO2->FIODIR
#define COOLANT_FLOOD_PORT LPC_GPIO2->FIOPIN
#define COOLANT_FLOOD_BIT 4 // SMALL MOSFET Q8 (P2.4)
#define COOLANT_MIST_DDR LPC_GPIO2->FIODIR
#define COOLANT_MIST_PORT LPC_GPIO2->FIOPIN
#define COOLANT_MIST_BIT 6 // SMALL MOSFET Q9 (P2.6)
#define ENABLE_M7 // enables COOLANT MIST
// Define user-control controls (cycle start, reset, feed hold) input pins.
// NOTE: All CONTROLs pins must be on the same port and not on a port with other input pins (limits).
#define CONTROL_DDR NotUsed
#define CONTROL_PIN NotUsed
#define CONTROL_PORT NotUsed
#define CONTROL_RESET_BIT 0 // Uno Analog Pin 0
#define CONTROL_FEED_HOLD_BIT 1 // Uno Analog Pin 1
#define CONTROL_CYCLE_START_BIT 2 // Uno Analog Pin 2
#define CONTROL_SAFETY_DOOR_BIT 1 // Uno Analog Pin 1 NOTE: Safety door is shared with feed hold. Enabled by config define.
#define CONTROL_INT PCIE1 // Pin change interrupt enable pin
#define CONTROL_INT_vect PCINT1_vect
#define CONTROL_PCMSK NotUsed // Pin change interrupt register
#define CONTROL_MASK ((1<<CONTROL_RESET_BIT)|(1<<CONTROL_FEED_HOLD_BIT)|(1<<CONTROL_CYCLE_START_BIT)|(1<<CONTROL_SAFETY_DOOR_BIT))
#define CONTROL_INVERT_MASK CONTROL_MASK // May be re-defined to only invert certain control pins.
// Define probe switch input pin.
#define PROBE_DDR NotUsed
#define PROBE_PIN NotUsed
#define PROBE_PORT NotUsed
#define PROBE_BIT 5 // Uno Analog Pin 5
#define PROBE_MASK (1<<PROBE_BIT)
// The LPC17xx has 6 PWM channels. Each channel has 2 pins. It can drive both pins simultaneously to the same value.
//
// PWM Channel PWM1_CH1 PWM1_CH2 PWM1_CH3 PWM1_CH4 PWM1_CH5 PWM1_CH6
// Primary pin P1.18 P1.20 P1.21 P1.23 P1.24 P1.26
// Secondary pin P2.0 P2.1 P2.2 P2.3 P2.4 P2.5
#define SPINDLE_PWM_CHANNEL PWM1_CH6 // BIG MOSFET Q6 (P2.5)
#define SPINDLE_PWM_USE_PRIMARY_PIN false
#define SPINDLE_PWM_USE_SECONDARY_PIN true
// Stepper current control
#define CURRENT_I2C Driver_I2C1 // I2C driver for current control. Comment out to disable (for C3d boards!)
#define CURRENT_MCP44XX_ADDR 0b0101100 // Address of MCP44XX
#define CURRENT_WIPERS {0, 1, 6, 7}; // Wiper registers (X, Y, Z, A)
#define CURRENT_FACTOR 113.33 // Convert amps to digipot value
// Variable spindle configuration below. Do not change unless you know what you are doing.
// NOTE: Only used when variable spindle is enabled.
#define SPINDLE_PWM_MAX_VALUE 255 // Don't change. 328p fast PWM mode fixes top value as 255.
#ifndef SPINDLE_PWM_MIN_VALUE
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
//#define SPINDLE_PWM_OFF_VALUE 0 // Defined in config.h
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define SPINDLE_TCCRA_REGISTER TCCR2A
#define SPINDLE_TCCRB_REGISTER TCCR2B
#define SPINDLE_OCR_REGISTER OCR2A
#define SPINDLE_COMB_BIT COM2A1
#endif
#ifdef CPU_MAP_C3D_REMIX // (Cohesion3D Remix Boards)
// Define serial port pins and interrupt vectors.
#define SERIAL_RX USART_RX_vect
#define SERIAL_UDRE USART_UDRE_vect
// Define step pulse output pins. NOTE: All step bit pins must be on the same port.
#define STEP_DDR LPC_GPIO2->FIODIR
#define STEP_PORT LPC_GPIO2->FIOPIN
#define X_STEP_BIT 0
#define Y_STEP_BIT 1
#define Z_STEP_BIT 2
#define A_STEP_BIT 3
#define STEP_MASK ((1<<X_STEP_BIT)|(1<<Y_STEP_BIT)|(1<<Z_STEP_BIT)|(1<<A_STEP_BIT)) // All step bits
// Define step direction output pins. NOTE: All direction pins must be on the same port.
#define DIRECTION_DDR LPC_GPIO0->FIODIR
#define DIRECTION_PORT LPC_GPIO0->FIOPIN
#define X_DIRECTION_BIT 5
#define Y_DIRECTION_BIT 11
#define Z_DIRECTION_BIT 20
#define A_DIRECTION_BIT 22
#define DIRECTION_MASK ((1<<X_DIRECTION_BIT)|(1<<Y_DIRECTION_BIT)|(1<<Z_DIRECTION_BIT)|(1<<A_DIRECTION_BIT)) // All direction bits
// Define stepper driver enable/disable output pin.
#define STEPPERS_DISABLE_DDR LPC_GPIO0->FIODIR
#define STEPPERS_DISABLE_PORT LPC_GPIO0->FIOPIN
#define X_DISABLE_BIT 4
#define Y_DISABLE_BIT 10
#define Z_DISABLE_BIT 19
#define A_DISABLE_BIT 21
#define STEPPERS_DISABLE_MASK ((1<<X_DISABLE_BIT)|(1<<Y_DISABLE_BIT)|(1<<Z_DISABLE_BIT)|(1<<A_DISABLE_BIT))
// Define homing/hard limit switch input pins and limit interrupt vectors.
// NOTE: All limit bit pins must be on the same port, but not on a port with other input pins (CONTROL).
#define LIMIT_DDR LPC_GPIO1->FIODIR
#define LIMIT_PIN LPC_GPIO1->FIOPIN
#define LIMIT_PORT LPC_GPIO1->FIOPIN
#define X_LIMIT_BIT 24 // X-MIN=24, X-MAX=25
#define Y_LIMIT_BIT 26 // Y-MIN=26, Y-MAX=27
#define Z_LIMIT_BIT 28 // Z-MIN=28, Z-MAX=29
#define A_LIMIT_BIT 29 // reuse p1.29 from Z-MAX
#define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)|(1<<Z_LIMIT_BIT)|(1<<A_LIMIT_BIT)) // All limit bits
// Define flood and mist coolant enable output pins.
#define COOLANT_FLOOD_DDR LPC_GPIO2->FIODIR
#define COOLANT_FLOOD_PORT LPC_GPIO2->FIOPIN
#define COOLANT_FLOOD_BIT 6 // MOSFET 2.6
#define COOLANT_MIST_DDR LPC_GPIO2->FIODIR
#define COOLANT_MIST_PORT LPC_GPIO2->FIOPIN
#define COOLANT_MIST_BIT 7 // MOSFET 2.7
#define ENABLE_M7 // enables COOLANT MIST
// Define user-control controls (cycle start, reset, feed hold) input pins.
// NOTE: All CONTROLs pins must be on the same port and not on a port with other input pins (limits).
#define CONTROL_DDR NotUsed
#define CONTROL_PIN NotUsed
#define CONTROL_PORT NotUsed
#define CONTROL_RESET_BIT 0 // Uno Analog Pin 0
#define CONTROL_FEED_HOLD_BIT 1 // Uno Analog Pin 1
#define CONTROL_CYCLE_START_BIT 2 // Uno Analog Pin 2
#define CONTROL_SAFETY_DOOR_BIT 1 // Uno Analog Pin 1 NOTE: Safety door is shared with feed hold. Enabled by config define.
#define CONTROL_INT PCIE1 // Pin change interrupt enable pin
#define CONTROL_INT_vect PCINT1_vect
#define CONTROL_PCMSK NotUsed // Pin change interrupt register
#define CONTROL_MASK ((1<<CONTROL_RESET_BIT)|(1<<CONTROL_FEED_HOLD_BIT)|(1<<CONTROL_CYCLE_START_BIT)|(1<<CONTROL_SAFETY_DOOR_BIT))
#define CONTROL_INVERT_MASK CONTROL_MASK // May be re-defined to only invert certain control pins.
// Define probe switch input pin.
#define PROBE_DDR NotUsed
#define PROBE_PIN NotUsed
#define PROBE_PORT NotUsed
#define PROBE_BIT 5 // Uno Analog Pin 5
#define PROBE_MASK (1<<PROBE_BIT)
// The LPC17xx has 6 PWM channels. Each channel has 2 pins. It can drive both pins simultaneously to the same value.
//
// PWM Channel PWM1_CH1 PWM1_CH2 PWM1_CH3 PWM1_CH4 PWM1_CH5 PWM1_CH6
// Primary pin P1.18 P1.20 P1.21 P1.23 P1.24 P1.26
// Secondary pin P2.0 P2.1 P2.2 P2.3 P2.4 P2.5
#define SPINDLE_PWM_CHANNEL PWM1_CH6 // BED MOSFET (P2.5)
#define SPINDLE_PWM_USE_PRIMARY_PIN false
#define SPINDLE_PWM_USE_SECONDARY_PIN true
// Variable spindle configuration below. Do not change unless you know what you are doing.
// NOTE: Only used when variable spindle is enabled.
#define SPINDLE_PWM_MAX_VALUE 255 // Don't change. 328p fast PWM mode fixes top value as 255.
#ifndef SPINDLE_PWM_MIN_VALUE
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
//#define SPINDLE_PWM_OFF_VALUE 0 // Defined in config.h
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define SPINDLE_TCCRA_REGISTER TCCR2A
#define SPINDLE_TCCRB_REGISTER TCCR2B
#define SPINDLE_OCR_REGISTER OCR2A
#define SPINDLE_COMB_BIT COM2A1
#endif
#ifdef CPU_MAP_C3D_MINI // (Cohesion3D Mini Boards)
// Define serial port pins and interrupt vectors.
#define SERIAL_RX USART_RX_vect
#define SERIAL_UDRE USART_UDRE_vect
// Define step pulse output pins. NOTE: All step bit pins must be on the same port.
#define STEP_DDR LPC_GPIO2->FIODIR
#define STEP_PORT LPC_GPIO2->FIOPIN
#define X_STEP_BIT 0
#define Y_STEP_BIT 1
#define Z_STEP_BIT 2
#define A_STEP_BIT 3
#define STEP_MASK ((1<<X_STEP_BIT)|(1<<Y_STEP_BIT)|(1<<Z_STEP_BIT)|(1<<A_STEP_BIT)) // All step bits
// Define step direction output pins. NOTE: All direction pins must be on the same port.
#define DIRECTION_DDR LPC_GPIO0->FIODIR
#define DIRECTION_PORT LPC_GPIO0->FIOPIN
#define X_DIRECTION_BIT 5
#define Y_DIRECTION_BIT 11
#define Z_DIRECTION_BIT 20
#define A_DIRECTION_BIT 22
#define DIRECTION_MASK ((1<<X_DIRECTION_BIT)|(1<<Y_DIRECTION_BIT)|(1<<Z_DIRECTION_BIT)|(1<<A_DIRECTION_BIT)) // All direction bits
// Define stepper driver enable/disable output pin.
#define STEPPERS_DISABLE_DDR LPC_GPIO0->FIODIR
#define STEPPERS_DISABLE_PORT LPC_GPIO0->FIOPIN
#define X_DISABLE_BIT 4
#define Y_DISABLE_BIT 10
#define Z_DISABLE_BIT 19
#define A_DISABLE_BIT 21
#define STEPPERS_DISABLE_MASK ((1<<X_DISABLE_BIT)|(1<<Y_DISABLE_BIT)|(1<<Z_DISABLE_BIT)|(1<<A_DISABLE_BIT))
// Define homing/hard limit switch input pins and limit interrupt vectors.
// NOTE: All limit bit pins must be on the same port, but not on a port with other input pins (CONTROL).
#define LIMIT_DDR LPC_GPIO1->FIODIR
#define LIMIT_PIN LPC_GPIO1->FIOPIN
#define LIMIT_PORT LPC_GPIO1->FIOPIN
#define X_LIMIT_BIT 24 // X-MIN=24, X-MAX=25
#define Y_LIMIT_BIT 26 // Y-MIN=26, Y-MAX=27
#define Z_LIMIT_BIT 28 // Z-MIN=28, Z-MAX=29
#define A_LIMIT_BIT 29 // reuse p1.29 from Z-MAX
#define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)|(1<<Z_LIMIT_BIT)|(1<<A_LIMIT_BIT)) // All limit bits
// Define flood and mist coolant enable output pins.
#define COOLANT_FLOOD_DDR NotUsed
#define COOLANT_FLOOD_PORT NotUsed
#define COOLANT_FLOOD_BIT 6 // not available
#define COOLANT_MIST_DDR LPC_GPIO2->FIODIR
#define COOLANT_MIST_PORT LPC_GPIO2->FIOPIN
#define COOLANT_MIST_BIT 7 // MOSFET 2 (P2.7)
#define ENABLE_M7 // enables COOLANT MIST
// Define user-control controls (cycle start, reset, feed hold) input pins.
// NOTE: All CONTROLs pins must be on the same port and not on a port with other input pins (limits).
#define CONTROL_DDR NotUsed
#define CONTROL_PIN NotUsed
#define CONTROL_PORT NotUsed
#define CONTROL_RESET_BIT 0 // Uno Analog Pin 0
#define CONTROL_FEED_HOLD_BIT 1 // Uno Analog Pin 1
#define CONTROL_CYCLE_START_BIT 2 // Uno Analog Pin 2
#define CONTROL_SAFETY_DOOR_BIT 1 // Uno Analog Pin 1 NOTE: Safety door is shared with feed hold. Enabled by config define.
#define CONTROL_INT PCIE1 // Pin change interrupt enable pin
#define CONTROL_INT_vect PCINT1_vect
#define CONTROL_PCMSK NotUsed // Pin change interrupt register
#define CONTROL_MASK ((1<<CONTROL_RESET_BIT)|(1<<CONTROL_FEED_HOLD_BIT)|(1<<CONTROL_CYCLE_START_BIT)|(1<<CONTROL_SAFETY_DOOR_BIT))
#define CONTROL_INVERT_MASK CONTROL_MASK // May be re-defined to only invert certain control pins.
// Define probe switch input pin.
#define PROBE_DDR NotUsed
#define PROBE_PIN NotUsed
#define PROBE_PORT NotUsed
#define PROBE_BIT 5 // Uno Analog Pin 5
#define PROBE_MASK (1<<PROBE_BIT)
// The LPC17xx has 6 PWM channels. Each channel has 2 pins. It can drive both pins simultaneously to the same value.
//
// PWM Channel PWM1_CH1 PWM1_CH2 PWM1_CH3 PWM1_CH4 PWM1_CH5 PWM1_CH6
// Primary pin P1.18 P1.20 P1.21 P1.23 P1.24 P1.26
// Secondary pin P2.0 P2.1 P2.2 P2.3 P2.4 P2.5
#define SPINDLE_PWM_CHANNEL PWM1_CH6 // BED MOSFET (P2.5)
#define SPINDLE_PWM_USE_PRIMARY_PIN false
#define SPINDLE_PWM_USE_SECONDARY_PIN true
// Variable spindle configuration below. Do not change unless you know what you are doing.
// NOTE: Only used when variable spindle is enabled.
#define SPINDLE_PWM_MAX_VALUE 255 // Don't change. 328p fast PWM mode fixes top value as 255.
#ifndef SPINDLE_PWM_MIN_VALUE
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
//#define SPINDLE_PWM_OFF_VALUE 0 // Defined in config.h
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define SPINDLE_TCCRA_REGISTER TCCR2A
#define SPINDLE_TCCRB_REGISTER TCCR2B
#define SPINDLE_OCR_REGISTER OCR2A
#define SPINDLE_COMB_BIT COM2A1
#endif
#ifdef CPU_MAP_MKS_SBASE // (MKS SBASE Boards)
// Define serial port pins and interrupt vectors.
#define SERIAL_RX USART_RX_vect
#define SERIAL_UDRE USART_UDRE_vect
// Define step pulse output pins. NOTE: All step bit pins must be on the same port.
#define STEP_DDR LPC_GPIO2->FIODIR
#define STEP_PORT LPC_GPIO2->FIOPIN
#define X_STEP_BIT 0
#define Y_STEP_BIT 1
#define Z_STEP_BIT 2
#define A_STEP_BIT 3
#define STEP_MASK ((1<<X_STEP_BIT)|(1<<Y_STEP_BIT)|(1<<Z_STEP_BIT)|(1<<A_STEP_BIT)) // All step bits
// Define step direction output pins. NOTE: All direction pins must be on the same port.
#define DIRECTION_DDR LPC_GPIO0->FIODIR
#define DIRECTION_PORT LPC_GPIO0->FIOPIN
#define X_DIRECTION_BIT 5
#define Y_DIRECTION_BIT 11
#define Z_DIRECTION_BIT 20
#define A_DIRECTION_BIT 22
#define DIRECTION_MASK ((1<<X_DIRECTION_BIT)|(1<<Y_DIRECTION_BIT)|(1<<Z_DIRECTION_BIT)|(1<<A_DIRECTION_BIT)) // All direction bits
// Define stepper driver enable/disable output pin.
#define STEPPERS_DISABLE_DDR LPC_GPIO0->FIODIR
#define STEPPERS_DISABLE_PORT LPC_GPIO0->FIOPIN
#define X_DISABLE_BIT 4
#define Y_DISABLE_BIT 10
#define Z_DISABLE_BIT 19
#define A_DISABLE_BIT 21
#define STEPPERS_DISABLE_MASK ((1<<X_DISABLE_BIT)|(1<<Y_DISABLE_BIT)|(1<<Z_DISABLE_BIT)|(1<<A_DISABLE_BIT))
// Define homing/hard limit switch input pins and limit interrupt vectors.
// NOTE: All limit bit pins must be on the same port, but not on a port with other input pins (CONTROL).
#define LIMIT_DDR LPC_GPIO1->FIODIR
#define LIMIT_PIN LPC_GPIO1->FIOPIN
#define LIMIT_PORT LPC_GPIO1->FIOPIN
#define X_LIMIT_BIT 24 // X-MIN=24, X-MAX=25
#define Y_LIMIT_BIT 26 // Y-MIN=26, Y-MAX=27
#define Z_LIMIT_BIT 28 // Z-MIN=28, Z-MAX=29
#define A_LIMIT_BIT 29 // reuse p1.29
#define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)|(1<<Z_LIMIT_BIT)|(1<<A_LIMIT_BIT)) // All limit bits
// Define flood and mist coolant enable output pins.
#define COOLANT_FLOOD_DDR LPC_GPIO2->FIODIR
#define COOLANT_FLOOD_PORT LPC_GPIO2->FIOPIN
#define COOLANT_FLOOD_BIT 6 // MOSFET 2.6
#define COOLANT_MIST_DDR LPC_GPIO2->FIODIR
#define COOLANT_MIST_PORT LPC_GPIO2->FIOPIN
#define COOLANT_MIST_BIT 7 // MOSFET 2.7
#define ENABLE_M7 // enables COOLANT MIST
// Define user-control controls (cycle start, reset, feed hold) input pins.
// NOTE: All CONTROLs pins must be on the same port and not on a port with other input pins (limits).
#define CONTROL_DDR NotUsed
#define CONTROL_PIN NotUsed
#define CONTROL_PORT NotUsed
#define CONTROL_RESET_BIT 0 // Uno Analog Pin 0
#define CONTROL_FEED_HOLD_BIT 1 // Uno Analog Pin 1
#define CONTROL_CYCLE_START_BIT 2 // Uno Analog Pin 2
#define CONTROL_SAFETY_DOOR_BIT 1 // Uno Analog Pin 1 NOTE: Safety door is shared with feed hold. Enabled by config define.
#define CONTROL_INT PCIE1 // Pin change interrupt enable pin
#define CONTROL_INT_vect PCINT1_vect
#define CONTROL_PCMSK NotUsed // Pin change interrupt register
#define CONTROL_MASK ((1<<CONTROL_RESET_BIT)|(1<<CONTROL_FEED_HOLD_BIT)|(1<<CONTROL_CYCLE_START_BIT)|(1<<CONTROL_SAFETY_DOOR_BIT))
#define CONTROL_INVERT_MASK CONTROL_MASK // May be re-defined to only invert certain control pins.
// Define probe switch input pin.
#define PROBE_DDR NotUsed
#define PROBE_PIN NotUsed
#define PROBE_PORT NotUsed
#define PROBE_BIT 5 // Uno Analog Pin 5
#define PROBE_MASK (1<<PROBE_BIT)
// The LPC17xx has 6 PWM channels. Each channel has 2 pins. It can drive both pins simultaneously to the same value.
//
// PWM Channel PWM1_CH1 PWM1_CH2 PWM1_CH3 PWM1_CH4 PWM1_CH5 PWM1_CH6
// Primary pin P1.18 P1.20 P1.21 P1.23 P1.24 P1.26
// Secondary pin P2.0 P2.1 P2.2 P2.3 P2.4 P2.5
#define SPINDLE_PWM_CHANNEL PWM1_CH6
#define SPINDLE_PWM_USE_PRIMARY_PIN false
#define SPINDLE_PWM_USE_SECONDARY_PIN true
// Stepper current control
#define CURRENT_I2C Driver_I2C1 // I2C driver for current control. Comment out to disable (for C3d boards!)
#define CURRENT_MCP44XX_ADDR 0b0101100 // Address of MCP44XX
#define CURRENT_WIPERS {0, 1, 6, 7}; // Wiper registers (X, Y, Z, A)
#define CURRENT_FACTOR 113.33 // Convert amps to digipot value
// Variable spindle configuration below. Do not change unless you know what you are doing.
// NOTE: Only used when variable spindle is enabled.
#define SPINDLE_PWM_MAX_VALUE 255 // Don't change. 328p fast PWM mode fixes top value as 255.
#ifndef SPINDLE_PWM_MIN_VALUE
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
//#define SPINDLE_PWM_OFF_VALUE 0 // Defined in config.h
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define SPINDLE_TCCRA_REGISTER TCCR2A
#define SPINDLE_TCCRB_REGISTER TCCR2B
#define SPINDLE_OCR_REGISTER OCR2A
#define SPINDLE_COMB_BIT COM2A1
#endif
#ifdef CPU_MAP_AZTEEG_X5 // (Azteeg X5 Boards) not tested yet!
// Define serial port pins and interrupt vectors.
#define SERIAL_RX USART_RX_vect
#define SERIAL_UDRE USART_UDRE_vect
// Define step pulse output pins. NOTE: All step bit pins must be on the same port.
#define STEP_DDR LPC_GPIO2->FIODIR
#define STEP_PORT LPC_GPIO2->FIOPIN
#define X_STEP_BIT 1
#define Y_STEP_BIT 2
#define Z_STEP_BIT 3
#define A_STEP_BIT 0
#define STEP_MASK ((1<<X_STEP_BIT)|(1<<Y_STEP_BIT)|(1<<Z_STEP_BIT)|(1<<A_STEP_BIT)) // All step bits
// Define step direction output pins. NOTE: All direction pins must be on the same port.
#define DIRECTION_DDR LPC_GPIO0->FIODIR
#define DIRECTION_PORT LPC_GPIO0->FIOPIN
#define X_DIRECTION_BIT 11
#define Y_DIRECTION_BIT 20
#define Z_DIRECTION_BIT 22
#define A_DIRECTION_BIT 5
#define DIRECTION_MASK ((1<<X_DIRECTION_BIT)|(1<<Y_DIRECTION_BIT)|(1<<Z_DIRECTION_BIT)|(1<<A_DIRECTION_BIT)) // All direction bits
// Define stepper driver enable/disable output pin.
#define STEPPERS_DISABLE_DDR LPC_GPIO0->FIODIR
#define STEPPERS_DISABLE_PORT LPC_GPIO0->FIOPIN
#define X_DISABLE_BIT 10
#define Y_DISABLE_BIT 19
#define Z_DISABLE_BIT 21
#define A_DISABLE_BIT 4
#define STEPPERS_DISABLE_MASK ((1<<X_DISABLE_BIT)|(1<<Y_DISABLE_BIT)|(1<<Z_DISABLE_BIT)|(1<<A_DISABLE_BIT))
// Define homing/hard limit switch input pins and limit interrupt vectors.
// NOTE: All limit bit pins must be on the same port, but not on a port with other input pins (CONTROL).
#define LIMIT_DDR LPC_GPIO1->FIODIR
#define LIMIT_PIN LPC_GPIO1->FIOPIN
#define LIMIT_PORT LPC_GPIO1->FIOPIN
#define X_LIMIT_BIT 24 // X-MIN=24, X-MAX=27
#define Y_LIMIT_BIT 25 // Y-MIN=25, Y-MAX=28
#define Z_LIMIT_BIT 26 // Z-MIN=26, Z-MAX=29
#define A_LIMIT_BIT 27 // reuse p1.27, as X-MAX is not used
#define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)|(1<<Z_LIMIT_BIT)|(1<<A_LIMIT_BIT)) // All limit bits
// Define flood and mist coolant enable output pins.
#define COOLANT_FLOOD_DDR LPC_GPIO2->FIODIR
#define COOLANT_FLOOD_PORT LPC_GPIO2->FIOPIN
#define COOLANT_FLOOD_BIT 4 // FAN MOSFET (P2.4)
#define COOLANT_MIST_DDR LPC_GPIO2->FIODIR
#define COOLANT_MIST_PORT LPC_GPIO2->FIOPIN
#define COOLANT_MIST_BIT 7 // BED MOSFET (P2.7)
#define ENABLE_M7 // enables COOLANT MIST
// Define user-control controls (cycle start, reset, feed hold) input pins.
// NOTE: All CONTROLs pins must be on the same port and not on a port with other input pins (limits).
#define CONTROL_DDR NotUsed
#define CONTROL_PIN NotUsed
#define CONTROL_PORT NotUsed
#define CONTROL_RESET_BIT 0 // Uno Analog Pin 0
#define CONTROL_FEED_HOLD_BIT 1 // Uno Analog Pin 1
#define CONTROL_CYCLE_START_BIT 2 // Uno Analog Pin 2
#define CONTROL_SAFETY_DOOR_BIT 1 // Uno Analog Pin 1 NOTE: Safety door is shared with feed hold. Enabled by config define.
#define CONTROL_INT PCIE1 // Pin change interrupt enable pin
#define CONTROL_INT_vect PCINT1_vect
#define CONTROL_PCMSK NotUsed // Pin change interrupt register
#define CONTROL_MASK ((1<<CONTROL_RESET_BIT)|(1<<CONTROL_FEED_HOLD_BIT)|(1<<CONTROL_CYCLE_START_BIT)|(1<<CONTROL_SAFETY_DOOR_BIT))
#define CONTROL_INVERT_MASK CONTROL_MASK // May be re-defined to only invert certain control pins.
// Define probe switch input pin.
#define PROBE_DDR NotUsed
#define PROBE_PIN NotUsed
#define PROBE_PORT NotUsed
#define PROBE_BIT 5 // Uno Analog Pin 5
#define PROBE_MASK (1<<PROBE_BIT)
// The LPC17xx has 6 PWM channels. Each channel has 2 pins. It can drive both pins simultaneously to the same value.
//
// PWM Channel PWM1_CH1 PWM1_CH2 PWM1_CH3 PWM1_CH4 PWM1_CH5 PWM1_CH6
// Primary pin P1.18 P1.20 P1.21 P1.23 P1.24 P1.26
// Secondary pin P2.0 P2.1 P2.2 P2.3 P2.4 P2.5
#define SPINDLE_PWM_CHANNEL PWM1_CH6 // use Hotend MOSFET (P2.5)
#define SPINDLE_PWM_USE_PRIMARY_PIN false
#define SPINDLE_PWM_USE_SECONDARY_PIN true
// Stepper current control via SPI not ported yet!
// Variable spindle configuration below. Do not change unless you know what you are doing.
// NOTE: Only used when variable spindle is enabled.
#define SPINDLE_PWM_MAX_VALUE 255 // Don't change. 328p fast PWM mode fixes top value as 255.
#ifndef SPINDLE_PWM_MIN_VALUE
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
//#define SPINDLE_PWM_OFF_VALUE 0 // Defined in config.h
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define SPINDLE_TCCRA_REGISTER TCCR2A
#define SPINDLE_TCCRB_REGISTER TCCR2B
#define SPINDLE_OCR_REGISTER OCR2A
#define SPINDLE_COMB_BIT COM2A1
#endif
/*
#ifdef CPU_MAP_CUSTOM_PROC
// For a custom pin map or different processor, copy and edit one of the available cpu

View File

@ -32,81 +32,153 @@
#define DEFAULT_X_STEPS_PER_MM 250.0
#define DEFAULT_Y_STEPS_PER_MM 250.0
#define DEFAULT_Z_STEPS_PER_MM 250.0
#define DEFAULT_A_STEPS_PER_MM 160.0
#define DEFAULT_X_MAX_RATE 500.0 // mm/min
#define DEFAULT_Y_MAX_RATE 500.0 // mm/min
#define DEFAULT_Z_MAX_RATE 500.0 // mm/min
#define DEFAULT_A_MAX_RATE 500.0 // mm/min
#define DEFAULT_X_ACCELERATION (10.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Y_ACCELERATION (10.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Z_ACCELERATION (10.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_A_ACCELERATION (10.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_X_CURRENT 0.6 // amps
#define DEFAULT_Y_CURRENT 0.6 // amps
#define DEFAULT_Z_CURRENT 0.0 // amps
#define DEFAULT_A_CURRENT 0.0 // amps
#define DEFAULT_X_MAX_TRAVEL 200.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 200.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 200.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_A_MAX_TRAVEL 1.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_PWM_OFF_VALUE 0 // %
#define DEFAULT_SPINDLE_PWM_MIN_VALUE 1 // %
#define DEFAULT_SPINDLE_PWM_MAX_VALUE 100 // %
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm (S-value)
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm (S-value)
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
#define DEFAULT_STEPPING_INVERT_MASK 0
#define DEFAULT_DIRECTION_INVERT_MASK 0
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
#define DEFAULT_REPORT_INCHES 0 // false
#define DEFAULT_INVERT_ST_ENABLE 0 // false
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
#define DEFAULT_INVERT_PROBE_PIN 0 // false
#define DEFAULT_LASER_MODE 0 // false
#define DEFAULT_HOMING_ENABLE 0 // false
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 500.0 // mm/min
#define DEFAULT_STATUS_REPORT_MASK 0 // WPos enabled
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
#define DEFAULT_REPORT_INCHES 0 // false
#define DEFAULT_INVERT_ST_ENABLE 0 // false
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
#define DEFAULT_INVERT_PROBE_PIN 0 // false
#define DEFAULT_LASER_MODE 0 // false
#define DEFAULT_HOMING_ENABLE 0 // false
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 500.0 // mm/min
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
#define HOMING_CYCLE_0 ((1<<X_AXIS)|(1<<Y_AXIS))
#endif
#ifdef DEFAULTS_K40
// Description: K40 Lasercutter (typical chinese 40W CO2 laser cutter/engraver)
#define DEFAULT_X_STEPS_PER_MM 160.0
#define DEFAULT_X_STEPS_PER_MM 160.0 // 200 stepps/rev. * 32 microstepps / 40mm/rev
#define DEFAULT_Y_STEPS_PER_MM 160.0
#define DEFAULT_Z_STEPS_PER_MM 160.0
#define DEFAULT_X_MAX_RATE 24000.0 // mm/min
#define DEFAULT_Y_MAX_RATE 24000.0 // mm/min
#define DEFAULT_Z_MAX_RATE 24000.0 // mm/min
#define DEFAULT_X_ACCELERATION (2500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Y_ACCELERATION (2500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Z_ACCELERATION (2500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_X_CURRENT 0.0 // amps
#define DEFAULT_Y_CURRENT 0.0 // amps
#define DEFAULT_Z_CURRENT 0.0 // amps
#define DEFAULT_A_CURRENT 0.0 // amps
#define DEFAULT_X_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 200.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 50.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_A_STEPS_PER_MM 160.0
#define DEFAULT_X_MAX_RATE 24000.0 // mm/min
#define DEFAULT_Y_MAX_RATE 24000.0 // mm/min
#define DEFAULT_Z_MAX_RATE 24000.0 // mm/min
#define DEFAULT_A_MAX_RATE 24000.0 // mm/min
#define DEFAULT_X_ACCELERATION (2500.0*60*60) // 2500*60*60 mm/min^2 = 2500 mm/sec^2
#define DEFAULT_Y_ACCELERATION (2500.0*60*60) // 2500*60*60 mm/min^2 = 2500 mm/sec^2
#define DEFAULT_Z_ACCELERATION (2500.0*60*60) // 2500*60*60 mm/min^2 = 2500 mm/sec^2
#define DEFAULT_A_ACCELERATION (2500.0*60*60) // 2500*60*60 mm/min^2 = 2500 mm/sec^2
#define DEFAULT_X_CURRENT 0.6 // amps
#define DEFAULT_Y_CURRENT 0.6 // amps
#define DEFAULT_Z_CURRENT 0.0 // amps
#define DEFAULT_A_CURRENT 0.0 // amps
#define DEFAULT_X_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 200.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 50.0 // mm NOTE: Must be a positive value.
#define DEFAULT_A_MAX_TRAVEL 100.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz (2000 - 20000)
#define DEFAULT_SPINDLE_PWM_OFF_VALUE 0 // %
#define DEFAULT_SPINDLE_PWM_MIN_VALUE 1 // %
#define DEFAULT_SPINDLE_PWM_MAX_VALUE 100 // %
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm (S-value)
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm (S-value)
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
#define DEFAULT_STEPPING_INVERT_MASK 0
#define DEFAULT_DIRECTION_INVERT_MASK 0
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
#define DEFAULT_STATUS_REPORT_MASK 0 // WPos enabled
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
#define DEFAULT_REPORT_INCHES 0 // false
#define DEFAULT_INVERT_ST_ENABLE 0 // false
#define DEFAULT_INVERT_LIMIT_PINS 1 // false
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
#define DEFAULT_INVERT_PROBE_PIN 0 // false
#define DEFAULT_LASER_MODE 1 // false
#define DEFAULT_HOMING_ENABLE 0 // false
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
#define DEFAULT_HOMING_FEED_RATE 50.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 6000.0 // mm/min
#define DEFAULT_DIRECTION_INVERT_MASK 3 // 3 = invert X+Y
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255// msec (0-254, 255 keeps steppers enabled)
#define DEFAULT_STATUS_REPORT_MASK 0 // WPos enabled
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
#define DEFAULT_REPORT_INCHES 0 // false
#define DEFAULT_INVERT_ST_ENABLE 0 // false
#define DEFAULT_INVERT_LIMIT_PINS 1 // true for microswitches / false for optical sensors
#define DEFAULT_SOFT_LIMIT_ENABLE 1 // true
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
#define DEFAULT_INVERT_PROBE_PIN 0 // false
#define DEFAULT_LASER_MODE 1 // true
#define DEFAULT_HOMING_ENABLE 1 // true
#define DEFAULT_HOMING_DIR_MASK 1 // move top/left
#define DEFAULT_HOMING_FEED_RATE 50.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 6000.0 // mm/min
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
#define DEFAULT_HOMING_PULLOFF 2.0 // mm
#define HOMING_CYCLE_0 ((1<<X_AXIS)|(1<<Y_AXIS))
#endif
#ifdef DEFAULTS_FABKIT
// Paste default settings definitions here.
#define DEFAULT_X_STEPS_PER_MM 80.0
#define DEFAULT_Y_STEPS_PER_MM 80.0
#define DEFAULT_Z_STEPS_PER_MM 640.0
#define DEFAULT_A_STEPS_PER_MM 160.0
#define DEFAULT_X_MAX_RATE 30000 // mm/min
#define DEFAULT_Y_MAX_RATE 4500 // mm/min
#define DEFAULT_Z_MAX_RATE 1200 // mm/min
#define DEFAULT_A_MAX_RATE 24000.0 // mm/min
#define DEFAULT_X_ACCELERATION (4000.0*60*60) // 4000*60*60 mm/min^2 = 4000 mm/sec^2
#define DEFAULT_Y_ACCELERATION (250.0*60*60) // 250*60*60 mm/min^2 = 250 mm/sec^2
#define DEFAULT_Z_ACCELERATION (150.0*60*60) // 150*60*60 mm/min^2 = 150 mm/sec^2
#define DEFAULT_A_ACCELERATION (150.0*60*60) // 150*60*60 mm/min^2 = 150 mm/sec^2
#define DEFAULT_X_CURRENT 1.5 // amps
#define DEFAULT_Y_CURRENT 1.5 // amps
#define DEFAULT_Z_CURRENT 1.5 // amps
#define DEFAULT_A_CURRENT 0.0 // amps
#define DEFAULT_X_MAX_TRAVEL 680.0 // mm
#define DEFAULT_Y_MAX_TRAVEL 460.0 // mm
#define DEFAULT_Z_MAX_TRAVEL 150.0 // mm
#define DEFAULT_A_MAX_TRAVEL 150.0 // mm
#define DEFAULT_SPINDLE_PWM_FREQ 50000 // Hz
#define DEFAULT_SPINDLE_PWM_OFF_VALUE 0 // %
#define DEFAULT_SPINDLE_PWM_MIN_VALUE 0 // %
#define DEFAULT_SPINDLE_PWM_MAX_VALUE 100 // %
#define DEFAULT_SPINDLE_RPM_MAX 0.7 // rpm (S-value)
#define DEFAULT_SPINDLE_RPM_MIN 0.08 // rpm (S-value)
#define DEFAULT_STEP_PULSE_MICROSECONDS 1
#define DEFAULT_STEPPING_INVERT_MASK 0
#define DEFAULT_DIRECTION_INVERT_MASK 2 // 2 = invert Y
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255// msec (0-254, 255 keeps steppers enabled)
#define DEFAULT_STATUS_REPORT_MASK 0 // WPos enabled
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
#define DEFAULT_REPORT_INCHES 0 // false
#define DEFAULT_INVERT_ST_ENABLE 0 // false
#define DEFAULT_INVERT_LIMIT_PINS 1 // true
#define DEFAULT_SOFT_LIMIT_ENABLE 1 // true
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
#define DEFAULT_INVERT_PROBE_PIN 0 // false
#define DEFAULT_LASER_MODE 1 // true
#define DEFAULT_HOMING_ENABLE 1 // true
#define DEFAULT_HOMING_DIR_MASK 1 // move top/left
#define DEFAULT_HOMING_FEED_RATE 60.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 6000.0 // mm/min
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
#define DEFAULT_HOMING_PULLOFF 2.0 // mm
#define HOMING_CYCLE_0 (1<<Z_AXIS)
#define HOMING_CYCLE_1 ((1<<X_AXIS)|(1<<Y_AXIS))
#endif
#ifdef DEFAULTS_SHERLINE_5400
@ -127,6 +199,7 @@
#define DEFAULT_X_MAX_TRAVEL 225.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 125.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 170.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_RPM_MAX 2800.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
@ -172,6 +245,7 @@
#define DEFAULT_X_MAX_TRAVEL 200.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 200.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 200.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
@ -217,6 +291,7 @@
#define DEFAULT_X_MAX_TRAVEL 290.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 290.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 100.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
@ -261,6 +336,7 @@
#define DEFAULT_X_MAX_TRAVEL 425.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 465.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 80.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
@ -306,6 +382,7 @@
#define DEFAULT_X_MAX_TRAVEL 290.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 290.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 100.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
@ -351,6 +428,7 @@
#define DEFAULT_X_MAX_TRAVEL 740.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 790.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 100.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
@ -394,6 +472,7 @@
#define DEFAULT_X_MAX_TRAVEL 190.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 180.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 150.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
@ -433,6 +512,7 @@
#define DEFAULT_X_MAX_TRAVEL 500.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 750.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 80.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
@ -472,6 +552,7 @@
#define DEFAULT_X_MAX_TRAVEL 1000.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 1000.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 1000.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_STEP_PULSE_MICROSECONDS 10

View File

@ -80,7 +80,7 @@ uint8_t gc_execute_line(char *line)
uint8_t coord_select = 0; // Tracks G10 P coordinate selection for execution
// Initialize bitflag tracking variables for axis indices compatible operations.
uint8_t axis_words = 0; // XYZ tracking
uint8_t axis_words = 0; // XYZA tracking
uint8_t ijk_words = 0; // IJK tracking
// Initialize command and value words and parser flags variables.
@ -296,7 +296,7 @@ uint8_t gc_execute_line(char *line)
legal g-code words and stores their value. Error-checking is performed later since some
words (I,J,K,L,P,R) have multiple connotations and/or depend on the issued commands. */
switch(letter){
// case 'A': // Not supported
case 'A': word_bit = WORD_A; gc_block.values.xyza[A_AXIS] = value; axis_words |= (1<<A_AXIS); break;
// case 'B': // Not supported
// case 'C': // Not supported
// case 'D': // Not supported
@ -316,9 +316,9 @@ uint8_t gc_execute_line(char *line)
if (value > MAX_TOOL_NUMBER) { FAIL(STATUS_GCODE_MAX_VALUE_EXCEEDED); }
gc_block.values.t = int_value;
break;
case 'X': word_bit = WORD_X; gc_block.values.xyz[X_AXIS] = value; axis_words |= (1<<X_AXIS); break;
case 'Y': word_bit = WORD_Y; gc_block.values.xyz[Y_AXIS] = value; axis_words |= (1<<Y_AXIS); break;
case 'Z': word_bit = WORD_Z; gc_block.values.xyz[Z_AXIS] = value; axis_words |= (1<<Z_AXIS); break;
case 'X': word_bit = WORD_X; gc_block.values.xyza[X_AXIS] = value; axis_words |= (1<<X_AXIS); break;
case 'Y': word_bit = WORD_Y; gc_block.values.xyza[Y_AXIS] = value; axis_words |= (1<<Y_AXIS); break;
case 'Z': word_bit = WORD_Z; gc_block.values.xyza[Z_AXIS] = value; axis_words |= (1<<Z_AXIS); break;
default: FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND);
}
@ -475,7 +475,7 @@ uint8_t gc_execute_line(char *line)
if (gc_block.modal.units == UNITS_MODE_INCHES) {
for (idx=0; idx<N_AXIS; idx++) { // Axes indices are consistent, so loop may be used.
if (bit_istrue(axis_words,bit(idx)) ) {
gc_block.values.xyz[idx] *= MM_PER_INCH;
gc_block.values.xyza[idx] *= MM_PER_INCH;
}
}
}
@ -549,11 +549,11 @@ uint8_t gc_execute_line(char *line)
if (gc_block.values.l == 20) {
// L20: Update coordinate system axis at current position (with modifiers) with programmed value
// WPos = MPos - WCS - G92 - TLO -> WCS = MPos - G92 - TLO - WPos
gc_block.values.ijk[idx] = gc_state.position[idx]-gc_state.coord_offset[idx]-gc_block.values.xyz[idx];
gc_block.values.ijk[idx] = gc_state.position[idx]-gc_state.coord_offset[idx]-gc_block.values.xyza[idx];
if (idx == TOOL_LENGTH_OFFSET_AXIS) { gc_block.values.ijk[idx] -= gc_state.tool_length_offset; }
} else {
// L2: Update coordinate system axis to programmed value.
gc_block.values.ijk[idx] = gc_block.values.xyz[idx];
gc_block.values.ijk[idx] = gc_block.values.xyza[idx];
}
} // Else, keep current stored value.
}
@ -567,10 +567,10 @@ uint8_t gc_execute_line(char *line)
for (idx=0; idx<N_AXIS; idx++) { // Axes indices are consistent, so loop may be used.
if (bit_istrue(axis_words,bit(idx)) ) {
// WPos = MPos - WCS - G92 - TLO -> G92 = MPos - WCS - TLO - WPos
gc_block.values.xyz[idx] = gc_state.position[idx]-block_coord_system[idx]-gc_block.values.xyz[idx];
if (idx == TOOL_LENGTH_OFFSET_AXIS) { gc_block.values.xyz[idx] -= gc_state.tool_length_offset; }
gc_block.values.xyza[idx] = gc_state.position[idx]-block_coord_system[idx]-gc_block.values.xyza[idx];
if (idx == TOOL_LENGTH_OFFSET_AXIS) { gc_block.values.xyza[idx] -= gc_state.tool_length_offset; }
} else {
gc_block.values.xyz[idx] = gc_state.coord_offset[idx];
gc_block.values.xyza[idx] = gc_state.coord_offset[idx];
}
}
break;
@ -585,17 +585,17 @@ uint8_t gc_execute_line(char *line)
if (axis_words) {
for (idx=0; idx<N_AXIS; idx++) { // Axes indices are consistent, so loop may be used to save flash space.
if ( bit_isfalse(axis_words,bit(idx)) ) {
gc_block.values.xyz[idx] = gc_state.position[idx]; // No axis word in block. Keep same axis position.
gc_block.values.xyza[idx] = gc_state.position[idx]; // No axis word in block. Keep same axis position.
} else {
// Update specified value according to distance mode or ignore if absolute override is active.
// NOTE: G53 is never active with G28/30 since they are in the same modal group.
if (gc_block.non_modal_command != NON_MODAL_ABSOLUTE_OVERRIDE) {
// Apply coordinate offsets based on distance mode.
if (gc_block.modal.distance == DISTANCE_MODE_ABSOLUTE) {
gc_block.values.xyz[idx] += block_coord_system[idx] + gc_state.coord_offset[idx];
if (idx == TOOL_LENGTH_OFFSET_AXIS) { gc_block.values.xyz[idx] += gc_state.tool_length_offset; }
gc_block.values.xyza[idx] += block_coord_system[idx] + gc_state.coord_offset[idx];
if (idx == TOOL_LENGTH_OFFSET_AXIS) { gc_block.values.xyza[idx] += gc_state.tool_length_offset; }
} else { // Incremental mode
gc_block.values.xyz[idx] += gc_state.position[idx];
gc_block.values.xyza[idx] += gc_state.position[idx];
}
}
}
@ -684,12 +684,12 @@ uint8_t gc_execute_line(char *line)
// Calculate the change in position along each selected axis
float x,y;
x = gc_block.values.xyz[axis_0]-gc_state.position[axis_0]; // Delta x between current position and target
y = gc_block.values.xyz[axis_1]-gc_state.position[axis_1]; // Delta y between current position and target
x = gc_block.values.xyza[axis_0]-gc_state.position[axis_0]; // Delta x between current position and target
y = gc_block.values.xyza[axis_1]-gc_state.position[axis_1]; // Delta y between current position and target
if (value_words & bit(WORD_R)) { // Arc Radius Mode
bit_false(value_words,bit(WORD_R));
if (isequal_position_vector(gc_state.position, gc_block.values.xyz)) { FAIL(STATUS_GCODE_INVALID_TARGET); } // [Invalid target]
if (isequal_position_vector(gc_state.position, gc_block.values.xyza)) { FAIL(STATUS_GCODE_INVALID_TARGET); } // [Invalid target]
// Convert radius value to proper units.
if (gc_block.modal.units == UNITS_MODE_INCHES) { gc_block.values.r *= MM_PER_INCH; }
@ -816,7 +816,7 @@ uint8_t gc_execute_line(char *line)
// an error, it issues an alarm to prevent further motion to the probe. It's also done there to
// allow the planner buffer to empty and move off the probe trigger before another probing cycle.
if (!axis_words) { FAIL(STATUS_GCODE_NO_AXIS_WORDS); } // [No axis words]
if (isequal_position_vector(gc_state.position, gc_block.values.xyz)) { FAIL(STATUS_GCODE_INVALID_TARGET); } // [Invalid target]
if (isequal_position_vector(gc_state.position, gc_block.values.xyza)) { FAIL(STATUS_GCODE_INVALID_TARGET); } // [Invalid target]
break;
}
}
@ -832,7 +832,7 @@ uint8_t gc_execute_line(char *line)
} else {
bit_false(value_words,(bit(WORD_N)|bit(WORD_F)|bit(WORD_S)|bit(WORD_T))); // Remove single-meaning value words.
}
if (axis_command) { bit_false(value_words,(bit(WORD_X)|bit(WORD_Y)|bit(WORD_Z))); } // Remove axis words.
if (axis_command) { bit_false(value_words,(bit(WORD_X)|bit(WORD_Y)|bit(WORD_Z)|bit(WORD_A))); } // Remove axis words.
if (value_words) { FAIL(STATUS_GCODE_UNUSED_WORDS); } // [Unused words]
/* -------------------------------------------------------------------------------------
@ -861,7 +861,7 @@ uint8_t gc_execute_line(char *line)
plan_data.condition = (gc_state.modal.spindle | gc_state.modal.coolant);
uint8_t status = jog_execute(&plan_data, &gc_block);
if (status == STATUS_OK) { memcpy(gc_state.position, gc_block.values.xyz, sizeof(gc_block.values.xyz)); }
if (status == STATUS_OK) { memcpy(gc_state.position, gc_block.values.xyza, sizeof(gc_block.values.xyza)); }
return(status);
}
@ -985,10 +985,10 @@ uint8_t gc_execute_line(char *line)
if (axis_command == AXIS_COMMAND_TOOL_LENGTH_OFFSET ) { // Indicates a change.
gc_state.modal.tool_length = gc_block.modal.tool_length;
if (gc_state.modal.tool_length == TOOL_LENGTH_OFFSET_CANCEL) { // G49
gc_block.values.xyz[TOOL_LENGTH_OFFSET_AXIS] = 0.0;
gc_block.values.xyza[TOOL_LENGTH_OFFSET_AXIS] = 0.0;
} // else G43.1
if ( gc_state.tool_length_offset != gc_block.values.xyz[TOOL_LENGTH_OFFSET_AXIS] ) {
gc_state.tool_length_offset = gc_block.values.xyz[TOOL_LENGTH_OFFSET_AXIS];
if ( gc_state.tool_length_offset != gc_block.values.xyza[TOOL_LENGTH_OFFSET_AXIS] ) {
gc_state.tool_length_offset = gc_block.values.xyza[TOOL_LENGTH_OFFSET_AXIS];
system_flag_wco_change();
}
}
@ -1022,7 +1022,7 @@ uint8_t gc_execute_line(char *line)
// Move to intermediate position before going home. Obeys current coordinate system and offsets
// and absolute and incremental modes.
pl_data->condition |= PL_COND_FLAG_RAPID_MOTION; // Set rapid motion condition flag.
if (axis_command) { mc_line(gc_block.values.xyz, pl_data); }
if (axis_command) { mc_line(gc_block.values.xyza, pl_data); }
mc_line(gc_block.values.ijk, pl_data);
memcpy(gc_state.position, gc_block.values.ijk, N_AXIS*sizeof(float));
break;
@ -1033,7 +1033,7 @@ uint8_t gc_execute_line(char *line)
settings_write_coord_data(SETTING_INDEX_G30,gc_state.position,false,true);
break;
case NON_MODAL_SET_COORDINATE_OFFSET:
memcpy(gc_state.coord_offset,gc_block.values.xyz,sizeof(gc_block.values.xyz));
memcpy(gc_state.coord_offset,gc_block.values.xyza,sizeof(gc_block.values.xyza));
system_flag_wco_change();
break;
case NON_MODAL_RESET_COORDINATE_OFFSET:
@ -1051,27 +1051,27 @@ uint8_t gc_execute_line(char *line)
if (axis_command == AXIS_COMMAND_MOTION_MODE) {
uint8_t gc_update_pos = GC_UPDATE_POS_TARGET;
if (gc_state.modal.motion == MOTION_MODE_LINEAR) {
mc_line(gc_block.values.xyz, pl_data);
mc_line(gc_block.values.xyza, pl_data);
} else if (gc_state.modal.motion == MOTION_MODE_SEEK) {
pl_data->condition |= PL_COND_FLAG_RAPID_MOTION; // Set rapid motion condition flag.
mc_line(gc_block.values.xyz, pl_data);
mc_line(gc_block.values.xyza, pl_data);
} else if ((gc_state.modal.motion == MOTION_MODE_CW_ARC) || (gc_state.modal.motion == MOTION_MODE_CCW_ARC)) {
mc_arc(gc_block.values.xyz, pl_data, gc_state.position, gc_block.values.ijk, gc_block.values.r,
mc_arc(gc_block.values.xyza, pl_data, gc_state.position, gc_block.values.ijk, gc_block.values.r,
axis_0, axis_1, axis_linear, bit_istrue(gc_parser_flags,GC_PARSER_ARC_IS_CLOCKWISE));
} else {
// NOTE: gc_block.values.xyz is returned from mc_probe_cycle with the updated position value. So
// NOTE: gc_block.values.xyza is returned from mc_probe_cycle with the updated position value. So
// upon a successful probing cycle, the machine position and the returned value should be the same.
#ifndef ALLOW_FEED_OVERRIDE_DURING_PROBE_CYCLES
pl_data->condition |= PL_COND_FLAG_NO_FEED_OVERRIDE;
#endif
gc_update_pos = mc_probe_cycle(gc_block.values.xyz, pl_data, gc_parser_flags);
gc_update_pos = mc_probe_cycle(gc_block.values.xyza, pl_data, gc_parser_flags);
}
// As far as the parser is concerned, the position is now == target. In reality the
// motion control system might still be processing the action and the real tool position
// in any intermediate location.
if (gc_update_pos == GC_UPDATE_POS_TARGET) {
memcpy(gc_state.position, gc_block.values.xyz, sizeof(gc_block.values.xyz)); // gc_state.position[] = gc_block.values.xyz[]
memcpy(gc_state.position, gc_block.values.xyza, sizeof(gc_block.values.xyza)); // gc_state.position[] = gc_block.values.xyza[]
} else if (gc_update_pos == GC_UPDATE_POS_SYSTEM) {
gc_sync_position(); // gc_state.position[] = sys_position
} // == GC_UPDATE_POS_NONE

View File

@ -149,6 +149,7 @@
#define WORD_X 10
#define WORD_Y 11
#define WORD_Z 12
#define WORD_A 13
// Define g-code parser position updating flags
#define GC_UPDATE_POS_TARGET 0 // Must be zero
@ -206,7 +207,7 @@ typedef struct {
float r; // Arc radius
float s; // Spindle speed
uint8_t t; // Tool selection
float xyz[3]; // X,Y,Z Translational axes
float xyza[N_AXIS]; // X,Y,Z,A Translational axes
} gc_values_t;

View File

@ -23,7 +23,7 @@
// Grbl versioning system
#define GRBL_VERSION "1.1f"
#define GRBL_VERSION_BUILD "20170131"
#define GRBL_VERSION_BUILD "20170511"
// Define standard libraries used by Grbl.
#include <avr/io.h>

View File

@ -33,11 +33,11 @@ uint8_t jog_execute(plan_line_data_t *pl_data, parser_block_t *gc_block)
#endif
if (bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE)) {
if (system_check_travel_limits(gc_block->values.xyz)) { return(STATUS_TRAVEL_EXCEEDED); }
if (system_check_travel_limits(gc_block->values.xyza)) { return(STATUS_TRAVEL_EXCEEDED); }
}
// Valid jog command. Plan, set state, and execute.
mc_line(gc_block->values.xyz,pl_data);
mc_line(gc_block->values.xyza,pl_data);
if (sys.state == STATE_IDLE) {
if (plan_get_current_block() != NULL) { // Check if there is a block to execute.
sys.state = STATE_JOG;

View File

@ -307,9 +307,17 @@ void limits_go_home(uint8_t cycle_mask)
set_axis_position = 0;
#else
if ( bit_istrue(settings.homing_dir_mask,bit(idx)) ) {
set_axis_position = lround((settings.max_travel[idx]+settings.homing_pulloff)*settings.steps_per_mm[idx]);
#ifdef HOMING_FORCE_POSITIVE_SPACE
set_axis_position = 0; //lround(settings.homing_pulloff*settings.steps_per_mm[idx]);
#else
set_axis_position = lround((settings.max_travel[idx]-settings.homing_pulloff)*settings.steps_per_mm[idx]);
#endif
} else {
set_axis_position = lround(-settings.homing_pulloff*settings.steps_per_mm[idx]);
#ifdef HOMING_FORCE_POSITIVE_SPACE
set_axis_position = lround(-settings.max_travel[idx]*settings.steps_per_mm[idx]);
#else
set_axis_position = lround(-settings.homing_pulloff*settings.steps_per_mm[idx]);
#endif
}
#endif

View File

@ -227,6 +227,9 @@ void mc_homing_cycle(uint8_t cycle_mask)
#ifdef HOMING_CYCLE_2
limits_go_home(HOMING_CYCLE_2); // Homing cycle 2
#endif
#ifdef HOMING_CYCLE_3
limits_go_home(HOMING_CYCLE_3); // Homing cycle 3
#endif
}
protocol_execute_realtime(); // Check for reset and set system abort.

View File

@ -31,6 +31,9 @@
#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)
//#define HOMING_CYCLE_C bit(C_AXIS)
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second

View File

@ -30,11 +30,13 @@
#define SOME_LARGE_VALUE 1.0E+38
// Axis array index values. Must start with 0 and be continuous.
#define N_AXIS 3 // Number of axes
#define N_AXIS 4 // Number of axes
#define X_AXIS 0 // Axis indexing value.
#define Y_AXIS 1
#define Z_AXIS 2
// #define A_AXIS 3
#define A_AXIS 3
//#define B_AXIS 4
//#define C_AXIS 5
// CoreXY motor assignments. DO NOT ALTER.
// NOTE: If the A and B motor axis bindings are changed, this effects the CoreXY equations.

View File

@ -336,6 +336,7 @@ uint8_t plan_buffer_line(float *target, plan_line_data_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];
#else
memcpy(position_steps, sys_position, sizeof(sys_position));
#endif

View File

@ -71,7 +71,6 @@ static void report_util_setting_string(uint8_t n) {
case 30: printPgmString(PSTR("rpm max")); break;
case 31: printPgmString(PSTR("rpm min")); break;
case 32: printPgmString(PSTR("laser")); break;
case 33: printPgmString(PSTR("spindle_pwm_freq")); break;
default:
n -= AXIS_SETTINGS_START_VAL;
uint8_t idx = 0;
@ -97,11 +96,6 @@ static void report_util_uint8_setting(uint8_t n, int val) {
print_uint8_base10(val);
report_util_line_feed(); // report_util_setting_string(n);
}
static void report_util_uint32_setting(uint8_t n, int val) {
report_util_setting_prefix(n);
print_uint32_base10(val);
report_util_line_feed(); // report_util_setting_string(n);
}
static void report_util_float_setting(uint8_t n, float val, uint8_t n_decimal) {
report_util_setting_prefix(n);
printFloat(val,n_decimal);
@ -214,7 +208,10 @@ void report_grbl_settings() {
#else
report_util_uint8_setting(32,0);
#endif
report_util_uint32_setting(33,settings.spindle_pwm_freq);
report_util_float_setting(33,settings.spindle_pwm_freq,N_DECIMAL_SETTINGVALUE);
report_util_float_setting(34,settings.spindle_pwm_off_value,N_DECIMAL_SETTINGVALUE);
report_util_float_setting(35,settings.spindle_pwm_min_value,N_DECIMAL_SETTINGVALUE);
report_util_float_setting(36,settings.spindle_pwm_max_value,N_DECIMAL_SETTINGVALUE);
// Print axis settings
uint8_t idx, set_idx;
uint8_t val = AXIS_SETTINGS_START_VAL;
@ -578,6 +575,9 @@ void report_realtime_status()
if (bit_istrue(lim_pin_state,bit(X_AXIS))) { serial_write('X'); }
if (bit_istrue(lim_pin_state,bit(Y_AXIS))) { serial_write('Y'); }
if (bit_istrue(lim_pin_state,bit(Z_AXIS))) { serial_write('Z'); }
if (bit_istrue(lim_pin_state,bit(A_AXIS))) { serial_write('A'); }
//if (bit_istrue(lim_pin_state,bit(B_AXIS))) { serial_write('B'); }
//if (bit_istrue(lim_pin_state,bit(C_AXIS))) { serial_write('C'); }
}
if (ctrl_pin_state) {
#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN

View File

@ -87,6 +87,9 @@ void settings_restore(uint8_t restore_flag) {
settings.arc_tolerance = DEFAULT_ARC_TOLERANCE;
settings.spindle_pwm_freq = DEFAULT_SPINDLE_PWM_FREQ;
settings.spindle_pwm_off_value = DEFAULT_SPINDLE_PWM_OFF_VALUE;
settings.spindle_pwm_min_value = DEFAULT_SPINDLE_PWM_MIN_VALUE;
settings.spindle_pwm_max_value = DEFAULT_SPINDLE_PWM_MAX_VALUE;
settings.rpm_max = DEFAULT_SPINDLE_RPM_MAX;
settings.rpm_min = DEFAULT_SPINDLE_RPM_MIN;
@ -109,18 +112,33 @@ 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_MM;
//settings.steps_per_mm[B_AXIS] = DEFAULT_B_STEPS_PER_MM;
//settings.steps_per_mm[C_AXIS] = DEFAULT_C_STEPS_PER_MM;
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.max_rate[C_AXIS] = DEFAULT_C_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.acceleration[C_AXIS] = DEFAULT_C_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.max_travel[C_AXIS] = (-DEFAULT_C_MAX_TRAVEL);
settings.current[X_AXIS] = DEFAULT_X_CURRENT;
settings.current[Y_AXIS] = DEFAULT_Y_CURRENT;
settings.current[Z_AXIS] = DEFAULT_Z_CURRENT;
settings.current[A_AXIS] = DEFAULT_A_CURRENT;
//settings.current[B_AXIS] = DEFAULT_B_CURRENT;
//settings.current[C_AXIS] = DEFAULT_C_CURRENT;
write_global_settings(false);
}
@ -319,6 +337,9 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
#endif
break;
case 33: settings.spindle_pwm_freq = value; spindle_init(); break; // Re-initialize spindle pwm calibration
case 34: settings.spindle_pwm_off_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
case 35: settings.spindle_pwm_min_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
case 36: settings.spindle_pwm_max_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
default:
return(STATUS_INVALID_STATEMENT);
}
@ -343,7 +364,11 @@ uint32_t get_step_pin_mask(uint8_t axis_idx)
{
if ( axis_idx == X_AXIS ) { return((1<<X_STEP_BIT)); }
if ( axis_idx == Y_AXIS ) { return((1<<Y_STEP_BIT)); }
return((1<<Z_STEP_BIT));
if ( axis_idx == Z_AXIS ) { return((1<<Z_STEP_BIT)); }
return((1<<A_STEP_BIT));
//if ( axis_idx == A_AXIS ) { return((1<<A_STEP_BIT)); }
//if ( axis_idx == B_AXIS ) { return((1<<B_STEP_BIT)); }
//return((1<<C_STEP_BIT));
}
@ -352,7 +377,11 @@ uint32_t get_direction_pin_mask(uint8_t axis_idx)
{
if ( axis_idx == X_AXIS ) { return((1<<X_DIRECTION_BIT)); }
if ( axis_idx == Y_AXIS ) { return((1<<Y_DIRECTION_BIT)); }
return((1<<Z_DIRECTION_BIT));
if ( axis_idx == Z_AXIS ) { return((1<<Z_DIRECTION_BIT)); }
return((1<<A_DIRECTION_BIT));
//if ( axis_idx == A_AXIS ) { return((1<<A_DIRECTION_BIT)); }
//if ( axis_idx == B_AXIS ) { return((1<<B_DIRECTION_BIT)); }
//return((1<<C_DIRECTION_BIT));
}
@ -361,5 +390,9 @@ uint32_t get_limit_pin_mask(uint8_t axis_idx)
{
if ( axis_idx == X_AXIS ) { return((1<<X_LIMIT_BIT)); }
if ( axis_idx == Y_AXIS ) { return((1<<Y_LIMIT_BIT)); }
return((1<<Z_LIMIT_BIT));
if ( axis_idx == Z_AXIS ) { return((1<<Z_LIMIT_BIT)); }
return((1<<A_LIMIT_BIT));
//if ( axis_idx == A_AXIS ) { return((1<<A_LIMIT_BIT)); }
//if ( axis_idx == B_AXIS ) { return((1<<B_LIMIT_BIT)); }
//return((1<<C_LIMIT_BIT));
}

View File

@ -27,7 +27,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 10 // NOTE: Check settings_reset() when moving to next version.
#define SETTINGS_VERSION 11 // NOTE: Check settings_reset() when moving to next version.
// Define bit flag masks for the boolean settings in settings.flag.
#define BITFLAG_REPORT_INCHES bit(0)
@ -92,7 +92,10 @@ typedef struct {
float junction_deviation;
float arc_tolerance;
uint16_t spindle_pwm_freq;
float spindle_pwm_freq; // Hz
float spindle_pwm_off_value; // Percent
float spindle_pwm_min_value; // Percent
float spindle_pwm_max_value; // Percent
float rpm_max;
float rpm_min;

View File

@ -25,10 +25,10 @@
#ifdef VARIABLE_SPINDLE
static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
static float spindle_pwm_period;
static float spindle_pwm_off_value;
static float spindle_pwm_min_value;
static float spindle_pwm_max_value;
float spindle_pwm_period;
float spindle_pwm_off_value;
float spindle_pwm_min_value;
float spindle_pwm_max_value;
#endif
@ -36,12 +36,10 @@ void spindle_init()
{
#ifdef VARIABLE_SPINDLE
spindle_pwm_period = (SystemCoreClock / settings.spindle_pwm_freq);
spindle_pwm_off_value = (spindle_pwm_period * 0.0); // SPINDLE_PWM_PERIOD * fraction
spindle_pwm_min_value = (spindle_pwm_period * 0.0); // SPINDLE_PWM_PERIOD * fraction
spindle_pwm_max_value = (spindle_pwm_period * 1.0); // SPINDLE_PWM_PERIOD * fraction
//pwm_init(&SPINDLE_PWM_CHANNEL, SPINDLE_PWM_USE_PRIMARY_PIN, SPINDLE_PWM_USE_SECONDARY_PIN, SPINDLE_PWM_PERIOD, 0);
pwm_init(&SPINDLE_PWM_CHANNEL, SPINDLE_PWM_USE_PRIMARY_PIN, SPINDLE_PWM_USE_SECONDARY_PIN, spindle_pwm_period, 0); //SPINDLE_PWM_PERIOD
spindle_pwm_off_value = (spindle_pwm_period * settings.spindle_pwm_off_value / 100);
spindle_pwm_min_value = (spindle_pwm_period * settings.spindle_pwm_min_value / 100);
spindle_pwm_max_value = (spindle_pwm_period * settings.spindle_pwm_max_value / 100);
pwm_init(&SPINDLE_PWM_CHANNEL, SPINDLE_PWM_USE_PRIMARY_PIN, SPINDLE_PWM_USE_SECONDARY_PIN, spindle_pwm_period, 0);
pwm_enable(&SPINDLE_PWM_CHANNEL);
/* not ported
@ -54,7 +52,6 @@ void spindle_init()
#endif
*/
//pwm_gradient = (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)/(settings.rpm_max-settings.rpm_min);
pwm_gradient = (spindle_pwm_max_value-spindle_pwm_min_value)/(settings.rpm_max-settings.rpm_min);
#else
@ -145,21 +142,21 @@ void spindle_stop()
rpm *= (0.010*sys.spindle_speed_ovr); // Scale by spindle speed override value.
if (rpm <= 0) {
sys.spindle_speed = 0;
pwm_value = spindle_pwm_off_value; //SPINDLE_PWM_OFF_VALUE
pwm_value = spindle_pwm_off_value;
}
else if (rpm <= settings.rpm_min) {
sys.spindle_speed = settings.rpm_min;
pwm_value = spindle_pwm_min_value; //SPINDLE_PWM_MIN_VALUE
pwm_value = spindle_pwm_min_value;
}
else if (rpm >= settings.rpm_max) {
sys.spindle_speed = settings.rpm_max;
pwm_value = spindle_pwm_max_value - 1; //SPINDLE_PWM_MAX_VALUE
pwm_value = spindle_pwm_max_value - 1;
}
else {
sys.spindle_speed = rpm;
pwm_value = floor((rpm - settings.rpm_min) * pwm_gradient) + spindle_pwm_min_value; //SPINDLE_PWM_MIN_VALUE
if(pwm_value >= spindle_pwm_max_value) //SPINDLE_PWM_MAX_VALUE
pwm_value = spindle_pwm_max_value - 1; //SPINDLE_PWM_MAX_VALUE
pwm_value = floor((rpm - settings.rpm_min) * pwm_gradient) + spindle_pwm_min_value;
if(pwm_value >= spindle_pwm_max_value)
pwm_value = spindle_pwm_max_value - 1;
}
return(pwm_value);
}

View File

@ -40,6 +40,10 @@ uint8_t spindle_get_state();
// Immediately sets spindle running state with direction and spindle rpm via PWM, if enabled.
// Called by spindle_sync() after sync and parking motion/spindle stop override during restore.
#ifdef VARIABLE_SPINDLE
extern float spindle_pwm_period;
extern float spindle_pwm_off_value;
extern float spindle_pwm_min_value;
extern float spindle_pwm_max_value;
// Called by g-code parser when setting spindle state and requires a buffer sync.
void spindle_sync(uint8_t state, float rpm);

View File

@ -97,7 +97,10 @@ typedef struct {
// Used by the bresenham line algorithm
uint32_t counter_x, // Counter variables for the bresenham line tracer
counter_y,
counter_z;
counter_z,
counter_a;
//counter_b,
//counter_c;
#ifdef STEP_PULSE_DELAY
uint32_t step_bits; // Stores out_bits output to complete the step pulse delay
#endif
@ -370,6 +373,9 @@ extern "C" void TIMER1_IRQHandler()
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;
//st.steps[C_AXIS] = st.exec_block->steps[C_AXIS] >> st.exec_segment->amass_level;
#endif
#ifdef VARIABLE_SPINDLE
@ -385,7 +391,7 @@ extern "C" void TIMER1_IRQHandler()
st_go_idle();
#ifdef VARIABLE_SPINDLE
// Ensure pwm is set properly upon completion of rate-controlled motion.
if (st.exec_block->is_pwm_rate_adjusted) { spindle_set_speed(SPINDLE_PWM_OFF_VALUE); }
if (st.exec_block->is_pwm_rate_adjusted) { spindle_set_speed(spindle_pwm_off_value); }
#endif
system_set_exec_state_flag(EXEC_CYCLE_STOP); // Flag main program for cycle end
return; // Nothing to do but exit.
@ -433,6 +439,41 @@ extern "C" void TIMER1_IRQHandler()
if (st.exec_block->direction_bits & (1<<Z_DIRECTION_BIT)) { sys_position[Z_AXIS]--; }
else { sys_position[Z_AXIS]++; }
}
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
st.counter_a += st.steps[A_AXIS];
#else
st.counter_a += st.exec_block->steps[A_AXIS];
#endif
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_block->direction_bits & (1<<A_DIRECTION_BIT)) { sys_position[A_AXIS]--; }
else { sys_position[A_AXIS]++; }
}
/*
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
st.counter_b += st.steps[B_AXIS];
#else
st.counter_b += st.exec_block->steps[B_AXIS];
#endif
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_block->direction_bits & (1<<B_DIRECTION_BIT)) { sys_position[B_AXIS]--; }
else { sys_position[B_AXIS]++; }
}
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
st.counter_c += st.steps[C_AXIS];
#else
st.counter_c += st.exec_block->steps[C_AXIS];
#endif
if (st.counter_c > st.exec_block->step_event_count) {
st.step_outbits |= (1<<C_STEP_BIT);
st.counter_c -= st.exec_block->step_event_count;
if (st.exec_block->direction_bits & (1<<C_DIRECTION_BIT)) { sys_position[C_AXIS]--; }
else { sys_position[C_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; }
@ -907,7 +948,7 @@ void st_prep_buffer()
prep.current_spindle_pwm = spindle_compute_pwm_value(rpm);
} else {
sys.spindle_speed = 0.0;
prep.current_spindle_pwm = SPINDLE_PWM_OFF_VALUE;
prep.current_spindle_pwm = spindle_pwm_off_value;
}
bit_false(sys.step_control,STEP_CONTROL_UPDATE_SPINDLE_PWM);
}

View File

@ -185,6 +185,9 @@ uint8_t system_execute_line(char *line)
case 'X': mc_homing_cycle(HOMING_CYCLE_X); break;
case 'Y': mc_homing_cycle(HOMING_CYCLE_Y); break;
case 'Z': mc_homing_cycle(HOMING_CYCLE_Z); break;
case 'A': mc_homing_cycle(HOMING_CYCLE_A); break;
//case 'B': mc_homing_cycle(HOMING_CYCLE_B); break;
//case 'C': mc_homing_cycle(HOMING_CYCLE_C); break;
default: return(STATUS_INVALID_STATEMENT);
}
#endif
@ -342,7 +345,11 @@ uint8_t system_check_travel_limits(float *target)
}
#else
// NOTE: max_travel is stored as negative
if (target[idx] > 0 || target[idx] < settings.max_travel[idx]) { return(true); }
#ifdef HOMING_FORCE_POSITIVE_SPACE
if (target[idx] < 0 || target[idx] > -settings.max_travel[idx]) { return(true); }
#else
if (target[idx] > 0 || target[idx] < settings.max_travel[idx]) { return(true); }
#endif
#endif
}
return(false);