coil_winder
Marcin K 2017-02-19 17:50:07 +01:00
commit cbeec817b6
28 zmienionych plików z 4502 dodań i 0 usunięć

6
.gitignore vendored 100644
Wyświetl plik

@ -0,0 +1,6 @@
*.d
*.o
*.gz
*.tar
*.elf
*swp

77
Makefile 100644
Wyświetl plik

@ -0,0 +1,77 @@
OBJECTS=main.o error.o init.o lexer.o parser.o symbol.o
elf:
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 motor_control.ino
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 motor_control.ino
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 motor_control.ino
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 motor_control.ino
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 debug.cpp
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 gcode_parser.cpp
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 kinematics.cpp
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 maths.cpp
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 motor.cpp
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 motor_control.ino
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 msg.cpp
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 pinio.cpp
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 queue.cpp
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 serial.cpp
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -M -MG -MP -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 timer-avr.cpp
avr-g++ -c -g -Os -w -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -w -x c++ -E -CC -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 motor_control.ino
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 debug.cpp -o debug.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 gcode_parser.cpp -o gcode_parser.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 kinematics.cpp -o kinematics.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 maths.cpp -o maths.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 motor.cpp -o motor.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 motor_control.ino -o motor_control.ino.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 msg.cpp -o msg.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 pinio.cpp -o pinio.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 queue.cpp -o queue.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 serial.cpp -o serial.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 timer-avr.cpp -o timer-avr.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 motor_control.ino.cpp -o motor_control.ino.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 motion_planner.cpp -o motion_planner.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 /usr/share/arduino/hardware/arduino/avr/cores/MightyCore/main.cpp -o main.cpp.o
avr-g++ -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 /usr/share/arduino/hardware/arduino/avr/cores/MightyCore/wiring.c -o wiring.o
avr-gcc -c -g -Os -Wall -std=gnu++11 -fno-exceptions -ffunction-sections -fdata-sections -fno-threadsafe-statics -MMD -mmcu=atmega32 -DF_CPU=16000000L -DARDUINO=10606 -DARDUINO_AVR_ATmega32 -DARDUINO_ARCH_AVR -I/usr/share/arduino/hardware/arduino/avr/cores/MightyCore -I/usr/share/arduino/hardware/arduino/avr/variants/mega32 /usr/share/arduino/hardware/arduino/avr/cores/MightyCore/hooks.c -o hooks.o
#avr-gcc -Wall -Os -Wl,--gc-sections -mmcu=atmega32 -o motor_control.ino.elf debug.cpp.o gcode_parser.cpp.o kinematics.cpp.o maths.cpp.o motor.cpp.o motor_control.ino.cpp.o msg.cpp.o pinio.cpp.o queue.cpp.o serial.cpp.o timer-avr.cpp.o motion_planner.cpp.o main.cpp.o wiring.o hooks.o -lm -Wl,--section-start=.siminfo=0x900000
avr-gcc -Wall -Os -Wl,--section-start=.siminfo=0x900000 -mmcu=atmega32 -o motor_control.ino.elf debug.cpp.o gcode_parser.cpp.o kinematics.cpp.o maths.cpp.o motor.cpp.o motor_control.ino.cpp.o msg.cpp.o pinio.cpp.o queue.cpp.o serial.cpp.o timer-avr.cpp.o motion_planner.cpp.o main.cpp.o wiring.o hooks.o -lm
hex: elf
avr-objcopy -O ihex -j .eeprom --set-section-flags=.eeprom=alloc,load --no-change-warnings --change-section-lma .eeprom=0 motor_control.ino.elf motor_control.ino.eep
avr-objcopy -O ihex -R .eeprom motor_control.ino.elf motor_control.ino.hex

502
arduino_32U4.h 100644
Wyświetl plik

@ -0,0 +1,502 @@
// teensy pin assignments
// UART xxx checks this against USBs?
//#define RXD DIO5
//#define TXD DIO6
//#define RXD0 DIO7
//#define TXD0 DIO8
//#define RXD1 DIO7
//#define TXD1 DIO8
// ATmega32U4 doesn't have a serial port 0, maybe its a USB?
// do some munging of port 0 to port 1 the help serial.c
#define UCSR0A UCSRA
#define U2X0 U2X
#define UBRR0 UBRRL
#define UCSR0B UCSRB
#define RXEN0 RXEN
#define TXEN0 TXEN
#define UCSR0C UCSRC
#define UCSZ01 UCSZ1
#define UCSZ00 UCSZ0
#define RXCIE0 RXCIE
#define UDRIE0 UDRIE
#define USART0_UDRE_vect USART1_UDRE_vect
#define UDR0 UDR
#define UCSR0B UCSRB
// SPI
#define SCK DIO1
#define MISO DIO3
#define MOSI DIO2
#define SS DIO0
// TWI (I2C)
#define SCL DIO5
#define SDA DIO6
// timers and PWM
// The 32U4 PWMs are fairly restricted. If you avoid timer 1 for the clock,
// two pairs of the PWMs are complements of each other:
// DIO11 & DIO12 on ~OC4D & OC4D and DIO14 & DIO15 on ~OC4B & OC4B
#define TIMER4_IS_10_BIT
#define OC0A DIO4
#define OC0B DIO5
#define OC3A DIO9 // 10 bit timer on OC4A, inverse of PWM on DIO10
#define OC4A D1O10
//#define OC4B DIO14 // inverse of PWM on DIO15
#define OC4B DIO15
//#define OC4D DIO11 // inverse of PWM on DIO12
#define OC4D DIO12
/*
pins
*/
#define DIO0_PIN PINB0
#define DIO0_RPORT PINB
#define DIO0_WPORT PORTB
#define DIO0_PWM NULL
#define DIO0_DDR DDRB
#define DIO1_PIN PINB1
#define DIO1_RPORT PINB
#define DIO1_WPORT PORTB
#define DIO1_PWM NULL
#define DIO1_DDR DDRB
#define DIO2_PIN PINB2
#define DIO2_RPORT PINB
#define DIO2_WPORT PORTB
#define DIO2_PWM NULL
#define DIO2_DDR DDRB
#define DIO3_PIN PINB3
#define DIO3_RPORT PINB
#define DIO3_WPORT PORTB
#define DIO3_PWM NULL
#define DIO3_DDR DDRB
#define DIO4_PIN PINB7
#define DIO4_RPORT PINB
#define DIO4_WPORT PORTB
// teensy card says RTS OC1C OC0A PB7 PWM / ATMega32U4 datasheet says PCINT7/OC0A/OC1C/~RTS PB7
// Timer 1 would be a problem drf 2012-01-09
// Timer 0 might be used by serial.c
#define DIO4_PWM &OCR0A
#define DIO4_DDR DDRB
#define DIO5_PIN PIND0
#define DIO5_RPORT PIND
#define DIO5_WPORT PORTD
#define DIO5_PWM &OCR0B
//#define DIO5_PWM NULL
#define DIO5_DDR DDRD
#define DIO6_PIN PIND1
#define DIO6_RPORT PIND
#define DIO6_WPORT PORTD
#define DIO6_PWM NULL
#define DIO6_DDR DDRD
#define DIO7_PIN PIND2
#define DIO7_RPORT PIND
#define DIO7_WPORT PORTD
#define DIO7_PWM NULL
#define DIO7_DDR DDRD
#define DIO8_PIN PIND3
#define DIO8_RPORT PIND
#define DIO8_WPORT PORTD
#define DIO8_PWM NULL
#define DIO8_DDR DDRD
#define DIO9_PIN PINC6
#define DIO9_RPORT PINC
#define DIO9_WPORT PORTC
#define DIO9_PWM &OCR3AL // inverse of DIO10_PWM
#define DIO9_DDR DDRC
#define DIO10_PIN PINC7
#define DIO10_RPORT PINC
#define DIO10_WPORT PORTC
// pin 10/c7 is on a 8/10 bit timer 4 and share the register with inverses
#define DIO10_PWM &OCR4A
#define DIO10_DDR DDRC
#define DIO11_PIN PIND6
#define DIO11_RPORT PIND
#define DIO11_WPORT PORTD
#define DIO11_PWM NULL // inverse of DIO12_PWM
#define DIO11_DDR DDRD
#define DIO12_PIN PIND7
#define DIO12_RPORT PIND
#define DIO12_WPORT PORTD
#define DIO12_PWM &OCR4D
#define DIO12_DDR DDRD
#define DIO13_PIN PINB4
#define DIO13_RPORT PINB
#define DIO13_WPORT PORTB
#define DIO13_PWM NULL
#define DIO13_DDR DDRB
#define DIO14_PIN PINB5
#define DIO14_RPORT PINB
#define DIO14_WPORT PORTB
#define DIO14_PWM NULL // inverse of DIO15_PWM
#define DIO14_DDR DDRB
#define DIO15_PIN PINB6
#define DIO15_RPORT PINB
#define DIO15_WPORT PORTB
#define DIO15_PWM &OCR4B
#define DIO15_DDR DDRB
#define DIO16_PIN PINF7
#define DIO16_RPORT PINF
#define DIO16_WPORT PORTF
#define DIO16_PWM NULL
#define DIO16_DDR DDRF
#define DIO17_PIN PINF6
#define DIO17_RPORT PINF
#define DIO17_WPORT PORTF
#define DIO17_PWM NULL
#define DIO17_DDR DDRF
#define DIO18_PIN PINF5
#define DIO18_RPORT PINF
#define DIO18_WPORT PORTF
#define DIO18_PWM NULL
#define DIO18_DDR DDRF
#define DIO19_PIN PINF4
#define DIO19_RPORT PINF
#define DIO19_WPORT PORTF
#define DIO19_PWM NULL
#define DIO19_DDR DDRF
#define DIO20_PIN PINF1
#define DIO20_RPORT PINF
#define DIO20_WPORT PORTF
#define DIO20_PWM NULL
#define DIO20_DDR DDRF
#define DIO21_PIN PINF0
#define DIO21_RPORT PINF
#define DIO21_WPORT PORTF
#define DIO21_PWM NULL
#define DIO21_DDR DDRF
#define DIO22_PIN PIND4
#define DIO22_RPORT PIND
#define DIO22_WPORT PORTD
#define DIO22_PWM NULL
#define DIO22_DDR DDRD
#define DIO23_PIN PIND5
#define DIO23_RPORT PIND
#define DIO23_WPORT PORTD
#define DIO23_PWM NULL
#define DIO23_DDR DDRD
#define DIO24_PIN PINE6
#define DIO24_RPORT PINE
#define DIO24_WPORT PORTE
#define DIO24_PWM NULL
#define DIO24_DDR DDRE
// ADC converters
#define AIO0_PIN PINF0
#define AIO0_RPORT PINF
#define AIO0_WPORT PORTF
#define AIO0_PWM NULL
#define AIO0_DDR DDRF
#define AIO0_ADC 0
#define AIO1_PIN PINF1
#define AIO1_RPORT PINF
#define AIO1_WPORT PORTF
#define AIO1_PWM NULL
#define AIO1_DDR DDRF
#define AIO1_ADC 1
#define AIO2_PIN PINF4
#define AIO2_RPORT PINF
#define AIO2_WPORT PORTF
#define AIO2_PWM NULL
#define AIO2_DDR DDRF
#define AIO2_ADC 2
#define AIO3_PIN PINF5
#define AIO3_RPORT PINF
#define AIO3_WPORT PORTF
#define AIO3_PWM NULL
#define AIO3_DDR DDRF
#define AIO3_ADC 3
#define AIO4_PIN PINF6
#define AIO4_RPORT PINF
#define AIO4_WPORT PORTF
#define AIO4_PWM NULL
#define AIO4_DDR DDRF
#define AIO4_ADC 4
#define AIO5_PIN PINF7
#define AIO5_RPORT PINF
#define AIO5_WPORT PORTF
#define AIO5_PWM NULL
#define AIO5_DDR DDRF
#define AIO5_ADC 5
#define AIO6_PIN PINB6
#define AIO6_RPORT PINB
#define AIO6_WPORT PORTB
#define AIO6_PWM NULL
#define AIO6_DDR DDRB
#define AIO6_ADC 6
#define AIO7_PIN PINB5
#define AIO7_RPORT PINB
#define AIO7_WPORT PORTB
#define AIO7_PWM NULL
#define AIO7_DDR DDRB
#define AIO7_ADC 7
#define AIO8_PIN PINB4
#define AIO8_RPORT PINB
#define AIO8_WPORT PORTB
#define AIO8_PWM NULL
#define AIO8_DDR DDRB
#define AIO8_ADC 8
#define AIO9_PIN PIND7
#define AIO9_RPORT PIND
#define AIO9_WPORT PORTD
#define AIO9_PWM NULL
#define AIO9_DDR DDRD
#define AIO9_ADC 9
#define AIO10_PIN PIND6
#define AIO10_RPORT PIND
#define AIO10_WPORT PORTD
#define AIO10_PWM NULL
#define AIO10_DDR DDRD
#define AIO10_ADC 10
#define AIO11_PIN PIND4
#define AIO11_RPORT PIND
#define AIO11_WPORT PORTD
#define AIO11_PWM NULL
#define AIO11_DDR DDRD
#define AIO11_ADC 11
// The PWM
// Port A isn't defined
// Port B is fully available
#undef PB0
#define PB0_PIN PINB0
#define PB0_RPORT PINB
#define PB0_WPORT PORTB
#define PB0_PWM NULL
#define PB0_DDR DDRB
#undef PB1
#define PB1_PIN PINB1
#define PB1_RPORT PINB
#define PB1_WPORT PORTB
#define PB1_PWM NULL
#define PB1_DDR DDRB
#undef PB2
#define PB2_PIN PINB2
#define PB2_RPORT PINB
#define PB2_WPORT PORTB
#define PB2_PWM NULL
#define PB2_DDR DDRB
#undef PB3
#define PB3_PIN PINB3
#define PB3_RPORT PINB
#define PB3_WPORT PORTB
#define PB3_PWM NULL
#define PB3_DDR DDRB
#undef PB4
#define PB4_PIN PINB4
#define PB4_RPORT PINB
#define PB4_WPORT PORTB
#define PB4_PWM NULL
#define PB4_DDR DDRB
#undef PB5
#define PB5_PIN PINB5
#define PB5_RPORT PINB
#define PB5_WPORT PORTB
#define PB5_PWM NULL
#define PB5_DDR DDRB
#undef PB6
#define PB6_PIN PINB6
#define PB6_RPORT PINB
#define PB6_WPORT PORTB
#define PB6_PWM NULL
#define PB6_DDR DDRB
#undef PB7
#define PB7_PIN PINB7
#define PB7_RPORT PINB
#define PB7_WPORT PORTB
#define PB7_PWM NULL
#define PB7_DDR DDRB
// Port C has only bits 6&7 available on pins
#undef PC1
#define PC1_PIN PINC1
#define PC1_RPORT PINC
#define PC1_WPORT PORTC
#define PC1_PWM NULL
#define PC1_DDR DDRC
#undef PC2
#define PC2_PIN PINC2
#define PC2_RPORT PINC
#define PC2_WPORT PORTC
#define PC2_PWM NULL
#define PC2_DDR DDRC
#undef PC3
#define PC3_PIN PINC3
#define PC3_RPORT PINC
#define PC3_WPORT PORTC
#define PC3_PWM NULL
#define PC3_DDR DDRC
#undef PC4
#define PC4_PIN PINC4
#define PC4_RPORT PINC
#define PC4_WPORT PORTC
#define PC4_PWM NULL
#define PC4_DDR DDRC
#undef PC5
#define PC5_PIN PINC5
#define PC5_RPORT PINC
#define PC5_WPORT PORTC
#define PC5_PWM NULL
#define PC5_DDR DDRC
#undef PC6
#define PC6_PIN PINC6
#define PC6_RPORT PINC
#define PC6_WPORT PORTC
#define PC6_PWM NULL
#define PC6_DDR DDRC
#undef PC7
#define PC7_PIN PINC7
#define PC7_RPORT PINC
#define PC7_WPORT PORTC
#define PC7_PWM NULL
#define PC7_DDR DDRC
//Port D is fully available
#undef PD0
#define PD0_PIN PIND0
#define PD0_RPORT PIND
#define PD0_WPORT PORTD
#define PD0_PWM NULL
#define PD0_DDR DDRD
#undef PD1
#define PD1_PIN PIND1
#define PD1_RPORT PIND
#define PD1_WPORT PORTD
#define PD1_PWM NULL
#define PD1_DDR DDRD
#undef PD2
#define PD2_PIN PIND2
#define PD2_RPORT PIND
#define PD2_WPORT PORTD
#define PD2_PWM NULL
#define PD2_DDR DDRD
#undef PD3
#define PD3_PIN PIND3
#define PD3_RPORT PIND
#define PD3_WPORT PORTD
#define PD3_PWM NULL
#define PD3_DDR DDRD
#undef PD4
#define PD4_PIN PIND4
#define PD4_RPORT PIND
#define PD4_WPORT PORTD
#define PD4_PWM NULL
#define PD4_DDR DDRD
#undef PD5
#define PD5_PIN PIND5
#define PD5_RPORT PIND
#define PD5_WPORT PORTD
#define PD5_PWM NULL
#define PD5_DDR DDRD
#undef PD6
#define PD6_PIN PIND6
#define PD6_RPORT PIND
#define PD6_WPORT PORTD
#define PD6_PWM NULL
#define PD6_DDR DDRD
#undef PD7
#define PD7_PIN PIND7
#define PD7_RPORT PIND
#define PD7_WPORT PORTD
#define PD7_PWM NULL
#define PD7_DDR DDRD
// Port E has only 2&6 available, does reset/bootload & be the ADC positive signal
#undef PE2
#define PE2_PIN PINE2
#define PE2_RPORT PINE
#define PE2_WPORT PORTE
#define PE2_PWM NULL
#define PE2_DDR DDRE
#undef PE6
#define PE6_PIN PINE6
#define PE6_RPORT PINE
#define PE6_WPORT PORTE
#define PE6_PWM NULL
#define PE6_DDR DDRE
//port F is missing bits 2 & 3 and does ADC and can do JTAG
#undef PF0
#define PF0_PIN PINF0
#define PF0_RPORT PINF
#define PF0_WPORT PORTF
#define PF0_PWM NULL
#define PF0_DDR DDRF
#undef PF1
#define PF1_PIN PINF1
#define PF1_RPORT PINF
#define PF1_WPORT PORTF
#define PF1_PWM NULL
#define PF1_DDR DDRF
#undef PF4
#define PF4_PIN PINF4
#define PF4_RPORT PINF
#define PF4_WPORT PORTF
#define PF4_PWM NULL
#define PF4_DDR DDRF
#undef PF5
#define PF5_PIN PINF5
#define PF5_RPORT PINF
#define PF5_WPORT PORTF
#define PF5_PWM NULL
#define PF5_DDR DDRF
#undef PF6
#define PF6_PIN PINF6
#define PF6_RPORT PINF
#define PF6_WPORT PORTF
#define PF6_PWM NULL
#define PF6_DDR DDRF
#undef PF7
#define PF7_PIN PINF7
#define PF7_RPORT PINF
#define PF7_WPORT PORTF
#define PF7_PWM NULL
#define PF7_DDR DDRF

227
config.h 100644
Wyświetl plik

@ -0,0 +1,227 @@
#ifndef _CONFIG_H
#define _CONFIG_H
#include <Arduino.h>
#include "arduino_32U4.h"
#define KINEMATICS_STRAIGHT
/** \def X_MIN X_MAX Y_MIN Y_MAX Z_MIN Z_MAX
Soft axis limits. Define them to your machine's size relative to what your
G-code considers to be the origin (typically the bed's center or the bed's
front left corner).
Note that relocating the origin at runtime with G92 will also relocate these
limits.
Not defining them at all will disable limits checking and make the binary
about 250 bytes smaller. Enabling only some of them is perfectly fine.
Units: millimeters
Sane values: according to printer build room size
Valid range: -1000.0 to 1000.0
*/
/*
#define X_MIN 0.0
#define X_MAX 200.0
#define Y_MIN 0.0
#define Y_MAX 200.0
#define Z_MIN 0.0
#define Z_MAX 140.0
*/
/*steps per meter*/
#define STEPS_PER_M_X 1280000
#define STEPS_PER_M_Y 1280000
#define STEPS_PER_M_Z 1280000
#define STEPS_PER_M_E 96271
/** \def SEARCH_FEEDRATE_X SEARCH_FEEDRATE_Y SEARCH_FEEDRATE_Z
Used when doing precision endstop search and as default feedrate.
(mm / min) 60 mm / min = 1 mm/sec
*/
#define SEARCH_FEEDRATE_X 400
#define SEARCH_FEEDRATE_Y 400
#define SEARCH_FEEDRATE_Z 400
/** \def MAXIMUM_FEEDRATE_X MAXIMUM_FEEDRATE_Y MAXIMUM_FEEDRATE_Z MAXIMUM_FEEDRATE_E
Used for G0 rapid moves and as a cap for all other feedrates. (mm / min)
*/
#define MAXIMUM_FEEDRATE_X 6000
#define MAXIMUM_FEEDRATE_Y 6000
#define MAXIMUM_FEEDRATE_Z 6000
#define MAXIMUM_FEEDRATE_E 20000
/** \def ACCELERATION
How fast to accelerate when using ACCELERATION_RAMPING. Start with 10 for
milling (high precision) or 1000 for printing.
Units: mm/s^2
Useful range: 1 to 10'000
*/
#define ACCELERATION 100
/** \def LOOKAHEAD
Define this to enable look-ahead during *ramping* acceleration to smoothly
transition between moves instead of performing a dead stop every move.
Enabling look-ahead requires about 3600 bytes of flash memory.
*/
#define LOOKAHEAD
/** \def MAX_JERK_X MAX_JERK_Y MAX_JERK_Z MAX_JERK_E
When performing look-ahead, we need to decide what an acceptable jerk to the
mechanics is. Look-ahead attempts to instantly change direction at movement
crossings, which means instant changes in the speed of the axes participating
in the movement. Define here how big the speed bumps on each of the axes is
allowed to be.
If you want a full stop before and after moving a specific axis, define
MAX_JERK of this axis to 0. This is often wanted for the Z axis. If you want
to ignore jerk on an axis, define it to twice the maximum feedrate of this
axis.
Having these values too low results in more than neccessary slowdown at
movement crossings, but is otherwise harmless. Too high values can result
in stepper motors suddenly stalling. If angles between movements in your
G-code are small and your printer runs through entire curves full speed,
there's no point in raising the values.
Units: mm/min
Sane values: 0 to 400
Valid range: 0 to 65535
*/
#define MAX_JERK_X 80
#define MAX_JERK_Y 80
#define MAX_JERK_Z 0
#define MAX_JERK_E 200
/** \def BAUD
Baud rate for the serial RS232 protocol connection to the host. Usually
115200, other common values are 19200, 38400 or 57600. Ignored when USB_SERIAL
is defined.
*/
#define BAUD 9600
/** \def XONXOFF
Xon/Xoff flow control.
Redundant when using RepRap Host for sending G-code, but mandatory when
sending G-code files with a plain terminal emulator, like GtkTerm (Linux),
CoolTerm (Mac) or HyperTerminal (Windows).
*/
#define XONXOFF
/**************PINOUT****************/
#define X_STEP_PIN PC3 // 19 PC3
#define X_DIR_PIN PC2 // 18 PC2
#define X_MIN_PIN DIO3
#define X_MAX_PIN DIO2
#define X_ENABLE_PIN PC4 // 20 PC4
#define X_INVERT_DIR
#define X_INVERT_MIN
#define X_INVERT_MAX
#define X_INVERT_ENABLE
#define Y_STEP_PIN DIO9 //22 PC6
#define Y_DIR_PIN PC5 //21 PC5
#define Y_MIN_PIN DIO8
#define Y_MAX_PIN DIO7
#define Y_ENABLE_PIN DIO10 //23 PC7
#define Y_INVERT_DIR
#define Y_INVERT_MIN
#define Y_INVERT_MAX
#define Y_INVERT_ENABLE
#define Z_STEP_PIN DIO11
#define Z_DIR_PIN DIO12
#define Z_MIN_PIN DIO13
#define Z_MAX_PIN DIO14
#define Z_ENABLE_PIN DIO15
#define Z_INVERT_DIR
#define Z_INVERT_MIN
#define Z_INVERT_MAX
#define Z_INVERT_ENABLE
#define E_STEP_PIN DIO23
#define E_DIR_PIN DIO0
#define E_ENABLE_PIN DIO22
#define E_INVERT_DIR
#define E_INVERT_ENABLE
#define ENCODER_PIN 17
#define PWR_OUT1_PIN 18
#define PWR_OUT2_PIN 19
#define ANALOG_IN_PIN 33
#define SWITCH1_PIN 34
#define SWITCH2_PIN 35
#define SWITCH3_PIN 16
/** \def MOVEBUFFER_SIZE
Move buffer size, in number of moves.
Note that each move takes a fair chunk of ram (107 bytes as of this writing),
so don't make the buffer too big. However, a larger movebuffer will probably
help with lots of short consecutive moves, as each move takes a bunch of
math (hence time) to set up so a longer buffer allows more of the math to
be done during preceding longer moves.
*/
#define MOVEBUFFER_SIZE 8
/** \def F_CPU
Actual CPU clock rate. #ifndef required for Arduino compatibility.
*/
#ifndef F_CPU
#define F_CPU 16000000UL
#endif
/** \def MOTHERBOARD
This is the motherboard, as opposed to the extruder. See extruder/ directory
for GEN3 extruder firmware.
*/
#define MOTHERBOARD
/** \def DEBUG_LED_PIN
Enable flashing of a LED during motor stepping.
Disabled by default. Uncommenting this makes the binary a few bytes larger
and adds a few cycles to the step timing interrrupt in timer.c. Also used
for precision profiling (profiling works even without actually having such
a LED in hardware), see
http://reprap.org/wiki/Teacup_Firmware#Doing_precision_profiling
*/
#define DEBUG_LED_PIN PC1
////////////////DEBUG/////////////////////
#define SIMINFO
#define DEBUG
#ifdef DEBUG
#define DEBUG_ECHO 1
#define DEBUG_INFO 2
#define DEBUG_ERRORS 4
#define DEBUG_DRYRUN 8
#define DEBUG_PID 16
#define DEBUG_DDA 32
#define DEBUG_POSITION 64
#else
// by setting these to zero, the compiler should optimise the relevant code out
#define DEBUG_PID 0
#define DEBUG_DDA 1
#define DEBUG_POSITION 1
#define DEBUG_ECHO 1
#define DEBUG_INFO 1
#define DEBUG_DRYRUN 1
#endif
extern volatile uint8_t debug_flags;
#ifndef BSS
#define BSS __attribute__ ((__section__ (".bss")))
#endif
#endif /* _CONFIG_H */

3
debug.cpp 100644
Wyświetl plik

@ -0,0 +1,3 @@
#include "config.h"
volatile uint8_t debug_flags = 0xFF;

200
gcode_parser.cpp 100644
Wyświetl plik

@ -0,0 +1,200 @@
#include "gcode_parser.h"
#include "queue.h"
#include "serial.h"
#define IS_DIGIT(c) (c >= '0' && c <= '9')
#define IS_LETTER(c) (c >= 'A' && c <= 'Z')
#define IS_WHITECHAR(c) (c == ' ' || c == '\t')
#define IS_ENDING(c) (c == '\n' || c == '\r')
#define ATOI(c) (c - '0')
GCODE_PARAM params[8];
uint8_t current_parameter;
TARGET next_target;
uint8_t (*current_state)(uint8_t c);
uint8_t start_parsing_parameter(uint8_t );
uint8_t start_parse_number(uint8_t);
/// convert a floating point input value into an integer with appropriate scaling.
/// \param *df pointer to floating point structure that holds fp value to convert
/// \param multiplicand multiply by this amount during conversion to integer
///
/// Tested for up to 42'000 mm (accurate), 420'000 mm (precision 10 um) and
/// 4'200'000 mm (precision 100 um).
static int32_t decfloat_to_int(uint32_t mantissa, uint8_t exponent, uint8_t sign, uint16_t multiplicand) {
// exponent=1 means we've seen a decimal point but no digits after it, and e=2 means we've seen a decimal point with one digit so it's too high by one if not zero
if (exponent)
exponent--;
// This raises range for mm by factor 1000 and for inches by factor 100.
// It's a bit expensive, but we should have the time while parsing.
while (exponent && multiplicand % 10 == 0) {
multiplicand /= 10;
exponent--;
}
mantissa *= multiplicand;
if (exponent)
mantissa = (mantissa + powers[exponent] / 2) / powers[exponent];
return sign ? -(int32_t)mantissa : (int32_t)mantissa;
}
void parser_reset()
{
uint8_t i;
current_state = start_parsing_parameter;
current_parameter = 0;
for(i = 0; i < 8; ++i)
{
//params[i].name = '\0';
params[i].value = 0;
params[i].exponent = 0;
params[i].is_negative = 0;
}
}
void parser_init()
{
next_target.F = SEARCH_FEEDRATE_Z;
next_target.e_multiplier = 256;
next_target.f_multiplier = 256;
parser_reset();
}
void process_command()
{
for(int i = 1; i <= current_parameter; ++i)
{
switch(params[i].name)
{
case 'X':
next_target.axis[X] = decfloat_to_int(params[i].value, params[i].exponent, params[i].is_negative, 1000);
break;
case 'Y':
next_target.axis[Y] = decfloat_to_int(params[i].value, params[i].exponent, params[i].is_negative, 1000);
break;
case 'F':
next_target.F = decfloat_to_int(params[i].value, params[i].exponent, params[i].is_negative, 1);
break;
}
}
switch(params[0].name)
{
case 'G':
//1
enqueue(&next_target);
break;
case 'M':
//114
update_current_position();
sersendf_P(PSTR("X:%lq,Y:%lq,Z:%lq,E:%lq,F:%lu\n"),
current_position.axis[X], current_position.axis[Y],
current_position.axis[Z], current_position.axis[E],
current_position.F);
break;
}
}
uint8_t gcode_error(uint8_t c)
{
if IS_ENDING(c)
parser_reset();
return 1;
}
uint8_t start_parsing_parameter(uint8_t c)
{
//ignore
if IS_WHITECHAR(c)
return 0;
// uppercase
if (c >= 'a' && c <= 'z')
c &= ~32;
if IS_LETTER(c)
{
params[current_parameter].name = c;
current_state = start_parse_number;
return 0;
}
current_state = gcode_error;
return 1;
}
uint8_t parse_digit(uint8_t c)
{
//process digit
if IS_DIGIT(c)
{
// this is simply mantissa = (mantissa * 10) + atoi(c) in different clothes
params[current_parameter].value = (params[current_parameter].value << 3) +
(params[current_parameter].value << 1) + ATOI(c);
if(params[current_parameter].exponent)
++params[current_parameter].exponent;
return 0;
}
//this digit is a end of parameter
if IS_WHITECHAR(c)
{
current_state = start_parsing_parameter;
++current_parameter;
return 0;
}
// all done, this digit is a end of instruction
if(c == '\n' || c == '\r') {
//process instruction
process_command();
parser_reset();
return 0;
}
if(c == '.')
{
params[current_parameter].exponent = 1;
return 0;
}
current_state = gcode_error;
return 1;
}
uint8_t start_parse_number(uint8_t c)
{
current_state = parse_digit;
//negative number
if(c == '-')
{
params[current_parameter].is_negative = 1;
return 0;
}
if IS_DIGIT(c)
{
parse_digit(c);
return 0;
}
current_state = gcode_error;
return 1;
}
uint8_t gcode_parse_char(uint8_t c) {
uint8_t result, checksum_char = c;
result = current_state(c);
if IS_ENDING(c)
{
if ( result == 1) //error
return 2;
return 1;
}
return 0;
}

23
gcode_parser.h 100644
Wyświetl plik

@ -0,0 +1,23 @@
#ifndef _GCODE_PARSER_H
#define _GCODE_PARSER_H
#include "motor.h"
typedef struct {
uint8_t name;
uint32_t value;
uint8_t exponent;
uint8_t is_negative;
} GCODE_PARAM;
/// the command being processed
//extern GCODE_COMMAND next_target;
extern const uint32_t powers[]; // defined in msg.c
/// accept the next character and process it
uint8_t gcode_parse_char(uint8_t c);
void parser_init();
#endif /* _GCODE_PARSE_H */

58
kinematics.cpp 100644
Wyświetl plik

@ -0,0 +1,58 @@
#include "kinematics.h"
/** \file G-code axis system to stepper motor axis system conversion.
*/
#include <stdlib.h>
#include "maths.h"
void
carthesian_to_carthesian(const TARGET *startpoint, const TARGET *target,
axes_uint32_t delta_um, axes_int32_t steps) {
uint8_t i;
for (i = X; i < E; i++) {
delta_um[i] = (uint32_t)labs(target->axis[i] - startpoint->axis[i]);
steps[i] = um_to_steps(target->axis[i], i);
}
/* Replacing the above five lines with this costs about 200 bytes binary
size on AVR, but also takes about 120 clock cycles less during movement
preparation. The smaller version was kept for our Arduino Nano friends.
delta_um[X] = (uint32_t)labs(target->axis[X] - startpoint->axis[X]);
steps[X] = um_to_steps(target->axis[X], X);
delta_um[Y] = (uint32_t)labs(target->axis[Y] - startpoint->axis[Y]);
steps[Y] = um_to_steps(target->axis[Y], Y);
delta_um[Z] = (uint32_t)labs(target->axis[Z] - startpoint->axis[Z]);
steps[Z] = um_to_steps(target->axis[Z], Z);
*/
}
void
carthesian_to_corexy(const TARGET *startpoint, const TARGET *target,
axes_uint32_t delta_um, axes_int32_t steps) {
delta_um[X] = (uint32_t)labs((target->axis[X] - startpoint->axis[X]) +
(target->axis[Y] - startpoint->axis[Y]));
delta_um[Y] = (uint32_t)labs((target->axis[X] - startpoint->axis[X]) -
(target->axis[Y] - startpoint->axis[Y]));
delta_um[Z] = (uint32_t)labs(target->axis[Z] - startpoint->axis[Z]);
axes_um_to_steps_corexy(target->axis, steps);
}
void axes_um_to_steps_cartesian(const axes_int32_t um, axes_int32_t steps) {
uint8_t i;
for (i = X; i < E; i++) {
steps[i] = um_to_steps(um[i], i);
}
}
void axes_um_to_steps_corexy(const axes_int32_t um, axes_int32_t steps) {
steps[X] = um_to_steps(um[X] + um[Y], X);
steps[Y] = um_to_steps(um[X] - um[Y], Y);
steps[Z] = um_to_steps(um[Z], Z);
}

54
kinematics.h 100644
Wyświetl plik

@ -0,0 +1,54 @@
#ifndef _KINEMATICS_H
#define _KINEMATICS_H
#include "config.h"
#include <stdint.h>
#include "motor.h"
void carthesian_to_carthesian(const TARGET *startpoint, const TARGET *target,
axes_uint32_t delta_um, axes_int32_t steps);
void carthesian_to_corexy(const TARGET *startpoint, const TARGET *target,
axes_uint32_t delta_um, axes_int32_t steps);
static void code_axes_to_stepper_axes(const TARGET *, const TARGET *, axes_uint32_t,
axes_int32_t)
__attribute__ ((always_inline));
inline void code_axes_to_stepper_axes(const TARGET *startpoint, const TARGET *target,
axes_uint32_t delta_um,
axes_int32_t steps) {
#if defined KINEMATICS_STRAIGHT
carthesian_to_carthesian(startpoint, target, delta_um, steps);
#elif defined KINEMATICS_COREXY
carthesian_to_corexy(startpoint, target, delta_um, steps);
// #elif defined KINEMATICS_SCARA
// return carthesian_to_scara(startpoint, target, delta_um, steps);
#else
#error KINEMATICS not defined or unknown, edit your config.h.
#endif
}
void axes_um_to_steps_cartesian(const axes_int32_t um, axes_int32_t steps);
void axes_um_to_steps_corexy(const axes_int32_t um, axes_int32_t steps);
// void axes_um_to_steps_scara(const axes_int32_t um, axes_int32_t steps);
static void axes_um_to_steps(const axes_int32_t, axes_int32_t)
__attribute__ ((always_inline));
inline void axes_um_to_steps(const axes_int32_t um, axes_int32_t steps) {
#if defined KINEMATICS_STRAIGHT
axes_um_to_steps_cartesian(um, steps);
#elif defined KINEMATICS_COREXY
axes_um_to_steps_corexy(um, steps);
// #elif defined KINEMATICS_SCARA
// axes_um_to_steps_scara(um, steps);
#else
#error KINEMATICS not defined or unknown, edit your config.h.
#endif
}
#endif /* _KINEMATICS_H */

192
maths.cpp 100644
Wyświetl plik

@ -0,0 +1,192 @@
#include "maths.h"
/*!
Pre-calculated constant values for axis um <=> steps conversions.
These should be calculated at run-time once in dda_init() if the
STEPS_PER_M_* constants are ever replaced with run-time options.
*/
const axes_uint32_t PROGMEM axis_qn_P = {
(uint32_t)STEPS_PER_M_X / UM_PER_METER,
(uint32_t)STEPS_PER_M_Y / UM_PER_METER,
(uint32_t)STEPS_PER_M_Z / UM_PER_METER,
(uint32_t)STEPS_PER_M_E / UM_PER_METER
};
const axes_uint32_t PROGMEM axis_qr_P = {
(uint32_t)STEPS_PER_M_X % UM_PER_METER,
(uint32_t)STEPS_PER_M_Y % UM_PER_METER,
(uint32_t)STEPS_PER_M_Z % UM_PER_METER,
(uint32_t)STEPS_PER_M_E % UM_PER_METER
};
/*!
Integer multiply-divide algorithm. Returns the same as muldiv(multiplicand, multiplier, divisor), but also allowing to use precalculated quotients and remainders.
\param multiplicand
\param qn ( = multiplier / divisor )
\param rn ( = multiplier % divisor )
\param divisor
\return rounded result of multiplicand * multiplier / divisor
Calculate a * b / c, without overflowing and without using 64-bit integers.
Doing this the standard way, a * b could easily overflow, even if the correct
overall result fits into 32 bits. This algorithm avoids this intermediate
overflow and delivers valid results for all cases where each of the three
operators as well as the result fits into 32 bits.
Found on http://stackoverflow.com/questions/4144232/
how-to-calculate-a-times-b-divided-by-c-only-using-32-bit-integer-types-even-i
*/
const int32_t muldivQR(int32_t multiplicand, uint32_t qn, uint32_t rn,
uint32_t divisor) {
uint32_t quotient = 0;
uint32_t remainder = 0;
uint8_t negative_flag = 0;
if (multiplicand < 0) {
negative_flag = 1;
multiplicand = -multiplicand;
}
while(multiplicand) {
if (multiplicand & 1) {
quotient += qn;
remainder += rn;
if (remainder >= divisor) {
quotient++;
remainder -= divisor;
}
}
multiplicand >>= 1;
qn <<= 1;
rn <<= 1;
if (rn >= divisor) {
qn++;
rn -= divisor;
}
}
// rounding
if (remainder > divisor / 2)
quotient++;
// remainder is valid here, but not returned
return negative_flag ? -((int32_t)quotient) : (int32_t)quotient;
}
/*!
integer inverse square root algorithm
\param a find the inverse of the square root of this number
\return 0x1000 / sqrt(a) - 1 < returnvalue <= 0x1000 / sqrt(a)
This is a binary search but it uses only the minimum required bits for each step.
*/
// courtesy of http://www.flipcode.com/archives/Fast_Approximate_Distance_Functions.shtml
/*! linear approximation 2d distance formula
\param dx distance in X plane
\param dy distance in Y plane
\return 3-part linear approximation of \f$\sqrt{\Delta x^2 + \Delta y^2}\f$
see http://www.flipcode.com/archives/Fast_Approximate_Distance_Functions.shtml
*/
uint32_t approx_distance(uint32_t dx, uint32_t dy) {
uint32_t min, max, approx;
// If either axis is zero, return the other one.
if (dx == 0 || dy == 0) return dx + dy;
if ( dx < dy ) {
min = dx;
max = dy;
} else {
min = dy;
max = dx;
}
approx = ( max * 1007 ) + ( min * 441 );
if ( max < ( min << 4 ))
approx -= ( max * 40 );
// add 512 for proper rounding
return (( approx + 512 ) >> 10 );
}
// courtesy of http://www.oroboro.com/rafael/docserv.php/index/programming/article/distance
/*! linear approximation 3d distance formula
\param dx distance in X plane
\param dy distance in Y plane
\param dz distance in Z plane
\return 3-part linear approximation of \f$\sqrt{\Delta x^2 + \Delta y^2 + \Delta z^2}\f$
see http://www.oroboro.com/rafael/docserv.php/index/programming/article/distance
*/
uint32_t approx_distance_3(uint32_t dx, uint32_t dy, uint32_t dz) {
uint32_t min, med, max, approx;
if ( dx < dy ) {
min = dy;
med = dx;
} else {
min = dx;
med = dy;
}
if ( dz < min ) {
max = med;
med = min;
min = dz;
} else if ( dz < med ) {
max = med;
med = dz;
} else {
max = dz;
}
approx = ( max * 860 ) + ( med * 851 ) + ( min * 520 );
if ( max < ( med << 1 )) approx -= ( max * 294 );
if ( max < ( min << 2 )) approx -= ( max * 113 );
if ( med < ( min << 2 )) approx -= ( med * 40 );
// add 512 for proper rounding
return (( approx + 512 ) >> 10 );
}
uint16_t int_inv_sqrt(uint16_t a) {
/// 16bits inverse (much faster than doing a full 32bits inverse)
/// the 0xFFFFU instead of 0x10000UL hack allows using 16bits and 8bits
/// variable for the first 8 steps without overflowing and it seems to
/// give better results for the ramping equation too :)
uint8_t z = 0, i;
uint16_t x, j;
uint32_t q = ((uint32_t)(0xFFFFU / a)) << 8;
for (i = 0x80; i; i >>= 1) {
uint16_t y;
z |= i;
y = (uint16_t)z * z;
if (y > (q >> 8))
z ^= i;
}
x = z << 4;
for (j = 0x8; j; j >>= 1) {
uint32_t y;
x |= j;
y = (uint32_t)x * x;
if (y > q)
x ^= j;
}
return x;
}
uint32_t acc_ramp_len(uint32_t feedrate, uint32_t steps_per_m) {
return (feedrate * feedrate) /
(((uint32_t)7200000UL * ACCELERATION) / steps_per_m);
}

81
maths.h 100644
Wyświetl plik

@ -0,0 +1,81 @@
#ifndef _MATHS_H
#define _MATHS_H
#include "motor.h"
/*! Preprocessor square root.
(uint32_t)(SQRT(i) + .5)
equals
(uint32_t)(sqrt(i) + .5)
These two provide identical results for all tested numbers across the
uint32 range. Casting to other sizes is also possible.
Can principally be used for calculations at runtime, too, but its compiled
size is prohibitively large (more than 20kB per instance).
Initial version found on pl.comp.lang.c, posted by Jean-Louis PATANE.
*/
#define SQR00(x) (((x) > 65535) ? (double)65535 : (double)(x) / 2)
#define SQR01(x) ((SQR00(x) + ((x) / SQR00(x))) / 2)
#define SQR02(x) ((SQR01(x) + ((x) / SQR01(x))) / 2)
#define SQR03(x) ((SQR02(x) + ((x) / SQR02(x))) / 2)
#define SQR04(x) ((SQR03(x) + ((x) / SQR03(x))) / 2)
#define SQR05(x) ((SQR04(x) + ((x) / SQR04(x))) / 2)
#define SQR06(x) ((SQR05(x) + ((x) / SQR05(x))) / 2)
#define SQR07(x) ((SQR06(x) + ((x) / SQR06(x))) / 2)
#define SQR08(x) ((SQR07(x) + ((x) / SQR07(x))) / 2)
#define SQR09(x) ((SQR08(x) + ((x) / SQR08(x))) / 2)
#define SQR10(x) ((SQR09(x) + ((x) / SQR09(x))) / 2)
#define SQR11(x) ((SQR10(x) + ((x) / SQR10(x))) / 2)
#define SQR12(x) ((SQR11(x) + ((x) / SQR11(x))) / 2)
// We use 9 iterations, note how SQR10() and up get ignored. You can add more
// iterations here, but beware, the length of the preprocessed term
// explodes, leading to several seconds compile time above about SQR10().
#define SQRT(x) ((SQR09(x) + ((x) / SQR09(x))) / 2)
/*!
Micrometer distance <=> motor step distance conversions.
*/
#define UM_PER_METER (1000000UL)
extern const axes_uint32_t PROGMEM axis_qn_P;
extern const axes_uint32_t PROGMEM axis_qr_P;
// return rounded result of multiplicand * multiplier / divisor
// this version is with quotient and remainder precalculated elsewhere
const int32_t muldivQR(int32_t multiplicand, uint32_t qn, uint32_t rn,
uint32_t divisor);
// return rounded result of multiplicand * multiplier / divisor
static int32_t muldiv(int32_t, uint32_t, uint32_t) __attribute__ ((always_inline));
inline int32_t muldiv(int32_t multiplicand, uint32_t multiplier,
uint32_t divisor) {
return muldivQR(multiplicand, multiplier / divisor,
multiplier % divisor, divisor);
}
static int32_t um_to_steps(int32_t, uint8_t ) __attribute__ ((always_inline));
inline int32_t um_to_steps(int32_t distance, uint8_t a) {
return muldivQR(distance, pgm_read_dword(&axis_qn_P[a]),
pgm_read_dword(&axis_qr_P[a]), UM_PER_METER);
}
// approximate 2D distance
uint32_t approx_distance(uint32_t dx, uint32_t dy);
// approximate 3D distance
uint32_t approx_distance_3(uint32_t dx, uint32_t dy, uint32_t dz);
// integer inverse square root, 12bits precision
uint16_t int_inv_sqrt(uint16_t a);
// Calculates acceleration ramp length in steps.
uint32_t acc_ramp_len(uint32_t feedrate, uint32_t steps_per_m);
#endif /* _MATHS_H */

338
motion_planner.cpp 100644
Wyświetl plik

@ -0,0 +1,338 @@
/** \file
\brief Digital differential analyser - this is where we figure out which steppers need to move, and when they need to move
*/
#include "motor.h"
#ifdef LOOKAHEAD
#include <string.h>
#include <stdlib.h>
#include <stddef.h>
#include <math.h>
#include "maths.h"
#include "queue.h"
#include "serial.h"
#include "pinio.h"
// For X axis only, should become obsolete:
#define ACCELERATE_RAMP_LEN(speed) (((speed)*(speed)) / (uint32_t)((7200000.0f * ACCELERATION) / (float)STEPS_PER_M_X))
#ifdef DEBUG
// Total number of moves joined together.
uint32_t lookahead_joined = 0;
// Moves that did not compute in time to be actually joined.
uint32_t lookahead_timeout = 0;
#endif
/// \var maximum_jerk_P
/// \brief maximum allowed feedrate jerk on each axis
static const axes_uint32_t PROGMEM maximum_jerk_P = {
MAX_JERK_X,
MAX_JERK_Y,
MAX_JERK_Z,
MAX_JERK_E
};
/**
* \brief Find maximum corner speed between two moves.
* \details Find out how fast we can move around around a corner without
* exceeding the expected jerk. Worst case this speed is zero, which means a
* full stop between both moves. Best case it's the lower of the maximum speeds.
*
* This function is expected to be called from within dda_create().
*
* \param [in] prev is the DDA structure of the move previous to the current one.
* \param [in] current is the DDA structure of the move currently created.
*
* \return dda->crossF
*/
void dda_find_crossing_speed(DDA *prev, DDA *current) {
uint32_t F, dv, speed_factor, max_speed_factor;
axes_int32_t prevF, currF;
uint8_t i;
// Bail out if there's nothing to join (e.g. G1 F1500).
if ( ! prev || prev->nullmove)
return;
// We always look at the smaller of both combined speeds,
// else we'd interpret intended speed changes as jerk.
F = prev->endpoint.F;
if (current->endpoint.F < F)
F = current->endpoint.F;
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
sersendf_P(PSTR("Distance: %lu, then %lu\n"),
prev->distance, current->distance);
// Find individual axis speeds.
// TODO: this is eight expensive muldiv()s. It should be possible to store
// currF as prevF for the next calculation somehow, to save 4 of
// these 8 muldiv()s. This would also allow to get rid of
// dda->delta_um[] and using delta_um[] from dda_create() instead.
// Caveat: bail out condition above and some other non-continuous
// situations might need some extra code for handling.
for (i = X; i < AXIS_COUNT; i++) {
prevF[i] = muldiv(prev->delta_um[i], F, prev->distance);
currF[i] = muldiv(current->delta_um[i], F, current->distance);
}
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
sersendf_P(PSTR("prevF: %ld %ld %ld %ld\ncurrF: %ld %ld %ld %ld\n"),
prevF[X], prevF[Y], prevF[Z], prevF[E],
currF[X], currF[Y], currF[Z], currF[E]);
/**
* What we want is (for each axis):
*
* delta velocity = dv = |v1 - v2| < max_jerk
*
* In case this isn't satisfied, we can slow down by some factor x until
* the equitation is satisfied:
*
* x * |v1 - v2| < max_jerk
*
* Now computation is pretty straightforward:
*
* max_jerk
* x = -----------
* |v1 - v2|
*
* if x > 1: continue full speed
* if x < 1: v = v_max * x
*
* See also: https://github.com/Traumflug/Teacup_Firmware/issues/45
*/
max_speed_factor = (uint32_t)2 << 8;
for (i = X; i < AXIS_COUNT; i++) {
dv = currF[i] > prevF[i] ? currF[i] - prevF[i] : prevF[i] - currF[i];
if (dv) {
speed_factor = ((uint32_t)pgm_read_dword(&maximum_jerk_P[i]) << 8) / dv;
if (speed_factor < max_speed_factor)
max_speed_factor = speed_factor;
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
sersendf_P(PSTR("%c: dv %lu of %lu factor %lu of %lu\n"),
'X' + i, dv, (uint32_t)pgm_read_dword(&maximum_jerk_P[i]),
speed_factor, (uint32_t)1 << 8);
}
}
if (max_speed_factor >= ((uint32_t)1 << 8))
current->crossF = F;
else
current->crossF = (F * max_speed_factor) >> 8;
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
sersendf_P(PSTR("Cross speed reduction from %lu to %lu\n"),
F, current->crossF);
return;
}
/**
* \brief Join 2 moves by removing the full stop between them, where possible.
* \details To join the moves, the deceleration ramp of the previous move and
* the acceleration ramp of the current move are shortened, resulting in a
* non-zero speed at that point. The target speed at the corner is already to
* be found in dda->crossF. See dda_find_corner_speed().
*
* Ideally, both ramps can be reduced to actually have Fcorner at the corner,
* but the surrounding movements might no be long enough to achieve this speed.
* Analysing both moves to find the best result is done here.
*
* TODO: to achieve better results with short moves (move distance < both ramps),
* this function should be able to enhance the corner speed on repeated
* calls when reverse-stepping through the movement queue.
*
* \param [in] prev is the DDA structure of the move previous to the current one.
* \param [in] current is the DDA structure of the move currently created.
*
* Premise: the 'current' move is not dispatched in the queue: it should remain
* constant while this function is running.
*
* Note: the planner always makes sure the movement can be stopped within the
* last move (= 'current'); as a result a lot of small moves will still limit the speed.
*/
void dda_join_moves(DDA *prev, DDA *current) {
// Calculating the look-ahead settings can take a while; before modifying
// the previous move, we need to locally store any values and write them
// when we are done (and the previous move is not already active).
uint32_t prev_F, prev_F_in_steps, prev_F_start_in_steps, prev_F_end_in_steps;
uint32_t prev_rampup, prev_rampdown, prev_total_steps;
uint32_t crossF, crossF_in_steps;
uint8_t prev_id;
// Similarly, we only want to modify the current move if we have the results of the calculations;
// until then, we do not want to touch the current move settings.
// Note: we assume 'current' will not be dispatched while this function runs, so we do not to
// back up the move settings: they will remain constant.
uint32_t this_F, this_F_in_steps, this_F_start_in_steps, this_rampup, this_rampdown, this_total_steps;
uint8_t this_id;
static uint32_t la_cnt = 0; // Counter: how many moves did we join?
#ifdef LOOKAHEAD_DEBUG
static uint32_t moveno = 0; // Debug counter to number the moves - helps while debugging
moveno++;
#endif
// Bail out if there's nothing to join (e.g. G1 F1500).
if ( ! prev || prev->nullmove || current->crossF == 0)
return;
// Show the proposed crossing speed - this might get adjusted below.
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
sersendf_P(PSTR("Initial crossing speed: %lu\n"), current->crossF);
// Make sure we have 2 moves and the previous move is not already active
if (prev->live == 0) {
// Perform an atomic copy to preserve volatile parameters during the calculations
ATOMIC_START
prev_id = prev->id;
prev_F = prev->endpoint.F;
prev_F_start_in_steps = prev->start_steps;
prev_F_end_in_steps = prev->end_steps;
prev_rampup = prev->rampup_steps;
prev_rampdown = prev->rampdown_steps;
prev_total_steps = prev->total_steps;
crossF = current->crossF;
this_id = current->id;
this_F = current->endpoint.F;
this_total_steps = current->total_steps;
ATOMIC_END
// Here we have to distinguish between feedrate along the movement
// direction and feedrate of the fast axis. They can differ by a factor
// of 2.
// Along direction: F, crossF.
// Along fast axis already: start_steps, end_steps.
//
// All calculations here are done along the fast axis, so recalculate
// F and crossF to match this, too.
prev_F = muldiv(prev->fast_um, prev_F, prev->distance);
this_F = muldiv(current->fast_um, current->endpoint.F, current->distance);
crossF = muldiv(current->fast_um, crossF, current->distance);
// TODO: calculate the steps from the fastest axis and not from X.
prev_F_in_steps = ACCELERATE_RAMP_LEN(prev_F);
this_F_in_steps = ACCELERATE_RAMP_LEN(this_F);
crossF_in_steps = ACCELERATE_RAMP_LEN(crossF);
// Show the proposed crossing speed - this might get adjusted below
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
sersendf_P(PSTR("Initial crossing speed: %lu\n"), crossF_in_steps);
// Compute the maximum speed we can reach for crossing.
crossF_in_steps = MIN(crossF_in_steps, this_total_steps);
crossF_in_steps = MIN(crossF_in_steps, prev_total_steps + prev_F_start_in_steps);
if (crossF_in_steps == 0)
return;
// Build ramps for previous move.
if (crossF_in_steps == prev_F_in_steps) {
prev_rampup = prev_F_in_steps - prev_F_start_in_steps;
prev_rampdown = 0;
}
else if (crossF_in_steps < prev_F_start_in_steps) {
uint32_t extra, limit;
prev_rampup = 0;
prev_rampdown = prev_F_start_in_steps - crossF_in_steps;
extra = (prev_total_steps - prev_rampdown) >> 1;
limit = prev_F_in_steps - prev_F_start_in_steps;
extra = MIN(extra, limit);
prev_rampup += extra;
prev_rampdown += extra;
}
else {
uint32_t extra, limit;
prev_rampup = crossF_in_steps - prev_F_start_in_steps;
prev_rampdown = 0;
extra = (prev_total_steps - prev_rampup) >> 1;
limit = prev_F_in_steps - crossF_in_steps;
extra = MIN(extra, limit);
prev_rampup += extra;
prev_rampdown += extra;
}
prev_rampdown = prev_total_steps - prev_rampdown;
prev_F_end_in_steps = crossF_in_steps;
// Build ramps for current move.
if (crossF_in_steps == this_F_in_steps) {
this_rampup = 0;
this_rampdown = crossF_in_steps;
}
else {
this_rampup = 0;
this_rampdown = crossF_in_steps;
uint32_t extra = (this_total_steps - this_rampdown) >> 1;
uint32_t limit = this_F_in_steps - crossF_in_steps;
extra = MIN(extra, limit);
this_rampup += extra;
this_rampdown += extra;
}
this_rampdown = this_total_steps - this_rampdown;
this_F_start_in_steps = crossF_in_steps;
if (DEBUG_DDA && (debug_flags & DEBUG_DDA)) {
sersendf_P(PSTR("prev_F_start: %lu\n"), prev_F_start_in_steps);
sersendf_P(PSTR("prev_F: %lu\n"), prev_F_in_steps);
sersendf_P(PSTR("prev_rampup: %lu\n"), prev_rampup);
sersendf_P(PSTR("prev_rampdown: %lu\n"),
prev_total_steps - prev_rampdown);
sersendf_P(PSTR("crossF: %lu\n"), crossF_in_steps);
sersendf_P(PSTR("this_rampup: %lu\n"), this_rampup);
sersendf_P(PSTR("this_rampdown: %lu\n"),
this_total_steps - this_rampdown);
sersendf_P(PSTR("this_F: %lu\n"), this_F_in_steps);
}
#ifdef DEBUG
uint8_t timeout = 0;
#endif
ATOMIC_START
// Evaluation: determine how we did...
#ifdef DEBUG
lookahead_joined++;
#endif
// Determine if we are fast enough - if not, just leave the moves
// Note: to test if the previous move was already executed and replaced by a new
// move, we compare the DDA id.
if(prev->live == 0 && prev->id == prev_id && current->live == 0 && current->id == this_id) {
prev->end_steps = prev_F_end_in_steps;
prev->rampup_steps = prev_rampup;
prev->rampdown_steps = prev_rampdown;
current->rampup_steps = this_rampup;
current->rampdown_steps = this_rampdown;
current->end_steps = 0;
current->start_steps = this_F_start_in_steps;
la_cnt++;
}
#ifdef DEBUG
else
timeout = 1;
#endif
ATOMIC_END
// If we were not fast enough, any feedback will happen outside the atomic block:
#ifdef DEBUG
if (timeout) {
sersendf_P(PSTR("// Notice: look ahead not fast enough\n"));
lookahead_timeout++;
}
#endif
}
}
#endif /* LOOKAHEAD */

592
motor.cpp 100644
Wyświetl plik

@ -0,0 +1,592 @@
#include "motor.h"
/** \file
\brief Digital differential analyser - this is where we figure out which steppers need to move, and when they need to move
*/
#include <string.h>
#include <stdlib.h>
#include <math.h>
#include "maths.h"
#include "kinematics.h"
#include "timer.h"
#include "serial.h"
#include "queue.h"
#include "gcode_parser.h"
#include "pinio.h"
/*
position tracking
*/
/// \var startpoint
/// \brief target position of last move in queue
TARGET BSS startpoint;
/// \var startpoint_steps
/// \brief target position of last move in queue, expressed in steps
TARGET BSS startpoint_steps;
/// \var steps_per_m_P
/// \brief motor steps required to advance one meter on each axis
static const axes_uint32_t PROGMEM steps_per_m_P = {
STEPS_PER_M_X,
STEPS_PER_M_Y,
STEPS_PER_M_Z,
STEPS_PER_M_E
};
/// \var maximum_feedrate_P
/// \brief maximum allowed feedrate on each axis
static const axes_uint32_t PROGMEM maximum_feedrate_P = {
MAXIMUM_FEEDRATE_X,
MAXIMUM_FEEDRATE_Y,
MAXIMUM_FEEDRATE_Z,
MAXIMUM_FEEDRATE_E
};
/// \var current_position
/// \brief actual position of extruder head
/// \todo make current_position = real_position (from endstops) + offset from G28 and friends
TARGET BSS current_position;
/// \var move_state
/// \brief numbers for tracking the current state of movement
MOVE_STATE BSS move_state;
/// \var c0_P
/// \brief Initialization constant for the ramping algorithm. Timer cycles for
/// first step interval.
static const axes_uint32_t PROGMEM c0_P = {
(uint32_t)((double)F_CPU / SQRT((double)STEPS_PER_M_X * ACCELERATION / 2000.)),
(uint32_t)((double)F_CPU / SQRT((double)STEPS_PER_M_Y * ACCELERATION / 2000.)),
(uint32_t)((double)F_CPU / SQRT((double)STEPS_PER_M_Z * ACCELERATION / 2000.)),
(uint32_t)((double)F_CPU / SQRT((double)STEPS_PER_M_E * ACCELERATION / 2000.))
};
/*! Inititalise DDA movement structures
*/
void dda_init(void) {
// set up default feedrate
if (startpoint.F == 0)
startpoint.F = SEARCH_FEEDRATE_Z;
if (startpoint.e_multiplier == 0)
startpoint.e_multiplier = 256;
if (startpoint.f_multiplier == 0)
startpoint.f_multiplier = 256;
}
/*! Set the direction of the 'n' axis
*/
static void set_direction(DDA *dda, uint8_t n, int32_t delta) {
uint8_t dir = (delta >= 0) ? 1 : 0;
if (n == X)
dda->x_direction = dir;
else if (n == Y)
dda->y_direction = dir;
else if (n == Z)
dda->z_direction = dir;
else if (n == E)
dda->e_direction = dir;
}
/*! Find the direction of the 'n' axis
*/
static int8_t get_direction(DDA *dda, uint8_t n) {
if ((n == X && dda->x_direction) ||
(n == Y && dda->y_direction) ||
(n == Z && dda->z_direction) ||
(n == E && dda->e_direction))
return 1;
else
return -1;
}
void dda_create(DDA *dda, const TARGET *target) {
axes_uint32_t delta_um;
axes_int32_t steps;
uint32_t distance, c_limit, c_limit_calc;
uint8_t i;
#ifdef LOOKAHEAD
// Number the moves to identify them; allowed to overflow.
static uint8_t idcnt = 0;
static DDA* prev_dda = NULL;
if ((prev_dda && prev_dda->done) || dda->waitfor_temp)
prev_dda = NULL;
#endif
if (dda->waitfor_temp)
return;
// We end at the passed target.
memcpy(&(dda->endpoint), target, sizeof(TARGET));
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
sersendf_P(PSTR("\nCreate: X %lq Y %lq Z %lq F %lu\n"),
dda->endpoint.axis[X], dda->endpoint.axis[Y],
dda->endpoint.axis[Z], dda->endpoint.F);
// Apply feedrate multiplier.
if (dda->endpoint.f_multiplier != 256) {
dda->endpoint.F *= dda->endpoint.f_multiplier;
dda->endpoint.F += 128;
dda->endpoint.F /= 256;
}
#ifdef LOOKAHEAD
// Set the start and stop speeds to zero for now = full stops between
// moves. Also fallback if lookahead calculations fail to finish in time.
dda->crossF = 0;
dda->start_steps = 0;
dda->end_steps = 0;
// Give this move an identifier.
dda->id = idcnt++;
#endif
// Handle bot axes. They're subject to kinematics considerations.
code_axes_to_stepper_axes(&startpoint, target, delta_um, steps);
for (i = X; i < E; i++) {
int32_t delta_steps;
delta_steps = steps[i] - startpoint_steps.axis[i];
dda->delta[i] = (uint32_t)labs(delta_steps);
startpoint_steps.axis[i] = steps[i];
set_direction(dda, i, delta_steps);
#ifdef LOOKAHEAD
// Also displacements in micrometers, but for the lookahead alogrithms.
// TODO: this is redundant. delta_um[] and dda->delta_um[] differ by
// just signedness and storage location. Ideally, dda is used
// as storage place only if neccessary (LOOKAHEAD turned on?)
// because this space is multiplied by the movement queue size.
//
// Update 2014/10: it was tried to use delta_um[]'s sign to set stepper
// direction in dda_start() to allow getting rid of
// some of this redundancy, but this increases dda_start()
// by at least 20 clock cycles. Not good for performance.
// Tried code can be found in the archive folder.
dda->delta_um[i] = (delta_steps >= 0) ?
(int32_t)delta_um[i] : -(int32_t)delta_um[i];
#endif
}
// Handle extruder axes. They act independently from the bots kinematics
// type, but are subject to other special handling.
steps[E] = um_to_steps(target->axis[E], E);
// Apply extrusion multiplier.
if (target->e_multiplier != 256) {
steps[E] *= target->e_multiplier;
steps[E] += 128;
steps[E] /= 256;
}
if ( ! target->e_relative) {
int32_t delta_steps;
delta_um[E] = (uint32_t)labs(target->axis[E] - startpoint.axis[E]);
delta_steps = steps[E] - startpoint_steps.axis[E];
dda->delta[E] = (uint32_t)labs(delta_steps);
startpoint_steps.axis[E] = steps[E];
set_direction(dda, E, delta_steps);
#ifdef LOOKAHEAD
// Also displacements in micrometers, but for the lookahead alogrithms.
// TODO: this is redundant. delta_um[] and dda->delta_um[] differ by
// just signedness and storage location. Ideally, dda is used
// as storage place only if neccessary (LOOKAHEAD turned on?)
// because this space is multiplied by the movement queue size.
dda->delta_um[E] = (delta_steps >= 0) ?
(int32_t)delta_um[E] : -(int32_t)delta_um[E];
#endif
}
else {
// When we get more extruder axes:
// for (i = E; i < AXIS_COUNT; i++) { ...
delta_um[E] = (uint32_t)labs(target->axis[E]);
dda->delta[E] = (uint32_t)labs(steps[E]);
#ifdef LOOKAHEAD
dda->delta_um[E] = target->axis[E];
#endif
dda->e_direction = (target->axis[E] >= 0)?1:0;
}
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
sersendf_P(PSTR("[%ld,%ld,%ld,%ld]"),
target->axis[X] - startpoint.axis[X], target->axis[Y] - startpoint.axis[Y],
target->axis[Z] - startpoint.axis[Z], target->axis[E] - startpoint.axis[E]);
// Admittedly, this looks like it's overcomplicated. Why store three 32-bit
// values if storing an axis number would be fully sufficient? Well, I'm not
// sure, but my feeling says that when we achieve true circles and Beziers,
// we'll have total_steps which matches neither of X, Y, Z or E. Accordingly,
// keep it for now. --Traumflug
for (i = X; i < AXIS_COUNT; i++) {
if (i == X || dda->delta[i] > dda->total_steps) {
dda->fast_axis = i;
dda->total_steps = dda->delta[i];
dda->fast_um = delta_um[i];
dda->fast_spm = pgm_read_dword(&steps_per_m_P[i]);
}
}
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
sersendf_P(PSTR(" [ts:%lu"), dda->total_steps);
if (dda->total_steps == 0) {
dda->nullmove = 1;
}
else {
// get steppers ready to go
//power_on();
stepper_enable();
x_enable();
y_enable();
e_enable();
// since it's unusual to combine X, Y and Z changes in a single move on reprap, check if we can use simpler approximations before trying the full 3d approximation.
if (delta_um[Z] == 0)
distance = approx_distance(delta_um[X], delta_um[Y]);
else if (delta_um[X] == 0 && delta_um[Y] == 0)
distance = delta_um[Z];
else
distance = approx_distance_3(delta_um[X], delta_um[Y], delta_um[Z]);
if (distance < 2)
distance = delta_um[E];
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
sersendf_P(PSTR(",ds:%lu"), distance);
// pre-calculate move speed in millimeter microseconds per step minute for less math in interrupt context
// mm (distance) * 60000000 us/min / step (total_steps) = mm.us per step.min
// note: um (distance) * 60000 == mm * 60000000
// so in the interrupt we must simply calculate
// mm.us per step.min / mm per min (F) = us per step
// break this calculation up a bit and lose some precision because 300,000um * 60000 is too big for a uint32
// calculate this with a uint64 if you need the precision, but it'll take longer so routines with lots of short moves may suffer
// 2^32/6000 is about 715mm which should be plenty
// changed * 10 to * (F_CPU / 100000) so we can work in cpu_ticks rather than microseconds.
// timer.c timer_set() routine altered for same reason
// changed distance * 6000 .. * F_CPU / 100000 to
// distance * 2400 .. * F_CPU / 40000 so we can move a distance of up to 1800mm without overflowing
uint32_t move_duration = ((distance * 2400) / dda->total_steps) * (F_CPU / 40000);
// similarly, find out how fast we can run our axes.
// do this for each axis individually, as the combined speed of two or more axes can be higher than the capabilities of a single one.
// TODO: instead of calculating c_min directly, it's probably more simple
// to calculate (maximum) move_duration for each axis, like done for
// ACCELERATION_TEMPORAL above. This should make re-calculating the
// allowed F easier.
c_limit = 0;
for (i = X; i < AXIS_COUNT; i++) {
c_limit_calc = (delta_um[i] * 2400L) /
dda->total_steps * (F_CPU / 40000) /
pgm_read_dword(&maximum_feedrate_P[i]);
if (c_limit_calc > c_limit)
c_limit = c_limit_calc;
}
dda->c_min = move_duration / dda->endpoint.F;
if (dda->c_min < c_limit) {
dda->c_min = c_limit;
dda->endpoint.F = move_duration / dda->c_min;
}
// Lookahead can deal with 16 bits ( = 1092 mm/s), only.
if (dda->endpoint.F > 65535)
dda->endpoint.F = 65535;
// Acceleration ramps are based on the fast axis, not the combined speed.
dda->rampup_steps =
acc_ramp_len(muldiv(dda->fast_um, dda->endpoint.F, distance),
dda->fast_spm);
if (dda->rampup_steps > dda->total_steps / 2)
dda->rampup_steps = dda->total_steps / 2;
dda->rampdown_steps = dda->total_steps - dda->rampup_steps;
#ifdef LOOKAHEAD
dda->distance = distance;
dda_find_crossing_speed(prev_dda, dda);
// TODO: this should become a reverse-stepping through the existing
// movement queue to allow higher speeds for short moves.
// dda_find_crossing_speed() is required only once.
dda_join_moves(prev_dda, dda);
dda->n = dda->start_steps;
if (dda->n == 0)
dda->c = pgm_read_dword(&c0_P[dda->fast_axis]);
else
dda->c = (pgm_read_dword(&c0_P[dda->fast_axis]) *
int_inv_sqrt(dda->n)) >> 13;
if (dda->c < dda->c_min)
dda->c = dda->c_min;
#else
dda->n = 0;
dda->c = pgm_read_dword(&c0_P[dda->fast_axis]);
#endif
} /* ! dda->total_steps == 0 */
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
serial_writestr_P(PSTR("] }\n"));
// next dda starts where we finish
memcpy(&startpoint, &dda->endpoint, sizeof(TARGET));
#ifdef LOOKAHEAD
prev_dda = dda;
#endif
}
void dda_start(DDA *dda) {
// called from interrupt context: keep it simple!
if (DEBUG_DDA && (debug_flags & DEBUG_DDA))
sersendf_P(PSTR("Start: X %lq Y %lq Z %lq F %lu\n"),
dda->endpoint.axis[X], dda->endpoint.axis[Y],
dda->endpoint.axis[Z], dda->endpoint.F);
if ( ! dda->nullmove) {
// get ready to go
//psu_timeout = 0;
if (dda->endstop_check)
endstops_on();
// set direction outputs
x_direction(dda->x_direction);
y_direction(dda->y_direction);
z_direction(dda->z_direction);
e_direction(dda->e_direction);
// initialise state variable
move_state.counter[X] = move_state.counter[Y] = move_state.counter[Z] = \
move_state.counter[E] = -(dda->total_steps >> 1);
memcpy(&move_state.steps[X], &dda->delta[X], sizeof(uint32_t) * 4);
move_state.endstop_stop = 0;
move_state.step_no = 0;
// ensure this dda starts
dda->live = 1;
// set timeout for first step
timer_set(dda->c, 0);
}
// else just a speed change, keep dda->live = 0
current_position.F = dda->endpoint.F;
}
void dda_step(DDA *dda) {
if (move_state.steps[X]) {
move_state.counter[X] -= dda->delta[X];
if (move_state.counter[X] < 0) {
x_step();
move_state.steps[X]--;
move_state.counter[X] += dda->total_steps;
}
}
if (move_state.steps[Y]) {
move_state.counter[Y] -= dda->delta[Y];
if (move_state.counter[Y] < 0) {
y_step();
move_state.steps[Y]--;
move_state.counter[Y] += dda->total_steps;
}
}
move_state.step_no++;
// If there are no steps left or an endstop stop happened, we have finished.
//
// TODO: with ACCELERATION_TEMPORAL this duplicates some code. See where
// dda->live is zero'd, about 10 lines above.
if ((move_state.steps[X] == 0 && move_state.steps[Y] == 0 &&
move_state.steps[Z] == 0 && move_state.steps[E] == 0)
|| (move_state.endstop_stop && dda->n <= 0)) {
dda->live = 0;
dda->done = 1;
#ifdef LOOKAHEAD
// If look-ahead was using this move, it could have missed our activation:
// make sure the ids do not match.
dda->id--;
#endif
// No need to restart timer here.
// After having finished, dda_start() will do it.
}
else {
//psu_timeout = 0;
timer_set(dda->c, 0);
}
// turn off step outputs, hopefully they've been on long enough by now to register with the drivers
// if not, too bad. or insert a (very!) small delay here, or fire up a spare timer or something.
// we also hope that we don't step before the drivers register the low- limit maximum speed if you think this is a problem.
unstep();
}
void dda_clock() {
DDA *dda;
static DDA *last_dda = NULL;
uint8_t endstop_trigger = 0;
uint32_t move_step_no, move_c;
int32_t move_n;
uint8_t recalc_speed;
uint8_t current_id ;
dda = queue_current_movement();
if (dda != last_dda) {
move_state.debounce_count_x =
move_state.debounce_count_z =
move_state.debounce_count_y = 0;
last_dda = dda;
}
if (dda == NULL)
return;
// Caution: we mangle step counters here without locking interrupts. This
// means, we trust dda isn't changed behind our back, which could
// in principle (but rarely) happen if endstops are checked not as
// endstop search, but as part of normal operations.
if (dda->endstop_check && ! move_state.endstop_stop) {
// If an endstop is definitely triggered, stop the movement.
if (endstop_trigger) {
// For always smooth operations, don't halt apruptly,
// but start deceleration here.
ATOMIC_START
move_state.endstop_stop = 1;
if (move_state.step_no < dda->rampup_steps) // still accelerating
dda->total_steps = move_state.step_no * 2;
else
// A "-=" would overflow earlier.
dda->total_steps = dda->total_steps - dda->rampdown_steps +
move_state.step_no;
dda->rampdown_steps = move_state.step_no;
ATOMIC_END
// Not atomic, because not used in dda_step().
dda->rampup_steps = 0; // in case we're still accelerating
endstops_off();
}
} /* ! move_state.endstop_stop */
// For maths about stepper speed profiles, see
// http://www.embedded.com/design/mcus-processors-and-socs/4006438/Generate-stepper-motor-speed-profiles-in-real-time
// and http://www.atmel.com/images/doc8017.pdf (Atmel app note AVR446)
ATOMIC_START
current_id = dda->id;
move_step_no = move_state.step_no;
// All other variables are read-only or unused in dda_step(),
// so no need for atomic operations.
ATOMIC_END
recalc_speed = 0;
if (move_step_no < dda->rampup_steps) {
#ifdef LOOKAHEAD
move_n = dda->start_steps + move_step_no;
#else
move_n = move_step_no;
#endif
recalc_speed = 1;
}
else if (move_step_no >= dda->rampdown_steps) {
#ifdef LOOKAHEAD
move_n = dda->total_steps - move_step_no + dda->end_steps;
#else
move_n = dda->total_steps - move_step_no;
#endif
recalc_speed = 1;
}
if (recalc_speed) {
if (move_n == 0)
move_c = pgm_read_dword(&c0_P[dda->fast_axis]);
else
// Explicit formula: c0 * (sqrt(n + 1) - sqrt(n)),
// approximation here: c0 * (1 / (2 * sqrt(n))).
// This >> 13 looks odd, but is verified with the explicit formula.
move_c = (pgm_read_dword(&c0_P[dda->fast_axis]) *
int_inv_sqrt(move_n)) >> 13;
// TODO: most likely this whole check is obsolete. It was left as a
// safety margin, only. Rampup steps calculation should be accurate
// now and give the requested target speed within a few percent.
if (move_c < dda->c_min) {
// We hit max speed not always exactly.
move_c = dda->c_min;
}
// Write results.
ATOMIC_START
/**
Apply new n & c values only if dda didn't change underneath us. It
is possible for dda to be modified since fetching values in the
ATOMIC above, e.g. when a new dda becomes live.
In case such a change happened, values in the new dda are more
recent than our calculation here, anyways.
*/
if (current_id == dda->id) {
dda->c = move_c;
dda->n = move_n;
}
ATOMIC_END
}
}
/// update global current_position struct
void update_current_position() {
DDA *dda = &movebuffer[mb_tail];
uint8_t i;
// Use smaller values to adjust to avoid overflow in later calculations,
// (STEPS_PER_M_X / 1000) is a bit inaccurate for low STEPS_PER_M numbers.
static const axes_uint32_t PROGMEM steps_per_mm_P = {
((STEPS_PER_M_X + 500) / 1000),
((STEPS_PER_M_Y + 500) / 1000),
((STEPS_PER_M_Z + 500) / 1000),
((STEPS_PER_M_E + 500) / 1000)
};
if (queue_empty()) {
for (i = X; i < AXIS_COUNT; i++) {
current_position.axis[i] = startpoint.axis[i];
}
}
else if (dda->live) {
for (i = X; i < AXIS_COUNT; i++) {
current_position.axis[i] = dda->endpoint.axis[i] -
(int32_t)get_direction(dda, i) *
// Should be: move_state.steps[i] * 1000000 / steps_per_m_P[i])
// but steps[i] can be like 1000000 already, so we'd overflow.
// Unfortunately, using muldiv() overwhelms the compiler.
// Also keep the parens around this term, else results go wrong.
((move_state.steps[i] * 1000) / pgm_read_dword(&steps_per_mm_P[i]));
}
if (dda->endpoint.e_relative)
current_position.axis[E] =
(move_state.steps[E] * 1000) / pgm_read_dword(&steps_per_mm_P[E]);
// current_position.F is updated in dda_start()
}
}

210
motor.h 100644
Wyświetl plik

@ -0,0 +1,210 @@
#ifndef _DDA_H
#define _DDA_H
#include <stdint.h>
#include "config.h"
// Enum to denote an axis
enum axis_e { X = 0, Y, Z, E, AXIS_COUNT };
/**
\typedef axes_uint32_t
\brief n-dimensional vector used to describe uint32_t axis information.
Stored value can be anything unsigned. Units should be specified when declared.
*/
typedef uint32_t axes_uint32_t[AXIS_COUNT];
/**
\typedef axes_int32_t
\brief n-dimensional vector used to describe int32_t axis information.
Stored value can be anything unsigned. Units should be specified when declared.
*/
typedef int32_t axes_int32_t[AXIS_COUNT];
/**
\struct TARGET
\brief target is simply a point in space/time
X, Y, Z and E are in micrometers unless explcitely stated. F is in mm/min.
*/
typedef struct {
axes_int32_t axis;
uint32_t F;
uint16_t e_multiplier;
uint16_t f_multiplier;
uint8_t e_relative :1; ///< bool: e axis relative? Overrides all_relative
} TARGET;
/**
\struct MOVE_STATE
\brief this struct is made for tracking the current state of the movement
Parts of this struct are initialised only once per reboot, so make sure dda_step() leaves them with a value compatible to begin a new movement at the end of the movement. Other parts are filled in by dda_start().
*/
typedef struct {
// bresenham counters
axes_int32_t counter; ///< counter for total_steps vs each axis
// step counters
axes_uint32_t steps; ///< number of steps on each axis
/// counts actual steps done
uint32_t step_no;
/// Endstop handling.
uint8_t endstop_stop; ///< Stop due to endstop trigger
uint8_t debounce_count_x, debounce_count_y, debounce_count_z;
} MOVE_STATE;
/**
\struct DDA
\brief this is a digital differential analyser data struct
This struct holds all the details of an individual multi-axis move, including pre-calculated acceleration data.
This struct is filled in by dda_create(), called from enqueue(), called mostly from gcode_process() and from a few other places too (eg \file homing.c)
*/
typedef struct {
/// this is where we should finish
TARGET endpoint;
union {
struct {
// status fields
uint8_t nullmove :1; ///< bool: no axes move, maybe we wait for temperatures or change speed
uint8_t live :1; ///< bool: this DDA is running and still has steps to do
uint8_t done :1; ///< bool: this DDA is done.
// wait for temperature to stabilise flag
uint8_t waitfor_temp :1; ///< bool: wait for temperatures to reach their set values
// directions
// As we have muldiv() now, overflows became much less an issue and
// it's likely time to get rid of these flags and use int instead of
// uint for distance/speed calculations. --Traumflug 2014-07-04
uint8_t x_direction :1; ///< direction flag for X axis
uint8_t y_direction :1; ///< direction flag for Y axis
uint8_t z_direction :1; ///< direction flag for Z axis
uint8_t e_direction :1; ///< direction flag for E axis
};
uint16_t allflags; ///< used for clearing all flags
};
// distances
axes_uint32_t delta; ///< number of steps on each axis
// uint8_t fast_axis; (see below)
uint32_t total_steps; ///< steps of the "fast" axis
uint32_t fast_um; ///< movement length of this fast axis
uint32_t fast_spm; ///< steps per meter of the fast axis
uint32_t c; ///< time until next step, 24.8 fixed point
/// precalculated step time offset variable
int32_t n;
/// number of steps accelerating
uint32_t rampup_steps;
/// number of last step before decelerating
uint32_t rampdown_steps;
/// 24.8 fixed point timer value, maximum speed
uint32_t c_min;
#ifdef LOOKAHEAD
// With the look-ahead functionality, it is possible to retain physical
// movement between G1 moves. These variables keep track of the entry and
// exit speeds between moves.
uint32_t distance;
uint32_t crossF;
// These two are based on the "fast" axis, the axis with the most steps.
uint32_t start_steps; ///< would be required to reach start feedrate
uint32_t end_steps; ///< would be required to stop from end feedrate
// Displacement vector, in um, based between the difference of the starting
// point and the target. Required to obtain the jerk between 2 moves.
// Note: x_delta and co are in steps, not um.
axes_int32_t delta_um;
// Number the moves to be able to test at the end of lookahead if the moves
// are the same. Note: we do not need a lot of granularity here: more than
// MOVEBUFFER_SIZE is already enough.
uint8_t id;
#endif
/// Small variables. Many CPUs can access 32-bit variables at word or double
/// word boundaries only and fill smaller variables in between with gaps,
/// so keep small variables grouped together to reduce the amount of these
/// gaps. See e.g. NXP application note AN10963, page 10f.
uint8_t fast_axis; ///< number of the fast axis
/// Endstop homing
uint8_t endstop_check; ///< Do we need to check endstops? 0x1=Check X, 0x2=Check Y, 0x4=Check Z
uint8_t endstop_stop_cond; ///< Endstop condition on which to stop motion: 0=Stop on detrigger, 1=Stop on trigger
} DDA;
/*
variables
*/
/// startpoint holds the endpoint of the most recently created DDA, so we know where the next one created starts. could also be called last_endpoint
extern TARGET startpoint;
/// the same as above, counted in motor steps
extern TARGET startpoint_steps;
/// current_position holds the machine's current position. this is only updated when we step, or when G92 (set home) is received.
extern TARGET current_position;
/*
methods
*/
// initialize dda structures
void dda_init(void);
// distribute a new startpoint
void dda_new_startpoint(void);
// create a DDA
void dda_create(DDA *dda, const TARGET *target);
// start a created DDA (called from timer interrupt)
void dda_start(DDA *dda);
// DDA takes one step (called from timer interrupt)
void dda_step(DDA *dda);
// regular movement maintenance
void dda_clock(void);
// update current_position
void update_current_position(void);
/*********************PLANNER*********************/
#ifdef LOOKAHEAD
// Sanity: make sure the defines are in place
#if ! defined MAX_JERK_X || ! defined MAX_JERK_Y || \
! defined MAX_JERK_Z || ! defined MAX_JERK_E
#error Your config.h does not specify one of MAX_JERK_X,
#error MAX_JERK_Y, MAX_JERK_Z or MAX_JERK_E while LOOKAHEAD is enabled!
#endif
// Sanity: the acceleration of Teacup is not implemented properly; as such we can only
// do move joining when all axis use the same steps per mm. This is usually not an issue
// for X and Y.
#if STEPS_PER_M_X != STEPS_PER_M_Y
#error "Look-ahead requires steps per m to be identical on the X and Y axis (for now)"
#endif
#define MAX(a,b) (((a)>(b))?(a):(b))
#define MIN(a,b) (((a)<(b))?(a):(b))
void dda_find_crossing_speed(DDA *prev, DDA *current);
void dda_join_moves(DDA *prev, DDA *current);
#endif /* LOOKAHEAD */
#endif /* _DDA_H */

47
motor_control.ino 100644
Wyświetl plik

@ -0,0 +1,47 @@
#include "queue.h"
#include "timer.h"
#include "serial.h"
#include "pinio.h"
#include "gcode_parser.h"
#include "queue.h"
uint8_t c, line_done, ack_waiting = 0;
void setup(){
cpu_init();
serial_init();
pinio_init();
timer_init();
dda_init();
parser_init();
sei();
serial_writestr_P(PSTR("start\nok\n"));
//enqueue_home(&t, 0, 0);
}
void loop()
{
if (queue_full() == 0) {
if (ack_waiting) {
serial_writestr_P(PSTR("ok\n"));
ack_waiting = 0;
}
if (//( ! gcode_active || gcode_active & GCODE_SOURCE_SERIAL) &&
serial_rxchars() != 0) {
//gcode_active = GCODE_SOURCE_SERIAL;
c = serial_popchar();
line_done = gcode_parse_char(c);
if (line_done) {
//gcode_active = 0;
if(line_done > 1)
serial_writestr_P(PSTR("err\n"));
else
ack_waiting = 1;
}
}
}
}

Wyświetl plik

@ -0,0 +1,57 @@
#include "queue.h"
#include "timer.h"
#include "serial.h"
#include "pinio.h"
#include "gcode_parser.h"
#include "queue.h"
#include "config.h"
#ifdef SIMINFO
#include "simulavr_info.h"
SIMINFO_DEVICE("atmega32");
SIMINFO_CPUFREQUENCY(F_CPU);
#ifdef BAUD
SIMINFO_SERIAL_IN("D0", "-", BAUD);
SIMINFO_SERIAL_OUT("D1", "-", BAUD);
#endif
#endif
uint8_t c, line_done, ack_waiting = 0;
void setup(){
cpu_init();
serial_init();
pinio_init();
timer_init();
dda_init();
parser_init();
sei();
serial_writestr_P(PSTR("start\nok\n"));
//enqueue_home(&t, 0, 0);
}
void loop()
{
if (queue_full() == 0) {
if (ack_waiting) {
serial_writestr_P(PSTR("ok\n"));
ack_waiting = 0;
}
if (//( ! gcode_active || gcode_active & GCODE_SOURCE_SERIAL) &&
serial_rxchars() != 0) {
//gcode_active = GCODE_SOURCE_SERIAL;
c = serial_popchar();
line_done = gcode_parse_char(c);
if (line_done) {
//gcode_active = 0;
if(line_done > 1)
serial_writestr_P(PSTR("err\n"));
else
ack_waiting = 1;
}
}
}
}

114
msg.cpp 100644
Wyświetl plik

@ -0,0 +1,114 @@
/** \file msg.c
\brief Primitives for sending numbers over links.
*/
#include "msg.h"
/** write a single hex digit
\param v hex digit to write, higher nibble ignored
*/
void write_hex4(void (*writechar)(uint8_t), uint8_t v) {
v &= 0xF;
if (v < 10)
writechar('0' + v);
else
writechar('A' - 10 + v);
}
/** write a pair of hex digits
\param v byte to write. One byte gives two hex digits
*/
void write_hex8(void (*writechar)(uint8_t), uint8_t v) {
write_hex4(writechar, v >> 4);
write_hex4(writechar, v & 0x0F);
}
/** write four hex digits
\param v word to write
*/
void write_hex16(void (*writechar)(uint8_t), uint16_t v) {
write_hex8(writechar, v >> 8);
write_hex8(writechar, v & 0xFF);
}
/** write eight hex digits
\param v long word to write
*/
void write_hex32(void (*writechar)(uint8_t), uint32_t v) {
write_hex16(writechar, v >> 16);
write_hex16(writechar, v & 0xFFFF);
}
/// list of powers of ten, used for dividing down decimal numbers for sending, and also for our crude floating point algorithm
extern const uint32_t powers[] = {1, 10, 100, 1000, 10000, 100000, 1000000, 10000000, 100000000, 1000000000};
/** write decimal digits from a long unsigned int
\param v number to send
*/
void write_uint32(void (*writechar)(uint8_t), uint32_t v) {
uint8_t e, t;
for (e = 9; e > 0; e--) {
if (v >= powers[e])
break;
}
do
{
for (t = 0; v >= powers[e]; v -= powers[e], t++);
writechar(t + '0');
}
while (e--);
}
/** write decimal digits from a long signed int
\param v number to send
*/
void write_int32(void (*writechar)(uint8_t), int32_t v) {
if (v < 0) {
writechar('-');
v = -v;
}
write_uint32(writechar, v);
}
/** write decimal digits from a long unsigned int
\param v number to send
\param fp number of decimal places to the right of the decimal point
*/
void write_uint32_vf(void (*writechar)(uint8_t), uint32_t v, uint8_t fp) {
uint8_t e, t;
for (e = 9; e > 0; e--) {
if (v >= powers[e])
break;
}
if (e < fp)
e = fp;
do
{
for (t = 0; v >= powers[e]; v -= powers[e], t++);
writechar(t + '0');
if (e == fp)
writechar('.');
}
while (e--);
}
/** write decimal digits from a long signed int
\param v number to send
\param fp number of decimal places to the right of the decimal point
*/
void write_int32_vf(void (*writechar)(uint8_t), int32_t v, uint8_t fp) {
if (v < 0) {
writechar('-');
v = -v;
}
write_uint32_vf(writechar, v, fp);
}

24
msg.h 100644
Wyświetl plik

@ -0,0 +1,24 @@
#ifndef _SERMSG_H
#define _SERMSG_H
#include <stdint.h>
// functions for sending hexadecimal
void write_hex4(void (*writechar)(uint8_t), uint8_t v);
void write_hex8(void (*writechar)(uint8_t), uint8_t v);
void write_hex16(void (*writechar)(uint8_t), uint16_t v);
void write_hex32(void (*writechar)(uint8_t), uint32_t v);
// functions for sending decimal
#define write_uint8(v, w) write_uint32(v, w)
#define write_int8(v, w) write_int32(v, w)
#define write_uint16(v, w) write_uint32(v, w)
#define write_int16(v, w) write_int32(v, w)
void write_uint32(void (*writechar)(uint8_t), uint32_t v);
void write_int32(void (*writechar)(uint8_t), int32_t v);
void write_uint32_vf(void (*writechar)(uint8_t), uint32_t v, uint8_t fp);
void write_int32_vf(void (*writechar)(uint8_t), int32_t v, uint8_t fp);
#endif /* _SERMSG_H */

115
pinio.cpp 100644
Wyświetl plik

@ -0,0 +1,115 @@
#include "pinio.h"
static char ps_is_on = 0;
/// step/psu timeout
volatile uint8_t psu_timeout = 0;
/** Initialise all I/O.
This sets pins as input or output, appropriate for their usage.
*/
void pinio_init(void) {
/// X Stepper.
SET_OUTPUT(X_STEP_PIN); WRITE(X_STEP_PIN, 0);
SET_OUTPUT(X_DIR_PIN); WRITE(X_DIR_PIN, 0);
#ifdef X_MIN_PIN
SET_INPUT(X_MIN_PIN);
PULL_OFF(X_MIN_PIN);
#endif
#ifdef X_MAX_PIN
SET_INPUT(X_MAX_PIN);
PULL_OFF(X_MAX_PIN);
#endif
/// Y Stepper.
SET_OUTPUT(Y_STEP_PIN); WRITE(Y_STEP_PIN, 0);
SET_OUTPUT(Y_DIR_PIN); WRITE(Y_DIR_PIN, 0);
#ifdef Y_MIN_PIN
SET_INPUT(Y_MIN_PIN);
PULL_OFF(Y_MIN_PIN);
#endif
#ifdef Y_MAX_PIN
SET_INPUT(Y_MAX_PIN);
PULL_OFF(Y_MAX_PIN);
#endif
/// Z Stepper.
#if defined Z_STEP_PIN && defined Z_DIR_PIN
SET_OUTPUT(Z_STEP_PIN); WRITE(Z_STEP_PIN, 0);
SET_OUTPUT(Z_DIR_PIN); WRITE(Z_DIR_PIN, 0);
#endif
#ifdef Z_MIN_PIN
SET_INPUT(Z_MIN_PIN);
PULL_OFF(Z_MIN_PIN);
#endif
#ifdef Z_MAX_PIN
SET_INPUT(Z_MAX_PIN);
PULL_OFF(Z_MAX_PIN);
#endif
#if defined E_STEP_PIN && defined E_DIR_PIN
SET_OUTPUT(E_STEP_PIN); WRITE(E_STEP_PIN, 0);
SET_OUTPUT(E_DIR_PIN); WRITE(E_DIR_PIN, 0);
#endif
/// Common Stepper Enable.
#ifdef STEPPER_ENABLE_PIN
SET_OUTPUT(STEPPER_ENABLE_PIN);
#ifdef STEPPER_INVERT_ENABLE
WRITE(STEPPER_ENABLE_PIN, 0);
#else
WRITE(STEPPER_ENABLE_PIN, 1);
#endif
#endif
/// X Stepper Enable.
#ifdef X_ENABLE_PIN
SET_OUTPUT(X_ENABLE_PIN);
#ifdef X_INVERT_ENABLE
WRITE(X_ENABLE_PIN, 0);
#else
WRITE(X_ENABLE_PIN, 1);
#endif
#endif
/// Y Stepper Enable.
#ifdef Y_ENABLE_PIN
SET_OUTPUT(Y_ENABLE_PIN);
#ifdef Y_INVERT_ENABLE
WRITE(Y_ENABLE_PIN, 0);
#else
WRITE(Y_ENABLE_PIN, 1);
#endif
#endif
/// Z Stepper Enable.
#ifdef Z_ENABLE_PIN
SET_OUTPUT(Z_ENABLE_PIN);
#ifdef Z_INVERT_ENABLE
WRITE(Z_ENABLE_PIN, 0);
#else
WRITE(Z_ENABLE_PIN, 1);
#endif
#endif
/// E Stepper Enable.
#ifdef E_ENABLE_PIN
SET_OUTPUT(E_ENABLE_PIN);
#ifdef E_INVERT_ENABLE
WRITE(E_ENABLE_PIN, 0);
#else
WRITE(E_ENABLE_PIN, 1);
#endif
#endif
#ifdef STEPPER_ENABLE_PIN
power_off();
#endif
#ifdef DEBUG_LED_PIN
SET_OUTPUT(DEBUG_LED_PIN);
WRITE(DEBUG_LED_PIN, 0);
#endif
}

438
pinio.h 100644
Wyświetl plik

@ -0,0 +1,438 @@
/** \file
\brief I/O primitives - step, enable, direction, endstops etc
*/
#ifndef _PINIO_H
#define _PINIO_H
#include "config.h"
// Configuration tests.
#ifdef USE_INTERNAL_PULLDOWNS
#ifdef USE_INTERNAL_PULLUPS
#error Cant use USE_INTERNAL_PULLUPS and ..._PULLDOWNS at the same time.
#endif
#endif
#ifndef MASK
/// MASKING- returns \f$2^PIN\f$
#define MASK(PIN) (1 << PIN)
#endif
/** Magic I/O routines, also known as "FastIO".
Now you can simply SET_OUTPUT(STEP); WRITE(STEP, 1); WRITE(STEP, 0);.
The point here is to move any pin/port mapping calculations into the
preprocessor. This way there is no longer math at runtime neccessary, all
instructions melt into a single one with fixed numbers.
This makes code for setting a pin small, smaller than calling a subroutine.
It also make code fast, on AVR a pin can be turned on and off in just two
clock cycles.
*/
#if defined __AVR__
#include <avr/io.h>
/// Read a pin.
#define _READ(IO) (IO ## _RPORT & MASK(IO ## _PIN))
/// Write to a pin.
#define _WRITE(IO, v) \
do { \
if (v) { IO ## _WPORT |= MASK(IO ## _PIN); } \
else { IO ## _WPORT &= ~MASK(IO ## _PIN); } \
} while (0)
/**
Setting pins as input/output: other than with ARMs, function of a pin
on AVR isn't given by a dedicated function register, but solely by the
on-chip peripheral connected to it. With the peripheral (e.g. UART, SPI,
...) connected, a pin automatically serves with this function. With the
peripheral disconnected, it automatically returns to general I/O function.
*/
/// Set pin as input.
#define _SET_INPUT(IO) do { IO ## _DDR &= ~MASK(IO ## _PIN); } while (0)
/// Set pin as output.
#define _SET_OUTPUT(IO) do { IO ## _DDR |= MASK(IO ## _PIN); } while (0)
/// Enable pullup resistor.
#define _PULLUP_ON(IO) _WRITE(IO, 1)
/// No such feature on ATmegas.
#define _PULLDOWN_ON(IO) atmegas_dont_support_pulldown_resistors()
/// Disable pullup resistor.
#define _PULL_OFF(IO) _WRITE(IO, 0)
#elif defined __ARMEL__
/**
The LPC1114 supports bit-banding by mapping the bit mask to the address.
See chapter 12 in the LPC111x User Manual. A read-modify-write cycle like
on AVR costs 5 clock cycles, this implementation works with 3 clock cycles.
*/
/// Read a pin.
#define _READ(IO) (IO ## _PORT->MASKED_ACCESS[MASK(IO ## _PIN)])
/// Write to a pin.
#define _WRITE(IO, v) \
do { \
IO ## _PORT->MASKED_ACCESS[MASK(IO ## _PIN)] = \
(v) ? MASK(IO ## _PIN) : 0; \
} while (0)
/**
Set pins as input/output. On ARM, each pin has its own IOCON register,
which allows to set its function and mode. We always set here standard
GPIO behavior. Peripherals using these pins may have to change this and
should do so in their own context.
*/
/// Set pin as input.
#define _SET_INPUT(IO) \
do { \
LPC_IOCON->IO ## _CMSIS = (IO ## _OUTPUT | IO_MODEMASK_REPEATER); \
IO ## _PORT->DIR &= ~MASK(IO ## _PIN); \
} while (0)
/// Set pin as output.
#define _SET_OUTPUT(IO) \
do { \
LPC_IOCON->IO ## _CMSIS = IO ## _OUTPUT; \
IO ## _PORT->DIR |= MASK(IO ## _PIN); \
} while (0)
/// Enable pullup resistor or switch from pulldown to pullup.
#define _PULLUP_ON(IO) \
do { \
LPC_IOCON->IO ## _CMSIS = (IO ## _OUTPUT | IO_MODEMASK_PULLUP); \
} while (0)
/// Enable pulldown resistor or switch from pullup to pulldown.
#define _PULLDOWN_ON(IO) \
do { \
LPC_IOCON->IO ## _CMSIS = (IO ## _OUTPUT | IO_MODEMASK_PULLDOWN); \
} while (0)
/// Disable pull resistor.
#define _PULL_OFF(IO) \
do { \
LPC_IOCON->IO ## _CMSIS = (IO ## _OUTPUT | IO_MODEMASK_INACTIVE); \
} while (0)
#elif defined SIMULATOR
#include "simulator.h"
bool _READ(pin_t pin);
void _WRITE(pin_t pin, bool on);
void _SET_OUTPUT(pin_t pin);
void _SET_INPUT(pin_t pin);
#define _PULLUP_ON(IO) _WRITE(IO, 1)
#define _PULL_OFF(IO) _WRITE(IO, 0)
#endif /* __AVR__, __ARMEL__, SIMULATOR */
/**
Why double up on these macros?
See http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
*/
/// Read a pin wrapper.
#define READ(IO) _READ(IO)
/// Write to a pin wrapper.
#define WRITE(IO, v) _WRITE(IO, v)
/// Set pin as input wrapper.
#define SET_INPUT(IO) _SET_INPUT(IO)
/// Set pin as output wrapper.
#define SET_OUTPUT(IO) _SET_OUTPUT(IO)
/// Enable pullup resistor or switch from pulldown to pullup.
#define PULLUP_ON(IO) _PULLUP_ON(IO)
/// Enable pulldown resistor or switch from pullup to pulldown.
#define PULLDOWN_ON(IO) _PULLDOWN_ON(IO)
/// Disable pull resistor.
#define PULL_OFF(IO) _PULL_OFF(IO)
/*
Power
*/
/// psu_timeout is set to zero when we step, and increases over time so we can
/// turn the motors off when they've been idle for a while.
/// A second function is to guarantee a minimum on time of the PSU.
/// Timeout counting is done in clock.c.
/// It is used inside and outside of interrupts, which is why it has been made volatile
/*extern volatile uint8_t psu_timeout;
static void power_init(void);
inline void power_init(void) {
#ifdef PS_MOSFET_PIN
WRITE(PS_MOSFET_PIN, 0);
SET_OUTPUT(PS_MOSFET_PIN);
#endif
}*/
void pinio_init(void);
void power_on(void);
void power_off(void);
/*
X Stepper
*/
#define _x_step(st) WRITE(X_STEP_PIN, st)
#define x_step() _x_step(1)
#ifndef X_INVERT_DIR
#define x_direction(dir) WRITE(X_DIR_PIN, dir)
#else
#define x_direction(dir) WRITE(X_DIR_PIN, (dir)^1)
#endif
#ifdef X_MIN_PIN
#ifndef X_INVERT_MIN
#define x_min() (READ(X_MIN_PIN)?1:0)
#else
#define x_min() (READ(X_MIN_PIN)?0:1)
#endif
#else
#define x_min() (0)
#endif
#ifdef X_MAX_PIN
#ifndef X_INVERT_MAX
#define x_max() (READ(X_MAX_PIN)?1:0)
#else
#define x_max() (READ(X_MAX_PIN)?0:1)
#endif
#else
#define x_max() (0)
#endif
/*
Y Stepper
*/
#define _y_step(st) WRITE(Y_STEP_PIN, st)
#define y_step() _y_step(1)
#ifndef Y_INVERT_DIR
#define y_direction(dir) WRITE(Y_DIR_PIN, dir)
#else
#define y_direction(dir) WRITE(Y_DIR_PIN, (dir)^1)
#endif
#ifdef Y_MIN_PIN
#ifndef Y_INVERT_MIN
#define y_min() (READ(Y_MIN_PIN)?1:0)
#else
#define y_min() (READ(Y_MIN_PIN)?0:1)
#endif
#else
#define y_min() (0)
#endif
#ifdef Y_MAX_PIN
#ifndef Y_INVERT_MAX
#define y_max() (READ(Y_MAX_PIN)?1:0)
#else
#define y_max() (READ(Y_MAX_PIN)?0:1)
#endif
#else
#define y_max() (0)
#endif
/*
Z Stepper
*/
#if defined Z_STEP_PIN && defined Z_DIR_PIN
#define _z_step(st) WRITE(Z_STEP_PIN, st)
#define z_step() _z_step(1)
#ifndef Z_INVERT_DIR
#define z_direction(dir) WRITE(Z_DIR_PIN, dir)
#else
#define z_direction(dir) WRITE(Z_DIR_PIN, (dir)^1)
#endif
#else
#define _z_step(x) do { } while (0)
#define z_step() do { } while (0)
#define z_direction(x) do { } while (0)
#endif
#ifdef Z_MIN_PIN
#ifndef Z_INVERT_MIN
#define z_min() (READ(Z_MIN_PIN)?1:0)
#else
#define z_min() (READ(Z_MIN_PIN)?0:1)
#endif
#else
#define z_min() (0)
#endif
#ifdef Z_MAX_PIN
#ifndef Z_INVERT_MAX
#define z_max() (READ(Z_MAX_PIN)?1:0)
#else
#define z_max() (READ(Z_MAX_PIN)?0:1)
#endif
#else
#define z_max() (0)
#endif
/*
Extruder
*/
#if defined E_STEP_PIN && defined E_DIR_PIN
#define _e_step(st) WRITE(E_STEP_PIN, st)
#define e_step() _e_step(1)
#ifndef E_INVERT_DIR
#define e_direction(dir) WRITE(E_DIR_PIN, dir)
#else
#define e_direction(dir) WRITE(E_DIR_PIN, (dir)^1)
#endif
#else
#define _e_step(st) do { } while (0)
#define e_step() do { } while (0)
#define e_direction(dir) do { } while (0)
#endif
/*
End Step - All Steppers
(so we don't have to delay in interrupt context)
*/
#define unstep() do { _x_step(0); _y_step(0); _z_step(0); _e_step(0); } while (0)
/*
Stepper Enable Pins
*/
#ifdef STEPPER_ENABLE_PIN
#ifdef STEPPER_INVERT_ENABLE
#define stepper_enable() do { WRITE(STEPPER_ENABLE_PIN, 0); } while (0)
#define stepper_disable() do { WRITE(STEPPER_ENABLE_PIN, 1); } while (0)
#else
#define stepper_enable() do { WRITE(STEPPER_ENABLE_PIN, 1); } while (0)
#define stepper_disable() do { WRITE(STEPPER_ENABLE_PIN, 0); } while (0)
#endif
#else
#define stepper_enable() do { } while (0)
#define stepper_disable() do { } while (0)
#endif
#ifdef X_ENABLE_PIN
#ifdef X_INVERT_ENABLE
#define x_enable() do { WRITE(X_ENABLE_PIN, 0); } while (0)
#define x_disable() do { WRITE(X_ENABLE_PIN, 1); } while (0)
#else
#define x_enable() do { WRITE(X_ENABLE_PIN, 1); } while (0)
#define x_disable() do { WRITE(X_ENABLE_PIN, 0); } while (0)
#endif
#else
#define x_enable() do { } while (0)
#define x_disable() do { } while (0)
#endif
#ifdef Y_ENABLE_PIN
#ifdef Y_INVERT_ENABLE
#define y_enable() do { WRITE(Y_ENABLE_PIN, 0); } while (0)
#define y_disable() do { WRITE(Y_ENABLE_PIN, 1); } while (0)
#else
#define y_enable() do { WRITE(Y_ENABLE_PIN, 1); } while (0)
#define y_disable() do { WRITE(Y_ENABLE_PIN, 0); } while (0)
#endif
#else
#define y_enable() do { } while (0)
#define y_disable() do { } while (0)
#endif
#ifdef Z_ENABLE_PIN
#ifdef Z_INVERT_ENABLE
#define z_enable() do { WRITE(Z_ENABLE_PIN, 0); } while (0)
#define z_disable() do { WRITE(Z_ENABLE_PIN, 1); } while (0)
#else
#define z_enable() do { WRITE(Z_ENABLE_PIN, 1); } while (0)
#define z_disable() do { WRITE(Z_ENABLE_PIN, 0); } while (0)
#endif
#else
#define z_enable() do { } while (0)
#define z_disable() do { } while (0)
#endif
#ifdef E_ENABLE_PIN
#ifdef E_INVERT_ENABLE
#define e_enable() do { WRITE(E_ENABLE_PIN, 0); } while (0)
#define e_disable() do { WRITE(E_ENABLE_PIN, 1); } while (0)
#else
#define e_enable() do { WRITE(E_ENABLE_PIN, 1); } while (0)
#define e_disable() do { WRITE(E_ENABLE_PIN, 0); } while (0)
#endif
#else
#define e_enable() do { } while (0)
#define e_disable() do { } while (0)
#endif
/*
Internal pullup resistors for endstops
*/
static void endstops_on(void) __attribute__ ((always_inline));
inline void endstops_on(void) {
#ifdef USE_INTERNAL_PULLUPS
#ifdef X_MIN_PIN
PULLUP_ON(X_MIN_PIN);
#endif
#ifdef X_MAX_PIN
PULLUP_ON(X_MAX_PIN);
#endif
#ifdef Y_MIN_PIN
PULLUP_ON(Y_MIN_PIN);
#endif
#ifdef Y_MAX_PIN
PULLUP_ON(Y_MAX_PIN);
#endif
#ifdef Z_MIN_PIN
PULLUP_ON(Z_MIN_PIN);
#endif
#ifdef Z_MAX_PIN
PULLUP_ON(Z_MAX_PIN);
#endif
#endif
#ifdef USE_INTERNAL_PULLDOWNS
#ifdef X_MIN_PIN
PULLDOWN_ON(X_MIN_PIN);
#endif
#ifdef X_MAX_PIN
PULLDOWN_ON(X_MAX_PIN);
#endif
#ifdef Y_MIN_PIN
PULLDOWN_ON(Y_MIN_PIN);
#endif
#ifdef Y_MAX_PIN
PULLDOWN_ON(Y_MAX_PIN);
#endif
#ifdef Z_MIN_PIN
PULLDOWN_ON(Z_MIN_PIN);
#endif
#ifdef Z_MAX_PIN
PULLDOWN_ON(Z_MAX_PIN);
#endif
#endif
}
static void endstops_off(void) __attribute__ ((always_inline));
inline void endstops_off(void) {
#if (defined USE_INTERNAL_PULLUPS) || (defined USE_INTERNAL_PULLDOWNS)
#ifdef X_MIN_PIN
PULL_OFF(X_MIN_PIN);
#endif
#ifdef X_MAX_PIN
PULL_OFF(X_MAX_PIN);
#endif
#ifdef Y_MIN_PIN
PULL_OFF(Y_MIN_PIN);
#endif
#ifdef Y_MAX_PIN
PULL_OFF(Y_MAX_PIN);
#endif
#ifdef Z_MIN_PIN
PULL_OFF(Z_MIN_PIN);
#endif
#ifdef Z_MAX_PIN
PULL_OFF(Z_MAX_PIN);
#endif
#endif
}
#endif /* _PINIO_H */

125
queue.cpp 100644
Wyświetl plik

@ -0,0 +1,125 @@
#include "queue.h"
/// movebuffer head pointer. Points to the last move in the queue.
/// this variable is used both in and out of interrupts, but is
/// only written outside of interrupts.
uint8_t mb_head = 0;
/// movebuffer tail pointer. Points to the currently executing move
/// this variable is read/written both in and out of interrupts.
uint8_t mb_tail = 0;
/// move buffer.
/// holds move queue
/// contents are read/written both in and out of interrupts, but
/// once writing starts in interrupts on a specific slot, the
/// slot will only be modified in interrupts until the slot is
/// is no longer live.
/// The size does not need to be a power of 2 anymore!
DDA BSS movebuffer[MOVEBUFFER_SIZE];
/// check if the queue is completely full
uint8_t queue_full() {
MEMORY_BARRIER();
return MB_NEXT(mb_head) == mb_tail;
}
/// check if the queue is completely empty
uint8_t queue_empty() {
uint8_t result;
ATOMIC_START
result = (mb_tail == mb_head && movebuffer[mb_tail].live == 0);
ATOMIC_END
return result;
}
DDA *queue_current_movement() {
DDA* current;
ATOMIC_START
current = &movebuffer[mb_tail];
if ( ! current->live || current->waitfor_temp || current->nullmove)
current = NULL;
ATOMIC_END
return current;
}
/// add a move to the movebuffer
/// \note this function waits for space to be available if necessary, check queue_full() first if waiting is a problem
/// This is the only function that modifies mb_head and it always called from outside an interrupt.
void enqueue_home(TARGET *t, uint8_t endstop_check, uint8_t endstop_stop_cond) {
// don't call this function when the queue is full, but just in case, wait for a move to complete and free up the space for the passed target
/*while (queue_full())
delay_us(100);
*/
uint8_t h = MB_NEXT(mb_head);;
DDA* new_movebuffer = &(movebuffer[h]);
// Initialise queue entry to a known state. This also clears flags like
// dda->live, dda->done and dda->wait_for_temp.
new_movebuffer->allflags = 0;
if (t != NULL) {
new_movebuffer->endstop_check = endstop_check;
new_movebuffer->endstop_stop_cond = endstop_stop_cond;
}
else {
// it's a wait for temp
new_movebuffer->waitfor_temp = 1;
}
dda_create(new_movebuffer, t);
mb_head = h;
uint8_t isdead;
ATOMIC_START
isdead = (movebuffer[mb_tail].live == 0);
ATOMIC_END
if (isdead) {
timer_reset();
next_move();
// Compensate for the cli() in timer_set().
sei();
}
}
// -------------------------------------------------------
// This is the one function called by the timer interrupt.
// It calls a few other functions, though.
// -------------------------------------------------------
/// Take a step or go to the next move.
void queue_step() {
// do our next step
DDA* current_movebuffer = &movebuffer[mb_tail];
if (current_movebuffer->live) {
dda_step(current_movebuffer);
}
// Start the next move if this one is done.
if (current_movebuffer->live == 0)
next_move();
}
// called from step timer when current move is complete
void next_move(void)
{
while ((queue_empty() == 0) && (movebuffer[mb_tail].live == 0)) {
// next item
uint8_t t = MB_NEXT(mb_tail);
DDA* current_movebuffer = &movebuffer[t];
// Tail must be set before calling timer_set(), as timer_set() reenables
// the timer interrupt, potentially exposing mb_tail to the timer
// interrupt routine.
mb_tail = t;
dda_start(current_movebuffer);
}
}

35
queue.h 100644
Wyświetl plik

@ -0,0 +1,35 @@
#ifndef _QUEUE_H
#define _QUEUE_H
#include "motor.h"
#include "timer.h"
extern uint8_t mb_head;
extern uint8_t mb_tail;
extern DDA movebuffer[MOVEBUFFER_SIZE];
// queue status methods
uint8_t queue_full(void);
uint8_t queue_empty(void);
DDA *queue_current_movement(void);
/// Find the next DDA index after 'x', where 0 <= x < MOVEBUFFER_SIZE
#define MB_NEXT(x) ((x) < MOVEBUFFER_SIZE - 1 ? (x) + 1 : 0)
// add a new target to the queue
// t == NULL means add a wait for target temp to the queue
void enqueue_home(TARGET *t, uint8_t endstop_check, uint8_t endstop_stop_cond);
// called from step timer when current move is complete
void next_move(void);
// take one step
void queue_step(void);
static void enqueue(TARGET *) __attribute__ ((always_inline));
inline void enqueue(TARGET *t) {
enqueue_home(t, 0, 0);
}
#endif /* _QUEUE_H */

115
ringbuffer.h 100644
Wyświetl plik

@ -0,0 +1,115 @@
/** \file
\brief Header for implementing a ringbuffer.
This header implements a macro-level ringbuffer. It's meant to be included
only in source files and only where needed. Such a sequence implements a
ringbuffer:
#define BUFSIZE 64
volatile uint8_t rxhead = 0;
volatile uint8_t rxtail = 0;
volatile uint8_t rxbuf[BUFSIZE];
#include "ringbuffer.h"
Requirements:
- The name 'BUFSIZE' has to be kept exactly. One can use two or more
ringbuffers in the same source file, but they all have to be the same
size.
- BUFSIZE has to be a power of two: 2, 4, 8, 16, 32, 64, 128 or 256.
- In the example above, 'rx' is the name of the buffer. <name>head,
<name>tail and <name>buf have to be named exactly.
Ringbuffer logic:
head = written data pointer.
tail = read data pointer.
When head == tail, buffer is empty.
When head + 1 == tail, buffer is full.
Thus, number of available spaces in buffer is (tail - head) & bufsize.
Can write:
(tail - head - 1) & (BUFSIZE - 1)
Write to buffer:
buf[head++] = data; head &= (BUFSIZE - 1);
Can read:
(head - tail) & (BUFSIZE - 1)
Read from buffer:
data = buf[tail++]; tail &= (BUFSIZE - 1);
*/
/** \def buf_canread()
Check if we can read from this buffer. Buffer pointers are left unchanged.
Example:
if (buf_canread(rx)) {
...
}
*/
#define buf_canread(buffer) ((buffer ## head - buffer ## tail ) & \
(BUFSIZE - 1))
/** \def buf_pop()
Actually read a byte from this buffer. This also forwards the buffer pointer.
It's imperative to check for availabilty of a byte before. Pop'ing an
empty buffer means to go through the whle buffer again.
Example:
uint8_t next_byte;
if (buf_canread(rx)) {
buf_pop(rx, next_byte);
}
*/
#define buf_pop(buffer, data) do { \
data = buffer ## buf[buffer ## tail]; \
buffer ## tail = (buffer ## tail + 1) & \
(BUFSIZE - 1); \
} while (0)
/** \def buf_canwrite()
Check if we can write to this buffer. Buffer pointers are left unchanged.
Example:
uint8_t data;
if (buf_canwrite(tx)) {
printf("There's room in the buffer, please send data.\n");
}
*/
#define buf_canwrite(buffer) ((buffer ## tail - buffer ## head - 1) & \
(BUFSIZE - 1))
/** \def buf_push()
Actually write to this buffer. This also forwards the buffer pointers. Like
with buf_pop() it's mandatory to test for available room before actually
writing, else valid data is overwritten.
Example:
void write_char_to_buffer(uint8_t data) {
if (buf_canwrite(tx))
buf_push(tx, data);
}
*/
#define buf_push(buffer, data) do { \
buffer ## buf[buffer ## head] = data; \
buffer ## head = (buffer ## head + 1) & \
(BUFSIZE - 1); \
} while (0)

295
serial.cpp 100644
Wyświetl plik

@ -0,0 +1,295 @@
#include "serial.h"
#include <avr/interrupt.h>
#include "timer.h"
#include "pinio.h"
#include <stdarg.h>
#include "msg.h"
/** \def BUFSIZE
Size of TX and RX buffers. MUST be a \f$2^n\f$ value.
Unlike ARM MCUs, which come with a hardware buffer, AVRs require a read and
transmit buffer implemented in software. This buffer not only raises
reliability, it also allows transmitting characters from interrupt context.
*/
#define BUFSIZE 64
/** \def ASCII_XOFF
ASCII XOFF character.
*/
#define ASCII_XOFF 19
/** \def ASCII_XON
ASCII XON character.
*/
#define ASCII_XON 17
#ifndef USB_SERIAL
#if __SIZEOF_INT__ == 2
#define GET_ARG(T) (va_arg(args, T))
#elif __SIZEOF_INT__ >= 4
#define GET_ARG(T) ((T)va_arg(args, int))
#endif
/** RX buffer.
rxhead is the head pointer and points to the next available space.
rxtail is the tail pointer and points to last character in the buffer.
*/
volatile uint8_t rxhead = 0;
volatile uint8_t rxtail = 0;
volatile uint8_t rxbuf[BUFSIZE];
/** TX buffer.
Same mechanism as RX buffer.
*/
volatile uint8_t txhead = 0;
volatile uint8_t txtail = 0;
volatile uint8_t txbuf[BUFSIZE];
#include "ringbuffer.h"
#ifdef XONXOFF
#define FLOWFLAG_STATE_XOFF 0
#define FLOWFLAG_SEND_XON 1
#define FLOWFLAG_SEND_XOFF 2
#define FLOWFLAG_STATE_XON 4
// initially, send an XON
volatile uint8_t flowflags = FLOWFLAG_SEND_XON;
#endif
/** Initialise serial subsystem.
Set up baud generator and interrupts, clear buffers.
*/
void serial_init() {
#if BAUD > 38401
UCSR0A = MASK(U2X0);
UBRR0 = (((F_CPU / 8) / BAUD) - 0.5);
#else
UCSR0A = 0;
UBRR0 = (((F_CPU / 16) / BAUD) - 0.5);
#endif
UCSR0B = MASK(RXEN0) | MASK(TXEN0);
UCSR0C = MASK(URSEL) | MASK(UCSZ01) | MASK(UCSZ00) |(0<<UMSEL)|(0<<UPM1)|(0<<UPM0)|(0<<USBS)|(0<<UCSZ2);
UCSR0B |= MASK(RXCIE0) | MASK(UDRIE0);
}
/** Receive interrupt.
We have received a character, stuff it in the RX buffer if we can, or drop
it if we can't. Using the pragma inside the function is incompatible with
Arduinos' gcc.
*/
#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
#ifdef USART_RXC_vect
ISR(USART_RXC_vect)
#else
ISR(USART0_RX_vect)
#endif
{
if (buf_canwrite(rx))
buf_push(rx, UDR0);
else {
// Not reading the character makes the interrupt logic to swamp us with
// retries, so better read it and throw it away.
//#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
uint8_t trash;
//#pragma GCC diagnostic pop
trash = UDR0;
}
#ifdef XONXOFF
if (flowflags & FLOWFLAG_STATE_XON && buf_canwrite(rx) <= 16) {
// The buffer has only 16 free characters left, so send an XOFF.
// More characters might come in until the XOFF takes effect.
flowflags = FLOWFLAG_SEND_XOFF | FLOWFLAG_STATE_XON;
// Enable TX interrupt so we can send this character.
UCSR0B |= MASK(UDRIE0);
}
#endif
}
#pragma GCC diagnostic pop
/** Transmit buffer ready interrupt.
Provide the next character to transmit if we can, otherwise disable this
interrupt.
*/
#ifdef USART_UDRE_vect
ISR(USART_UDRE_vect)
#else
ISR(USART0_UDRE_vect)
#endif
{
#ifdef XONXOFF
if (flowflags & FLOWFLAG_SEND_XON) {
UDR0 = ASCII_XON;
flowflags = FLOWFLAG_STATE_XON;
}
else if (flowflags & FLOWFLAG_SEND_XOFF) {
UDR0 = ASCII_XOFF;
flowflags = FLOWFLAG_STATE_XOFF;
}
else
#endif
if (buf_canread(tx))
buf_pop(tx, UDR0);
else
UCSR0B &= ~MASK(UDRIE0);
}
/** Check how many characters can be read.
*/
uint8_t serial_rxchars() {
return buf_canread(rx);
}
/** Read one character.
*/
uint8_t serial_popchar() {
uint8_t c = 0;
// It's imperative that we check, because if the buffer is empty and we
// pop, we'll go through the whole buffer again.
if (buf_canread(rx))
buf_pop(rx, c);
#ifdef XONXOFF
if ((flowflags & FLOWFLAG_STATE_XON) == 0 && buf_canread(rx) <= 16) {
// The buffer has (BUFSIZE - 16) free characters again, so send an XON.
flowflags = FLOWFLAG_SEND_XON;
UCSR0B |= MASK(UDRIE0);
}
#endif
return c;
}
/**
Write string from FLASH.
Extensions to output flash memory pointers. This prevents the data to
become part of the .data segment instead of the .code segment. That means
less memory is consumed for multi-character writes.
For single character writes (i.e. '\n' instead of "\n"), using
serial_writechar() directly is the better choice.
*/
void serial_writestr_P(PGM_P data_P)
{
uint8_t r, i = 0;
// yes, this is *supposed* to be assignment rather than comparison, so we break when r is assigned zero
while ((r = pgm_read_byte(&data_P[i++])))
serial_writechar(r);
}
/** Send one character.
*/
void serial_writechar(uint8_t data) {
// Check if interrupts are enabled.
if (SREG & MASK(SREG_I)) {
// If they are, we should be ok to block since the tx buffer is emptied
// from an interrupt.
for ( ; buf_canwrite(tx) == 0; ) ;
buf_push(tx, data);
}
else {
// Interrupts are disabled -- maybe we're in one?
// Anyway, instead of blocking, only write if we have room.
if (buf_canwrite(tx))
buf_push(tx, data);
}
// Enable TX interrupt so we can send this character.
UCSR0B |= MASK(UDRIE0);
}
#endif /* USB_SERIAL */
void sendf_P(void (*writechar)(uint8_t), PGM_P format_P, ...) {
va_list args;
va_start(args, format_P);
uint16_t i = 0;
uint8_t c = 1, j = 0;
while ((c = pgm_read_byte(&format_P[i++]))) {
if (j) {
switch(c) {
case 's':
j = 1;
break;
case 'l':
j = 4;
break;
case 'u':
if (j == 1)
write_uint8(writechar, (uint8_t)GET_ARG(uint16_t));
else if (j == 2)
write_uint16(writechar, (uint16_t)GET_ARG(uint16_t));
else
write_uint32(writechar, GET_ARG(uint32_t));
j = 0;
break;
case 'd':
if (j == 1)
write_int8(writechar, (int8_t)GET_ARG(int16_t));
else if (j == 2)
write_int16(writechar, (int16_t)GET_ARG(int16_t));
else
write_int32(writechar, GET_ARG(int32_t));
j = 0;
break;
case 'c':
writechar((uint8_t)GET_ARG(uint16_t));
j = 0;
break;
case 'x':
writechar('0');
writechar('x');
if (j == 1)
write_hex8(writechar, (uint8_t)GET_ARG(uint16_t));
else if (j == 2)
write_hex16(writechar, (uint16_t)GET_ARG(uint16_t));
else
write_hex32(writechar, GET_ARG(uint32_t));
j = 0;
break;
/* case 'p':
serwrite_hex16(writechar, GET_ARG(uint16_t));*/
case 'q':
write_int32_vf(writechar, GET_ARG(uint32_t), 3);
j = 0;
break;
default:
writechar(c);
j = 0;
break;
}
}
else {
if (c == '%') {
j = 2;
}
else {
writechar(c);
}
}
}
va_end(args);
}

