Merge branch 'master' of git@github.com:triffid/FiveD_on_Arduino
Conflicts: gcode.c
This commit is contained in:
commit
a0543d3329
2
Makefile
2
Makefile
|
|
@ -14,7 +14,7 @@
|
||||||
|
|
||||||
PROGRAM = mendel
|
PROGRAM = mendel
|
||||||
|
|
||||||
SOURCES = $(PROGRAM).c serial.c dda.c gcode.c timer.c clock.c temp.c sermsg.c dda_queue.c watchdog.c debug.c sersendf.c heater.c analog.c
|
SOURCES = $(PROGRAM).c serial.c dda.c gcode.c timer.c clock.c temp.c sermsg.c dda_queue.c watchdog.c debug.c sersendf.c heater.c analog.c delay.c
|
||||||
|
|
||||||
##############################################################################
|
##############################################################################
|
||||||
# #
|
# #
|
||||||
|
|
|
||||||
|
|
@ -8,6 +8,7 @@
|
||||||
#include "serial.h"
|
#include "serial.h"
|
||||||
#include "sermsg.h"
|
#include "sermsg.h"
|
||||||
#include "temp.h"
|
#include "temp.h"
|
||||||
|
#include "delay.h"
|
||||||
|
|
||||||
uint8_t mb_head = 0;
|
uint8_t mb_head = 0;
|
||||||
uint8_t mb_tail = 0;
|
uint8_t mb_tail = 0;
|
||||||
|
|
|
||||||
|
|
@ -0,0 +1,50 @@
|
||||||
|
#include "delay.h"
|
||||||
|
|
||||||
|
#include "watchdog.h"
|
||||||
|
|
||||||
|
// delay( microseconds )
|
||||||
|
void delay(uint32_t delay) {
|
||||||
|
wd_reset();
|
||||||
|
while (delay > 65535) {
|
||||||
|
delayMicrosecondsInterruptible(65533);
|
||||||
|
delay -= 65535;
|
||||||
|
wd_reset();
|
||||||
|
}
|
||||||
|
delayMicrosecondsInterruptible(delay & 0xFFFF);
|
||||||
|
wd_reset();
|
||||||
|
}
|
||||||
|
|
||||||
|
// delay_ms( milliseconds )
|
||||||
|
void delay_ms(uint32_t delay) {
|
||||||
|
wd_reset();
|
||||||
|
while (delay > 65) {
|
||||||
|
delayMicrosecondsInterruptible(64999);
|
||||||
|
delay -= 65;
|
||||||
|
wd_reset();
|
||||||
|
}
|
||||||
|
delayMicrosecondsInterruptible(delay * 1000);
|
||||||
|
wd_reset();
|
||||||
|
}
|
||||||
|
|
||||||
|
void delayMicrosecondsInterruptible(uint16_t us)
|
||||||
|
{
|
||||||
|
// for a one-microsecond delay, simply return. the overhead
|
||||||
|
// of the function call yields a delay of approximately 1 1/8 us.
|
||||||
|
if (--us == 0)
|
||||||
|
return;
|
||||||
|
|
||||||
|
// the following loop takes a quarter of a microsecond (4 cycles)
|
||||||
|
// per iteration, so execute it four times for each microsecond of
|
||||||
|
// delay requested.
|
||||||
|
us <<= 2;
|
||||||
|
|
||||||
|
// account for the time taken in the preceeding commands.
|
||||||
|
us -= 2;
|
||||||
|
|
||||||
|
// busy wait
|
||||||
|
__asm__ __volatile__ ("1: sbiw %0,1" "\n\t" // 2 cycles
|
||||||
|
"brne 1b" :
|
||||||
|
"=w" (us) :
|
||||||
|
"0" (us) // 2 cycles
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
@ -0,0 +1,13 @@
|
||||||
|
#ifndef _DELAY_H
|
||||||
|
#define _DELAY_H
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
void delay(uint32_t delay);
|
||||||
|
|
||||||
|
void delay_ms(uint32_t delay);
|
||||||
|
|
||||||
|
#define delay_us(d) delayMicrosecondsInterruptible(d)
|
||||||
|
void delayMicrosecondsInterruptible(unsigned int us);
|
||||||
|
|
||||||
|
#endif /* _DELAY_H */
|
||||||
20
gcode.c
20
gcode.c
|
|
@ -14,6 +14,7 @@
|
||||||
#include "debug.h"
|
#include "debug.h"
|
||||||
#include "heater.h"
|
#include "heater.h"
|
||||||
#include "sersendf.h"
|
#include "sersendf.h"
|
||||||
|
#include "delay.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Switch user friendly values to coding friendly values
|
Switch user friendly values to coding friendly values
|
||||||
|
|
@ -669,18 +670,26 @@ void process_gcode_command(GCODE_COMMAND *gcmd) {
|
||||||
// M190- power on
|
// M190- power on
|
||||||
case 190:
|
case 190:
|
||||||
power_on();
|
power_on();
|
||||||
#ifdef GEN3
|
#ifdef X_ENABLE_PIN
|
||||||
WRITE(X_ENABLE_PIN, 0);
|
WRITE(X_ENABLE_PIN, 0);
|
||||||
WRITE(Y_ENABLE_PIN, 0);
|
|
||||||
WRITE(Z_ENABLE_PIN, 0);
|
|
||||||
steptimeout = 0;
|
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef Y_ENABLE_PIN
|
||||||
|
WRITE(Y_ENABLE_PIN, 0);
|
||||||
|
#endif
|
||||||
|
#ifdef Z_ENABLE_PIN
|
||||||
|
WRITE(Z_ENABLE_PIN, 0);
|
||||||
|
#endif
|
||||||
|
steptimeout = 0;
|
||||||
break;
|
break;
|
||||||
// M191- power off
|
// M191- power off
|
||||||
case 191:
|
case 191:
|
||||||
#ifdef GEN3
|
#ifdef X_ENABLE_PIN
|
||||||
WRITE(X_ENABLE_PIN, 1);
|
WRITE(X_ENABLE_PIN, 1);
|
||||||
|
#endif
|
||||||
|
#ifdef Y_ENABLE_PIN
|
||||||
WRITE(Y_ENABLE_PIN, 1);
|
WRITE(Y_ENABLE_PIN, 1);
|
||||||
|
#endif
|
||||||
|
#ifdef Z_ENABLE_PIN
|
||||||
WRITE(Z_ENABLE_PIN, 1);
|
WRITE(Z_ENABLE_PIN, 1);
|
||||||
#endif
|
#endif
|
||||||
power_off();
|
power_off();
|
||||||
|
|
@ -780,7 +789,6 @@ void request_resend(void) {
|
||||||
#else
|
#else
|
||||||
serial_writestr_P(PSTR("Resend:"));
|
serial_writestr_P(PSTR("Resend:"));
|
||||||
#endif
|
#endif
|
||||||
serial_writestr_P(PSTR("rs "));
|
|
||||||
serwrite_uint8(next_target.N);
|
serwrite_uint8(next_target.N);
|
||||||
serial_writechar('\n');
|
serial_writechar('\n');
|
||||||
}
|
}
|
||||||
|
|
|
||||||
47
timer.c
47
timer.c
|
|
@ -102,50 +102,3 @@ void setTimer(uint32_t delay)
|
||||||
setTimerCeiling(getTimerCeiling(delay)); // set timeout
|
setTimerCeiling(getTimerCeiling(delay)); // set timeout
|
||||||
setTimerResolution(getTimerResolution(delay)); // restart timer with proper prescaler
|
setTimerResolution(getTimerResolution(delay)); // restart timer with proper prescaler
|
||||||
}
|
}
|
||||||
|
|
||||||
// delay( microseconds )
|
|
||||||
void delay(uint32_t delay) {
|
|
||||||
wd_reset();
|
|
||||||
while (delay > 65535) {
|
|
||||||
delayMicrosecondsInterruptible(65533);
|
|
||||||
delay -= 65535;
|
|
||||||
wd_reset();
|
|
||||||
}
|
|
||||||
delayMicrosecondsInterruptible(delay & 0xFFFF);
|
|
||||||
wd_reset();
|
|
||||||
}
|
|
||||||
|
|
||||||
// delay_ms( milliseconds )
|
|
||||||
void delay_ms(uint32_t delay) {
|
|
||||||
wd_reset();
|
|
||||||
while (delay > 65) {
|
|
||||||
delayMicrosecondsInterruptible(64999);
|
|
||||||
delay -= 65;
|
|
||||||
wd_reset();
|
|
||||||
}
|
|
||||||
delayMicrosecondsInterruptible(delay * 1000);
|
|
||||||
wd_reset();
|
|
||||||
}
|
|
||||||
|
|
||||||
void delayMicrosecondsInterruptible(uint16_t us)
|
|
||||||
{
|
|
||||||
// for a one-microsecond delay, simply return. the overhead
|
|
||||||
// of the function call yields a delay of approximately 1 1/8 us.
|
|
||||||
if (--us == 0)
|
|
||||||
return;
|
|
||||||
|
|
||||||
// the following loop takes a quarter of a microsecond (4 cycles)
|
|
||||||
// per iteration, so execute it four times for each microsecond of
|
|
||||||
// delay requested.
|
|
||||||
us <<= 2;
|
|
||||||
|
|
||||||
// account for the time taken in the preceeding commands.
|
|
||||||
us -= 2;
|
|
||||||
|
|
||||||
// busy wait
|
|
||||||
__asm__ __volatile__ ("1: sbiw %0,1" "\n\t" // 2 cycles
|
|
||||||
"brne 1b" :
|
|
||||||
"=w" (us) :
|
|
||||||
"0" (us) // 2 cycles
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
|
||||||
7
timer.h
7
timer.h
|
|
@ -21,13 +21,6 @@ uint16_t getTimerCeiling(const uint32_t delay);
|
||||||
|
|
||||||
void setTimer(uint32_t delay);
|
void setTimer(uint32_t delay);
|
||||||
|
|
||||||
void delay(uint32_t delay);
|
|
||||||
|
|
||||||
void delay_ms(uint32_t delay);
|
|
||||||
|
|
||||||
#define delay_us(d) delayMicrosecondsInterruptible(d)
|
|
||||||
void delayMicrosecondsInterruptible(unsigned int us);
|
|
||||||
|
|
||||||
#define enableTimerInterrupt() do { TIMSK1 |= (1<<OCIE1A); } while (0)
|
#define enableTimerInterrupt() do { TIMSK1 |= (1<<OCIE1A); } while (0)
|
||||||
#define disableTimerInterrupt() do { TIMSK1 &= ~(1<<OCIE1A); } while (0)
|
#define disableTimerInterrupt() do { TIMSK1 &= ~(1<<OCIE1A); } while (0)
|
||||||
#define timerInterruptIsEnabled() (TIMSK1 & (1 << OCIE1A))
|
#define timerInterruptIsEnabled() (TIMSK1 & (1 << OCIE1A))
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue