├── .gitattributes
├── .gitignore
├── test
├── test.py
├── settings
│ └── kikigey89.settings
└── matlab
│ ├── matlab_convert.py
│ └── grbl_sim.m
├── coolant_control.h
├── probe.h
├── limits.h
├── eeprom.h
├── spindle_control.h
├── coolant_control.c
├── print.h
├── stepper.h
├── probe.c
├── serial.h
├── protocol.h
├── script
├── simple_stream.py
└── stream.py
├── nuts_bolts.h
├── motion_control.h
├── report.h
├── Makefile
├── main.c
├── system.h
├── planner.h
├── nuts_bolts.c
├── spindle_control.c
├── settings.h
├── print.c
├── eeprom.c
├── serial.c
├── gcode.h
├── README.md
├── system.c
├── settings.c
├── limits.c
├── defaults.h
├── protocol.c
└── cpu_map.h
/.gitattributes:
--------------------------------------------------------------------------------
1 | *.hex binary
2 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | *.o
2 | *.elf
3 | *.DS_Store
4 | *.d
5 |
--------------------------------------------------------------------------------
/test/test.py:
--------------------------------------------------------------------------------
1 | import random
2 | import serial
3 | import time
4 | ser = serial.Serial('/dev/tty.usbmodem24111', 115200, timeout=0.001)
5 | time.sleep(1)
6 | outstanding = 0
7 | data = ''
8 | while True:
9 | time.sleep(0.1)
10 | data += ser.read()
11 | pos = data.find('\n')
12 | if pos == -1:
13 | line = ''
14 | else:
15 | line = data[0:pos + 1]
16 | data = data[pos + 1:]
17 | if line == '' and outstanding < 3:
18 | while outstanding < 3:
19 | ser.write("G0 Z%0.3f\n" % (0.01 * (random.random() - 0.5)))
20 | #ser.write("M3\n")
21 | outstanding += 1
22 | continue
23 | if line == 'ok\r\n':
24 | outstanding -= 1
25 | print outstanding, repr(line.rstrip())
--------------------------------------------------------------------------------
/coolant_control.h:
--------------------------------------------------------------------------------
1 | /*
2 | coolant_control.h - spindle control methods
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 |
21 | #ifndef coolant_control_h
22 | #define coolant_control_h
23 |
24 |
25 | void coolant_init();
26 | void coolant_stop();
27 | void coolant_run(uint8_t mode);
28 |
29 | #endif
--------------------------------------------------------------------------------
/test/settings/kikigey89.settings:
--------------------------------------------------------------------------------
1 | (Machine settings provided by @kikigey89)
2 | $0=87.489 (x, step/mm)
3 | $1=87.489 (y, step/mm)
4 | $2=1280.000 (z, step/mm)
5 | $3=1000.000 (x max rate, mm/min)
6 | $4=1000.000 (y max rate, mm/min)
7 | $5=500.000 (z max rate, mm/min)
8 | $6=10.000 (x accel, mm/sec^2)
9 | $7=10.000 (y accel, mm/sec^2)
10 | $8=10.000 (z accel, mm/sec^2)
11 | $9=211.000 (x max travel, mm)
12 | $10=335.000 (y max travel, mm)
13 | $11=70.000 (z max travel, mm)
14 | $12=20 (step pulse, usec)
15 | $13=160 (step port invert mask:10100000)
16 | $14=160 (dir port invert mask:10100000)
17 | $15=50 (step idle delay, msec)
18 | $16=0.010 (junction deviation, mm)
19 | $17=0.002 (arc tolerance, mm)
20 | $19=0 (report inches, bool)
21 | $20=1 (auto start, bool)
22 | $21=0 (invert step enable, bool)
23 | $22=0 (invert limit pins, bool)
24 | $23=0 (soft limits, bool)
25 | $24=0 (hard limits, bool)
26 | $25=0 (homing cycle, bool)
27 | $26=0 (homing dir invert mask:00000000)
28 | $27=50.000 (homing feed, mm/min)
29 | $28=500.000 (homing seek, mm/min)
30 | $29=10 (homing debounce, msec)
31 | $30=3.000 (homing pull-off, mm)
--------------------------------------------------------------------------------
/probe.h:
--------------------------------------------------------------------------------
1 | /*
2 | probe.h - code pertaining to probing methods
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 |
21 | #ifndef probe_h
22 | #define probe_h
23 |
24 | // Values that define the probing state machine.
25 | #define PROBE_OFF 0 // No probing. (Must be zero.)
26 | #define PROBE_ACTIVE 1 // Actively watching the input pin.
27 |
28 |
29 | // Probe pin initialization routine.
30 | void probe_init();
31 |
32 | // Returns probe pin state.
33 | uint8_t probe_get_state();
34 |
35 | // Monitors probe pin state and records the system position when detected. Called by the
36 | // stepper ISR per ISR tick.
37 | void probe_state_monitor();
38 |
39 | #endif
40 |
--------------------------------------------------------------------------------
/limits.h:
--------------------------------------------------------------------------------
1 | /*
2 | limits.h - code pertaining to limit-switches and performing the homing cycle
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | */
25 |
26 | #ifndef limits_h
27 | #define limits_h
28 |
29 |
30 | // Initialize the limits module
31 | void limits_init();
32 |
33 | void limits_disable();
34 |
35 | // Perform one portion of the homing cycle based on the input settings.
36 | void limits_go_home(uint8_t cycle_mask);
37 |
38 | // Check for soft limit violations
39 | void limits_soft_check(float *target);
40 |
41 | #endif
--------------------------------------------------------------------------------
/eeprom.h:
--------------------------------------------------------------------------------
1 | /*
2 | eeprom.h - EEPROM methods
3 | Part of Grbl
4 |
5 | The MIT License (MIT)
6 |
7 | GRBL(tm) - Embedded CNC g-code interpreter and motion-controller
8 | Copyright (c) 2009-2011 Simen Svale Skogsrud
9 |
10 | Permission is hereby granted, free of charge, to any person obtaining a copy
11 | of this software and associated documentation files (the "Software"), to deal
12 | in the Software without restriction, including without limitation the rights
13 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
14 | copies of the Software, and to permit persons to whom the Software is
15 | furnished to do so, subject to the following conditions:
16 |
17 | The above copyright notice and this permission notice shall be included in
18 | all copies or substantial portions of the Software.
19 |
20 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
21 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
22 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
23 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
24 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
25 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
26 | THE SOFTWARE.
27 | */
28 |
29 | #ifndef eeprom_h
30 | #define eeprom_h
31 |
32 | unsigned char eeprom_get_char(unsigned int addr);
33 | void eeprom_put_char(unsigned int addr, unsigned char new_value);
34 | void memcpy_to_eeprom_with_checksum(unsigned int destination, char *source, unsigned int size);
35 | int memcpy_from_eeprom_with_checksum(char *destination, unsigned int source, unsigned int size);
36 |
37 | #endif
38 |
--------------------------------------------------------------------------------
/spindle_control.h:
--------------------------------------------------------------------------------
1 | /*
2 | spindle_control.h - spindle control methods
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2012 Sungeun K. Jeon
25 | */
26 | #include "system.h"
27 | #ifndef spindle_control_h
28 | #define spindle_control_h
29 |
30 |
31 | // Initializes spindle pins and hardware PWM, if enabled.
32 | void spindle_init();
33 |
34 | #ifdef VARIABLE_SPINDLE
35 | // calaculates the RPM for the spindle, takes the value
36 | // from S gcode and calculates the PWM duty cycle
37 | uint8_t calculate_pwm_from_rpm(float rpm);
38 | // Starts spindle.
39 | void spindle_start();
40 | // writes new precalulated value to register
41 | void spindle_rpm_update(uint8_t pwm);
42 | #endif
43 |
44 | // Sets spindle direction and spindle rpm via PWM, if enabled.
45 | void spindle_run(uint8_t direction, float rpm, uint8_t motion);
46 |
47 | // Kills spindle.
48 | void spindle_stop();
49 |
50 | void spindle_pause();
51 | void spindle_unpause();
52 |
53 | #endif
54 |
--------------------------------------------------------------------------------
/coolant_control.c:
--------------------------------------------------------------------------------
1 | /*
2 | coolant_control.c - coolant control methods
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 |
21 | #include "system.h"
22 | #include "coolant_control.h"
23 | #include "protocol.h"
24 | #include "gcode.h"
25 |
26 |
27 | void coolant_init()
28 | {
29 | COOLANT_FLOOD_DDR |= (1 << COOLANT_FLOOD_BIT);
30 | #ifdef ENABLE_M7
31 | COOLANT_MIST_DDR |= (1 << COOLANT_MIST_BIT);
32 | #endif
33 | coolant_stop();
34 | }
35 |
36 |
37 | void coolant_stop()
38 | {
39 | COOLANT_FLOOD_PORT &= ~(1 << COOLANT_FLOOD_BIT);
40 | #ifdef ENABLE_M7
41 | COOLANT_MIST_PORT &= ~(1 << COOLANT_MIST_BIT);
42 | #endif
43 | }
44 |
45 |
46 | void coolant_run(uint8_t mode)
47 | {
48 | if (sys.state == STATE_CHECK_MODE) { return; }
49 |
50 | protocol_auto_cycle_start(); //temp fix for M8 lockup
51 | protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
52 | if (mode == COOLANT_FLOOD_ENABLE) {
53 | COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT);
54 |
55 | #ifdef ENABLE_M7
56 | } else if (mode == COOLANT_MIST_ENABLE) {
57 | COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT);
58 | #endif
59 |
60 | } else {
61 | coolant_stop();
62 | }
63 | }
64 |
--------------------------------------------------------------------------------
/print.h:
--------------------------------------------------------------------------------
1 | /*
2 | print.h - Functions for formatting output strings
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #ifndef print_h
28 | #define print_h
29 |
30 |
31 | void printString(const char *s);
32 |
33 | void printPgmString(const char *s);
34 |
35 | void printInteger(long n);
36 |
37 | void print_uint32_base10(uint32_t n);
38 |
39 | void print_uint8_base2(uint8_t n);
40 |
41 | void print_uint8_base10(uint8_t n);
42 |
43 | void printFloat(float n, uint8_t decimal_places);
44 |
45 | // Floating value printing handlers for special variables types used in Grbl.
46 | // - CoordValue: Handles all position or coordinate values in inches or mm reporting.
47 | // - RateValue: Handles feed rate and current velocity in inches or mm reporting.
48 | // - SettingValue: Handles all floating point settings values (always in mm.)
49 | void printFloat_CoordValue(float n);
50 |
51 | void printFloat_RateValue(float n);
52 |
53 | void printFloat_SettingValue(float n);
54 |
55 | // Debug tool to print free memory in bytes at the called point. Not used otherwise.
56 | void printFreeMemory();
57 |
58 | #endif
--------------------------------------------------------------------------------
/stepper.h:
--------------------------------------------------------------------------------
1 | /*
2 | stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011 Sungeun K. Jeon
25 | */
26 |
27 | #ifndef stepper_h
28 | #define stepper_h
29 |
30 | #ifndef SEGMENT_BUFFER_SIZE
31 | #define SEGMENT_BUFFER_SIZE 6
32 | #endif
33 |
34 | // Initialize and setup the stepper motor subsystem
35 | void stepper_init();
36 |
37 | // Enable steppers, but cycle does not start unless called by motion control or runtime command.
38 | void st_wake_up();
39 |
40 | // Immediately disables steppers
41 | void st_go_idle();
42 |
43 | // Generate the step and direction port invert masks.
44 | void st_generate_step_dir_invert_masks();
45 |
46 | // Reset the stepper subsystem variables
47 | void st_reset();
48 |
49 | // Reloads step segment buffer. Called continuously by runtime execution system.
50 | void st_prep_buffer();
51 |
52 | // Called by planner_recalculate() when the executing block is updated by the new plan.
53 | void st_update_plan_block_parameters();
54 |
55 | // Called by runtime status reporting if realtime rate reporting is enabled in config.h.
56 | #ifdef REPORT_REALTIME_RATE
57 | float st_get_realtime_rate();
58 | #endif
59 |
60 | #endif
61 |
--------------------------------------------------------------------------------
/probe.c:
--------------------------------------------------------------------------------
1 | /*
2 | probe.c - code pertaining to probing methods
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 |
21 | #include "system.h"
22 | #include "settings.h"
23 | #include "probe.h"
24 |
25 | // Inverts the probe pin state depending on user settings.
26 | uint8_t probe_invert_mask;
27 |
28 |
29 | // Probe pin initialization routine.
30 | void probe_init()
31 | {
32 | PROBE_DDR &= ~(PROBE_MASK); // Configure as input pins
33 | if (bit_istrue(settings.flags,BITFLAG_INVERT_PROBE_PIN)) {
34 | PROBE_PORT &= ~(PROBE_MASK); // Normal low operation. Requires external pull-down.
35 | probe_invert_mask = 0;
36 | } else {
37 | PROBE_PORT |= PROBE_MASK; // Enable internal pull-up resistors. Normal high operation.
38 | probe_invert_mask = PROBE_MASK;
39 | }
40 | }
41 |
42 |
43 | // Returns the probe pin state. Triggered = true. Called by gcode parser and probe state monitor.
44 | uint8_t probe_get_state() { return((PROBE_PIN & PROBE_MASK) ^ probe_invert_mask); }
45 |
46 |
47 | // Monitors probe pin state and records the system position when detected. Called by the
48 | // stepper ISR per ISR tick.
49 | // NOTE: This function must be extremely efficient as to not bog down the stepper ISR.
50 | void probe_state_monitor()
51 | {
52 | if (sys.probe_state == PROBE_ACTIVE) {
53 | if (probe_get_state()) {
54 | sys.probe_state = PROBE_OFF;
55 | memcpy(sys.probe_position, sys.position, sizeof(float)*N_AXIS);
56 | bit_true(sys.execute, EXEC_FEED_HOLD);
57 | }
58 | }
59 | }
60 |
--------------------------------------------------------------------------------
/serial.h:
--------------------------------------------------------------------------------
1 | /*
2 | serial.c - Low level functions for sending and recieving bytes via the serial port
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #ifndef serial_h
28 | #define serial_h
29 |
30 |
31 | #ifndef RX_BUFFER_SIZE
32 | #define RX_BUFFER_SIZE 128
33 | #endif
34 | #ifndef TX_BUFFER_SIZE
35 | #define TX_BUFFER_SIZE 64
36 | #endif
37 |
38 | #define SERIAL_NO_DATA 0xff
39 |
40 | #ifdef ENABLE_XONXOFF
41 | #define RX_BUFFER_FULL 96 // XOFF high watermark
42 | #define RX_BUFFER_LOW 64 // XON low watermark
43 | #define SEND_XOFF 1
44 | #define SEND_XON 2
45 | #define XOFF_SENT 3
46 | #define XON_SENT 4
47 | #define XOFF_CHAR 0x13
48 | #define XON_CHAR 0x11
49 | #endif
50 |
51 | void serial_init();
52 |
53 | // Writes one byte to the TX serial buffer. Called by main program.
54 | void serial_write(uint8_t data);
55 |
56 | // Fetches the first byte in the serial read buffer. Called by main program.
57 | uint8_t serial_read();
58 |
59 | // Reset and empty data in read buffer. Used by e-stop and reset.
60 | void serial_reset_read_buffer();
61 |
62 | // Returns the number of bytes used in the RX serial buffer.
63 | uint8_t serial_get_rx_buffer_count();
64 |
65 | // Returns the number of bytes used in the TX serial buffer.
66 | // NOTE: Not used except for debugging and ensuring no TX bottlenecks.
67 | uint8_t serial_get_tx_buffer_count();
68 |
69 | #endif
70 |
--------------------------------------------------------------------------------
/protocol.h:
--------------------------------------------------------------------------------
1 | /*
2 | protocol.h - controls Grbl execution protocol and procedures
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #ifndef protocol_h
28 | #define protocol_h
29 |
30 | // Line buffer size from the serial input stream to be executed.
31 | // NOTE: Not a problem except for extreme cases, but the line buffer size can be too small
32 | // and g-code blocks can get truncated. Officially, the g-code standards support up to 256
33 | // characters. In future versions, this will be increased, when we know how much extra
34 | // memory space we can invest into here or we re-write the g-code parser not to have this
35 | // buffer.
36 | #ifndef LINE_BUFFER_SIZE
37 | #define LINE_BUFFER_SIZE 80
38 | #endif
39 |
40 | // Starts Grbl main loop. It handles all incoming characters from the serial port and executes
41 | // them as they complete. It is also responsible for finishing the initialization procedures.
42 | void protocol_main_loop();
43 |
44 | // Checks and executes a runtime command at various stop points in main program
45 | void protocol_execute_runtime();
46 |
47 | // Notify the stepper subsystem to start executing the g-code program in buffer.
48 | // void protocol_cycle_start();
49 |
50 | // Reinitializes the buffer after a feed hold for a resume.
51 | // void protocol_cycle_reinitialize();
52 |
53 | // Initiates a feed hold of the running program
54 | // void protocol_feed_hold();
55 |
56 | // Executes the auto cycle feature, if enabled.
57 | void protocol_auto_cycle_start();
58 |
59 | // Block until all buffered steps are executed
60 | void protocol_buffer_synchronize();
61 |
62 | #endif
63 |
--------------------------------------------------------------------------------
/script/simple_stream.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | """\
3 | Simple g-code streaming script for grbl
4 |
5 | Provided as an illustration of the basic communication interface
6 | for grbl. When grbl has finished parsing the g-code block, it will
7 | return an 'ok' or 'error' response. When the planner buffer is full,
8 | grbl will not send a response until the planner buffer clears space.
9 |
10 | G02/03 arcs are special exceptions, where they inject short line
11 | segments directly into the planner. So there may not be a response
12 | from grbl for the duration of the arc.
13 |
14 | ---------------------
15 | The MIT License (MIT)
16 |
17 | Copyright (c) 2012 Sungeun K. Jeon
18 |
19 | Permission is hereby granted, free of charge, to any person obtaining a copy
20 | of this software and associated documentation files (the "Software"), to deal
21 | in the Software without restriction, including without limitation the rights
22 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
23 | copies of the Software, and to permit persons to whom the Software is
24 | furnished to do so, subject to the following conditions:
25 |
26 | The above copyright notice and this permission notice shall be included in
27 | all copies or substantial portions of the Software.
28 |
29 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
30 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
31 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
32 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
33 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
34 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
35 | THE SOFTWARE.
36 | ---------------------
37 | """
38 |
39 | import serial
40 | import time
41 |
42 | # Open grbl serial port
43 | s = serial.Serial('/dev/tty.usbmodem1811',115200)
44 |
45 | # Open g-code file
46 | f = open('grbl.gcode','r');
47 |
48 | # Wake up grbl
49 | s.write("\r\n\r\n")
50 | time.sleep(2) # Wait for grbl to initialize
51 | s.flushInput() # Flush startup text in serial input
52 |
53 | # Stream g-code to grbl
54 | for line in f:
55 | l = line.strip() # Strip all EOL characters for consistency
56 | print 'Sending: ' + l,
57 | s.write(l + '\n') # Send g-code block to grbl
58 | grbl_out = s.readline() # Wait for grbl response with carriage return
59 | print ' : ' + grbl_out.strip()
60 |
61 | # Wait here until grbl is finished to close serial port and file.
62 | raw_input(" Press to exit and disable grbl.")
63 |
64 | # Close file and serial port
65 | f.close()
66 | s.close()
--------------------------------------------------------------------------------
/nuts_bolts.h:
--------------------------------------------------------------------------------
1 | /*
2 | nuts_bolts.h - Header file for shared definitions, variables, and functions
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #ifndef nuts_bolts_h
28 | #define nuts_bolts_h
29 |
30 | #define false 0
31 | #define true 1
32 |
33 | #define N_AXIS 3 // Number of axes
34 | #define X_AXIS 0 // Axis indexing value. Must start with 0 and be continuous.
35 | #define Y_AXIS 1
36 | #define Z_AXIS 2
37 | // #define A_AXIS 3
38 |
39 | #define MM_PER_INCH (25.40)
40 | #define INCH_PER_MM (0.0393701)
41 |
42 | #define TICKS_PER_MICROSECOND (F_CPU/1000000)
43 |
44 | // Useful macros
45 | #define clear_vector(a) memset(a, 0, sizeof(a))
46 | #define clear_vector_float(a) memset(a, 0.0, sizeof(float)*N_AXIS)
47 | // #define clear_vector_long(a) memset(a, 0.0, sizeof(long)*N_AXIS)
48 | #define max(a,b) (((a) > (b)) ? (a) : (b))
49 | #define min(a,b) (((a) < (b)) ? (a) : (b))
50 |
51 | // Bit field and masking macros
52 | #define bit(n) (1 << n)
53 | #define bit_true_atomic(x,mask) {uint8_t sreg = SREG; cli(); (x) |= (mask); SREG = sreg; }
54 | #define bit_false_atomic(x,mask) {uint8_t sreg = SREG; cli(); (x) &= ~(mask); SREG = sreg; }
55 | #define bit_toggle_atomic(x,mask) {uint8_t sreg = SREG; cli(); (x) ^= (mask); SREG = sreg; }
56 | #define bit_true(x,mask) (x) |= (mask)
57 | #define bit_false(x,mask) (x) &= ~(mask)
58 | #define bit_istrue(x,mask) ((x & mask) != 0)
59 | #define bit_isfalse(x,mask) ((x & mask) == 0)
60 |
61 | // Read a floating point value from a string. Line points to the input buffer, char_counter
62 | // is the indexer pointing to the current character of the line, while float_ptr is
63 | // a pointer to the result variable. Returns true when it succeeds
64 | uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr);
65 |
66 | // Delays variable-defined milliseconds. Compiler compatibility fix for _delay_ms().
67 | void delay_ms(uint16_t ms);
68 |
69 | // Delays variable-defined microseconds. Compiler compatibility fix for _delay_us().
70 | void delay_us(uint32_t us);
71 |
72 | // Computes hypotenuse, avoiding avr-gcc's bloated version and the extra error checking.
73 | float hypot_f(float x, float y);
74 |
75 | #endif
76 |
--------------------------------------------------------------------------------
/motion_control.h:
--------------------------------------------------------------------------------
1 | /*
2 | motion_control.h - high level interface for issuing motion commands
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #ifndef motion_control_h
28 | #define motion_control_h
29 |
30 | #define HOMING_CYCLE_LINE_NUMBER -1
31 |
32 | // Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
33 | // unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
34 | // (1 minute)/feed_rate time.
35 | #ifdef USE_LINE_NUMBERS
36 | void mc_line(float *target, float feed_rate, uint8_t invert_feed_rate, float rpm, uint8_t direction, int32_t line_number);
37 | #else
38 | void mc_line(float *target, float feed_rate, uint8_t invert_feed_rate, float rpm, uint8_t direction);
39 | #endif
40 |
41 | // Execute an arc in offset mode format. position == current xyz, target == target xyz,
42 | // offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is
43 | // the direction of helical travel, radius == circle radius, isclockwise boolean. Used
44 | // for vector transformation direction.
45 | #ifdef USE_LINE_NUMBERS
46 | void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate,
47 | uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear,
48 | float rpm, uint8_t direction, int32_t line_number);
49 | #else
50 | void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate,
51 | uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear,
52 | float rpm, uint8_t direction);
53 | #endif
54 |
55 | // Dwell for a specific number of seconds
56 | void mc_dwell(float seconds);
57 |
58 | // Perform homing cycle to locate machine zero. Requires limit switches.
59 | void mc_homing_cycle();
60 |
61 | // Perform tool length probe cycle. Requires probe switch.
62 | #ifdef USE_LINE_NUMBERS
63 | void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate, int32_t line_number);
64 | #else
65 | void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate);
66 | #endif
67 |
68 | // Performs system reset. If in motion state, kills all motion and sets system alarm.
69 | void mc_reset();
70 |
71 | #endif
72 |
--------------------------------------------------------------------------------
/report.h:
--------------------------------------------------------------------------------
1 | /*
2 | report.h - reporting and messaging methods
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | #ifndef report_h
21 | #define report_h
22 |
23 | // Define Grbl status codes.
24 | #define STATUS_OK 0
25 | #define STATUS_EXPECTED_COMMAND_LETTER 1
26 | #define STATUS_BAD_NUMBER_FORMAT 2
27 | #define STATUS_INVALID_STATEMENT 3
28 | #define STATUS_NEGATIVE_VALUE 4
29 | #define STATUS_SETTING_DISABLED 5
30 | #define STATUS_SETTING_STEP_PULSE_MIN 6
31 | #define STATUS_SETTING_READ_FAIL 7
32 | #define STATUS_IDLE_ERROR 8
33 | #define STATUS_ALARM_LOCK 9
34 | #define STATUS_SOFT_LIMIT_ERROR 10
35 | #define STATUS_OVERFLOW 11
36 |
37 | #define STATUS_GCODE_UNSUPPORTED_COMMAND 20
38 | #define STATUS_GCODE_MODAL_GROUP_VIOLATION 21
39 | #define STATUS_GCODE_UNDEFINED_FEED_RATE 22
40 | #define STATUS_GCODE_COMMAND_VALUE_NOT_INTEGER 23
41 | #define STATUS_GCODE_AXIS_COMMAND_CONFLICT 24
42 | #define STATUS_GCODE_WORD_REPEATED 25
43 | #define STATUS_GCODE_NO_AXIS_WORDS 26
44 | #define STATUS_GCODE_INVALID_LINE_NUMBER 27
45 | #define STATUS_GCODE_VALUE_WORD_MISSING 28
46 | #define STATUS_GCODE_UNSUPPORTED_COORD_SYS 29
47 | #define STATUS_GCODE_G53_INVALID_MOTION_MODE 30
48 | #define STATUS_GCODE_AXIS_WORDS_EXIST 31
49 | #define STATUS_GCODE_NO_AXIS_WORDS_IN_PLANE 32
50 | #define STATUS_GCODE_INVALID_TARGET 33
51 | #define STATUS_GCODE_ARC_RADIUS_ERROR 34
52 | #define STATUS_GCODE_NO_OFFSETS_IN_PLANE 35
53 | #define STATUS_GCODE_UNUSED_WORDS 36
54 | #define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37
55 |
56 | // Define Grbl alarm codes. Less than zero to distinguish alarm error from status error.
57 | #define ALARM_LIMIT_ERROR -1
58 | #define ALARM_ABORT_CYCLE -2
59 | #define ALARM_PROBE_FAIL -3
60 |
61 | // Define Grbl feedback message codes.
62 | #define MESSAGE_CRITICAL_EVENT 1
63 | #define MESSAGE_ALARM_LOCK 2
64 | #define MESSAGE_ALARM_UNLOCK 3
65 | #define MESSAGE_ENABLED 4
66 | #define MESSAGE_DISABLED 5
67 |
68 | // Prints system status messages.
69 | void report_status_message(uint8_t status_code);
70 |
71 | // Prints system alarm messages.
72 | void report_alarm_message(int8_t alarm_code);
73 |
74 | // Prints miscellaneous feedback messages.
75 | void report_feedback_message(uint8_t message_code);
76 |
77 | // Prints welcome message
78 | void report_init_message();
79 |
80 | // Prints Grbl help and current global settings
81 | void report_grbl_help();
82 |
83 | // Prints Grbl global settings
84 | void report_grbl_settings();
85 |
86 | // Prints realtime status report
87 | void report_realtime_status();
88 |
89 | // Prints recorded probe position
90 | void report_probe_parameters();
91 |
92 | // Prints Grbl NGC parameters (coordinate offsets, probe)
93 | void report_ngc_parameters();
94 |
95 | // Prints current g-code parser mode state
96 | void report_gcode_modes();
97 |
98 | // Prints startup line
99 | void report_startup_line(uint8_t n, char *line);
100 |
101 | // Prints build info and user info
102 | void report_build_info(char *line);
103 |
104 | #endif
105 |
--------------------------------------------------------------------------------
/Makefile:
--------------------------------------------------------------------------------
1 | # Part of Grbl
2 | #
3 | # Copyright (c) 2009-2011 Simen Svale Skogsrud
4 | # Copyright (c) 2012 Sungeun K. Jeon
5 | #
6 | # Grbl is free software: you can redistribute it and/or modify
7 | # it under the terms of the GNU General Public License as published by
8 | # the Free Software Foundation, either version 3 of the License, or
9 | # (at your option) any later version.
10 | #
11 | # Grbl is distributed in the hope that it will be useful,
12 | # but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | # GNU General Public License for more details.
15 | #
16 | # You should have received a copy of the GNU General Public License
17 | # along with Grbl. If not, see .
18 |
19 |
20 | # This is a prototype Makefile. Modify it according to your needs.
21 | # You should at least check the settings for
22 | # DEVICE ....... The AVR device you compile for
23 | # CLOCK ........ Target AVR clock rate in Hertz
24 | # OBJECTS ...... The object files created from your source files. This list is
25 | # usually the same as the list of source files with suffix ".o".
26 | # PROGRAMMER ... Options to avrdude which define the hardware you use for
27 | # uploading to the AVR and the interface where this hardware
28 | # is connected.
29 | # FUSES ........ Parameters for avrdude to flash the fuses appropriately.
30 |
31 | GIT_HASH := $(shell git describe --abbrev=7 --dirty --always --tags)
32 | DEVICE ?= atmega328p
33 | CLOCK = 16000000
34 | PROGRAMMER ?= -c avrisp2 -P usb
35 | OBJECTS = main.o motion_control.o gcode.o spindle_control.o coolant_control.o serial.o \
36 | protocol.o stepper.o eeprom.o settings.o planner.o nuts_bolts.o limits.o \
37 | print.o probe.o report.o system.o
38 | # FUSES = -U hfuse:w:0xd9:m -U lfuse:w:0x24:m
39 | FUSES = -U hfuse:w:0xd2:m -U lfuse:w:0xff:m
40 | # update that line with this when programmer is back up:
41 | # FUSES = -U hfuse:w:0xd7:m -U lfuse:w:0xff:m
42 |
43 | # Tune the lines below only if you know what you are doing:
44 |
45 | AVRDUDE = avrdude $(PROGRAMMER) -p $(DEVICE) -B 10 -F
46 | COMPILE = avr-gcc -Wall -Os -DF_CPU=$(CLOCK) -DGIT_VERSION=\"$(GIT_HASH)\" -mmcu=$(DEVICE) -I. -ffunction-sections
47 |
48 | # symbolic targets:
49 | all: grbl.hex
50 |
51 | .c.o:
52 | $(COMPILE) -c $< -o $@
53 | @$(COMPILE) -MM $< > $*.d
54 |
55 | .S.o:
56 | $(COMPILE) -x assembler-with-cpp -c $< -o $@
57 | # "-x assembler-with-cpp" should not be necessary since this is the default
58 | # file type for the .S (with capital S) extension. However, upper case
59 | # characters are not always preserved on Windows. To ensure WinAVR
60 | # compatibility define the file type manually.
61 |
62 | .c.s:
63 | $(COMPILE) -S $< -o $@
64 |
65 | flash: all
66 | $(AVRDUDE) -U flash:w:grbl.hex:i
67 |
68 | fuse:
69 | $(AVRDUDE) $(FUSES)
70 |
71 | # Xcode uses the Makefile targets "", "clean" and "install"
72 | install: flash fuse
73 |
74 | # if you use a bootloader, change the command below appropriately:
75 | load: all
76 | bootloadHID grbl.hex
77 |
78 | clean:
79 | rm -f grbl.hex main.elf $(OBJECTS) $(OBJECTS:.o=.d)
80 |
81 | # file targets:
82 | main.elf: $(OBJECTS)
83 | $(COMPILE) -o main.elf $(OBJECTS) -lm -Wl,--gc-sections
84 |
85 | grbl.hex: main.elf
86 | rm -f grbl.hex
87 | avr-objcopy -j .text -j .data -O ihex main.elf grbl.hex
88 | avr-size --format=berkeley main.elf
89 | # If you have an EEPROM section, you must also create a hex file for the
90 | # EEPROM and add it to the "flash" target.
91 |
92 | # Targets for code debugging and analysis:
93 | disasm: main.elf
94 | avr-objdump -d main.elf
95 |
96 | cpp:
97 | $(COMPILE) -E main.c
98 |
99 | # include generated header dependencies
100 | -include $(OBJECTS:.o=.d)
101 |
--------------------------------------------------------------------------------
/main.c:
--------------------------------------------------------------------------------
1 | /*
2 | main.c - An embedded CNC Controller with rs274/ngc (g-code) support
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #include "system.h"
28 | #include "serial.h"
29 | #include "settings.h"
30 | #include "protocol.h"
31 | #include "gcode.h"
32 | #include "planner.h"
33 | #include "stepper.h"
34 | #include "spindle_control.h"
35 | #include "coolant_control.h"
36 | #include "motion_control.h"
37 | #include "limits.h"
38 | #include "probe.h"
39 | #include "report.h"
40 |
41 |
42 | // Declare system global variable structure
43 | system_t sys;
44 |
45 |
46 | int main(void)
47 | {
48 | // Initialize system upon power-up.
49 | serial_init(); // Setup serial baud rate and interrupts
50 | settings_init(); // Load grbl settings from EEPROM
51 | stepper_init(); // Configure stepper pins and interrupt timers
52 | system_init(); // Configure pinout pins and pin-change interrupt
53 |
54 | memset(&sys, 0, sizeof(sys)); // Clear all system variables
55 | sys.abort = true; // Set abort to complete initialization
56 | sei(); // Enable interrupts
57 |
58 | // Check for power-up and set system alarm if homing is enabled to force homing cycle
59 | // by setting Grbl's alarm state. Alarm locks out all g-code commands, including the
60 | // startup scripts, but allows access to settings and internal commands. Only a homing
61 | // cycle '$H' or kill alarm locks '$X' will disable the alarm.
62 | // NOTE: The startup script will run after successful completion of the homing cycle, but
63 | // not after disabling the alarm locks. Prevents motion startup blocks from crashing into
64 | // things uncontrollably. Very bad.
65 | #ifdef HOMING_INIT_LOCK
66 | if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) { sys.state = STATE_ALARM; }
67 | #endif
68 |
69 | // Grbl initialization loop upon power-up or a system abort. For the latter, all processes
70 | // will return to this loop to be cleanly re-initialized.
71 | for(;;) {
72 |
73 | // TODO: Separate configure task that require interrupts to be disabled, especially upon
74 | // a system abort and ensuring any active interrupts are cleanly reset.
75 |
76 | // Reset Grbl primary systems.
77 | serial_reset_read_buffer(); // Clear serial read buffer
78 | gc_init(); // Set g-code parser to default state
79 | spindle_init();
80 | coolant_init();
81 | limits_init();
82 | probe_init();
83 | plan_reset(); // Clear block buffer and planner variables
84 | st_reset(); // Clear stepper subsystem variables.
85 |
86 | // Sync cleared gcode and planner positions to current system position.
87 | plan_sync_position();
88 | gc_sync_position();
89 |
90 | // Reset system variables.
91 | sys.abort = false;
92 | sys.execute = 0;
93 | if (bit_istrue(settings.flags,BITFLAG_AUTO_START)) { sys.auto_start = true; }
94 | else { sys.auto_start = false; }
95 |
96 | // Start Grbl main loop. Processes program inputs and executes them.
97 | protocol_main_loop();
98 |
99 | }
100 | return 0; /* Never reached */
101 | }
102 |
--------------------------------------------------------------------------------
/system.h:
--------------------------------------------------------------------------------
1 | /*
2 | system.h - Header for system level commands and real-time processes
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 |
21 | #ifndef system_h
22 | #define system_h
23 |
24 | // Define system header files and standard libraries used by Grbl
25 | #include
26 | #include
27 | #include
28 | #include
29 | #include
30 | #include
31 | #include
32 | #include
33 | #include
34 | #include
35 | #include
36 |
37 | // Define Grbl configuration and shared header files
38 | #include "config.h"
39 | #include "defaults.h"
40 | #include "cpu_map.h"
41 | #include "nuts_bolts.h"
42 |
43 |
44 | // Define system executor bit map. Used internally by runtime protocol as runtime command flags,
45 | // which notifies the main program to execute the specified runtime command asynchronously.
46 | // NOTE: The system executor uses an unsigned 8-bit volatile variable (8 flag limit.) The default
47 | // flags are always false, so the runtime protocol only needs to check for a non-zero value to
48 | // know when there is a runtime command to execute.
49 | #define EXEC_STATUS_REPORT bit(0) // bitmask 00000001
50 | #define EXEC_CYCLE_START bit(1) // bitmask 00000010
51 | #define EXEC_CYCLE_STOP bit(2) // bitmask 00000100
52 | #define EXEC_FEED_HOLD bit(3) // bitmask 00001000
53 | #define EXEC_RESET bit(4) // bitmask 00010000
54 | #define EXEC_ALARM bit(5) // bitmask 00100000
55 | #define EXEC_CRIT_EVENT bit(6) // bitmask 01000000
56 | // #define bit(7) // bitmask 10000000
57 |
58 | // Define system state bit map. The state variable primarily tracks the individual functions
59 | // of Grbl to manage each without overlapping. It is also used as a messaging flag for
60 | // critical events.
61 | #define STATE_IDLE 0 // Must be zero. No flags.
62 | #define STATE_ALARM bit(0) // In alarm state. Locks out all g-code processes. Allows settings access.
63 | #define STATE_CHECK_MODE bit(1) // G-code check mode. Locks out planner and motion only.
64 | #define STATE_HOMING bit(2) // Performing homing cycle
65 | #define STATE_QUEUED bit(3) // Indicates buffered blocks, awaiting cycle start.
66 | #define STATE_CYCLE bit(4) // Cycle is running
67 | #define STATE_HOLD bit(5) // Executing feed hold
68 | // #define STATE_JOG bit(6) // Jogging mode is unique like homing.
69 |
70 |
71 | // Define global system variables
72 | typedef struct {
73 | uint8_t abort; // System abort flag. Forces exit back to main loop for reset.
74 | uint8_t state; // Tracks the current state of Grbl.
75 | volatile uint8_t execute; // Global system runtime executor bitflag variable. See EXEC bitmasks.
76 | uint8_t homing_axis_lock;
77 | int32_t position[N_AXIS]; // Real-time machine (aka home) position vector in steps.
78 | // NOTE: This may need to be a volatile variable, if problems arise.
79 | uint8_t auto_start; // Planner auto-start flag. Toggled off during feed hold. Defaulted by settings.
80 | volatile uint8_t probe_state; // Probing state value. Used to coordinate the probing cycle with stepper ISR.
81 | int32_t probe_position[N_AXIS]; // Last probe position in machine coordinates and steps.
82 | } system_t;
83 | extern system_t sys;
84 |
85 |
86 | // Initialize the serial protocol
87 | void system_init();
88 |
89 | // Executes an internal system command, defined as a string starting with a '$'
90 | uint8_t system_execute_line(char *line);
91 |
92 | // Checks and executes a runtime command at various stop points in main program
93 | void system_execute_runtime();
94 |
95 | // Execute the startup script lines stored in EEPROM upon initialization
96 | void system_execute_startup(char *line);
97 |
98 | #endif
99 |
--------------------------------------------------------------------------------
/planner.h:
--------------------------------------------------------------------------------
1 | /*
2 | planner.h - buffers movement commands and manages the acceleration profile plan
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #ifndef planner_h
28 | #define planner_h
29 |
30 |
31 | // The number of linear motions that can be in the plan at any give time
32 | #ifndef BLOCK_BUFFER_SIZE
33 | #ifdef USE_LINE_NUMBERS
34 | #define BLOCK_BUFFER_SIZE 16
35 | #else
36 | #define BLOCK_BUFFER_SIZE 18
37 | #endif
38 | #endif
39 |
40 | // This struct stores a linear movement of a g-code block motion with its critical "nominal" values
41 | // are as specified in the source g-code.
42 | typedef struct {
43 | // Fields used by the bresenham algorithm for tracing the line
44 | // NOTE: Used by stepper algorithm to execute the block correctly. Do not alter these values.
45 | float spindle_speed; // RPM
46 | uint8_t spindle_direction; // status of the spindle
47 | uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
48 | uint32_t steps[N_AXIS]; // Step count along each axis
49 | uint32_t step_event_count; // The maximum step axis count and number of steps required to complete this block.
50 |
51 | // Fields used by the motion planner to manage acceleration
52 | float entry_speed_sqr; // The current planned entry speed at block junction in (mm/min)^2
53 | float max_entry_speed_sqr; // Maximum allowable entry speed based on the minimum of junction limit and
54 | // neighboring nominal speeds with overrides in (mm/min)^2
55 | float max_junction_speed_sqr; // Junction entry speed limit based on direction vectors in (mm/min)^2
56 | float nominal_speed_sqr; // Axis-limit adjusted nominal speed for this block in (mm/min)^2
57 | float acceleration; // Axis-limit adjusted line acceleration in (mm/min^2)
58 | float millimeters; // The remaining distance for this block to be executed in (mm)
59 | // uint8_t max_override; // Maximum override value based on axis speed limits
60 |
61 | #ifdef USE_LINE_NUMBERS
62 | int32_t line_number;
63 | #endif
64 | } plan_block_t;
65 |
66 |
67 | // Initialize and reset the motion plan subsystem
68 | void plan_reset();
69 |
70 | // Add a new linear movement to the buffer. target[N_AXIS] is the signed, absolute target position
71 | // in millimeters. Feed rate specifies the speed of the motion. If feed rate is inverted, the feed
72 | // rate is taken to mean "frequency" and would complete the operation in 1/feed_rate minutes.
73 | #ifdef USE_LINE_NUMBERS
74 | void plan_buffer_line(float *target, float feed_rate, uint8_t invert_feed_rate, float rpm, uint8_t direction, int32_t line_number);
75 | #else
76 | void plan_buffer_line(float *target, float feed_rate, uint8_t invert_feed_rate, float rpm, uint8_t direction);
77 | #endif
78 |
79 | // Called when the current block is no longer needed. Discards the block and makes the memory
80 | // availible for new blocks.
81 | void plan_discard_current_block();
82 |
83 | // Gets the current block. Returns NULL if buffer empty
84 | plan_block_t *plan_get_current_block();
85 |
86 | // Called periodically by step segment buffer. Mostly used internally by planner.
87 | uint8_t plan_next_block_index(uint8_t block_index);
88 |
89 | // Called by step segment buffer when computing executing block velocity profile.
90 | float plan_get_exec_block_exit_speed();
91 |
92 | // Reset the planner position vector (in steps)
93 | void plan_sync_position();
94 |
95 | // Reinitialize plan with a partially completed block
96 | void plan_cycle_reinitialize();
97 |
98 | // Returns the number of active blocks are in the planner buffer.
99 | uint8_t plan_get_block_buffer_count();
100 |
101 | // Returns the status of the block ring buffer. True, if buffer is full.
102 | uint8_t plan_check_full_buffer();
103 |
104 | #endif
105 |
--------------------------------------------------------------------------------
/nuts_bolts.c:
--------------------------------------------------------------------------------
1 | /*
2 | nuts_bolts.c - Shared functions
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #include "system.h"
28 | #include "print.h"
29 |
30 |
31 | #define MAX_INT_DIGITS 8 // Maximum number of digits in int32 (and float)
32 |
33 |
34 | // Extracts a floating point value from a string. The following code is based loosely on
35 | // the avr-libc strtod() function by Michael Stumpf and Dmitry Xmelkov and many freely
36 | // available conversion method examples, but has been highly optimized for Grbl. For known
37 | // CNC applications, the typical decimal value is expected to be in the range of E0 to E-4.
38 | // Scientific notation is officially not supported by g-code, and the 'E' character may
39 | // be a g-code word on some CNC systems. So, 'E' notation will not be recognized.
40 | // NOTE: Thanks to Radu-Eosif Mihailescu for identifying the issues with using strtod().
41 | uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr)
42 | {
43 | char *ptr = line + *char_counter;
44 | unsigned char c;
45 |
46 | // Grab first character and increment pointer. No spaces assumed in line.
47 | c = *ptr++;
48 |
49 | // Capture initial positive/minus character
50 | bool isnegative = false;
51 | if (c == '-') {
52 | isnegative = true;
53 | c = *ptr++;
54 | } else if (c == '+') {
55 | c = *ptr++;
56 | }
57 |
58 | // Extract number into fast integer. Track decimal in terms of exponent value.
59 | uint32_t intval = 0;
60 | int8_t exp = 0;
61 | uint8_t ndigit = 0;
62 | bool isdecimal = false;
63 | while(1) {
64 | c -= '0';
65 | if (c <= 9) {
66 | ndigit++;
67 | if (ndigit <= MAX_INT_DIGITS) {
68 | if (isdecimal) { exp--; }
69 | intval = (((intval << 2) + intval) << 1) + c; // intval*10 + c
70 | } else {
71 | if (!(isdecimal)) { exp++; } // Drop overflow digits
72 | }
73 | } else if (c == (('.'-'0') & 0xff) && !(isdecimal)) {
74 | isdecimal = true;
75 | } else {
76 | break;
77 | }
78 | c = *ptr++;
79 | }
80 |
81 | // Return if no digits have been read.
82 | if (!ndigit) { return(false); };
83 |
84 | // Convert integer into floating point.
85 | float fval;
86 | fval = (float)intval;
87 |
88 | // Apply decimal. Should perform no more than two floating point multiplications for the
89 | // expected range of E0 to E-4.
90 | if (fval != 0) {
91 | while (exp <= -2) {
92 | fval *= 0.01;
93 | exp += 2;
94 | }
95 | if (exp < 0) {
96 | fval *= 0.1;
97 | } else if (exp > 0) {
98 | do {
99 | fval *= 10.0;
100 | } while (--exp > 0);
101 | }
102 | }
103 |
104 | // Assign floating point value with correct sign.
105 | if (isnegative) {
106 | *float_ptr = -fval;
107 | } else {
108 | *float_ptr = fval;
109 | }
110 |
111 | *char_counter = ptr - line - 1; // Set char_counter to next statement
112 |
113 | return(true);
114 | }
115 |
116 |
117 | // Delays variable defined milliseconds. Compiler compatibility fix for _delay_ms(),
118 | // which only accepts constants in future compiler releases.
119 | void delay_ms(uint16_t ms)
120 | {
121 | while ( ms-- ) { _delay_ms(1); }
122 | }
123 |
124 |
125 | // Delays variable defined microseconds. Compiler compatibility fix for _delay_us(),
126 | // which only accepts constants in future compiler releases. Written to perform more
127 | // efficiently with larger delays, as the counter adds parasitic time in each iteration.
128 | void delay_us(uint32_t us)
129 | {
130 | while (us) {
131 | if (us < 10) {
132 | _delay_us(1);
133 | us--;
134 | } else if (us < 100) {
135 | _delay_us(10);
136 | us -= 10;
137 | } else if (us < 1000) {
138 | _delay_us(100);
139 | us -= 100;
140 | } else {
141 | _delay_ms(1);
142 | us -= 1000;
143 | }
144 | }
145 | }
146 |
147 |
148 | // Simple hypotenuse computation function.
149 | float hypot_f(float x, float y) { return(sqrt(x*x + y*y)); }
150 |
--------------------------------------------------------------------------------
/spindle_control.c:
--------------------------------------------------------------------------------
1 | /*
2 | spindle_control.c - spindle control methods
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2012 Sungeun K. Jeon
25 | */
26 |
27 | #include "spindle_control.h"
28 | #include "system.h"
29 | #include "protocol.h"
30 | #include "gcode.h"
31 | #include "settings.h"
32 |
33 | void spindle_init()
34 | {
35 | // On the Uno, spindle enable and PWM are shared. Other CPUs have seperate enable pin.
36 | #ifdef VARIABLE_SPINDLE
37 | SPINDLE_PWM_DDR |= (1<0){ //only if it was enabled before.
56 | TCCRA_REGISTER |= (1< SPINDLE_RPM_RANGE ) { rpm = SPINDLE_RPM_RANGE; } // Prevent uint8 overflow
94 | return (uint8_t) floor( rpm*(255.0/SPINDLE_RPM_RANGE) + 0.5);
95 | }
96 | #endif
97 |
98 | void spindle_run(uint8_t direction, float rpm, uint8_t motion)
99 | {
100 | if (sys.state == STATE_CHECK_MODE) { return; }
101 |
102 | // Empty planner buffer to ensure spindle is set when programmed.
103 | // Only do this without real time spindle control or if there was
104 | // a block without motion.
105 | #ifdef LASER_SPINDLE
106 | if (bit_isfalse(settings.flags,BITFLAG_LASER) || motion == BLOCK_HAS_NO_MOTION)
107 | #endif
108 | protocol_auto_cycle_start(); //temp fix for M3 lockup
109 | #ifdef LASER_SPINDLE
110 | if (bit_isfalse(settings.flags,BITFLAG_LASER) || motion == BLOCK_HAS_NO_MOTION)
111 | #endif
112 | protocol_buffer_synchronize();
113 | // Halt or set spindle direction and rpm.
114 | if (direction == SPINDLE_DISABLE) {
115 | spindle_stop();
116 | } else {
117 | if (direction == SPINDLE_ENABLE_CW) {
118 | SPINDLE_DIRECTION_PORT &= ~(1<.
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #ifndef settings_h
28 | #define settings_h
29 |
30 |
31 | #define GRBL_VERSION "0.9g"
32 | #define GRBL_VERSION_BUILD GIT_VERSION
33 |
34 | // Version of the EEPROM data. Will be used to migrate existing data from older versions of Grbl
35 | // when firmware is upgraded. Always stored in byte 0 of eeprom
36 | #define SETTINGS_VERSION 9
37 |
38 | // Define bit flag masks for the boolean settings in settings.flag.
39 | #define BITFLAG_REPORT_INCHES bit(0)
40 | #define BITFLAG_AUTO_START bit(1)
41 | #define BITFLAG_INVERT_ST_ENABLE bit(2)
42 | #define BITFLAG_HARD_LIMIT_ENABLE bit(3)
43 | #define BITFLAG_HOMING_ENABLE bit(4)
44 | #define BITFLAG_SOFT_LIMIT_ENABLE bit(5)
45 | #define BITFLAG_INVERT_LIMIT_PINS bit(6)
46 | #define BITFLAG_INVERT_PROBE_PIN bit(7)
47 | #define BITFLAG_LASER bit(8)
48 |
49 | // Define status reporting boolean enable bit flags in settings.status_report_mask
50 | #define BITFLAG_RT_STATUS_MACHINE_POSITION bit(0)
51 | #define BITFLAG_RT_STATUS_WORK_POSITION bit(1)
52 | #define BITFLAG_RT_STATUS_PLANNER_BUFFER bit(2)
53 | #define BITFLAG_RT_STATUS_SERIAL_RX bit(3)
54 |
55 | // Define EEPROM memory address location values for Grbl settings and parameters
56 | // NOTE: The Atmega328p has 1KB EEPROM. The upper half is reserved for parameters and
57 | // the startup script. The lower half contains the global settings and space for future
58 | // developments.
59 | #define EEPROM_ADDR_GLOBAL 1U
60 | #define EEPROM_ADDR_PARAMETERS 512U
61 | #define EEPROM_ADDR_STARTUP_BLOCK 768U
62 | #define EEPROM_ADDR_BUILD_INFO 942U
63 |
64 | // Define EEPROM address indexing for coordinate parameters
65 | #define N_COORDINATE_SYSTEM 6 // Number of supported work coordinate systems (from index 1)
66 | #define SETTING_INDEX_NCOORD N_COORDINATE_SYSTEM+1 // Total number of system stored (from index 0)
67 | // NOTE: Work coordinate indices are (0=G54, 1=G55, ... , 6=G59)
68 | #define SETTING_INDEX_G28 N_COORDINATE_SYSTEM // Home position 1
69 | #define SETTING_INDEX_G30 N_COORDINATE_SYSTEM+1 // Home position 2
70 | // #define SETTING_INDEX_G92 N_COORDINATE_SYSTEM+2 // Coordinate offset (G92.2,G92.3 not supported)
71 |
72 | // Define Grbl axis settings numbering scheme. Starts at START_VAL, every INCREMENT, over N_SETTINGS.
73 | #define AXIS_N_SETTINGS 4
74 | #define AXIS_SETTINGS_START_VAL 100 // NOTE: Reserving settings values >= 100 for axis settings. Up to 255.
75 | #define AXIS_SETTINGS_INCREMENT 10 // Must be greater than the number of axis settings
76 |
77 | // Global persistent settings (Stored from byte EEPROM_ADDR_GLOBAL onwards)
78 | typedef struct {
79 | // Axis settings
80 | float steps_per_mm[N_AXIS];
81 | float max_rate[N_AXIS];
82 | float acceleration[N_AXIS];
83 | float max_travel[N_AXIS];
84 |
85 | // Remaining Grbl settings
86 | uint8_t pulse_microseconds;
87 | uint8_t step_invert_mask;
88 | uint8_t dir_invert_mask;
89 | uint8_t stepper_idle_lock_time; // If max value 255, steppers do not disable.
90 | uint8_t status_report_mask; // Mask to indicate desired report data.
91 | float junction_deviation;
92 | float arc_tolerance;
93 |
94 | uint16_t flags; // Contains default boolean settings
95 |
96 | uint8_t homing_dir_mask;
97 | float homing_feed_rate;
98 | float homing_seek_rate;
99 | uint16_t homing_debounce_delay;
100 | float homing_pulloff;
101 | } settings_t;
102 | extern settings_t settings;
103 |
104 | // Initialize the configuration subsystem (load settings from EEPROM)
105 | void settings_init();
106 |
107 | // A helper method to set new settings from command line
108 | uint8_t settings_store_global_setting(uint8_t parameter, float value);
109 |
110 | // Stores the protocol line variable as a startup line in EEPROM
111 | void settings_store_startup_line(uint8_t n, char *line);
112 |
113 | // Reads an EEPROM startup line to the protocol line variable
114 | uint8_t settings_read_startup_line(uint8_t n, char *line);
115 |
116 | // Stores build info user-defined string
117 | void settings_store_build_info(char *line);
118 |
119 | // Reads build info user-defined string
120 | uint8_t settings_read_build_info(char *line);
121 |
122 | // Writes selected coordinate data to EEPROM
123 | void settings_write_coord_data(uint8_t coord_select, float *coord_data);
124 |
125 | // Reads selected coordinate data from EEPROM
126 | uint8_t settings_read_coord_data(uint8_t coord_select, float *coord_data);
127 |
128 | // Returns the step pin mask according to Grbl's internal axis numbering
129 | uint8_t get_step_pin_mask(uint8_t i);
130 |
131 | // Returns the direction pin mask according to Grbl's internal axis numbering
132 | uint8_t get_direction_pin_mask(uint8_t i);
133 |
134 | // Returns the limit pin mask according to Grbl's internal axis numbering
135 | uint8_t get_limit_pin_mask(uint8_t i);
136 |
137 |
138 | #endif
139 |
--------------------------------------------------------------------------------
/print.c:
--------------------------------------------------------------------------------
1 | /*
2 | print.c - Functions for formatting output strings
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #include "system.h"
28 | #include "serial.h"
29 | #include "settings.h"
30 |
31 |
32 | void printString(const char *s)
33 | {
34 | while (*s)
35 | serial_write(*s++);
36 | }
37 |
38 |
39 | // Print a string stored in PGM-memory
40 | void printPgmString(const char *s)
41 | {
42 | char c;
43 | while ((c = pgm_read_byte_near(s++)))
44 | serial_write(c);
45 | }
46 |
47 |
48 | // void printIntegerInBase(unsigned long n, unsigned long base)
49 | // {
50 | // unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars.
51 | // unsigned long i = 0;
52 | //
53 | // if (n == 0) {
54 | // serial_write('0');
55 | // return;
56 | // }
57 | //
58 | // while (n > 0) {
59 | // buf[i++] = n % base;
60 | // n /= base;
61 | // }
62 | //
63 | // for (; i > 0; i--)
64 | // serial_write(buf[i - 1] < 10 ?
65 | // '0' + buf[i - 1] :
66 | // 'A' + buf[i - 1] - 10);
67 | // }
68 |
69 |
70 | void print_uint8_base2(uint8_t n)
71 | {
72 | unsigned char buf[8];
73 | uint8_t i = 0;
74 |
75 | for (; i < 8; i++) {
76 | buf[i] = n & 1;
77 | n >>= 1;
78 | }
79 |
80 | for (; i > 0; i--)
81 | serial_write('0' + buf[i - 1]);
82 | }
83 |
84 |
85 | void print_uint8_base10(uint8_t n)
86 | {
87 | if (n == 0) {
88 | serial_write('0');
89 | return;
90 | }
91 |
92 | unsigned char buf[3];
93 | uint8_t i = 0;
94 |
95 | while (n > 0) {
96 | buf[i++] = n % 10 + '0';
97 | n /= 10;
98 | }
99 |
100 | for (; i > 0; i--)
101 | serial_write(buf[i - 1]);
102 | }
103 |
104 |
105 | void print_uint32_base10(unsigned long n)
106 | {
107 | if (n == 0) {
108 | serial_write('0');
109 | return;
110 | }
111 |
112 | unsigned char buf[10];
113 | uint8_t i = 0;
114 |
115 | while (n > 0) {
116 | buf[i++] = n % 10;
117 | n /= 10;
118 | }
119 |
120 | for (; i > 0; i--)
121 | serial_write('0' + buf[i-1]);
122 | }
123 |
124 |
125 | void printInteger(long n)
126 | {
127 | if (n < 0) {
128 | serial_write('-');
129 | print_uint32_base10((-n));
130 | } else {
131 | print_uint32_base10(n);
132 | }
133 | }
134 |
135 |
136 | // Convert float to string by immediately converting to a long integer, which contains
137 | // more digits than a float. Number of decimal places, which are tracked by a counter,
138 | // may be set by the user. The integer is then efficiently converted to a string.
139 | // NOTE: AVR '%' and '/' integer operations are very efficient. Bitshifting speed-up
140 | // techniques are actually just slightly slower. Found this out the hard way.
141 | void printFloat(float n, uint8_t decimal_places)
142 | {
143 | if (n < 0) {
144 | serial_write('-');
145 | n = -n;
146 | }
147 |
148 | uint8_t decimals = decimal_places;
149 | while (decimals >= 2) { // Quickly convert values expected to be E0 to E-4.
150 | n *= 100;
151 | decimals -= 2;
152 | }
153 | if (decimals) { n *= 10; }
154 | n += 0.5; // Add rounding factor. Ensures carryover through entire value.
155 |
156 | // Generate digits backwards and store in string.
157 | unsigned char buf[10];
158 | uint8_t i = 0;
159 | uint32_t a = (long)n;
160 | buf[decimal_places] = '.'; // Place decimal point, even if decimal places are zero.
161 | while(a > 0) {
162 | if (i == decimal_places) { i++; } // Skip decimal point location
163 | buf[i++] = (a % 10) + '0'; // Get digit
164 | a /= 10;
165 | }
166 | while (i < decimal_places) {
167 | buf[i++] = '0'; // Fill in zeros to decimal point for (n < 1)
168 | }
169 | if (i == decimal_places) { // Fill in leading zero, if needed.
170 | i++;
171 | buf[i++] = '0';
172 | }
173 |
174 | // Print the generated string.
175 | for (; i > 0; i--)
176 | serial_write(buf[i-1]);
177 | }
178 |
179 |
180 | // Floating value printing handlers for special variables types used in Grbl and are defined
181 | // in the config.h.
182 | // - CoordValue: Handles all position or coordinate values in inches or mm reporting.
183 | // - RateValue: Handles feed rate and current velocity in inches or mm reporting.
184 | // - SettingValue: Handles all floating point settings values (always in mm.)
185 | void printFloat_CoordValue(float n) {
186 | if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)) {
187 | printFloat(n*INCH_PER_MM,N_DECIMAL_COORDVALUE_INCH);
188 | } else {
189 | printFloat(n,N_DECIMAL_COORDVALUE_MM);
190 | }
191 | }
192 |
193 | void printFloat_RateValue(float n) {
194 | if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)) {
195 | printFloat(n*INCH_PER_MM,N_DECIMAL_RATEVALUE_INCH);
196 | } else {
197 | printFloat(n,N_DECIMAL_RATEVALUE_MM);
198 | }
199 | }
200 |
201 | void printFloat_SettingValue(float n) { printFloat(n,N_DECIMAL_SETTINGVALUE); }
202 |
203 |
204 | // Debug tool to print free memory in bytes at the called point. Not used otherwise.
205 | void printFreeMemory()
206 | {
207 | extern int __heap_start, *__brkval;
208 | uint16_t free; // Up to 64k values.
209 | free = (int) &free - (__brkval == 0 ? (int) &__heap_start : (int) __brkval);
210 | printInteger((int32_t)free);
211 | printString(" ");
212 | }
213 |
--------------------------------------------------------------------------------
/eeprom.c:
--------------------------------------------------------------------------------
1 | // This file has been prepared for Doxygen automatic documentation generation.
2 | /*! \file ********************************************************************
3 | *
4 | * Atmel Corporation
5 | *
6 | * \li File: eeprom.c
7 | * \li Compiler: IAR EWAAVR 3.10c
8 | * \li Support mail: avr@atmel.com
9 | *
10 | * \li Supported devices: All devices with split EEPROM erase/write
11 | * capabilities can be used.
12 | * The example is written for ATmega48.
13 | *
14 | * \li AppNote: AVR103 - Using the EEPROM Programming Modes.
15 | *
16 | * \li Description: Example on how to use the split EEPROM erase/write
17 | * capabilities in e.g. ATmega48. All EEPROM
18 | * programming modes are tested, i.e. Erase+Write,
19 | * Erase-only and Write-only.
20 | *
21 | * $Revision: 1.6 $
22 | * $Date: Friday, February 11, 2005 07:16:44 UTC $
23 | ****************************************************************************/
24 | #include
25 | #include
26 |
27 | /* These EEPROM bits have different names on different devices. */
28 | #ifndef EEPE
29 | #define EEPE EEWE //!< EEPROM program/write enable.
30 | #define EEMPE EEMWE //!< EEPROM master program/write enable.
31 | #endif
32 |
33 | /* These two are unfortunately not defined in the device include files. */
34 | #define EEPM1 5 //!< EEPROM Programming Mode Bit 1.
35 | #define EEPM0 4 //!< EEPROM Programming Mode Bit 0.
36 |
37 | /* Define to reduce code size. */
38 | #define EEPROM_IGNORE_SELFPROG //!< Remove SPM flag polling.
39 |
40 | /*! \brief Read byte from EEPROM.
41 | *
42 | * This function reads one byte from a given EEPROM address.
43 | *
44 | * \note The CPU is halted for 4 clock cycles during EEPROM read.
45 | *
46 | * \param addr EEPROM address to read from.
47 | * \return The byte read from the EEPROM address.
48 | */
49 | unsigned char eeprom_get_char( unsigned int addr )
50 | {
51 | do {} while( EECR & (1< 0; size--) {
133 | checksum = (checksum << 1) || (checksum >> 7);
134 | checksum += *source;
135 | eeprom_put_char(destination++, *(source++));
136 | }
137 | eeprom_put_char(destination, checksum);
138 | }
139 |
140 | int memcpy_from_eeprom_with_checksum(char *destination, unsigned int source, unsigned int size) {
141 | unsigned char data, checksum = 0;
142 | for(; size > 0; size--) {
143 | data = eeprom_get_char(source++);
144 | checksum = (checksum << 1) || (checksum >> 7);
145 | checksum += data;
146 | *(destination++) = data;
147 | }
148 | return(checksum == eeprom_get_char(source));
149 | }
150 |
151 | // end of file
152 |
--------------------------------------------------------------------------------
/script/stream.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | """\
3 |
4 | Stream g-code to grbl controller
5 |
6 | This script differs from the simple_stream.py script by
7 | tracking the number of characters in grbl's serial read
8 | buffer. This allows grbl to fetch the next line directly
9 | from the serial buffer and does not have to wait for a
10 | response from the computer. This effectively adds another
11 | buffer layer to prevent buffer starvation.
12 |
13 | CHANGELOG:
14 | - 20140714: Updated baud rate to 115200. Added a settings
15 | write mode via simple streaming method. MIT-licensed.
16 |
17 | TODO:
18 | - Add runtime command capabilities
19 |
20 | ---------------------
21 | The MIT License (MIT)
22 |
23 | Copyright (c) 2012-2014 Sungeun K. Jeon
24 |
25 | Permission is hereby granted, free of charge, to any person obtaining a copy
26 | of this software and associated documentation files (the "Software"), to deal
27 | in the Software without restriction, including without limitation the rights
28 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
29 | copies of the Software, and to permit persons to whom the Software is
30 | furnished to do so, subject to the following conditions:
31 |
32 | The above copyright notice and this permission notice shall be included in
33 | all copies or substantial portions of the Software.
34 |
35 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
36 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
37 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
38 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
39 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
40 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
41 | THE SOFTWARE.
42 | ---------------------
43 | """
44 |
45 | import serial
46 | import re
47 | import time
48 | import sys
49 | import argparse
50 | # import threading
51 |
52 | RX_BUFFER_SIZE = 128
53 |
54 | # Define command line argument interface
55 | parser = argparse.ArgumentParser(description='Stream g-code file to grbl. (pySerial and argparse libraries required)')
56 | parser.add_argument('gcode_file', type=argparse.FileType('r'),
57 | help='g-code filename to be streamed')
58 | parser.add_argument('device_file',
59 | help='serial device path')
60 | parser.add_argument('-q','--quiet',action='store_true', default=False,
61 | help='suppress output text')
62 | parser.add_argument('-s','--settings',action='store_true', default=False,
63 | help='settings write mode')
64 | args = parser.parse_args()
65 |
66 | # Periodic timer to query for status reports
67 | # TODO: Need to track down why this doesn't restart consistently before a release.
68 | # def periodic():
69 | # s.write('?')
70 | # t = threading.Timer(0.1, periodic) # In seconds
71 | # t.start()
72 |
73 | # Initialize
74 | s = serial.Serial(args.device_file,115200)
75 | f = args.gcode_file
76 | verbose = True
77 | if args.quiet : verbose = False
78 | settings_mode = False
79 | if args.settings : settings_mode = True
80 |
81 | # Wake up grbl
82 | print "Initializing grbl..."
83 | s.write("\r\n\r\n")
84 |
85 | # Wait for grbl to initialize and flush startup text in serial input
86 | time.sleep(2)
87 | s.flushInput()
88 |
89 | # Stream g-code to grbl
90 | l_count = 0
91 | if settings_mode:
92 | # Send settings file via simple call-response streaming method. Settings must be streamed
93 | # in this manner since the EEPROM accessing cycles shut-off the serial interrupt.
94 | print "SETTINGS MODE: Streaming", args.gcode_file.name, " to ", args.device_file
95 | for line in f:
96 | l_count += 1 # Iterate line counter
97 | # l_block = re.sub('\s|\(.*?\)','',line).upper() # Strip comments/spaces/new line and capitalize
98 | l_block = line.strip() # Strip all EOL characters for consistency
99 | if verbose: print 'SND: ' + str(l_count) + ':' + l_block,
100 | s.write(l_block + '\n') # Send g-code block to grbl
101 | grbl_out = s.readline().strip() # Wait for grbl response with carriage return
102 | if verbose: print 'REC:',grbl_out
103 | else:
104 | # Send g-code program via a more agressive streaming protocol that forces characters into
105 | # Grbl's serial read buffer to ensure Grbl has immediate access to the next g-code command
106 | # rather than wait for the call-response serial protocol to finish. This is done by careful
107 | # counting of the number of characters sent by the streamer to Grbl and tracking Grbl's
108 | # responses, such that we never overflow Grbl's serial read buffer.
109 | g_count = 0
110 | c_line = []
111 | # periodic() # Start status report periodic timer
112 | for line in f:
113 | l_count += 1 # Iterate line counter
114 | # l_block = re.sub('\s|\(.*?\)','',line).upper() # Strip comments/spaces/new line and capitalize
115 | l_block = line.strip()
116 | c_line.append(len(l_block)+1) # Track number of characters in grbl serial read buffer
117 | grbl_out = ''
118 | while sum(c_line) >= RX_BUFFER_SIZE-1 | s.inWaiting() :
119 | out_temp = s.readline().strip() # Wait for grbl response
120 | if out_temp.find('ok') < 0 and out_temp.find('error') < 0 :
121 | print " Debug: ",out_temp # Debug response
122 | else :
123 | grbl_out += out_temp;
124 | g_count += 1 # Iterate g-code counter
125 | grbl_out += str(g_count); # Add line finished indicator
126 | del c_line[0] # Delete the block character count corresponding to the last 'ok'
127 | if verbose: print "SND: " + str(l_count) + " : " + l_block,
128 | s.write(l_block + '\n') # Send g-code block to grbl
129 | if verbose : print "BUF:",str(sum(c_line)),"REC:",grbl_out
130 |
131 | # Wait for user input after streaming is completed
132 | print "G-code streaming finished!\n"
133 | print "WARNING: Wait until grbl completes buffered g-code blocks before exiting."
134 | raw_input(" Press to exit and disable grbl.")
135 |
136 | # Close file and serial port
137 | f.close()
138 | s.close()
--------------------------------------------------------------------------------
/serial.c:
--------------------------------------------------------------------------------
1 | /*
2 | serial.c - Low level functions for sending and recieving bytes via the serial port
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #include
28 | #include "system.h"
29 | #include "serial.h"
30 | #include "motion_control.h"
31 | #include "protocol.h"
32 |
33 |
34 | uint8_t serial_rx_buffer[RX_BUFFER_SIZE];
35 | uint8_t serial_rx_buffer_head = 0;
36 | volatile uint8_t serial_rx_buffer_tail = 0;
37 |
38 | uint8_t serial_tx_buffer[TX_BUFFER_SIZE];
39 | uint8_t serial_tx_buffer_head = 0;
40 | volatile uint8_t serial_tx_buffer_tail = 0;
41 |
42 |
43 | #ifdef ENABLE_XONXOFF
44 | volatile uint8_t flow_ctrl = XON_SENT; // Flow control state variable
45 | #endif
46 |
47 |
48 | // Returns the number of bytes used in the RX serial buffer.
49 | uint8_t serial_get_rx_buffer_count()
50 | {
51 | uint8_t rtail = serial_rx_buffer_tail; // Copy to limit multiple calls to volatile
52 | if (serial_rx_buffer_head >= rtail) { return(serial_rx_buffer_head-rtail); }
53 | return (RX_BUFFER_SIZE - (rtail-serial_rx_buffer_head));
54 | }
55 |
56 |
57 | // Returns the number of bytes used in the TX serial buffer.
58 | // NOTE: Not used except for debugging and ensuring no TX bottlenecks.
59 | uint8_t serial_get_tx_buffer_count()
60 | {
61 | uint8_t ttail = serial_tx_buffer_tail; // Copy to limit multiple calls to volatile
62 | if (serial_tx_buffer_head >= ttail) { return(serial_tx_buffer_head-ttail); }
63 | return (TX_BUFFER_SIZE - (ttail-serial_tx_buffer_head));
64 | }
65 |
66 |
67 | void serial_init()
68 | {
69 | // Set baud rate
70 | #if BAUD_RATE < 57600
71 | uint16_t UBRR0_value = ((F_CPU / (8L * BAUD_RATE)) - 1)/2 ;
72 | UCSR0A &= ~(1 << U2X0); // baud doubler off - Only needed on Uno XXX
73 | #else
74 | uint16_t UBRR0_value = ((F_CPU / (4L * BAUD_RATE)) - 1)/2;
75 | UCSR0A |= (1 << U2X0); // baud doubler on for high baud rates, i.e. 115200
76 | #endif
77 | UBRR0H = UBRR0_value >> 8;
78 | UBRR0L = UBRR0_value;
79 |
80 | // enable rx and tx
81 | UCSR0B |= 1<= RX_BUFFER_FULL) && flow_ctrl == XON_SENT) {
190 | flow_ctrl = SEND_XOFF;
191 | UCSR0B |= (1 << UDRIE0); // Force TX
192 | }
193 | #endif
194 |
195 | }
196 | //TODO: else alarm on overflow?
197 | }
198 | }
199 |
200 |
201 | void serial_reset_read_buffer()
202 | {
203 | serial_rx_buffer_tail = serial_rx_buffer_head;
204 |
205 | #ifdef ENABLE_XONXOFF
206 | flow_ctrl = XON_SENT;
207 | #endif
208 | }
209 |
--------------------------------------------------------------------------------
/gcode.h:
--------------------------------------------------------------------------------
1 | /*
2 | gcode.h - rs274/ngc parser.
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #ifndef gcode_h
28 | #define gcode_h
29 |
30 |
31 | // Define modal group internal numbers for checking multiple command violations and tracking the
32 | // type of command that is called in the block. A modal group is a group of g-code commands that are
33 | // mutually exclusive, or cannot exist on the same line, because they each toggle a state or execute
34 | // a unique motion. These are defined in the NIST RS274-NGC v3 g-code standard, available online,
35 | // and are similar/identical to other g-code interpreters by manufacturers (Haas,Fanuc,Mazak,etc).
36 | // NOTE: Modal group define values must be sequential and starting from zero.
37 | #define MODAL_GROUP_G0 0 // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal
38 | #define MODAL_GROUP_G1 1 // [G0,G1,G2,G3,G38.2,G80] Motion
39 | #define MODAL_GROUP_G2 2 // [G17,G18,G19] Plane selection
40 | #define MODAL_GROUP_G3 3 // [G90,G91] Distance mode
41 | #define MODAL_GROUP_G5 4 // [G93,G94] Feed rate mode
42 | #define MODAL_GROUP_G6 5 // [G20,G21] Units
43 | #define MODAL_GROUP_G8 6 // [G43,G43.1,G49] Tool length offset
44 | #define MODAL_GROUP_G12 7 // [G54,G55,G56,G57,G58,G59] Coordinate system selection
45 |
46 | #define MODAL_GROUP_M4 8 // [M0,M1,M2,M30] Stopping
47 | #define MODAL_GROUP_M7 9 // [M3,M4,M5] Spindle turning
48 | #define MODAL_GROUP_M8 10 // [M7,M8,M9] Coolant control
49 |
50 | #define OTHER_INPUT_F 11
51 | #define OTHER_INPUT_S 12
52 | #define OTHER_INPUT_T 13
53 |
54 | // Define command actions for within execution-type modal groups (motion, stopping, non-modal). Used
55 | // internally by the parser to know which command to execute.
56 |
57 | // Modal Group G0: Non-modal actions
58 | #define NON_MODAL_NO_ACTION 0 // (Default: Must be zero)
59 | #define NON_MODAL_DWELL 1 // G4
60 | #define NON_MODAL_SET_COORDINATE_DATA 2 // G10
61 | #define NON_MODAL_GO_HOME_0 3 // G28
62 | #define NON_MODAL_SET_HOME_0 4 // G28.1
63 | #define NON_MODAL_GO_HOME_1 5 // G30
64 | #define NON_MODAL_SET_HOME_1 6 // G30.1
65 | #define NON_MODAL_ABSOLUTE_OVERRIDE 7 // G53
66 | #define NON_MODAL_SET_COORDINATE_OFFSET 8 // G92
67 | #define NON_MODAL_RESET_COORDINATE_OFFSET 9 //G92.1
68 |
69 | // Modal Group G1: Motion modes
70 | #define MOTION_MODE_SEEK 0 // G0 (Default: Must be zero)
71 | #define MOTION_MODE_LINEAR 1 // G1
72 | #define MOTION_MODE_CW_ARC 2 // G2
73 | #define MOTION_MODE_CCW_ARC 3 // G3
74 | #define MOTION_MODE_PROBE 4 // G38.2
75 | #define MOTION_MODE_NONE 5 // G80
76 |
77 | // Modal Group G2: Plane select
78 | #define PLANE_SELECT_XY 0 // G17 (Default: Must be zero)
79 | #define PLANE_SELECT_ZX 1 // G18
80 | #define PLANE_SELECT_YZ 2 // G19
81 |
82 | // Modal Group G3: Distance mode
83 | #define DISTANCE_MODE_ABSOLUTE 0 // G90 (Default: Must be zero)
84 | #define DISTANCE_MODE_INCREMENTAL 1 // G91
85 |
86 | // Modal Group M4: Program flow
87 | #define PROGRAM_FLOW_RUNNING 0 // (Default: Must be zero)
88 | #define PROGRAM_FLOW_PAUSED 1 // M0, M1
89 | #define PROGRAM_FLOW_COMPLETED 2 // M2, M30
90 |
91 | // Modal Group G5: Feed rate mode
92 | #define FEED_RATE_MODE_UNITS_PER_MIN 0 // G94 (Default: Must be zero)
93 | #define FEED_RATE_MODE_INVERSE_TIME 1 // G93
94 |
95 | // Modal Group G6: Units mode
96 | #define UNITS_MODE_MM 0 // G21 (Default: Must be zero)
97 | #define UNITS_MODE_INCHES 1 // G20
98 |
99 | // Modal Group M7: Spindle control
100 | #define SPINDLE_DISABLE 0 // M5 (Default: Must be zero)
101 | #define SPINDLE_ENABLE_CW 1 // M3
102 | #define SPINDLE_ENABLE_CCW 2 // M4
103 |
104 | // Modal Group M8: Coolant control
105 | #define COOLANT_DISABLE 0 // M9 (Default: Must be zero)
106 | #define COOLANT_MIST_ENABLE 1 // M7
107 | #define COOLANT_FLOOD_ENABLE 2 // M8
108 |
109 | // Modal Group G8: Tool length offset
110 | #define TOOL_LENGTH_OFFSET_CANCEL 0 // G49 (Default: Must be zero)
111 | #define TOOL_LENGTH_OFFSET_ENABLE_DYNAMIC 1 // G43.1
112 |
113 | // Modal Group G12: Active work coordinate system
114 | // N/A: Stores coordinate system value (54-59) to change to.
115 |
116 | #define WORD_F 0
117 | #define WORD_I 1
118 | #define WORD_J 2
119 | #define WORD_K 3
120 | #define WORD_L 4
121 | #define WORD_N 5
122 | #define WORD_P 6
123 | #define WORD_R 7
124 | #define WORD_S 8
125 | #define WORD_T 9
126 | #define WORD_X 10
127 | #define WORD_Y 11
128 | #define WORD_Z 12
129 |
130 | #ifdef LASER_SPINDLE
131 | // Status of the g code block
132 | #define BLOCK_HAS_NO_MOTION 0 // (Default: Must be zero)
133 | #define BLOCK_HAS_MOTION 1 // no motion in gcode
134 | #endif
135 |
136 |
137 | // NOTE: When this struct is zeroed, the above defines set the defaults for the system.
138 | typedef struct {
139 | uint8_t motion; // {G0,G1,G2,G3,G38.2,G80}
140 | uint8_t feed_rate; // {G93,G94}
141 | uint8_t units; // {G20,G21}
142 | uint8_t distance; // {G90,G91}
143 | uint8_t plane_select; // {G17,G18,G19}
144 | uint8_t tool_length; // {G43.1,G49}
145 | uint8_t coord_select; // {G54,G55,G56,G57,G58,G59}
146 | uint8_t program_flow; // {M0,M1,M2,M30}
147 | uint8_t coolant; // {M7,M8,M9}
148 | uint8_t spindle; // {M3,M4,M5}
149 | } gc_modal_t;
150 |
151 | typedef struct {
152 | float f; // Feed
153 | float ijk[3]; // I,J,K Axis arc offsets
154 | uint8_t l; // G10 or canned cycles parameters
155 | int32_t n; // Line number
156 | float p; // G10 or dwell parameters
157 | // float q; // G82 peck drilling
158 | float r; // Arc radius
159 | float s; // Spindle speed
160 | uint8_t t; // Tool selection
161 | float xyz[3]; // X,Y,Z Translational axes
162 | } gc_values_t;
163 |
164 |
165 | typedef struct {
166 | gc_modal_t modal;
167 |
168 | float spindle_speed; // RPM
169 | float feed_rate; // Millimeters/min
170 | uint8_t tool; // Tracks tool number. NOT USED.
171 | // int32_t line_number; // Last line number sent
172 |
173 | float position[N_AXIS]; // Where the interpreter considers the tool to be at this point in the code
174 |
175 | float coord_system[N_AXIS]; // Current work coordinate system (G54+). Stores offset from absolute machine
176 | // position in mm. Loaded from EEPROM when called.
177 | float coord_offset[N_AXIS]; // Retains the G92 coordinate offset (work coordinates) relative to
178 | // machine zero in mm. Non-persistent. Cleared upon reset and boot.
179 | float tool_length_offset; // Tracks tool length offset value when enabled.
180 | } parser_state_t;
181 | extern parser_state_t gc_state;
182 |
183 | typedef struct {
184 | // uint16_t command_words; // NOTE: If this bitflag variable fills, G and M words can be separated.
185 | // uint16_t value_words;
186 | #ifdef LASER_SPINDLE
187 | uint8_t motion;
188 | #endif
189 | uint8_t non_modal_command;
190 | gc_modal_t modal;
191 | gc_values_t values;
192 |
193 | } parser_block_t;
194 | extern parser_block_t gc_block;
195 |
196 | // Initialize the parser
197 | void gc_init();
198 |
199 | // Execute one block of rs275/ngc/g-code
200 | uint8_t gc_execute_line(char *line);
201 |
202 | // Set g-code parser position. Input in steps.
203 | void gc_sync_position();
204 |
205 | #endif
206 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | #Grbl - Mr Beam Edition
2 |
3 | Mr Beam uses grbl for stepper motor and laser control for its portable and affordable laser cutter and engraver kits. It runs on an Arduino Uno and requires a Mr Beam Shield [Mr Beam Shield](http://shop.mr-beam.org/product/mr-beam-shield) for driving motors and the laser.
4 |
5 | This is a modified version of the grbl v0.9. The original grbl description follows.
6 |
7 | #Grbl - An embedded g-code interpreter and motion-controller for the Arduino/AVR328 microcontroller
8 | ------------
9 |
10 | Grbl is a no-compromise, high performance, low cost alternative to parallel-port-based motion control for CNC milling. It will run on a vanilla Arduino (Duemillanove/Uno) as long as it sports an Atmega 328.
11 |
12 | The controller is written in highly optimized C utilizing every clever feature of the AVR-chips to achieve precise timing and asynchronous operation. It is able to maintain up to 30kHz of stable, jitter free control pulses.
13 |
14 | It accepts standards-compliant G-code and has been tested with the output of several CAM tools with no problems. Arcs, circles and helical motion are fully supported, as well as, other basic functional g-code commands. Functions and variables are not currently supported, but may be included in future releases in a form of a pre-processor.
15 |
16 | Grbl includes full acceleration management with look ahead. That means the controller will look up to 18 motions into the future and plan its velocities ahead to deliver smooth acceleration and jerk-free cornering.
17 |
18 | * Note on licensing: All previous Grbl versions (v0.8 and prior) are licensed under the MIT software license. The current and future branches of Grbl (v0.9 and after) will remain under GPLv3 licensing until the next version is pushed, where the obsoleted version will then be updated to the MIT-license. This decision was made to ensure Grbl will always be an open-source project while making the code permissive for others.
19 |
20 | * For more information and help, check out our **[Wiki pages!](https://github.com/grbl/grbl/wiki)** If you find that the information is out-dated, please to help us keep it updated by editing it or notifying our community! Thanks!
21 |
22 | * Current Lead Developer: Sonny Jeon, Ph.D. (2011-2014)
23 | * The Originator/Creator/Pioneer/Father of Grbl: Simen Svale Skogsrud (2009-2011)
24 |
25 | ------------
26 |
27 | ##Update Summary for v0.9 from v0.8
28 | - **_BETA_ status:** Minor bugs may exist. Under final testing for master release. Please report any issues to administrators so we can push this out quickly!
29 | - **IMPORTANT: Default serial baudrate is now 115200! (Up from 9600)**
30 | - **_NEW_ Super Smooth Stepper Algorithm:** Complete overhaul of the handling of the stepper driver to simplify and reduce task time per ISR tick. Much smoother operation with the new Adaptive Multi-Axis Step Smoothing (AMASS) algorithm which does what its name implies (see stepper.c source for details). Users should immediately see significant improvements in how their machines move and overall performance!
31 | - **Stability and Robustness Updates:** Grbl's overall stability has been focused on for this version. The planner and step-execution interface has been completely re-written for robustness and incorruptibility by the introduction of an intermediate step segment buffer that "checks-out" steps from the planner buffer in real-time. This means we can now fearlessly drive Grbl to it's highest limits. Combined with the new stepper algorithm and planner optimizations, this translated to **5x to 10x** overall performance increases in our testing! Also, stability and robustness tests have been reported to easily take 1.4 million (yes, **million**) line g-code programs like a champ!
32 | - **(x4)+ Faster Planner:** Planning computations improved four-fold or more by optimizing end-to-end operations, which included streamlining the computations and introducing a planner pointer to locate un-improvable portions of the buffer and not waste cycles recomputing them.
33 | - **Compile-able via Arduino IDE!:** Grbl's source code may be now download and altered, and then be compiled and flashed directly through the Arduino IDE, which should work on all platforms. See the Wiki for details on how to do it.
34 | - **G-Code Parser Overhaul:** Completely re-written from the ground-up for 100%-compliance* to the g-code standard. (* Parts of the NIST standard are a bit out-dated and arbitrary, so we altered some minor things to make more sense. Differences are outlined in the source code.) We also took steps to allow us to break up the g-code parser into distinct separate tasks, which is key for some future development ideas and improvements.
35 | - **Independent Acceleration and Velocity Settings:** Each axes may be defined with unique acceleration and velocity parameters and Grbl will automagically calculate the maximum acceleration and velocity through a path depending on the direction traveled. This is very useful for machines that have very different axes properties, like the ShapeOko's z-axis.
36 | - **Soft Limits:** Checks if any motion command exceeds workspace limits before executing it, and alarms out, if detected. Another safety feature, but, unlike hard limits, position does not get lost, as it forces a feed hold before erroring out. NOTE: This still requires limit switches for homing so Grbl knows where the machine origin is, and the new max axis travel settings configured correctly for the machine.
37 | - **Probing:** The G38.2 straight probe and G43.1/49 tool offset g-code commands are now supported. A simple probe switch must be connected to the Uno analog pin 5 (normally-open to ground). Grbl will report the probe position back to the user when the probing cycle detects a pin state change.
38 | - **Tool Length Offsets:** Probing doesn't make sense without tool length offsets(TLO), so we added it! The G43.1 dynamic TLO (described by linuxcnc.org) and G49 TLO cancel commands are now supported. G43.1 dynamic TLO works like the normal G43 TLO(NOT SUPPORTED) but requires an additional axis word with the offset value attached. We did this so Grbl does not have to track and maintain a tool offset database in its memory. Perhaps in the future, we will support a tool database, but not for this version.
39 | - **Improved Arc Performance:** The larger the arc radius, the faster Grbl will trace it! We are now defining arcs in terms of arc chordal tolerance, rather than a fixed segment length. This automatically scales the arc segment length such that maximum radial error of the segment from the true arc is never more than the chordal tolerance value of a super-accurate default of 0.002 mm.
40 | - **CPU Pin Mapping:** In an effort for Grbl to be compatible with other AVR architectures, such as the 1280 or 2560, a new cpu_map.h pin configuration file has been created to allow Grbl to be compiled for them. This is currently user supported, so your mileage may vary. If you run across a bug, please let us know or better send us a fix! Thanks in advance!
41 | - **New Grbl SIMULATOR! (by @jgeisler and @ashelly):** A completely independent wrapper of the Grbl main source code that may be compiled as an executable on a computer. No Arduino required. Simply simulates the responses of Grbl as if it was on an Arduino. May be used for many things: checking out how Grbl works, pre-process moves for GUI graphics, debugging of new features, etc. Much left to do, but potentially very powerful, as the dummy AVR variables can be written to output anything you need.
42 | - **Configurable Real-time Status Reporting:** Users can now customize the type of real-time data Grbl reports back when they issue a '?' status report. This includes data such as: machine position, work position, planner buffer usage, serial RX buffer usage.
43 | - **Updated Homing Routine:** Sets workspace volume in all negative space regardless of limit switch position. Common on pro CNCs. But, the behavior may be changed by a compile-time option though. Now tied directly into the main planner and stepper modules to reduce flash space and allow maximum speeds during seeking.
44 | - **Optional Limit Pin Sharing:** Limit switches can be combined to share the same pins to free up precious I/O pins for other purposes. When combined, users must adjust the homing cycle mask in config.h to not home the axes on a shared pin at the same time. Don't worry; hard limits and the homing cycle still work just like they did before.
45 | - **Optional Variable Spindle Speed Output:** Available only as a compile-time option through the config.h file. Enables PWM output for 'S' g-code commands. Enabling this feature will swap the Z-limit D11 pin and spindle enable D12 pin to access the hardware PWM on pin D12. The Z-limit pin, now on D12, should work just as it did before.
46 | - **Additional Compile-Time Feature Options:** Line number tracking, real-time feed rate reporting.
47 | - **SLATED FOR v1.0 DEVELOPMENT** Jogging controls and feedrate/spindle/coolant overrides. (In v0.9, the framework for feedrate overrides are in-place, only the minor details to complete it have yet to be installed.)
48 |
49 | -
50 | ```
51 | List of Supported G-Codes in Grbl v0.9
52 | - Non-Modal Commands: G4, G10 L2, G10 L20, G28, G30, G28.1, G30.1, G53, G92, G92.1
53 | - Motion Modes: G0, G1, G2, G3, G38.1, G80
54 | - Feed Rate Modes: G93, G94
55 | - Unit Modes: G20, G21
56 | - Distance Modes: G90, G91
57 | - Plane Select Modes: G17, G18, G19
58 | - Tool Length Offset Modes: G43.1, G49
59 | - Coordinate System Modes: G54, G55, G56, G57, G58, G59
60 | - Program Flow: M0, M1, M2, M30*
61 | - Coolant Control: M7*, M8, M9
62 | - Spindle Control: M3, M4, M5
63 | ```
64 |
65 | -------------
66 | Grbl is an open-source project and fueled by the free-time of our intrepid administrators and altruistic users. If you'd like to donate, all proceeds will be used to help fund supporting hardware and testing equipment. Thank you!
67 |
68 | [](https://www.paypal.com/cgi-bin/webscr?cmd=_s-xclick&hosted_button_id=EBQWAWQAAT878)
69 |
70 |
--------------------------------------------------------------------------------
/system.c:
--------------------------------------------------------------------------------
1 | /*
2 | system.c - Handles system level commands and real-time processes
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 |
21 | #include "system.h"
22 | #include "settings.h"
23 | #include "gcode.h"
24 | #include "motion_control.h"
25 | #include "report.h"
26 | #include "print.h"
27 |
28 |
29 | void system_init()
30 | {
31 | PINOUT_DDR &= ~(PINOUT_MASK); // Configure as input pins
32 | PINOUT_PORT |= PINOUT_MASK; // Enable internal pull-up resistors. Normal high operation.
33 | PINOUT_PCMSK |= PINOUT_MASK; // Enable specific pins of the Pin Change Interrupt
34 | PCICR |= (1 << PINOUT_INT); // Enable Pin Change Interrupt
35 | }
36 |
37 |
38 | // Pin change interrupt for pin-out commands, i.e. cycle start, feed hold, and reset. Sets
39 | // only the runtime command execute variable to have the main program execute these when
40 | // its ready. This works exactly like the character-based runtime commands when picked off
41 | // directly from the incoming serial data stream.
42 | ISR(PINOUT_INT_vect)
43 | {
44 | // Enter only if any pinout pin is actively low.
45 | if ((PINOUT_PIN & PINOUT_MASK) ^ PINOUT_MASK) {
46 | if (bit_isfalse(PINOUT_PIN,bit(PIN_RESET))) {
47 | mc_reset();
48 | } else if (bit_isfalse(PINOUT_PIN,bit(PIN_FEED_HOLD))) {
49 | bit_true(sys.execute, EXEC_FEED_HOLD);
50 | } else if (bit_isfalse(PINOUT_PIN,bit(PIN_CYCLE_START))) {
51 | bit_true(sys.execute, EXEC_CYCLE_START);
52 | }
53 | }
54 | }
55 |
56 |
57 | // Executes user startup script, if stored.
58 | void system_execute_startup(char *line)
59 | {
60 | uint8_t n;
61 | for (n=0; n < N_STARTUP_LINE; n++) {
62 | if (!(settings_read_startup_line(n, line))) {
63 | report_status_message(STATUS_SETTING_READ_FAIL);
64 | } else {
65 | if (line[0] != 0) {
66 | printString(line); // Echo startup line to indicate execution.
67 | report_status_message(gc_execute_line(line));
68 | }
69 | }
70 | }
71 | }
72 |
73 |
74 | // Directs and executes one line of formatted input from protocol_process. While mostly
75 | // incoming streaming g-code blocks, this also executes Grbl internal commands, such as
76 | // settings, initiating the homing cycle, and toggling switch states. This differs from
77 | // the runtime command module by being susceptible to when Grbl is ready to execute the
78 | // next line during a cycle, so for switches like block delete, the switch only effects
79 | // the lines that are processed afterward, not necessarily real-time during a cycle,
80 | // since there are motions already stored in the buffer. However, this 'lag' should not
81 | // be an issue, since these commands are not typically used during a cycle.
82 | uint8_t system_execute_line(char *line)
83 | {
84 | uint8_t char_counter = 1;
85 | uint8_t helper_var = 0; // Helper variable
86 | float parameter, value;
87 | switch( line[char_counter] ) {
88 | case 0 : report_grbl_help(); break;
89 | case '$' : // Prints Grbl settings
90 | if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); }
91 | else { report_grbl_settings(); }
92 | break;
93 | case 'G' : // Prints gcode parser state
94 | if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); }
95 | else { report_gcode_modes(); }
96 | break;
97 | case 'C' : // Set check g-code mode [IDLE/CHECK]
98 | if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); }
99 | // Perform reset when toggling off. Check g-code mode should only work if Grbl
100 | // is idle and ready, regardless of alarm locks. This is mainly to keep things
101 | // simple and consistent.
102 | if ( sys.state == STATE_CHECK_MODE ) {
103 | mc_reset();
104 | report_feedback_message(MESSAGE_DISABLED);
105 | } else {
106 | if (sys.state) { return(STATUS_IDLE_ERROR); } // Requires no alarm mode.
107 | sys.state = STATE_CHECK_MODE;
108 | report_feedback_message(MESSAGE_ENABLED);
109 | }
110 | break;
111 | case 'X' : // Disable alarm lock [ALARM]
112 | if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); }
113 | if (sys.state == STATE_ALARM) {
114 | report_feedback_message(MESSAGE_ALARM_UNLOCK);
115 | sys.state = STATE_IDLE;
116 | // Don't run startup script. Prevents stored moves in startup from causing accidents.
117 | } // Otherwise, no effect.
118 | break;
119 | // case 'J' : break; // Jogging methods
120 | // TODO: Here jogging can be placed for execution as a seperate subprogram. It does not need to be
121 | // susceptible to other runtime commands except for e-stop. The jogging function is intended to
122 | // be a basic toggle on/off with controlled acceleration and deceleration to prevent skipped
123 | // steps. The user would supply the desired feedrate, axis to move, and direction. Toggle on would
124 | // start motion and toggle off would initiate a deceleration to stop. One could 'feather' the
125 | // motion by repeatedly toggling to slow the motion to the desired location. Location data would
126 | // need to be updated real-time and supplied to the user through status queries.
127 | // More controlled exact motions can be taken care of by inputting G0 or G1 commands, which are
128 | // handled by the planner. It would be possible for the jog subprogram to insert blocks into the
129 | // block buffer without having the planner plan them. It would need to manage de/ac-celerations
130 | // on its own carefully. This approach could be effective and possibly size/memory efficient.
131 | default :
132 | // Block any system command that requires the state as IDLE/ALARM. (i.e. EEPROM, homing)
133 | if ( !(sys.state == STATE_IDLE || sys.state == STATE_ALARM) ) { return(STATUS_IDLE_ERROR); }
134 | switch( line[char_counter] ) {
135 | case '#' : // Print Grbl NGC parameters
136 | if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); }
137 | else { report_ngc_parameters(); }
138 | break;
139 | case 'H' : // Perform homing cycle [IDLE/ALARM]
140 | if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) {
141 | // Only perform homing if Grbl is idle or lost.
142 | mc_homing_cycle();
143 | if (!sys.abort) { system_execute_startup(line); } // Execute startup scripts after successful homing.
144 | } else { return(STATUS_SETTING_DISABLED); }
145 | break;
146 | case 'I' : // Print or store build info. [IDLE/ALARM]
147 | if ( line[++char_counter] == 0 ) {
148 | settings_read_build_info(line);
149 | report_build_info(line);
150 | } else { // Store startup line [IDLE/ALARM]
151 | if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); }
152 | helper_var = char_counter; // Set helper variable as counter to start of user info line.
153 | do {
154 | line[char_counter-helper_var] = line[char_counter];
155 | } while (line[char_counter++] != 0);
156 | settings_store_build_info(line);
157 | }
158 | break;
159 | case 'N' : // Startup lines. [IDLE/ALARM]
160 | if ( line[++char_counter] == 0 ) { // Print startup lines
161 | for (helper_var=0; helper_var < N_STARTUP_LINE; helper_var++) {
162 | if (!(settings_read_startup_line(helper_var, line))) {
163 | report_status_message(STATUS_SETTING_READ_FAIL);
164 | } else {
165 | report_startup_line(helper_var,line);
166 | }
167 | }
168 | break;
169 | } else { // Store startup line [IDLE Only] Prevents motion during ALARM.
170 | if (sys.state != STATE_IDLE) { return(STATUS_IDLE_ERROR); } // Store only when idle.
171 | helper_var = true; // Set helper_var to flag storing method.
172 | // No break. Continues into default: to read remaining command characters.
173 | }
174 | default : // Storing setting methods [IDLE/ALARM]
175 | if(!read_float(line, &char_counter, ¶meter)) { return(STATUS_BAD_NUMBER_FORMAT); }
176 | if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); }
177 | if (helper_var) { // Store startup line
178 | // Prepare sending gcode block to gcode parser by shifting all characters
179 | helper_var = char_counter; // Set helper variable as counter to start of gcode block
180 | do {
181 | line[char_counter-helper_var] = line[char_counter];
182 | } while (line[char_counter++] != 0);
183 | // Execute gcode block to ensure block is valid.
184 | helper_var = gc_execute_line(line); // Set helper_var to returned status code.
185 | if (helper_var) { return(helper_var); }
186 | else {
187 | helper_var = trunc(parameter); // Set helper_var to int value of parameter
188 | settings_store_startup_line(helper_var,line);
189 | }
190 | } else { // Store global setting.
191 | if(!read_float(line, &char_counter, &value)) { return(STATUS_BAD_NUMBER_FORMAT); }
192 | if((line[char_counter] != 0) || (parameter > 255)) { return(STATUS_INVALID_STATEMENT); }
193 | return(settings_store_global_setting((uint8_t)parameter, value));
194 | }
195 | }
196 | }
197 | return(STATUS_OK); // If '$' command makes it to here, then everything's ok.
198 | }
199 |
--------------------------------------------------------------------------------
/settings.c:
--------------------------------------------------------------------------------
1 | /*
2 | settings.c - eeprom configuration handling
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #include "system.h"
28 | #include "settings.h"
29 | #include "eeprom.h"
30 | #include "protocol.h"
31 | #include "report.h"
32 | #include "limits.h"
33 | #include "stepper.h"
34 |
35 | settings_t settings;
36 |
37 |
38 | // Method to store startup lines into EEPROM
39 | void settings_store_startup_line(uint8_t n, char *line)
40 | {
41 | uint32_t addr = n*(LINE_BUFFER_SIZE+1)+EEPROM_ADDR_STARTUP_BLOCK;
42 | memcpy_to_eeprom_with_checksum(addr,(char*)line, LINE_BUFFER_SIZE);
43 | }
44 |
45 |
46 | // Method to store build info into EEPROM
47 | void settings_store_build_info(char *line)
48 | {
49 | memcpy_to_eeprom_with_checksum(EEPROM_ADDR_BUILD_INFO,(char*)line, LINE_BUFFER_SIZE);
50 | }
51 |
52 |
53 | // Method to store coord data parameters into EEPROM
54 | void settings_write_coord_data(uint8_t coord_select, float *coord_data)
55 | {
56 | uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS;
57 | memcpy_to_eeprom_with_checksum(addr,(char*)coord_data, sizeof(float)*N_AXIS);
58 | }
59 |
60 |
61 | // Method to store Grbl global settings struct and version number into EEPROM
62 | void write_global_settings()
63 | {
64 | eeprom_put_char(0, SETTINGS_VERSION);
65 | memcpy_to_eeprom_with_checksum(EEPROM_ADDR_GLOBAL, (char*)&settings, sizeof(settings_t));
66 | }
67 |
68 |
69 | // Method to reset Grbl global settings back to defaults.
70 | void settings_reset() {
71 | settings.pulse_microseconds = DEFAULT_STEP_PULSE_MICROSECONDS;
72 | settings.stepper_idle_lock_time = DEFAULT_STEPPER_IDLE_LOCK_TIME;
73 | settings.step_invert_mask = DEFAULT_STEPPING_INVERT_MASK;
74 | settings.dir_invert_mask = DEFAULT_DIRECTION_INVERT_MASK;
75 | settings.status_report_mask = DEFAULT_STATUS_REPORT_MASK;
76 | settings.junction_deviation = DEFAULT_JUNCTION_DEVIATION;
77 | settings.arc_tolerance = DEFAULT_ARC_TOLERANCE;
78 | settings.homing_dir_mask = DEFAULT_HOMING_DIR_MASK;
79 | settings.homing_feed_rate = DEFAULT_HOMING_FEED_RATE;
80 | settings.homing_seek_rate = DEFAULT_HOMING_SEEK_RATE;
81 | settings.homing_debounce_delay = DEFAULT_HOMING_DEBOUNCE_DELAY;
82 | settings.homing_pulloff = DEFAULT_HOMING_PULLOFF;
83 |
84 | settings.flags = 0;
85 | if (DEFAULT_REPORT_INCHES) { settings.flags |= BITFLAG_REPORT_INCHES; }
86 | if (DEFAULT_AUTO_START) { settings.flags |= BITFLAG_AUTO_START; }
87 | if (DEFAULT_INVERT_ST_ENABLE) { settings.flags |= BITFLAG_INVERT_ST_ENABLE; }
88 | if (DEFAULT_INVERT_LIMIT_PINS) { settings.flags |= BITFLAG_INVERT_LIMIT_PINS; }
89 | if (DEFAULT_SOFT_LIMIT_ENABLE) { settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE; }
90 | if (DEFAULT_HARD_LIMIT_ENABLE) { settings.flags |= BITFLAG_HARD_LIMIT_ENABLE; }
91 | if (DEFAULT_HOMING_ENABLE) { settings.flags |= BITFLAG_HOMING_ENABLE; }
92 | if (DEFAULT_LASER) { settings.flags |= BITFLAG_LASER; }
93 |
94 | settings.steps_per_mm[X_AXIS] = DEFAULT_X_STEPS_PER_MM;
95 | settings.steps_per_mm[Y_AXIS] = DEFAULT_Y_STEPS_PER_MM;
96 | settings.steps_per_mm[Z_AXIS] = DEFAULT_Z_STEPS_PER_MM;
97 | settings.max_rate[X_AXIS] = DEFAULT_X_MAX_RATE;
98 | settings.max_rate[Y_AXIS] = DEFAULT_Y_MAX_RATE;
99 | settings.max_rate[Z_AXIS] = DEFAULT_Z_MAX_RATE;
100 | settings.acceleration[X_AXIS] = DEFAULT_X_ACCELERATION;
101 | settings.acceleration[Y_AXIS] = DEFAULT_Y_ACCELERATION;
102 | settings.acceleration[Z_AXIS] = DEFAULT_Z_ACCELERATION;
103 | settings.max_travel[X_AXIS] = (-DEFAULT_X_MAX_TRAVEL);
104 | settings.max_travel[Y_AXIS] = (-DEFAULT_Y_MAX_TRAVEL);
105 | settings.max_travel[Z_AXIS] = (-DEFAULT_Z_MAX_TRAVEL);
106 |
107 | write_global_settings();
108 | }
109 |
110 |
111 | // Reads startup line from EEPROM. Updated pointed line string data.
112 | uint8_t settings_read_startup_line(uint8_t n, char *line)
113 | {
114 | uint32_t addr = n*(LINE_BUFFER_SIZE+1)+EEPROM_ADDR_STARTUP_BLOCK;
115 | if (!(memcpy_from_eeprom_with_checksum((char*)line, addr, LINE_BUFFER_SIZE))) {
116 | // Reset line with default value
117 | line[0] = 0; // Empty line
118 | settings_store_startup_line(n, line);
119 | return(false);
120 | }
121 | return(true);
122 | }
123 |
124 |
125 | // Reads startup line from EEPROM. Updated pointed line string data.
126 | uint8_t settings_read_build_info(char *line)
127 | {
128 | if (!(memcpy_from_eeprom_with_checksum((char*)line, EEPROM_ADDR_BUILD_INFO, LINE_BUFFER_SIZE))) {
129 | // Reset line with default value
130 | line[0] = 0; // Empty line
131 | settings_store_build_info(line);
132 | // No error. Usually only happens once when called for first time.
133 | }
134 | return(true);
135 | }
136 |
137 |
138 | // Read selected coordinate data from EEPROM. Updates pointed coord_data value.
139 | uint8_t settings_read_coord_data(uint8_t coord_select, float *coord_data)
140 | {
141 | uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS;
142 | if (!(memcpy_from_eeprom_with_checksum((char*)coord_data, addr, sizeof(float)*N_AXIS))) {
143 | // Reset with default zero vector
144 | clear_vector_float(coord_data);
145 | settings_write_coord_data(coord_select,coord_data);
146 | return(false);
147 | }
148 | return(true);
149 | }
150 |
151 |
152 | // Reads Grbl global settings struct from EEPROM.
153 | uint8_t read_global_settings() {
154 | // Check version-byte of eeprom
155 | uint8_t version = eeprom_get_char(0);
156 | if (version == SETTINGS_VERSION) {
157 | // Read settings-record and check checksum
158 | if (!(memcpy_from_eeprom_with_checksum((char*)&settings, EEPROM_ADDR_GLOBAL, sizeof(settings_t)))) {
159 | return(false);
160 | }
161 | } else {
162 | return(false);
163 | }
164 | return(true);
165 | }
166 |
167 |
168 | // A helper method to set settings from command line
169 | uint8_t settings_store_global_setting(uint8_t parameter, float value) {
170 | if (value < 0.0) { return(STATUS_NEGATIVE_VALUE); }
171 | if (parameter >= AXIS_SETTINGS_START_VAL) {
172 | // Store axis configuration. Axis numbering sequence set by AXIS_SETTING defines.
173 | // NOTE: Ensure the setting index corresponds to the report.c settings printout.
174 | parameter -= AXIS_SETTINGS_START_VAL;
175 | uint8_t set_idx = 0;
176 | while (set_idx < AXIS_N_SETTINGS) {
177 | if (parameter < N_AXIS) {
178 | // Valid axis setting found.
179 | switch (set_idx) {
180 | case 0: settings.steps_per_mm[parameter] = value; break;
181 | case 1: settings.max_rate[parameter] = value; break;
182 | case 2: settings.acceleration[parameter] = value*60*60; break; // Convert to mm/min^2 for grbl internal use.
183 | case 3: settings.max_travel[parameter] = -value; break; // Store as negative for grbl internal use.
184 | }
185 | break; // Exit while-loop after setting has been configured and proceed to the EEPROM write call.
186 | } else {
187 | set_idx++;
188 | // If axis index greater than N_AXIS or setting index greater than number of axis settings, error out.
189 | if ((parameter < AXIS_SETTINGS_INCREMENT) || (set_idx == AXIS_N_SETTINGS)) { return(STATUS_INVALID_STATEMENT); }
190 | parameter -= AXIS_SETTINGS_INCREMENT;
191 | }
192 | }
193 | } else {
194 | // Store non-axis Grbl settings
195 | uint8_t int_value = trunc(value);
196 | switch(parameter) {
197 | case 0:
198 | if (int_value < 3) { return(STATUS_SETTING_STEP_PULSE_MIN); }
199 | settings.pulse_microseconds = int_value; break;
200 | case 1: settings.stepper_idle_lock_time = int_value; break;
201 | case 2:
202 | settings.step_invert_mask = int_value;
203 | st_generate_step_dir_invert_masks(); // Regenerate step and direction port invert masks.
204 | break;
205 | case 3:
206 | settings.dir_invert_mask = int_value;
207 | st_generate_step_dir_invert_masks(); // Regenerate step and direction port invert masks.
208 | break;
209 | case 4: // Reset to ensure change. Immediate re-init may cause problems.
210 | if (int_value) { settings.flags |= BITFLAG_INVERT_ST_ENABLE; }
211 | else { settings.flags &= ~BITFLAG_INVERT_ST_ENABLE; }
212 | break;
213 | case 5: // Reset to ensure change. Immediate re-init may cause problems.
214 | if (int_value) { settings.flags |= BITFLAG_INVERT_LIMIT_PINS; }
215 | else { settings.flags &= ~BITFLAG_INVERT_LIMIT_PINS; }
216 | break;
217 | case 6: // Reset to ensure change. Immediate re-init may cause problems.
218 | if (int_value) { settings.flags |= BITFLAG_INVERT_PROBE_PIN; }
219 | else { settings.flags &= ~BITFLAG_INVERT_PROBE_PIN; }
220 | break;
221 | case 10: settings.status_report_mask = int_value;
222 | case 11: settings.junction_deviation = value; break;
223 | case 12: settings.arc_tolerance = value; break;
224 | case 13:
225 | if (int_value) { settings.flags |= BITFLAG_REPORT_INCHES; }
226 | else { settings.flags &= ~BITFLAG_REPORT_INCHES; }
227 | break;
228 | case 14: // Reset to ensure change. Immediate re-init may cause problems.
229 | if (int_value) { settings.flags |= BITFLAG_AUTO_START; }
230 | else { settings.flags &= ~BITFLAG_AUTO_START; }
231 | break;
232 | case 20:
233 | if (int_value) {
234 | if (bit_isfalse(settings.flags, BITFLAG_HOMING_ENABLE)) { return(STATUS_SOFT_LIMIT_ERROR); }
235 | settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE;
236 | } else { settings.flags &= ~BITFLAG_SOFT_LIMIT_ENABLE; }
237 | break;
238 | case 21:
239 | if (int_value) { settings.flags |= BITFLAG_HARD_LIMIT_ENABLE; }
240 | else { settings.flags &= ~BITFLAG_HARD_LIMIT_ENABLE; }
241 | limits_init(); // Re-init to immediately change. NOTE: Nice to have but could be problematic later.
242 | break;
243 | case 22:
244 | if (int_value) { settings.flags |= BITFLAG_HOMING_ENABLE; }
245 | else {
246 | settings.flags &= ~BITFLAG_HOMING_ENABLE;
247 | settings.flags &= ~BITFLAG_SOFT_LIMIT_ENABLE; // Force disable soft-limits.
248 | }
249 | break;
250 | case 23: settings.homing_dir_mask = int_value; break;
251 | case 24: settings.homing_feed_rate = value; break;
252 | case 25: settings.homing_seek_rate = value; break;
253 | case 26: settings.homing_debounce_delay = int_value; break;
254 | case 27: settings.homing_pulloff = value; break;
255 | #ifdef LASER_SPINDLE
256 | case 40:
257 | if (int_value) { settings.flags |= BITFLAG_LASER; }
258 | else { settings.flags &= ~BITFLAG_LASER; }
259 | break;
260 | #endif
261 | default:
262 | return(STATUS_INVALID_STATEMENT);
263 | }
264 | }
265 | write_global_settings();
266 | return(STATUS_OK);
267 | }
268 |
269 |
270 | // Initialize the config subsystem
271 | void settings_init() {
272 | if(!read_global_settings()) {
273 | report_status_message(STATUS_SETTING_READ_FAIL);
274 | settings_reset();
275 | report_grbl_settings();
276 | }
277 | // Read all parameter data into a dummy variable. If error, reset to zero, otherwise do nothing.
278 | float coord_data[N_AXIS];
279 | uint8_t i;
280 | for (i=0; i<=SETTING_INDEX_NCOORD; i++) {
281 | if (!settings_read_coord_data(i, coord_data)) {
282 | report_status_message(STATUS_SETTING_READ_FAIL);
283 | }
284 | }
285 | // NOTE: Startup lines are handled and called by main.c at the end of initialization.
286 | }
287 |
288 |
289 | // Returns step pin mask according to Grbl internal axis indexing.
290 | uint8_t get_step_pin_mask(uint8_t axis_idx)
291 | {
292 | if ( axis_idx == X_AXIS ) { return((1< 1: raise Exception('More than one line number in block.')
96 | g_cmd = g_cmd[1:] # Remove line number word
97 | g_num = g_num[1:]
98 | # Block item repeat checks? (0<=n'M'<5, G/M modal groups)
99 |
100 | # Initialize block state
101 | blk = { 'next_action' : 'DEFAULT',
102 | 'absolute_override' : False,
103 | 'target_xyz' : deepcopy(gc['current_xyz']),
104 | 'offset_ijk' : [0,0,0],
105 | 'radius_mode' : False,
106 | 'unsupported': [] }
107 |
108 | # Pass 1
109 | for cmd,num in zip(g_cmd,g_num) :
110 | fnum = float(num)
111 | inum = int(fnum)
112 | if cmd is 'G' :
113 | if inum is 0 : gc['motion_mode'] = 'SEEK'
114 | elif inum is 1 : gc['motion_mode'] = 'LINEAR'
115 | elif inum is 2 : gc['motion_mode'] = 'CW_ARC'
116 | elif inum is 3 : gc['motion_mode'] = 'CCW_ARC'
117 | elif inum is 4 : blk['next_action'] = 'DWELL'
118 | elif inum is 17 : gc['plane_axis'] = [0,1,2] # Select XY Plane
119 | elif inum is 18 : gc['plane_axis'] = [0,2,1] # Select XZ Plane
120 | elif inum is 19 : gc['plane_axis'] = [1,2,0] # Select YZ Plane
121 | elif inum is 20 : gc['inches_mode'] = True
122 | elif inum is 21 : gc['inches_mode'] = False
123 | elif inum in [28,30] : blk['next_action'] = 'GO_HOME'
124 | elif inum is 53 : blk['absolute_override'] = True
125 | elif inum is 54 : pass
126 | elif inum is 80 : gc['motion_mode'] = 'MOTION_CANCEL'
127 | elif inum is 90 : gc['absolute_mode'] = True
128 | elif inum is 91 : gc['absolute_mode'] = False
129 | elif inum is 92 : blk['next_action'] = 'SET_OFFSET'
130 | elif inum is 93 : gc['inverse_feedrate_mode'] = True
131 | elif inum is 94 : gc['inverse_feedrate_mode'] = False
132 | else :
133 | print 'Unsupported command ' + cmd + num + ' on line ' + str(l_count)
134 | if remove_unsupported : blk['unsupported'].append(zip(g_cmd,g_num).index((cmd,num)))
135 | elif cmd is 'M' :
136 | if inum in [0,1] : pass # Program Pause
137 | elif inum in [2,30,60] : pass # Program Completed
138 | elif inum is 3 : pass # Spindle Direction 1
139 | elif inum is 4 : pass # Spindle Direction -1
140 | elif inum is 5 : pass # Spindle Direction 0
141 | else :
142 | print 'Unsupported command ' + cmd + num + ' on line ' + str(l_count)
143 | if remove_unsupported : blk['unsupported'].append(zip(g_cmd,g_num).index((cmd,num)))
144 | elif cmd is 'T' : pass # Tool Number
145 |
146 | # Pass 2
147 | for cmd,num in zip(g_cmd,g_num) :
148 | fnum = float(num)
149 | if cmd is 'F' : gc['feed_rate'] = unit_conv(fnum) # Feed Rate
150 | elif cmd in ['I','J','K'] : blk['offset_ijk'][ord(cmd)-ord('I')] = unit_conv(fnum) # Arc Center Offset
151 | elif cmd is 'N' : pass
152 | elif cmd is 'P' : p = fnum # Misc value parameter
153 | elif cmd is 'R' : r = unit_conv(fnum); blk['radius_mode'] = True # Arc Radius Mode
154 | elif cmd is 'S' : pass # Spindle Speed
155 | elif cmd in ['X','Y','Z'] : # Target Coordinates
156 | if (gc['absolute_mode'] | blk['absolute_override']) :
157 | blk['target_xyz'][ord(cmd)-ord('X')] = unit_conv(fnum)
158 | else :
159 | blk['target_xyz'][ord(cmd)-ord('X')] += unit_conv(fnum)
160 |
161 | # Execute actions
162 | if blk['next_action'] is 'GO_HOME' :
163 | gc['current_xyz'] = deepcopy(blk['target_xyz']) # Update position
164 | elif blk['next_action'] is 'SET_OFFSET' :
165 | pass
166 | elif blk['next_action'] is 'DWELL' :
167 | if p < 0 : raise Exception('Dwell time negative.')
168 | else : # 'DEFAULT'
169 | if gc['motion_mode'] is 'SEEK' :
170 | fout.write('0 '+fout_conv(gc['feed_rate']))
171 | fout.write(' '+fout_conv(blk['target_xyz'][0]))
172 | fout.write(' '+fout_conv(blk['target_xyz'][1]))
173 | fout.write(' '+fout_conv(blk['target_xyz'][2]))
174 | fout.write('\n')
175 | gc['current_xyz'] = deepcopy(blk['target_xyz']) # Update position
176 | elif gc['motion_mode'] is 'LINEAR' :
177 | fout.write('1 '+fout_conv(gc['feed_rate']))
178 | fout.write(' '+fout_conv(blk['target_xyz'][0]))
179 | fout.write(' '+fout_conv(blk['target_xyz'][1]))
180 | fout.write(' '+fout_conv(blk['target_xyz'][2]))
181 | fout.write('\n')
182 | gc['current_xyz'] = deepcopy(blk['target_xyz']) # Update position
183 | elif gc['motion_mode'] in ['CW_ARC','CCW_ARC'] :
184 | axis = gc['plane_axis']
185 |
186 | # Convert radius mode to ijk mode
187 | if blk['radius_mode'] :
188 | x = blk['target_xyz'][axis[0]]-gc['current_xyz'][axis[0]]
189 | y = blk['target_xyz'][axis[1]]-gc['current_xyz'][axis[1]]
190 | if not (x==0 and y==0) : raise Exception('Same target and current XYZ not allowed in arc radius mode.')
191 | h_x2_div_d = -sqrt(4 * r*r - x*x - y*y)/hypot(x,y)
192 | if isnan(h_x2_div_d) : raise Exception('Floating point error in arc conversion')
193 | if gc['motion_mode'] is 'CCW_ARC' : h_x2_div_d = -h_x2_div_d
194 | if r < 0 : h_x2_div_d = -h_x2_div_d
195 | blk['offset_ijk'][axis[0]] = (x-(y*h_x2_div_d))/2;
196 | blk['offset_ijk'][axis[1]] = (y+(x*h_x2_div_d))/2;
197 | else :
198 | radius = sqrt(blk['offset_ijk'][axis[0]]**2+blk['offset_ijk'][axis[1]]**2)
199 |
200 | center_axis0 = gc['current_xyz'][axis[0]]+blk['offset_ijk'][axis[0]]
201 | center_axis1 = gc['current_xyz'][axis[1]]+blk['offset_ijk'][axis[1]]
202 | linear_travel = blk['target_xyz'][axis[2]]-gc['current_xyz'][axis[2]]
203 | r_axis0 = -blk['offset_ijk'][axis[0]]
204 | r_axis1 = -blk['offset_ijk'][axis[1]]
205 | rt_axis0 = blk['target_xyz'][axis[0]] - center_axis0;
206 | rt_axis1 = blk['target_xyz'][axis[1]] - center_axis1;
207 | clockwise_sign = 1
208 | if gc['motion_mode'] is 'CW_ARC' : clockwise_sign = -1
209 |
210 | angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1)
211 | if gc['motion_mode'] is 'CW_ARC' :
212 | if angular_travel >= 0 :
213 | angular_travel -= 2*pi
214 | else :
215 | if angular_travel <= 0 :
216 | angular_travel += 2*pi
217 |
218 | millimeters_of_travel = sqrt((angular_travel*radius)**2 + abs(linear_travel)**2)
219 |
220 | mm_per_arc_segment = sqrt(4*(2*radius*arc_tolerance-arc_tolerance**2))
221 | segments = int(millimeters_of_travel/mm_per_arc_segment)
222 | print segments
223 | print l_count
224 | theta_per_segment = angular_travel/segments
225 | linear_per_segment = linear_travel/segments
226 | cos_T = 1-0.5*theta_per_segment*theta_per_segment
227 | sin_T = theta_per_segment-theta_per_segment**3/6
228 | print(fout_conv(mm_per_arc_segment))
229 | print theta_per_segment*180/pi
230 |
231 | arc_target = [0,0,0]
232 | arc_target[axis[2]] = gc['current_xyz'][axis[2]]
233 |
234 | count = 0
235 | for i in range(1,segments+1) :
236 | if i < segments :
237 | if count < n_arc_correction :
238 | r_axisi = r_axis0*sin_T + r_axis1*cos_T
239 | r_axis0 = r_axis0*cos_T - r_axis1*sin_T
240 | r_axis1 = deepcopy(r_axisi)
241 | count += 1
242 | else :
243 | cos_Ti = cos((i-1)*theta_per_segment)
244 | sin_Ti = sin((i-1)*theta_per_segment)
245 | print n_arc_correction*(r_axis0 -( -blk['offset_ijk'][axis[0]]*cos_Ti + blk['offset_ijk'][axis[1]]*sin_Ti))
246 | print n_arc_correction*(r_axis1 -( -blk['offset_ijk'][axis[0]]*sin_Ti - blk['offset_ijk'][axis[1]]*cos_Ti))
247 | cos_Ti = cos(i*theta_per_segment)
248 | sin_Ti = sin(i*theta_per_segment)
249 | r_axis0 = -blk['offset_ijk'][axis[0]]*cos_Ti + blk['offset_ijk'][axis[1]]*sin_Ti
250 | r_axis1 = -blk['offset_ijk'][axis[0]]*sin_Ti - blk['offset_ijk'][axis[1]]*cos_Ti
251 | count = 0
252 | arc_target[axis[0]] = center_axis0 + r_axis0
253 | arc_target[axis[1]] = center_axis1 + r_axis1
254 | arc_target[axis[2]] += linear_per_segment
255 | else :
256 | arc_target = deepcopy(blk['target_xyz']) # Last segment at target_xyz
257 | # Write only changed variables.
258 | fout.write('1 '+fout_conv(gc['feed_rate']))
259 | fout.write(' '+fout_conv(arc_target[0]))
260 | fout.write(' '+fout_conv(arc_target[1]))
261 | fout.write(' '+fout_conv(arc_target[2]))
262 | fout.write('\n')
263 | gc['current_xyz'] = deepcopy(arc_target) # Update position
264 |
265 |
266 | print 'Done!'
267 |
268 | # Close files
269 | fin.close()
270 | fout.close()
--------------------------------------------------------------------------------
/limits.c:
--------------------------------------------------------------------------------
1 | /*
2 | limits.c - code pertaining to limit-switches and performing the homing cycle
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2012 Sungeun K. Jeon
25 | */
26 |
27 | #include "system.h"
28 | #include "settings.h"
29 | #include "protocol.h"
30 | #include "planner.h"
31 | #include "stepper.h"
32 | #include "motion_control.h"
33 | #include "limits.h"
34 | #include "report.h"
35 | #include "gcode.h"
36 |
37 | // Homing axis search distance multiplier. Computed by this value times the axis max travel.
38 | #define HOMING_AXIS_SEARCH_SCALAR 1.5 // Must be > 1 to ensure limit switch will be engaged.
39 |
40 |
41 | void limits_init()
42 | {
43 | LIMIT_DDR &= ~(LIMIT_MASK); // Set as input pins
44 |
45 | if (bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) {
46 | LIMIT_PORT &= ~(LIMIT_MASK); // Normal low operation. Requires external pull-down.
47 | } else {
48 | LIMIT_PORT |= (LIMIT_MASK); // Enable internal pull-up resistors. Normal high operation.
49 | }
50 |
51 | if (bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE)) {
52 | LIMIT_PCMSK |= LIMIT_MASK; // Enable specific pins of the Pin Change Interrupt
53 | PCICR |= (1 << LIMIT_INT); // Enable Pin Change Interrupt
54 | } else {
55 | limits_disable();
56 | }
57 |
58 | #ifdef ENABLE_SOFTWARE_DEBOUNCE
59 | MCUSR &= ~(1< settings.max_travel[idx]) { max_travel = settings.max_travel[idx]; }
147 | }
148 | max_travel *= -HOMING_AXIS_SEARCH_SCALAR; // Ensure homing switches engaged by over-estimating max travel.
149 |
150 | plan_reset(); // Reset planner buffer to zero planner current position and to clear previous motions.
151 |
152 | do {
153 | // Initialize invert_pin boolean based on approach and invert pin user setting.
154 | if (bit_isfalse(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) { invert_pin = approach; }
155 | else { invert_pin = !approach; }
156 |
157 | // Initialize and declare variables needed for homing routine.
158 | uint8_t n_active_axis = 0;
159 | uint8_t axislock = 0;
160 |
161 | for (idx=0; idx 0);
216 |
217 | // The active cycle axes should now be homed and machine limits have been located. By
218 | // default, grbl defines machine space as all negative, as do most CNCs. Since limit switches
219 | // can be on either side of an axes, check and set axes machine zero appropriately. Also,
220 | // set up pull-off maneuver from axes limit switches that have been homed. This provides
221 | // some initial clearance off the switches and should also help prevent them from falsely
222 | // triggering when hard limits are enabled or when more than one axes shares a limit pin.
223 | for (idx=0; idx -settings.max_travel[idx]) { soft_limit_error = true; }
281 | } else {
282 | if (target[idx] > 0 || target[idx] < settings.max_travel[idx]) { soft_limit_error = true; }
283 | }
284 | #else
285 | // NOTE: max_travel is stored as negative
286 | if (target[idx] > 0 || target[idx] < settings.max_travel[idx]) { soft_limit_error = true; }
287 | #endif
288 |
289 | if (soft_limit_error) {
290 | // Force feed hold if cycle is active. All buffered blocks are guaranteed to be within
291 | // workspace volume so just come to a controlled stop so position is not lost. When complete
292 | // enter alarm mode.
293 | if (sys.state == STATE_CYCLE) {
294 | bit_true_atomic(sys.execute, EXEC_FEED_HOLD);
295 | do {
296 | protocol_execute_runtime();
297 | if (sys.abort) { return; }
298 | } while ( sys.state != STATE_IDLE || sys.state != STATE_QUEUED);
299 | }
300 |
301 | mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
302 | bit_true_atomic(sys.execute, (EXEC_ALARM | EXEC_CRIT_EVENT)); // Indicate soft limit critical event
303 | protocol_execute_runtime(); // Execute to enter critical event loop and system abort
304 | return;
305 | }
306 | }
307 | }
308 |
--------------------------------------------------------------------------------
/defaults.h:
--------------------------------------------------------------------------------
1 | /*
2 | defaults.h - defaults settings configuration file
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 |
21 | /* The defaults.h file serves as a central default settings file for different machine
22 | types, from DIY CNC mills to CNC conversions of off-the-shelf machines. The settings
23 | here are supplied by users, so your results may vary. However, this should give you
24 | a good starting point as you get to know your machine and tweak the settings for your
25 | our nefarious needs. */
26 |
27 | #ifndef defaults_h
28 | #define defaults_h
29 |
30 | #ifdef DEFAULTS_GENERIC
31 | // Grbl generic default settings. Should work across different machines.
32 | #define DEFAULT_X_STEPS_PER_MM 250.0
33 | #define DEFAULT_Y_STEPS_PER_MM 250.0
34 | #define DEFAULT_Z_STEPS_PER_MM 250.0
35 | #define DEFAULT_X_MAX_RATE 500.0 // mm/min
36 | #define DEFAULT_Y_MAX_RATE 500.0 // mm/min
37 | #define DEFAULT_Z_MAX_RATE 500.0 // mm/min
38 | #define DEFAULT_X_ACCELERATION (10.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
39 | #define DEFAULT_Y_ACCELERATION (10.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
40 | #define DEFAULT_Z_ACCELERATION (10.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
41 | #define DEFAULT_X_MAX_TRAVEL 200.0 // mm
42 | #define DEFAULT_Y_MAX_TRAVEL 200.0 // mm
43 | #define DEFAULT_Z_MAX_TRAVEL 200.0 // mm
44 | #define DEFAULT_STEP_PULSE_MICROSECONDS 10
45 | #define DEFAULT_STEPPING_INVERT_MASK 0
46 | #define DEFAULT_DIRECTION_INVERT_MASK ((1<.
19 | */
20 | /*
21 | This file is based on work from Grbl v0.8, distributed under the
22 | terms of the MIT-license. See COPYING for more details.
23 | Copyright (c) 2009-2011 Simen Svale Skogsrud
24 | Copyright (c) 2011-2012 Sungeun K. Jeon
25 | */
26 |
27 | #include "system.h"
28 | #include "serial.h"
29 | #include "settings.h"
30 | #include "protocol.h"
31 | #include "gcode.h"
32 | #include "planner.h"
33 | #include "stepper.h"
34 | #include "motion_control.h"
35 | #include "report.h"
36 | #include "spindle_control.h"
37 |
38 |
39 | static char line[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
40 |
41 |
42 | // Directs and executes one line of formatted input from protocol_process. While mostly
43 | // incoming streaming g-code blocks, this also directs and executes Grbl internal commands,
44 | // such as settings, initiating the homing cycle, and toggling switch states.
45 | static void protocol_execute_line(char *line)
46 | {
47 | protocol_execute_runtime(); // Runtime command check point.
48 | if (sys.abort) { return; } // Bail to calling function upon system abort
49 |
50 | if (line[0] == 0) {
51 | // Empty or comment line. Send status message for syncing purposes.
52 | report_status_message(STATUS_OK);
53 |
54 | } else if (line[0] == '$') {
55 | // Grbl '$' system command
56 | report_status_message(system_execute_line(line));
57 |
58 | } else if (sys.state == STATE_ALARM) {
59 | // Everything else is gcode. Block if in alarm mode.
60 | report_status_message(STATUS_ALARM_LOCK);
61 |
62 | } else {
63 | // Parse and execute g-code block!
64 | report_status_message(gc_execute_line(line));
65 | }
66 | }
67 |
68 |
69 | /*
70 | GRBL PRIMARY LOOP:
71 | */
72 | void protocol_main_loop()
73 | {
74 | // ------------------------------------------------------------
75 | // Complete initialization procedures upon a power-up or reset.
76 | // ------------------------------------------------------------
77 |
78 | // Print welcome message
79 | report_init_message();
80 |
81 | // Check for and report alarm state after a reset, error, or an initial power up.
82 | if (sys.state == STATE_ALARM) {
83 | report_feedback_message(MESSAGE_ALARM_LOCK);
84 | } else {
85 | // All systems go!
86 | sys.state = STATE_IDLE; // Set system to ready. Clear all state flags.
87 | system_execute_startup(line); // Execute startup script.
88 | }
89 |
90 | // ---------------------------------------------------------------------------------
91 | // Primary loop! Upon a system abort, this exits back to main() to reset the system.
92 | // ---------------------------------------------------------------------------------
93 |
94 | uint8_t iscomment = false;
95 | uint8_t char_counter = 0;
96 | uint8_t c;
97 | for (;;) {
98 |
99 | // Process one line of incoming serial data, as the data becomes available. Performs an
100 | // initial filtering by removing spaces and comments and capitalizing all letters.
101 |
102 | // NOTE: While comment, spaces, and block delete(if supported) handling should technically
103 | // be done in the g-code parser, doing it here helps compress the incoming data into Grbl's
104 | // line buffer, which is limited in size. The g-code standard actually states a line can't
105 | // exceed 256 characters, but the Arduino Uno does not have the memory space for this.
106 | // With a better processor, it would be very easy to pull this initial parsing out as a
107 | // seperate task to be shared by the g-code parser and Grbl's system commands.
108 |
109 | while((c = serial_read()) != SERIAL_NO_DATA) {
110 | if ((c == '\n') || (c == '\r')) { // End of line reached
111 | line[char_counter] = 0; // Set string termination character.
112 | protocol_execute_line(line); // Line is complete. Execute it!
113 | iscomment = false;
114 | char_counter = 0;
115 | } else {
116 | if (iscomment) {
117 | // Throw away all comment characters
118 | if (c == ')') {
119 | // End of comment. Resume line.
120 | iscomment = false;
121 | }
122 | } else {
123 | if (c <= ' ') {
124 | // Throw away whitepace and control characters
125 | } else if (c == '/') {
126 | // Block delete NOT SUPPORTED. Ignore character.
127 | // NOTE: If supported, would simply need to check the system if block delete is enabled.
128 | } else if (c == '(') {
129 | // Enable comments flag and ignore all characters until ')' or EOL.
130 | // NOTE: This doesn't follow the NIST definition exactly, but is good enough for now.
131 | // In the future, we could simply remove the items within the comments, but retain the
132 | // comment control characters, so that the g-code parser can error-check it.
133 | iscomment = true;
134 | // } else if (c == ';') {
135 | // Comment character to EOL NOT SUPPORTED. LinuxCNC definition. Not NIST.
136 |
137 | // TODO: Install '%' feature
138 | // } else if (c == '%') {
139 | // Program start-end percent sign NOT SUPPORTED.
140 | // NOTE: This maybe installed to tell Grbl when a program is running vs manual input,
141 | // where, during a program, the system auto-cycle start will continue to execute
142 | // everything until the next '%' sign. This will help fix resuming issues with certain
143 | // functions that empty the planner buffer to execute its task on-time.
144 |
145 | } else if (char_counter >= (LINE_BUFFER_SIZE-1)) {
146 | // Detect line buffer overflow. Report error and reset line buffer.
147 | report_status_message(STATUS_OVERFLOW);
148 | iscomment = false;
149 | char_counter = 0;
150 | } else if (c >= 'a' && c <= 'z') { // Upcase lowercase
151 | line[char_counter++] = c-'a'+'A';
152 | } else {
153 | line[char_counter++] = c;
154 | }
155 | }
156 | }
157 | }
158 |
159 | // If there are no more characters in the serial read buffer to be processed and executed,
160 | // this indicates that g-code streaming has either filled the planner buffer or has
161 | // completed. In either case, auto-cycle start, if enabled, any queued moves.
162 | protocol_auto_cycle_start();
163 |
164 | protocol_execute_runtime(); // Runtime command check point.
165 | if (sys.abort) { return; } // Bail to main() program loop to reset system.
166 |
167 | }
168 |
169 | return; /* Never reached */
170 | }
171 |
172 |
173 | // Executes run-time commands, when required. This is called from various check points in the main
174 | // program, primarily where there may be a while loop waiting for a buffer to clear space or any
175 | // point where the execution time from the last check point may be more than a fraction of a second.
176 | // This is a way to execute runtime commands asynchronously (aka multitasking) with grbl's g-code
177 | // parsing and planning functions. This function also serves as an interface for the interrupts to
178 | // set the system runtime flags, where only the main program handles them, removing the need to
179 | // define more computationally-expensive volatile variables. This also provides a controlled way to
180 | // execute certain tasks without having two or more instances of the same task, such as the planner
181 | // recalculating the buffer upon a feedhold or override.
182 | // NOTE: The sys.execute variable flags are set by any process, step or serial interrupts, pinouts,
183 | // limit switches, or the main program.
184 | void protocol_execute_runtime()
185 | {
186 | uint8_t rt_exec = sys.execute; // Copy to avoid calling volatile multiple times
187 | if (rt_exec) { // Enter only if any bit flag is true
188 |
189 | // System alarm. Everything has shutdown by something that has gone severely wrong. Report
190 | // the source of the error to the user. If critical, Grbl disables by entering an infinite
191 | // loop until system reset/abort.
192 | if (rt_exec & (EXEC_ALARM | EXEC_CRIT_EVENT)) {
193 | sys.state = STATE_ALARM; // Set system alarm state
194 | #ifdef LASER_SPINDLE // laser off when machine on hold
195 | spindle_pause();
196 | #endif
197 |
198 | // Critical events. Hard/soft limit events identified by both critical event and alarm exec
199 | // flags. Probe fail is identified by the critical event exec flag only.
200 | if (rt_exec & EXEC_CRIT_EVENT) {
201 | if (rt_exec & EXEC_ALARM) { report_alarm_message(ALARM_LIMIT_ERROR); }
202 | else { report_alarm_message(ALARM_PROBE_FAIL); }
203 | report_feedback_message(MESSAGE_CRITICAL_EVENT);
204 | bit_false_atomic(sys.execute,EXEC_RESET); // Disable any existing reset
205 | do {
206 | // Nothing. Block EVERYTHING until user issues reset or power cycles. Hard limits
207 | // typically occur while unattended or not paying attention. Gives the user time
208 | // to do what is needed before resetting, like killing the incoming stream. The
209 | // same could be said about soft limits. While the position is not lost, the incoming
210 | // stream could be still engaged and cause a serious crash if it continues afterwards.
211 | } while (bit_isfalse(sys.execute,EXEC_RESET));
212 |
213 | // Standard alarm event. Only abort during motion qualifies.
214 | } else {
215 | // Runtime abort command issued during a cycle, feed hold, or homing cycle. Message the
216 | // user that position may have been lost and set alarm state to enable the alarm lockout
217 | // to indicate the possible severity of the problem.
218 | report_alarm_message(ALARM_ABORT_CYCLE);
219 | }
220 | bit_false_atomic(sys.execute,(EXEC_ALARM | EXEC_CRIT_EVENT));
221 | }
222 |
223 | // Execute system abort.
224 | if (rt_exec & EXEC_RESET) {
225 | #ifdef LASER_SPINDLE // laser off when machine on hold
226 | spindle_pause();
227 | #endif
228 | sys.abort = true; // Only place this is set true.
229 | return; // Nothing else to do but exit.
230 | }
231 |
232 | // Execute and serial print status
233 | if (rt_exec & EXEC_STATUS_REPORT) {
234 | report_realtime_status();
235 | bit_false_atomic(sys.execute,EXEC_STATUS_REPORT);
236 | }
237 |
238 | // Execute a feed hold with deceleration, only during cycle.
239 | if (rt_exec & EXEC_FEED_HOLD) {
240 | // !!! During a cycle, the segment buffer has just been reloaded and full. So the math involved
241 | // with the feed hold should be fine for most, if not all, operational scenarios.
242 | if (sys.state == STATE_CYCLE) {
243 | sys.state = STATE_HOLD;
244 | st_update_plan_block_parameters();
245 | st_prep_buffer();
246 | sys.auto_start = false; // Disable planner auto start upon feed hold.
247 | }
248 | bit_false_atomic(sys.execute,EXEC_FEED_HOLD);
249 | }
250 |
251 | // Execute a cycle start by starting the stepper interrupt begin executing the blocks in queue.
252 | if (rt_exec & EXEC_CYCLE_START) {
253 | if (sys.state == STATE_QUEUED) {
254 | sys.state = STATE_CYCLE;
255 | #ifdef LASER_SPINDLE // laser off when machine on hold
256 | spindle_unpause();
257 | #endif
258 |
259 | st_prep_buffer(); // Initialize step segment buffer before beginning cycle.
260 | st_wake_up();
261 | if (bit_istrue(settings.flags,BITFLAG_AUTO_START)) {
262 | sys.auto_start = true; // Re-enable auto start after feed hold.
263 | } else {
264 | sys.auto_start = false; // Reset auto start per settings.
265 | }
266 | }
267 | bit_false_atomic(sys.execute,EXEC_CYCLE_START);
268 | }
269 |
270 | // Reinitializes the cycle plan and stepper system after a feed hold for a resume. Called by
271 | // runtime command execution in the main program, ensuring that the planner re-plans safely.
272 | // NOTE: Bresenham algorithm variables are still maintained through both the planner and stepper
273 | // cycle reinitializations. The stepper path should continue exactly as if nothing has happened.
274 | // NOTE: EXEC_CYCLE_STOP is set by the stepper subsystem when a cycle or feed hold completes.
275 | if (rt_exec & EXEC_CYCLE_STOP) {
276 | if ( plan_get_current_block() ) {
277 | #ifdef LASER_SPINDLE // laser off when machine on hold
278 | spindle_pause();
279 | #endif
280 | sys.state = STATE_QUEUED;
281 | }
282 | else { sys.state = STATE_IDLE; }
283 | bit_false_atomic(sys.execute,EXEC_CYCLE_STOP);
284 | }
285 |
286 | }
287 |
288 | // Overrides flag byte (sys.override) and execution should be installed here, since they
289 | // are runtime and require a direct and controlled interface to the main stepper program.
290 |
291 | // Reload step segment buffer
292 | if (sys.state & (STATE_CYCLE | STATE_HOLD | STATE_HOMING)) { st_prep_buffer(); }
293 |
294 | }
295 |
296 |
297 | // Block until all buffered steps are executed or in a cycle state. Works with feed hold
298 | // during a synchronize call, if it should happen. Also, waits for clean cycle end.
299 | void protocol_buffer_synchronize()
300 | {
301 | // If system is queued, ensure cycle resumes if the auto start flag is present.
302 | protocol_auto_cycle_start();
303 | // Check and set auto start to resume cycle after synchronize and caller completes.
304 | if (sys.state == STATE_CYCLE) { sys.auto_start = true; }
305 | while (plan_get_current_block() || (sys.state == STATE_CYCLE)) {
306 | protocol_execute_runtime(); // Check and execute run-time commands
307 | if (sys.abort) { return; } // Check for system abort
308 | }
309 | }
310 |
311 |
312 | // Auto-cycle start has two purposes: 1. Resumes a plan_synchronize() call from a function that
313 | // requires the planner buffer to empty (spindle enable, dwell, etc.) 2. As a user setting that
314 | // automatically begins the cycle when a user enters a valid motion command manually. This is
315 | // intended as a beginners feature to help new users to understand g-code. It can be disabled
316 | // as a beginner tool, but (1.) still operates. If disabled, the operation of cycle start is
317 | // manually issuing a cycle start command whenever the user is ready and there is a valid motion
318 | // command in the planner queue.
319 | // NOTE: This function is called from the main loop and mc_line() only and executes when one of
320 | // two conditions exist respectively: There are no more blocks sent (i.e. streaming is finished,
321 | // single commands), or the planner buffer is full and ready to go.
322 | void protocol_auto_cycle_start() { if (sys.auto_start) { bit_true_atomic(sys.execute, EXEC_CYCLE_START); } }
323 |
--------------------------------------------------------------------------------
/cpu_map.h:
--------------------------------------------------------------------------------
1 | /*
2 | cpu_map.h - CPU and pin mapping configuration file
3 | Part of Grbl v0.9
4 |
5 | Copyright (c) 2012-2014 Sungeun K. Jeon
6 |
7 | Grbl is free software: you can redistribute it and/or modify
8 | it under the terms of the GNU General Public License as published by
9 | the Free Software Foundation, either version 3 of the License, or
10 | (at your option) any later version.
11 |
12 | Grbl is distributed in the hope that it will be useful,
13 | but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | GNU General Public License for more details.
16 |
17 | You should have received a copy of the GNU General Public License
18 | along with Grbl. If not, see .
19 | */
20 |
21 | /* The cpu_map.h file serves as a central pin mapping settings file for different processor
22 | types, i.e. AVR 328p or AVR Mega 2560. Grbl officially supports the Arduino Uno, but the
23 | other supplied pin mappings are supplied by users, so your results may vary. */
24 |
25 | // NOTE: This is still a work in progress. We are still centralizing the configurations to
26 | // this file, so your success may vary for other CPUs.
27 |
28 | #ifndef cpu_map_h
29 | #define cpu_map_h
30 |
31 | //----------------------------------------------------------------------------------------
32 |
33 | #ifdef CPU_MAP_ATMEGA328P // (Arduino Uno) Officially supported by Grbl.
34 |
35 | // Define serial port pins and interrupt vectors.
36 | #define SERIAL_RX USART_RX_vect
37 | #define SERIAL_UDRE USART_UDRE_vect
38 |
39 | // Define step pulse output pins. NOTE: All step bit pins must be on the same port.
40 | #define STEP_DDR DDRD
41 | #define STEP_PORT PORTD
42 | #define X_STEP_BIT 2 // Uno Digital Pin 2
43 | #define Y_STEP_BIT 3 // Uno Digital Pin 3
44 | #define Z_STEP_BIT 4 // Uno Digital Pin 4
45 | #define STEP_MASK ((1<, this feeds the simulator planner one line motion
36 | % block. The left side is the first block in the buffer and the one that will be executed
37 | % by the stepper module first. The right side is the end of the planner buffer, where the
38 | % most recent streamed block is appended onto the planner buffer. Grbl's planner
39 | % optimizes the velocity profiles between the beginning and end of the buffer based on
40 | % the acceleration limits, intended velocity/feedrate, and line motion junction angles
41 | % with their corresponding velocity limits (i.e. junctions with acute angles needs to come
42 | % to a complete stop vs straight junctions can continue through at full speed.)
43 |
44 | % ----------------------------------------------------------------------------------------
45 |
46 |
47 | % Main function
48 | % NOTE: This is just a way to keep all functions in one place, but all non-global variables
49 | % are cleared as soon as this script completes.
50 | function main()
51 |
52 | % Load pre-parsed gcode moves.
53 | close all;
54 | warning off;
55 | clearvars -global
56 | fid = fopen('matlab.gcode','r');
57 | gcode = textscan(fid,'%d8%f32%f32%f32%f32');
58 | nblock = length(gcode{1});
59 |
60 | % Plot all g-code moves.
61 | figure
62 | line(gcode{3},gcode{4},gcode{5});
63 | axis equal;
64 | % axis([min(gcode{3}) max(gcode{3}) min(gcode{4}) max(gcode{4}) min(gcode{5}) max(gcode{5})]);
65 | title('G-code programming line motions');
66 | view(3);
67 |
68 | % Set up figure for planner queue
69 | figure
70 |
71 | % Print help.
72 | disp('');
73 | disp(' BLUE line indicates completed planner blocks that require no recalculation.');
74 | disp(' RED line indicates planner blocks that have been recalculated.');
75 | disp(' GREEN line indicates the location of the BPLANNED pointer. Always a recalculated block.');
76 | disp(' BLACK dotted-line and ''x'' indicates block nominal speed and max junction velocity, respectively.');
77 | disp(' CYAN ''.'' indicates block initial entry speed.');
78 |
79 | % Define Grbl settings.
80 | BUFFER_SIZE = 18; % Number of planner blocks in its ring buffer.
81 | steps_per_mm = 200;
82 | seekrate = 2500; % mm/min
83 | acceleration = [100 100 100]; % mm/sec^2 [ X Y Z ] axes
84 | junction_deviation = 0.1; % mm. See Grbl documentation on this parameter.
85 | inch_2_mm = 25.4;
86 | ACCELERATION_TICKS_PER_SECOND = 100;
87 |
88 | gcode{2} = gcode{2};
89 | gcode{2} = inch_2_mm*gcode{2};
90 | gcode{3} = inch_2_mm*gcode{3};
91 | gcode{4} = inch_2_mm*gcode{4};
92 | gcode{5} = inch_2_mm*gcode{5};
93 |
94 | % Initialize blocks
95 | block.steps = [];
96 | block.step_event_count = [];
97 | block.delta_mm = [];
98 | block.millimeters = [];
99 | block.acceleration = [];
100 | block.speed = [];
101 | block.nominal_speed = [];
102 | block.max_entry_speed = [];
103 | block.entry_speed = [];
104 | block.recalculate_flag = false;
105 | for i = 2:BUFFER_SIZE
106 | block(i) = block(1);
107 | end
108 |
109 | % Initialize planner
110 | position = [0 0 0];
111 | prev_unit_vec = [0 0 0];
112 | previous_nominal_speed = 0;
113 | pos = 0;
114 |
115 | % BHEAD and BTAIL act as pointers to the block head and tail.
116 | % BPLANNED acts as a pointer of the location of the end of a completed/optimized plan.
117 | bhead = 1;
118 | btail = 1;
119 | bplanned = 1;
120 |
121 | global block bhead btail bplanned nind acceleration BUFFER_SIZE pos ACCELERATION_TICKS_PER_SECOND
122 |
123 | % Main loop. Simulates plan_buffer_line(). All of the precalculations for the newest incoming
124 | % block occurs here. Anything independent of the planner changes.
125 | for i = 1:nblock
126 |
127 | target = round([gcode{3}(i) gcode{4}(i) gcode{5}(i)].*steps_per_mm);
128 | if gcode{1}(i) == 1
129 | feedrate = gcode{2}(i);
130 | else
131 | feedrate = seekrate;
132 | end
133 |
134 | nind = next_block_index(bhead);
135 | if nind == btail
136 | % Simulate a constantly full buffer. Move buffer tail.
137 | bind = next_block_index(btail);
138 | % Push planned pointer if encountered. Prevents it from looping back around the ring buffer.
139 | if btail == bplanned; bplanned = bind; end
140 | btail = bind;
141 | end
142 |
143 | block(bhead).steps = abs(target-position);
144 | block(bhead).step_event_count = max(block(bhead).steps);
145 |
146 | % Bail if this is a zero-length block
147 | if block(bhead).step_event_count == 0
148 | disp(['Zero-length block in line ',int2str(i)]);
149 | else
150 |
151 | % Compute path vector in terms of absolute step target and current positions
152 | delta_mm = single((target-position)./steps_per_mm);
153 | block(bhead).millimeters = single(norm(delta_mm));
154 | inverse_millimeters = single(1/block(bhead).millimeters);
155 |
156 | % Compute path unit vector
157 | unit_vec = delta_mm/block(bhead).millimeters;
158 |
159 | % Calculate speed in mm/minute for each axis
160 | inverse_minute = single(feedrate * inverse_millimeters);
161 | block(bhead).speed = delta_mm*inverse_minute;
162 | block(bhead).nominal_speed = block(bhead).millimeters*inverse_minute;
163 |
164 | % Calculate block acceleration. Operates on absolute value of unit vector.
165 | [max_acc,ind] = max(abs(unit_vec)./acceleration); % Determine limiting acceleration
166 | block(bhead).acceleration = acceleration(ind)/abs(unit_vec(ind));
167 |
168 | % Compute maximum junction speed
169 | block(bhead).max_entry_speed = 0.0;
170 | if previous_nominal_speed > 0.0
171 | cos_theta = dot(-previous_unit_vec,unit_vec);
172 | if (cos_theta < 0.95)
173 | block(bhead).max_entry_speed = min([block(bhead).nominal_speed,previous_nominal_speed]);
174 | if (cos_theta > -0.95)
175 | sin_theta_d2 = sqrt(0.5*(1.0-cos_theta));
176 | block(bhead).max_entry_speed = min([block(bhead).max_entry_speed,sqrt(block(bhead).acceleration*3600*junction_deviation*sin_theta_d2/(1.0-sin_theta_d2))]);
177 | end
178 | end
179 | end
180 |
181 | block(bhead).entry_speed = 0; % Just initialize. Set accurately in the replanning function.
182 | block(bhead).recalculate_flag = true; % Plotting flag to indicate this block has been updated.
183 |
184 | previous_unit_vec = unit_vec;
185 | previous_nominal_speed = block(bhead).nominal_speed;
186 | position = target;
187 |
188 | bhead = nind; % Block complete. Push buffer pointer.
189 | planner_recalculate();
190 |
191 | plot_buffer_velocities();
192 | end
193 | end
194 | return
195 |
196 | % Computes the next block index in the planner ring buffer
197 | function block_index = next_block_index(block_index)
198 | global BUFFER_SIZE
199 | block_index = block_index + 1;
200 | if block_index > BUFFER_SIZE
201 | block_index = 1;
202 | end
203 | return
204 |
205 | % Computes the previous block index in the planner ring buffer
206 | function block_index = prev_block_index(block_index)
207 | global BUFFER_SIZE
208 | block_index = block_index-1;
209 | if block_index < 1
210 | block_index = BUFFER_SIZE;
211 | end
212 | return
213 |
214 |
215 | % Planner recalculate function. The magic happens here.
216 | function planner_recalculate(block)
217 |
218 | global block bhead btail bplanned acceleration
219 |
220 | bind = prev_block_index(bhead);
221 | if bind == bplanned; return; end % Bail, if only one block in buffer. Can't be operated on.
222 |
223 | % Reverse Pass: Coarsely maximize all possible deceleration curves back-planning from the last
224 | % block in buffer. Cease planning when the last optimal planned or tail pointer is reached.
225 | % NOTE: Forward pass will later refine and correct the reverse pass to create an optimal plan.
226 | next = [];
227 | curr = bind; % Last block in buffer.
228 |
229 | % Calculate maximum entry speed for last block in buffer, where the exit speed is always zero.
230 | block(curr).entry_speed = min([block(curr).max_entry_speed,sqrt(2*block(curr).acceleration*60*60*block(curr).millimeters)]);
231 |
232 | bind = prev_block_index(bind); % Btail or second to last block
233 | if (bind == bplanned)
234 | % Only two plannable blocks in buffer. Reverse pass complete.
235 | % Check if the first block is the tail. If so, notify stepper module to update its current parameters.
236 | % if bind == btail; update_tail_block; end
237 | else
238 | % Three or more plannable blocks in buffer. Loop it.
239 | while bind ~= bplanned % Loop until bplanned point hits. Replans to last plan point.
240 | next = curr;
241 | curr = bind;
242 | bind = prev_block_index( bind ); % Previous block pointer.
243 |
244 | % Check if the first block is the tail. If so, notify stepper module to update its current parameters.
245 | % if bind == btail; update_tail_block; end
246 |
247 | % Compute maximum entry speed decelerating over the current block from its exit speed.
248 | if block(curr).entry_speed ~= block(curr).max_entry_speed
249 | block(curr).recalculate_flag = true; % Plotting flag to indicate this block has been updated.
250 | block(curr).entry_speed = min([ block(curr).max_entry_speed,...
251 | sqrt(block(next).entry_speed^2 + 2*block(curr).acceleration*60*60*block(curr).millimeters)]);
252 | end
253 |
254 | end
255 | end
256 |
257 | % For two blocks, reverse pass is skipped, but forward pass plans second block entry speed
258 | % onward. This prevents the first, or the potentially executing block, from being over-written.
259 | % NOTE: Can never be bhead, since bsafe is always in active buffer.
260 | next = bplanned;
261 | bind = next_block_index(bplanned); % Start at bplanned
262 | while bind ~= bhead
263 | curr = next;
264 | next = bind;
265 |
266 | % An acceleration block is always an optimally planned block since it starts from the first
267 | % block's current speed or a maximum junction speed. Compute accelerations from this block
268 | % and update the next block's entry speed.
269 | if (block(curr).entry_speed < block(next).entry_speed)
270 | % Once speed is set by forward planner, the plan for this block is finished and optimal.
271 | % Increment the planner pointer forward one block.
272 |
273 | entry_speed = sqrt(block(curr).entry_speed^2 + 2*block(curr).acceleration*60*60*block(curr).millimeters);
274 | if (block(next).entry_speed > entry_speed)
275 | block(next).entry_speed = entry_speed;
276 | bplanned = bind;
277 | end
278 |
279 | end
280 |
281 | % Check if the next block entry speed is at max_entry_speed. If so, move the planned pointer, since
282 | % this entry speed cannot be improved anymore and all prior blocks have been completed and optimally planned.
283 | if block(next).entry_speed == block(next).max_entry_speed
284 | bplanned = bind;
285 | end
286 |
287 | % Recalculate trapezoid can be installed here, since it scans through all of the plannable blocks.
288 | % NOTE: Eventually this will only be computed when being executed.
289 |
290 | bind = next_block_index( bind );
291 |
292 | end
293 |
294 | return
295 |
296 | % ----------------------------------------------------------------------------------------
297 | % PLOTTING FUNCTIONS
298 |
299 | % Plots the entire buffer plan into a MATLAB figure to visual the plan.
300 | % BLUE line indicates completed planner blocks that require no recalculation.
301 | % RED line indicates planner blocks that have been recalculated.
302 | % GREEN line indicates the location of the BPLANNED pointer. Always a recalculated block.
303 | % BLACK dotted-line and 'x' indicates block nominal speed and max junction velocity, respectively.
304 | % CYAN '.' indicates block initial entry speed.
305 | function plot_buffer_velocities()
306 | global block bhead btail bplanned acceleration pos ACCELERATION_TICKS_PER_SECOND
307 | bind = btail;
308 | curr = [];
309 | next = [];
310 |
311 | pos_initial = 0;
312 | pos = 0;
313 | while bind ~= bhead
314 | curr = next;
315 | next = bind;
316 | hold on;
317 | if ~isempty(curr)
318 | accel_d = estimate_acceleration_distance(block(curr).entry_speed, block(curr).nominal_speed, block(curr).acceleration*60*60);
319 | decel_d = estimate_acceleration_distance(block(curr).nominal_speed, block(next).entry_speed,-block(curr).acceleration*60*60);
320 | plateau_d = block(curr).millimeters-accel_d-decel_d;
321 | if plateau_d < 0
322 | accel_d = intersection_distance(block(curr).entry_speed, block(next).entry_speed, block(curr).acceleration*60*60, block(curr).millimeters);
323 | if accel_d < 0
324 | accel_d = 0;
325 | elseif accel_d > block(curr).millimeters
326 | accel_d = block(curr).millimeters;
327 | end
328 | plateau_d = 0;
329 | end
330 | color = 'b';
331 | if (block(curr).recalculate_flag || block(next).recalculate_flag)
332 | block(curr).recalculate_flag = false;
333 | color = 'r';
334 | end
335 | if bplanned == curr
336 | color = 'g';
337 | end
338 |
339 | plot_trap(pos,block(curr).entry_speed,block(next).entry_speed,block(curr).nominal_speed,block(curr).acceleration,accel_d,plateau_d,block(curr).millimeters,color)
340 | plot([pos pos+block(curr).millimeters],block(curr).nominal_speed*[1 1],'k:') % BLACK dotted indicates
341 | plot(pos,block(curr).max_entry_speed,'kx')
342 |
343 | pos = pos + block(curr).millimeters;
344 | plot(pos,block(next).entry_speed,'c.');
345 | end
346 | bind = next_block_index( bind );
347 | end
348 |
349 | accel_d = estimate_acceleration_distance(block(next).entry_speed, block(next).nominal_speed, block(next).acceleration*60*60);
350 | decel_d = estimate_acceleration_distance(block(next).nominal_speed, 0, -block(next).acceleration*60*60);
351 | plateau_d = block(next).millimeters-accel_d-decel_d;
352 | if plateau_d < 0
353 | accel_d = intersection_distance(block(next).entry_speed, 0, block(next).acceleration*60*60, block(next).millimeters);
354 | if accel_d < 0
355 | accel_d = 0;
356 | elseif accel_d > block(next).millimeters
357 | accel_d = block(next).millimeters;
358 | end
359 | plateau_d = 0;
360 | end
361 | block(next).recalculate_flag = false;
362 | color = 'r';
363 | if bplanned == next
364 | color= 'g';
365 | end
366 |
367 | plot_trap(pos,block(next).entry_speed,0,block(next).nominal_speed,block(next).acceleration,accel_d,plateau_d,block(next).millimeters,color)
368 | plot([pos pos+block(next).millimeters],block(next).nominal_speed*[1 1],'k:')
369 | plot(pos,block(next).max_entry_speed,'kx')
370 |
371 | plot(pos,block(next).entry_speed,'.');
372 | pos = pos + block(next).millimeters;
373 | plot(pos,0,'rx');
374 | xlabel('mm');
375 | ylabel('mm/sec');
376 | xlim([pos_initial pos])
377 | title('Planner buffer optimized velocity profile');
378 | pause();
379 | hold off;
380 |
381 | plot(pos,0)
382 | return
383 |
384 |
385 | function d_a = estimate_acceleration_distance(initial_rate, target_rate, acceleration,rate_delta)
386 | d_a = (target_rate*target_rate-initial_rate*initial_rate)/(2*acceleration);
387 | return
388 |
389 | function d_i = intersection_distance(initial_rate, final_rate, acceleration, distance, rate_delta)
390 | d_i = (2*acceleration*distance-initial_rate*initial_rate+final_rate*final_rate)/(4*acceleration);
391 | return
392 |
393 |
394 | % Simply plots the ac/de-celeration curves and plateaus of a trapezoid.
395 | function plot_trap(pos,initial_rate,final_rate,rate,accel,accel_d,plateau_d,millimeters,color)
396 |
397 | dx = 1.0; % Line segment length
398 | linex = [pos]; liney = [initial_rate];
399 |
400 | % Acceleration
401 | np = floor(accel_d/dx);
402 | if np
403 | v = initial_rate;
404 | for i = 1:np
405 | v = sqrt(v^2+2*accel*60*60*dx);
406 | linex = [linex pos+i*dx];
407 | liney = [liney v];
408 | end
409 | end
410 |
411 | % Plateau
412 | v = sqrt(initial_rate^2 + 2*accel*60*60*accel_d);
413 | if v < rate
414 | rate = v;
415 | end
416 | linex = [linex pos+[accel_d accel_d+plateau_d]];
417 | liney = [liney [rate rate]];
418 |
419 | % Deceleration
420 | np = floor((millimeters-accel_d-plateau_d)/dx);
421 | if np
422 | v = rate;
423 | for i = 1:np
424 | v = sqrt(v^2-2*accel*60*60*dx);
425 | linex = [linex pos+i*dx+accel_d+plateau_d];
426 | liney = [liney v];
427 | end
428 | end
429 |
430 | linex = [linex pos+millimeters];
431 | liney = [ liney final_rate];
432 | plot(linex,liney,color);
433 |
434 | return
435 |
436 |
437 |
438 |
--------------------------------------------------------------------------------