44
serial.h 100644
Wyświetl plik

@ -0,0 +1,44 @@
#ifndef _SERIAL_H
#define _SERIAL_H
#include "config.h"
#include <stdint.h>
/**
Before we had display support, all messages went to the serial link,
so this destination was hardcoded. This macro avoids changing a whole lot
of older code.
Deprecated macro? Convenience macro? Dunno.
*/
#define sersendf_P(...) sendf_P(serial_writechar, __VA_ARGS__)
void sendf_P(void (*writechar)(uint8_t), PGM_P format_P, ...);
#ifdef USB_SERIAL
#include "usb_serial.h"
#define serial_init() usb_init()
#define serial_rxchars() usb_serial_available()
#define serial_popchar() usb_serial_getchar()
#else
// initialise serial subsystem
void serial_init(void);
// return number of characters in the receive buffer,
// and number of spaces in the send buffer
uint8_t serial_rxchars(void);
// uint8_t serial_txchars(void);
// read one character
uint8_t serial_popchar(void);
// send one character
void serial_writechar(uint8_t data);
#endif /* USB_SERIAL */
void serial_writestr(uint8_t *data);
// write from flash
void serial_writestr_P(PGM_P data_P);
#endif /* _SERIAL_H */

171
simulavr_info.h 100644
Wyświetl plik

@ -0,0 +1,171 @@
/*
****************************************************************************
*
* simulavr - A simulator for the Atmel AVR family of microcontrollers.
* Copyright (C) 2013 Markus Hitter <mah@jump-ing.de>
* ELF storage strategy inspired by simavr by Michel Pollet.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*
****************************************************************************
*
* $Id$
*
* This header provides macros to embed simulator setup information into
* a compiled ELF binary.
*
* Example:
*
* Add this somewhere at the root level of your AVR code:
*
* #include "simulavr_info.h"
* SIMINFO_DEVICE("atmega644");
* SIMINFO_CPUFREQUENCY(F_CPU);
*
* Then link as usual, but add these linker flags to avr-gcc to prohibit
* the linker from removing the info sections at the link stage:
*
* -Wl,--section-start=.siminfo=0x900000
* -u siminfo_device
* -u siminfo_cpufrequency
* -u siminfo_serial_in
* -u siminfo_serial_out
*
* The value choosen here to be 0x900000 can be choosen freely, but must
* be above 0x840400, else it can conflict with program / eeprom / fuses /
* lockbits / signature data, see ELFLoad() in src/avrreadelf.cpp, line 215ff.
*
* Having this done, running the ELF binary in the simulator will
* automatically inform simulavr for which AVR variant and CPU frequency
* the binary was built, making the corresponding command line parameters
* obsolete. In case you give both, in-binary and CLI parameters, CLI
* parameters take precedence.
*
* The really nice thing about this mechanism is, it doesn't alter the
* executed binary at all. You can upload and run this on real hardware,
* not a single byte of Flash memory or a single CPU cycle at runtime wasted.
*/
#ifndef __SIMULAVR_INFO_H__
#define __SIMULAVR_INFO_H__
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
#define SIMINFO_SECTION __attribute__((used)) __attribute__((section(".siminfo")))
enum {
SIMINFO_TAG_NOTAG = 0, // keep this unused as a protection against empty data
SIMINFO_TAG_DEVICE,
SIMINFO_TAG_CPUFREQUENCY,
SIMINFO_TAG_SERIAL_OUT,
SIMINFO_TAG_SERIAL_IN,
};
struct siminfo_long_t {
uint8_t tag;
uint8_t length;
uint32_t value;
} __attribute__((__packed__));
struct siminfo_string_t {
uint8_t tag;
uint8_t length;
char string[9];
} __attribute__((__packed__));
struct siminfo_serial_t {
uint8_t tag;
uint8_t length;
char pin[3];
uint32_t baudrate;
char filename[2];
} __attribute__((__packed__));
/*
* This gives the device type, like "attiny45", "atmega128", "atmega644", etc.
*/
#define SIMINFO_DEVICE(name) \
const struct siminfo_string_t siminfo_device SIMINFO_SECTION = { \
SIMINFO_TAG_DEVICE, \
/* We could use sizeof(siminfo_device) here, but avr-gcc has \
been seen to set length to 0 (zero), then. */ \
sizeof(name) + 2, \
name \
}
/*
* This gives the cpu frequency, like 8000000UL or 16000000UL.
*/
#define SIMINFO_CPUFREQUENCY(value) \
const struct siminfo_long_t siminfo_cpufrequency SIMINFO_SECTION = { \
SIMINFO_TAG_CPUFREQUENCY, \
sizeof(uint32_t) + 2, \
value \
}
/*
* Create a serial in (Rx, to AVR) component. The the sent characters/bytes
* will be taken from the given file. This component can be connected to the
* same file as a serial out, if it's a special file like a real serial device
* or a pipe. Connecting both to the same regular file will mess things up.
*
* Using "-" as file name means connecting to the console (stdin/stdout).
*
* The pin to connect is named by a 2-character string, where "E2" means
* pin 2 on port E.
*
* Why a baud rate? Well, the component doesn't just write to the UART receive
* register, but synthesizes actual serial signals on the pin, which in turn
* should be interpreted by your AVR code. If your code sets a baud rate not
* matching the one given here, serial communications won't work. Just like a
* real serial device configured to work at 19200 baud won't work on a real
* serial port set to something else.
*
* Other parameters are fixed to 8N1, which means 8 bits, no parity, 1 stop bit.
*/
#define SIMINFO_SERIAL_IN(pin, filename, baudrate) \
const struct siminfo_serial_t siminfo_serial_in SIMINFO_SECTION = { \
SIMINFO_TAG_SERIAL_IN, \
sizeof(char[3]) + sizeof(uint32_t) + sizeof(filename) + 2, \
pin, \
baudrate, \
filename \
}
/*
* Create a serial out (Tx, from AVR) component. Same as above, but the
* other direction. The serial port pin is continuously read and interpreted.
*/
#define SIMINFO_SERIAL_OUT(pin, filename, baudrate) \
const struct siminfo_serial_t siminfo_serial_out SIMINFO_SECTION = { \
SIMINFO_TAG_SERIAL_OUT, \
sizeof(char[3]) + sizeof(uint32_t) + sizeof(filename) + 2, \
pin, \
baudrate, \
filename \
}
#ifdef __cplusplus
};
#endif
#endif /* __SIMULAVR_INFO_H__ */

268
timer-avr.cpp 100644
Wyświetl plik

@ -0,0 +1,268 @@
/** \file
\brief Timer management, AVR and simulator specific part.
To be included from timer.c.
Teacup uses timer1 to generate both step pulse clock and system clock.
We achieve this by using the output compare registers to generate the two clocks while the timer free-runs.
Teacup has tried numerous timer management methods, and this is the best so far.
*/
//#if defined TEACUP_C_INCLUDE && (defined __AVR__ || defined SIMULATOR)
#include "config.h"
#include "pinio.h"
//#include "clock.h"
//#include "cpu.h"
//#include "memory_barrier.h"
#ifdef MOTHERBOARD
#include "queue.h"
#endif
/**
Time until next step, as output compare register is too small for long
step times.
*/
uint32_t next_step_time;
/** System clock interrupt.
Comparator B is the system clock, happens every TICK_TIME.
*/
ISR(TIMER1_COMPB_vect) {
static volatile uint8_t busy = 0;
// set output compare register to the next clock tick
OCR1B = (OCR1B + TICK_TIME) & 0xFFFF;
//clock_tick();
/**
Lengthy calculations ahead! Make sure we didn't re-enter, then allow
nested interrupts.
*/
if ( ! busy) {
busy = 1;
sei();
dda_clock();
busy = 0;
}
}
#ifdef MOTHERBOARD
/** Step interrupt.
Comparator A is the step timer. It has higher priority then B.
*/
ISR(TIMER1_COMPA_vect) {
// Check if this is a real step, or just a next_step_time "overflow"
if (next_step_time < 65536) {
// step!
#ifdef DEBUG_LED_PIN
WRITE(DEBUG_LED_PIN, 1);
#endif
// disable this interrupt. if we set a new timeout, it will be re-enabled when appropriate
TIMSK &= ~MASK(OCIE1A);
// stepper tick
queue_step();
// led off
#ifdef DEBUG_LED_PIN
WRITE(DEBUG_LED_PIN, 0);
#endif
return;
}
next_step_time -= 65536;
// Similar algorithm as described in timer_set() below.
if (next_step_time < 65536) {
OCR1A = (OCR1A + next_step_time) & 0xFFFF;
} else if(next_step_time < 75536){
OCR1A = (OCR1A - 10000) & 0xFFFF;
next_step_time += 10000;
}
// leave OCR1A as it was
}
#endif /* ifdef MOTHERBOARD */
/** Timer initialisation.
Initialise timer and enable system clock interrupt. Step interrupt is
enabled later, when we start using it.
*/
void timer_init() {
// no outputs
TCCR1A = 0;
// Normal Mode
TCCR1B = MASK(CS10);
// set up "clock" comparator for first tick
OCR1B = TICK_TIME & 0xFFFF;
// enable interrupt
TIMSK = MASK(OCIE1B);
#ifdef SIMULATOR
// Tell simulator
sim_timer_set();
#endif
}
#ifdef MOTHERBOARD
/** Specify how long until the step timer should fire.
\param delay Delay for the next step interrupt, in CPU ticks.
\param check_short Tell whether to check for impossibly short requests. This
should be set to 1 for calls from the step interrupt. Short requests
then return 1 and do not schedule a timer interrupt. The calling code
usually wants to handle this case.
Calls from elsewhere should set it to 0. In this case a timer
interrupt is always scheduled.
\return A flag whether the requested time was too short to allow scheduling
an interrupt. This is meaningful for ACCELERATION_TEMPORAL, where
requested delays can be zero or even negative. In this case, the
calling code should repeat the stepping code immediately and also
assume the timer to not change his idea of when the last step
happened.
Strategy of this timer is to schedule timer interrupts not starting at the
time of the call, but starting at the time of the previous timer interrupt
fired. This ignores the processing time taken in the step interrupt so far,
offering smooth and even step distribution. Flipside of this coin is,
one has to call timer_reset() before scheduling a step at an arbitrary time.
This enables the step interrupt, but also disables interrupts globally.
So, if you use it from inside the step interrupt, make sure to do so
as late as possible. If you use it from outside the step interrupt,
do a sei() after it to make the interrupt actually fire.
*/
uint8_t timer_set(int32_t delay, uint8_t check_short) {
uint16_t step_start = 0;
// An interrupt would make all our timing calculations invalid,
// so stop that here.
cli();
CLI_SEI_BUG_MEMORY_BARRIER();
// Assume all steps belong to one move. Within one move the delay is
// from one step to the next one, which should be more or less the same
// as from one step interrupt to the next one. The last step interrupt happend
// at OCR1A, so start delay from there.
step_start = OCR1A;
next_step_time = delay;
// From here on we assume the requested delay is long enough to allow
// completion of the current interrupt before the next one is about to
// happen.
// Now we know how long we actually want to delay, so set the timer.
if (next_step_time < 65536) {
// set the comparator directly to the next real step
OCR1A = (next_step_time + step_start) & 0xFFFF;
}
else if (next_step_time < 75536) {
// Next comparator interrupt would have to trigger another
// interrupt within a short time (possibly within 1 cycle).
// Avoid the impossible by firing the interrupt earlier.
OCR1A = (step_start - 10000) & 0xFFFF;
next_step_time += 10000;
}
else {
OCR1A = step_start;
}
// Enable this interrupt, but only do it after disabling
// global interrupts (see above). This will cause push any possible
// timer1a interrupt to the far side of the return, protecting the
// stack from recursively clobbering memory.
TIMSK |= MASK(OCIE1A);
#ifdef SIMULATOR
// Tell simulator
sim_timer_set();
#endif
return 0;
}
/** Timer reset.
Reset the timer, so step interrupts scheduled at an arbitrary point in time
don't lead to a full round through the timer counter.
On AVR we simply do nothing, such a full round through the timer is just
2^16 / F_CPU = 3 to 4 milliseconds.
*/
void timer_reset() {
}
/** Stop timers.
This means to be an emergency stop.
*/
void timer_stop() {
// disable all interrupts
TIMSK = 0;
#ifdef SIMULATOR
// Tell simulator
sim_timer_stop();
#endif
}
#endif /* ifdef MOTHERBOARD */
//#endif /* defined TEACUP_C_INCLUDE && (defined __AVR__ || defined SIMULATOR) */
#include <avr/io.h>
/** Initialise the CPU.
This sets up the CPU the way we need it. It disables modules we don't use,
so they don't mess on the I/O pins they're connected to.
*/
void cpu_init() {
#ifdef PRR
#if defined I2C && defined SPI
PRR = MASK(PRADC);
#elif defined SPI
PRR = MASK(PRADC) | MASK(PRTWI);
#elif defined I2C
PRR = MASK(PRADC) | MASK(PRSPI);
#else
PRR = MASK(PRADC) | MASK(PRTWI) | MASK(PRSPI);
#endif
#elif defined PRR0
#if defined I2C && defined SPI
PRR0 = MASK(PRADC);
#elif defined SPI
PRR0 = MASK(PRADC) | MASK(PRTWI);
#elif defined I2C
PRR0 = MASK(PRADC) | MASK(PRSPI);
#else
PRR0 = MASK(PRADC) | MASK(PRTWI) | MASK(PRSPI);
#endif
#if defined(PRUSART3)
// Don't use USART2 or USART3. Leave USART1 for GEN3 and derivatives.
PRR1 |= MASK(PRUSART3) | MASK(PRUSART2);
#endif
#if defined(PRUSART2)
// Don't use USART2 or USART3. Leave USART1 for GEN3 and derivatives.
PRR1 |= MASK(PRUSART2);
#endif
#endif
ACSR = MASK(ACD);
}

91
timer.h 100644
Wyświetl plik

@ -0,0 +1,91 @@
#ifndef _TIMER_H
#define _TIMER_H
#include <stdint.h>
//#include "arduino.h" // For F_CPU on ARM.
// time-related constants
#define US * (F_CPU / 1000000)
#define MS * (F_CPU / 1000)
/// How often we overflow and update our clock.
/// With F_CPU = 16MHz, max is < 4.096ms (TICK_TIME = 65535).
#define TICK_TIME (2 MS)
/// Convert back to ms from cpu ticks so our system clock runs
/// properly if you change TICK_TIME.
#define TICK_TIME_MS (TICK_TIME / (F_CPU / 1000))
#if defined __AVR__
#include <avr/version.h>
// Provide a memory barrier to the compiler. This informs
// the compiler that is should write any cached values that
// are destined for a global variable and discard any other
// cached values from global variables.
//
// Note that this behavior does apply to all global variables,
// not just volatile ones. However, cached local variables
// are not affected as they are not externally visible.
#define MEMORY_BARRIER() __asm volatile( "" ::: "memory" )
// There is a bug in the CLI/SEI functions in older versions of
// avr-libc - they should be defined to include a memory barrier.
// This macro is used to define the barrier in the code so that
// it will be easy to remove once the bug has become ancient history.
// At the moment the bug is included in most of the distributed
// compilers.
#if __AVR_LIBC_VERSION__ < 10700UL
#define CLI_SEI_BUG_MEMORY_BARRIER() MEMORY_BARRIER()
#else
#define CLI_SEI_BUG_MEMORY_BARRIER()
#endif
#define ATOMIC_START { \
uint8_t save_reg = SREG; \
cli(); \
CLI_SEI_BUG_MEMORY_BARRIER();
#define ATOMIC_END MEMORY_BARRIER(); \
SREG = save_reg; \
}
#elif defined __ARMEL__
#define ATOMIC_START cli();
#define ATOMIC_END sei();
#define MEMORY_BARRIER()
#elif defined SIMULATOR
#define CLI_SEI_BUG_MEMORY_BARRIER()
#define MEMORY_BARRIER()
#define ATOMIC_START { \
uint8_t save_reg = sim_interrupts; \
cli();
#define ATOMIC_END MEMORY_BARRIER(); \
if (save_reg) sei(); \
}
#endif /* __AVR__, __ARMEL__, SIMULATOR */
void timer_init(void);
uint8_t timer_set(int32_t delay, uint8_t check_short);
void timer_reset(void);
void timer_stop(void);
// Should be called every TICK_TIME (currently 2 ms).
//void clock_tick(void);
//void clock(void);
void cpu_init();
#endif /* _TIMER_H */