replace symlinks with hardlinks because windows is stupid, will make future commits look messier than necessary

This commit is contained in:
Michael Moon 2010-12-13 20:09:04 +11:00
parent 5dfd76a718
commit eaf8a9dcec
16 changed files with 1702 additions and 16 deletions

View File

@ -1 +0,0 @@
../analog.c

103
extruder/analog.c Normal file
View File

@ -0,0 +1,103 @@
#include "analog.h"
#include <avr/interrupt.h>
#ifndef ANALOG_MASK
#warning ANALOG_MASK not defined - analog subsystem disabled
#define ANALOG_MASK 0
#endif
uint8_t adc_running_mask, adc_counter;
#if ANALOG_MASK & 2
#define ANALOG_START 1
#define ANALOG_START_MASK 2
#elif ANALOG_MASK & 4
#define ANALOG_START 2
#define ANALOG_START_MASK 4
#elif ANALOG_MASK & 8
#define ANALOG_START 3
#define ANALOG_START_MASK 8
#elif ANALOG_MASK & 16
#define ANALOG_START 4
#define ANALOG_START_MASK 16
#elif ANALOG_MASK & 32
#define ANALOG_START 5
#define ANALOG_START_MASK 32
#elif ANALOG_MASK & 64
#define ANALOG_START 6
#define ANALOG_START_MASK 64
#elif ANALOG_MASK & 128
#define ANALOG_START 7
#define ANALOG_START_MASK 128
#else
// ANALOG_MASK == 1 or 0, either way defines are the same except they're not used if ANALOG_MASK == 0
#define ANALOG_START 0
#define ANALOG_START_MASK 1
#endif
volatile uint16_t adc_result[8] __attribute__ ((__section__ (".bss")));
void analog_init() {
#if ANALOG_MASK > 0
#ifdef PRR
PRR &= ~MASK(PRADC);
#elif defined PRR0
PRR0 &= ~MASK(PRADC);
#endif
ADMUX = REFERENCE;
// ADC frequency must be less than 200khz or we lose precision. At 16MHz system clock, we must use the full prescale value of 128 to get an ADC clock of 125khz.
ADCSRA = MASK(ADEN) | MASK(ADPS2) | MASK(ADPS1) | MASK(ADPS0);
adc_counter = 0;
adc_running_mask = 1;
AIO0_DDR &= ANALOG_MASK;
DIDR0 = ANALOG_MASK & 0x3F;
// now we start the first conversion and leave the rest to the interrupt
ADCSRA |= MASK(ADIE) | MASK(ADSC);
#endif /* ANALOG_MASK > 0 */
}
ISR(ADC_vect, ISR_NOBLOCK) {
// emulate free-running mode but be more deterministic about exactly which result we have, since this project has long-running interrupts
adc_result[ADMUX & 0x0F] = ADC;
// find next channel
do {
adc_counter++;
adc_running_mask <<= 1;
if (adc_counter == 8) {
adc_counter = ANALOG_START;
adc_running_mask = ANALOG_START_MASK;
}
} while ((adc_running_mask & ANALOG_MASK) == 0);
// start next conversion
ADMUX = (adc_counter) | REFERENCE;
ADCSRA |= MASK(ADSC);
}
uint16_t analog_read(uint8_t channel) {
#if ANALOG_MASK > 0
uint16_t r;
uint8_t sreg;
// save interrupt flag
sreg = SREG;
// disable interrupts
cli();
// atomic 16-bit copy
r = adc_result[channel];
// restore interrupt flag
SREG = sreg;
return r;
#else
return 0;
#endif
}

View File

@ -1 +0,0 @@
../analog.h

31
extruder/analog.h Normal file
View File

@ -0,0 +1,31 @@
#ifndef _ANALOG_H
#define _ANALOG_H
#include <stdint.h>
#define REFERENCE_AREF 0
#define REFERENCE_AVCC 64
#if defined (__AVR_ATmega168__) || defined (__AVR_ATmega328__) || defined (__AVR_ATmega328P__)
#define REFERENCE_1V1 192
#elif defined (__AVR_ATmega_644__) || defined (__AVR_ATmega644p__)
#define REFERENCE_1V1 128
#define REFERENCE_2V56 192
#endif
#include "config.h"
#ifndef REFERENCE
#warning define REFERENCE as one of
#if defined (__AVR_ATmega168__) || defined (__AVR_ATmega328__) || defined (__AVR_ATmega328P__)
#warning REFERENCE_AREF, REFERENCE_AVCC or REFERENCE_1V1
#elif defined (__AVR_ATmega_644__) || defined (__AVR_ATmega644p__)
#warning REFERENCE_AREF, REFERENCE_AVCC, REFERENCE_1V1 or REFERENCE_2V56
#endif
#warning in your config.h
#error REFERENCE undefined
#endif
void analog_init(void);
uint16_t analog_read(uint8_t channel);
#endif /* _ANALOG_H */

View File

@ -1 +0,0 @@
../arduino.h

64
extruder/arduino.h Normal file
View File

@ -0,0 +1,64 @@
#ifndef _ARDUINO_H
#define _ARDUINO_H
#include <avr/io.h>
/*
utility functions
*/
#ifndef MASK
#define MASK(PIN) (1 << PIN)
#endif
/*
magic I/O routines
now you can simply SET_OUTPUT(STEP); WRITE(STEP, 1); WRITE(STEP, 0);
*/
#define _READ(IO) (IO ## _RPORT & MASK(IO ## _PIN))
#define _WRITE(IO, v) do { if (v) { IO ## _WPORT |= MASK(IO ## _PIN); } else { IO ## _WPORT &= ~MASK(IO ## _PIN); }; } while (0)
#define _TOGGLE(IO) do { IO ## _RPORT = MASK(IO ## _PIN); } while (0)
#define _SET_INPUT(IO) do { IO ## _DDR &= ~MASK(IO ## _PIN); } while (0)
#define _SET_OUTPUT(IO) do { IO ## _DDR |= MASK(IO ## _PIN); } while (0)
#define _GET_INPUT(IO) ((IO ## _DDR & MASK(IO ## _PIN)) == 0)
#define _GET_OUTPUT(IO) ((IO ## _DDR & MASK(IO ## _PIN)) != 0)
// why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
#define READ(IO) _READ(IO)
#define WRITE(IO, v) _WRITE(IO, v)
#define TOGGLE(IO) _TOGGLE(IO)
#define SET_INPUT(IO) _SET_INPUT(IO)
#define SET_OUTPUT(IO) _SET_OUTPUT(IO)
#define GET_INPUT(IO) _GET_INPUT(IO)
#define GET_OUTPUT(IO) _GET_OUTPUT(IO)
/*
ports and functions
added as necessary or if I feel like it- not a comprehensive list!
*/
#if defined (__AVR_ATmega168__) || defined (__AVR_ATmega328__) || defined (__AVR_ATmega328P__)
#include "arduino_168_328p.h"
#endif /* _AVR_ATmega{168,328,328P}__ */
#if defined (__AVR_ATmega644__) || defined (__AVR_ATmega644P__) || defined (__AVR_ATmega644PA__)
#include "arduino_644.h"
#endif /* _AVR_ATmega{644,644P,644PA}__ */
#if defined (__AVR_ATmega1280__)
#include "arduino_1280.h"
#endif /* __AVR_ATmega1280__ */
#ifndef DIO0_PIN
#error pins for this chip not defined in arduino.h! If you write an appropriate pin definition and have this firmware work on your chip, please tell us via the forum thread
#endif
#endif /* _ARDUINO_H */

View File

@ -1 +0,0 @@
../arduino_168_328p.h

226
extruder/arduino_168_328p.h Normal file
View File

@ -0,0 +1,226 @@
// UART
#define RXD DIO0
#define TXD DIO1
// SPI
#define SCK DIO13
#define MISO DIO12
#define MOSI DIO11
#define SS DIO10
// TWI (I2C)
#define SCL AIO5
#define SDA AIO4
// timers and PWM
#define OC0A DIO6
#define OC0B DIO5
#define OC1A DIO9
#define OC1B DIO10
#define OC2A DIO11
#define OC2B DIO3
#define DEBUG_LED AIO5
/*
pins
*/
#define DIO0_PIN PIND0
#define DIO0_RPORT PIND
#define DIO0_WPORT PORTD
#define DIO0_DDR DDRD
#define DIO1_PIN PIND1
#define DIO1_RPORT PIND
#define DIO1_WPORT PORTD
#define DIO1_DDR DDRD
#define DIO2_PIN PIND2
#define DIO2_RPORT PIND
#define DIO2_WPORT PORTD
#define DIO2_DDR DDRD
#define DIO3_PIN PIND3
#define DIO3_RPORT PIND
#define DIO3_WPORT PORTD
#define DIO3_DDR DDRD
#define DIO4_PIN PIND4
#define DIO4_RPORT PIND
#define DIO4_WPORT PORTD
#define DIO4_DDR DDRD
#define DIO5_PIN PIND5
#define DIO5_RPORT PIND
#define DIO5_WPORT PORTD
#define DIO5_DDR DDRD
#define DIO6_PIN PIND6
#define DIO6_RPORT PIND
#define DIO6_WPORT PORTD
#define DIO6_DDR DDRD
#define DIO7_PIN PIND7
#define DIO7_RPORT PIND
#define DIO7_WPORT PORTD
#define DIO7_DDR DDRD
#define DIO8_PIN PINB0
#define DIO8_RPORT PINB
#define DIO8_WPORT PORTB
#define DIO8_DDR DDRB
#define DIO9_PIN PINB1
#define DIO9_RPORT PINB
#define DIO9_WPORT PORTB
#define DIO9_DDR DDRB
#define DIO10_PIN PINB2
#define DIO10_RPORT PINB
#define DIO10_WPORT PORTB
#define DIO10_DDR DDRB
#define DIO11_PIN PINB3
#define DIO11_RPORT PINB
#define DIO11_WPORT PORTB
#define DIO11_DDR DDRB
#define DIO12_PIN PINB4
#define DIO12_RPORT PINB
#define DIO12_WPORT PORTB
#define DIO12_DDR DDRB
#define DIO13_PIN PINB5
#define DIO13_RPORT PINB
#define DIO13_WPORT PORTB
#define DIO13_DDR DDRB
#define AIO0_PIN PINC0
#define AIO0_RPORT PINC
#define AIO0_WPORT PORTC
#define AIO0_DDR DDRC
#define AIO1_PIN PINC1
#define AIO1_RPORT PINC
#define AIO1_WPORT PORTC
#define AIO1_DDR DDRC
#define AIO2_PIN PINC2
#define AIO2_RPORT PINC
#define AIO2_WPORT PORTC
#define AIO2_DDR DDRC
#define AIO3_PIN PINC3
#define AIO3_RPORT PINC
#define AIO3_WPORT PORTC
#define AIO3_DDR DDRC
#define AIO4_PIN PINC4
#define AIO4_RPORT PINC
#define AIO4_WPORT PORTC
#define AIO4_DDR DDRC
#define AIO5_PIN PINC5
#define AIO5_RPORT PINC
#define AIO5_WPORT PORTC
#define AIO5_DDR DDRC
#define PB0_PIN PINB0
#define PB0_RPORT PINB
#define PB0_WPORT PORTB
#define PB0_DDR DDRB
#define PB1_PIN PINB1
#define PB1_RPORT PINB
#define PB1_WPORT PORTB
#define PB1_DDR DDRB
#define PB2_PIN PINB2
#define PB2_RPORT PINB
#define PB2_WPORT PORTB
#define PB2_DDR DDRB
#define PB3_PIN PINB3
#define PB3_RPORT PINB
#define PB3_WPORT PORTB
#define PB3_DDR DDRB
#define PB4_PIN PINB4
#define PB4_RPORT PINB
#define PB4_WPORT PORTB
#define PB4_DDR DDRB
#define PB5_PIN PINB5
#define PB5_RPORT PINB
#define PB5_WPORT PORTB
#define PB5_DDR DDRB
#define PB6_PIN PINB6
#define PB6_RPORT PINB
#define PB6_WPORT PORTB
#define PB6_DDR DDRB
#define PB7_PIN PINB7
#define PB7_RPORT PINB
#define PB7_WPORT PORTB
#define PB7_DDR DDRB
#define PC0_PIN PINC0
#define PC0_RPORT PINC
#define PC0_WPORT PORTC
#define PC0_DDR DDRC
#define PC1_PIN PINC1
#define PC1_RPORT PINC
#define PC1_WPORT PORTC
#define PC1_DDR DDRC
#define PC2_PIN PINC2
#define PC2_RPORT PINC
#define PC2_WPORT PORTC
#define PC2_DDR DDRC
#define PC3_PIN PINC3
#define PC3_RPORT PINC
#define PC3_WPORT PORTC
#define PC3_DDR DDRC
#define PC4_PIN PINC4
#define PC4_RPORT PINC
#define PC4_WPORT PORTC
#define PC4_DDR DDRC
#define PC5_PIN PINC5
#define PC5_RPORT PINC
#define PC5_WPORT PORTC
#define PC5_DDR DDRC
#define PC6_PIN PINC6
#define PC6_RPORT PINC
#define PC6_WPORT PORTC
#define PC6_DDR DDRC
#define PC7_PIN PINC7
#define PC7_RPORT PINC
#define PC7_WPORT PORTC
#define PC7_DDR DDRC
#define PD0_PIN PIND0
#define PD0_RPORT PIND
#define PD0_WPORT PORTD
#define PD0_DDR DDRD
#define PD1_PIN PIND1
#define PD1_RPORT PIND
#define PD1_WPORT PORTD
#define PD1_DDR DDRD
#define PD2_PIN PIND2
#define PD2_RPORT PIND
#define PD2_WPORT PORTD
#define PD2_DDR DDRD
#define PD3_PIN PIND3
#define PD3_RPORT PIND
#define PD3_WPORT PORTD
#define PD3_DDR DDRD
#define PD4_PIN PIND4
#define PD4_RPORT PIND
#define PD4_WPORT PORTD
#define PD4_DDR DDRD
#define PD5_PIN PIND5
#define PD5_RPORT PIND
#define PD5_WPORT PORTD
#define PD5_DDR DDRD
#define PD6_PIN PIND6
#define PD6_RPORT PIND
#define PD6_WPORT PORTD
#define PD6_DDR DDRD
#define PD7_PIN PIND7
#define PD7_RPORT PIND
#define PD7_WPORT PORTD
#define PD7_DDR DDRD

View File

@ -1 +0,0 @@
../debug.h

21
extruder/debug.h Normal file
View File

@ -0,0 +1,21 @@
#ifndef _DEBUG_H
#define _DEBUG_H
#include <stdint.h>
#ifdef DEBUG
#define DEBUG_PID 1
#define DEBUG_DDA 2
#define DEBUG_POSITION 4
#else
// by setting these to zero, the compiler should optimise the relevant code out
#define DEBUG_PID 0
#define DEBUG_DDA 0
#define DEBUG_POSITION 0
#endif
#define DEBUG_ECHO 128
extern volatile uint8_t debug_flags;
#endif /* _DEBUG_H */

View File

@ -1 +0,0 @@
../delay.c

50
extruder/delay.c Normal file
View File

@ -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
);
}

View File

@ -1 +0,0 @@
../delay.h

15
extruder/delay.h Normal file
View File

@ -0,0 +1,15 @@
#ifndef _DELAY_H
#define _DELAY_H
#include <stdint.h>
#define WAITING_DELAY 10 MS
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 */

View File

@ -1 +0,0 @@
../heater.c

251
extruder/heater.c Normal file
View File

@ -0,0 +1,251 @@
#include "heater.h"
#include <stdlib.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
#include "arduino.h"
#include "debug.h"
#ifndef EXTRUDER
#include "sersendf.h"
#endif
#define HEATER_C
#include "config.h"
// this struct holds the heater PID factors that are stored in the EEPROM during poweroff
struct {
int32_t p_factor;
int32_t i_factor;
int32_t d_factor;
int16_t i_limit;
} heaters_pid[NUM_HEATERS];
// this struct holds the runtime heater data- PID integrator history, temperature history, sanity checker
struct {
int16_t heater_i;
uint16_t temp_history[TH_COUNT];
uint8_t temp_history_pointer;
#ifdef HEATER_SANITY_CHECK
uint16_t sanity_counter;
uint16_t sane_temperature;
#endif
} heaters_runtime[NUM_HEATERS];
#define DEFAULT_P 8192
#define DEFAULT_I 512
#define DEFAULT_D 24576
#define DEFAULT_I_LIMIT 384
// this lives in the eeprom so we can save our PID settings for each heater
typedef struct {
int32_t EE_p_factor;
int32_t EE_i_factor;
int32_t EE_d_factor;
int16_t EE_i_limit;
} EE_factor;
EE_factor EEMEM EE_factors[NUM_HEATERS];
void heater_init() {
#if NUM_HEATERS > 0
uint8_t i;
// setup pins
for (i = 0; i < NUM_HEATERS; i++) {
*(heaters[i].heater_port) &= ~MASK(heaters[i].heater_pin);
// DDR is always 1 address below PORT. ugly code but saves ram and an extra field in heaters[] which will never be used anywhere but here
*(heaters[i].heater_port - 1) |= MASK(heaters[i].heater_pin);
if (heaters[i].heater_pwm) {
*heaters[i].heater_pwm = 0;
// this is somewhat ugly too, but switch() won't accept pointers for reasons unknown
switch((uint16_t) heaters[i].heater_pwm) {
case (uint16_t) &OCR0A:
TCCR0A |= MASK(COM0A1);
break;
case (uint16_t) &OCR0B:
TCCR0A |= MASK(COM0B1);
break;
case (uint16_t) &OCR2A:
TCCR2A |= MASK(COM2A1);
break;
case (uint16_t) &OCR2B:
TCCR2A |= MASK(COM2B1);
break;
}
}
#ifdef HEATER_SANITY_CHECK
// 0 is a "sane" temperature when we're trying to cool down
heaters_runtime[i].sane_temperature = 0;
#endif
// read factors from eeprom
heaters_pid[i].p_factor = eeprom_read_dword((uint32_t *) &EE_factors[i].EE_p_factor);
heaters_pid[i].i_factor = eeprom_read_dword((uint32_t *) &EE_factors[i].EE_i_factor);
heaters_pid[i].d_factor = eeprom_read_dword((uint32_t *) &EE_factors[i].EE_d_factor);
heaters_pid[i].i_limit = eeprom_read_word((uint16_t *) &EE_factors[i].EE_i_limit);
if ((heaters_pid[i].p_factor == 0) && (heaters_pid[i].i_factor == 0) && (heaters_pid[i].d_factor == 0) && (heaters_pid[i].i_limit == 0)) {
heaters_pid[i].p_factor = DEFAULT_P;
heaters_pid[i].i_factor = DEFAULT_I;
heaters_pid[i].d_factor = DEFAULT_D;
heaters_pid[i].i_limit = DEFAULT_I_LIMIT;
}
}
#endif
}
void heater_save_settings() {
uint8_t i;
for (i = 0; i < NUM_HEATERS; i++) {
eeprom_write_dword((uint32_t *) &EE_factors[i].EE_p_factor, heaters_pid[i].p_factor);
eeprom_write_dword((uint32_t *) &EE_factors[i].EE_i_factor, heaters_pid[i].i_factor);
eeprom_write_dword((uint32_t *) &EE_factors[i].EE_d_factor, heaters_pid[i].d_factor);
eeprom_write_word((uint16_t *) &EE_factors[i].EE_i_limit, heaters_pid[i].i_limit);
}
}
void heater_tick(uint8_t h, uint16_t current_temp, uint16_t target_temp) {
#if NUM_HEATERS > 0
int16_t heater_p;
int16_t heater_d;
uint8_t pid_output;
int16_t t_error = target_temp - current_temp;
heaters_runtime[h].temp_history[heaters_runtime[h].temp_history_pointer++] = current_temp;
heaters_runtime[h].temp_history_pointer &= (TH_COUNT - 1);
// PID stuff
// proportional
heater_p = t_error;
// integral
heaters_runtime[h].heater_i += t_error;
// prevent integrator wind-up
if (heaters_runtime[h].heater_i > heaters_pid[h].i_limit)
heaters_runtime[h].heater_i = heaters_pid[h].i_limit;
else if (heaters_runtime[h].heater_i < -heaters_pid[h].i_limit)
heaters_runtime[h].heater_i = -heaters_pid[h].i_limit;
// derivative
// note: D follows temp rather than error so there's no large derivative when the target changes
heater_d = heaters_runtime[h].temp_history[heaters_runtime[h].temp_history_pointer] - current_temp;
// combine factors
int32_t pid_output_intermed = (
(
(((int32_t) heater_p) * heaters_pid[h].p_factor) +
(((int32_t) heaters_runtime[h].heater_i) * heaters_pid[h].i_factor) +
(((int32_t) heater_d) * heaters_pid[h].d_factor)
) / PID_SCALE
);
// rebase and limit factors
if (pid_output_intermed > 255)
pid_output = 255;
else if (pid_output_intermed < 0)
pid_output = 0;
else
pid_output = pid_output_intermed & 0xFF;
#ifdef DEBUG
if (debug_flags & DEBUG_PID)
sersendf_P(PSTR("T{E:%d, P:%d * %ld = %ld / I:%d * %ld = %ld / D:%d * %ld = %ld # O: %ld = %u}\n"), t_error, heater_p, heaters_pid[h].p_factor, (int32_t) heater_p * heaters_pid[h].p_factor / PID_SCALE, heaters_runtime[h].heater_i, heaters_pid[h].i_factor, (int32_t) heaters_runtime[h].heater_i * heaters_pid[h].i_factor / PID_SCALE, heater_d, heaters_pid[h].d_factor, (int32_t) heater_d * heaters_pid[h].d_factor / PID_SCALE, pid_output_intermed, pid_output);
#endif
#ifdef HEATER_SANITY_CHECK
// check heater sanity
// implementation is a moving window with some slow-down to compensate for thermal mass
if (target_temp > (current_temp + TEMP_HYSTERESIS)) {
// heating
if (current_temp > heaters_runtime[h].sane_temperature)
// hotter than sane- good since we're heating unless too hot
heaters_runtime[h].sane_temperature = current_temp;
else {
if (heaters_runtime[h].sanity_counter < 40)
heaters_runtime[h].sanity_counter++;
else {
heaters_runtime[h].sanity_counter = 0;
// ratchet up expected temp
heaters_runtime[h].sane_temperature++;
}
}
// limit to target, so if we overshoot by too much for too long an error is flagged
if (heaters_runtime[h].sane_temperature > target_temp)
heaters_runtime[h].sane_temperature = target_temp;
}
else if (target_temp < (current_temp - TEMP_HYSTERESIS)) {
// cooling
if (current_temp < heaters_runtime[h].sane_temperature)
// cooler than sane- good since we're cooling
heaters_runtime[h].sane_temperature = current_temp;
else {
if (heaters_runtime[h].sanity_counter < 125)
heaters_runtime[h].sanity_counter++;
else {
heaters_runtime[h].sanity_counter = 0;
// ratchet down expected temp
heaters_runtime[h].sane_temperature--;
}
}
// if we're at or below 60 celsius, don't freak out if we can't drop any more.
if (current_temp <= 240)
heaters_runtime[h].sane_temperature = current_temp;
// limit to target, so if we don't cool down for too long an error is flagged
else if (heaters_runtime[h].sane_temperature < target_temp)
heaters_runtime[h].sane_temperature = target_temp;
}
// we're within HYSTERESIS of our target
else {
heaters_runtime[h].sane_temperature = current_temp;
heaters_runtime[h].sanity_counter = 0;
}
// compare where we're at to where we should be
if (labs(current_temp - heaters_runtime[h].sane_temperature) > TEMP_HYSTERESIS) {
// no change, or change in wrong direction for a long time- heater is broken!
pid_output = 0;
sersendf_P(PSTR("!! heater %d broken- temp is %d.%dC, target is %d.%dC, didn't reach %d.%dC in %d0 milliseconds\n"), h, current_temp >> 2, (current_temp & 3) * 25, target_temp >> 2, (target_temp & 3) * 25, heaters_runtime[h].sane_temperature >> 2, (heaters_runtime[h].sane_temperature & 3) * 25, heaters_runtime[h].sanity_counter);
}
#endif /* HEATER_SANITY_CHECK */
heater_set(h, pid_output);
#endif /* if NUM_HEATERS > 0 */
}
void heater_set(uint8_t index, uint8_t value) {
#if NUM_HEATERS > 0
if (heaters[index].heater_pwm) {
*(heaters[index].heater_pwm) = value;
#ifdef DEBUG
if (debug_flags & DEBUG_PID)
sersendf_P(PSTR("PWM{%u = %u}\n"), index, OCR0A);
#endif
}
else {
if (value >= 8)
*(heaters[index].heater_port) |= MASK(heaters[index].heater_pin);
else
*(heaters[index].heater_port) &= ~MASK(heaters[index].heater_pin);
}
#endif /* if NUM_HEATERS > 0 */
}
void pid_set_p(uint8_t index, int32_t p) {
heaters_pid[index].p_factor = p;
}
void pid_set_i(uint8_t index, int32_t i) {
heaters_pid[index].i_factor = i;
}
void pid_set_d(uint8_t index, int32_t d) {
heaters_pid[index].d_factor = d;
}
void pid_set_i_limit(uint8_t index, int32_t i_limit) {
heaters_pid[index].i_limit = i_limit;
}

View File

@ -1 +0,0 @@
../heater.h

20
extruder/heater.h Normal file
View File

@ -0,0 +1,20 @@
#ifndef _HEATER_H
#define _HEATER_H
#include <stdint.h>
#define enable_heater() heater_set(0, 64)
#define disable_heater() heater_set(0, 0)
void heater_init(void);
void heater_save_settings(void);
void heater_set(uint8_t index, uint8_t value);
void heater_tick(uint8_t h, uint16_t current_temp, uint16_t target_temp);
void pid_set_p(uint8_t index, int32_t p);
void pid_set_i(uint8_t index, int32_t i);
void pid_set_d(uint8_t index, int32_t d);
void pid_set_i_limit(uint8_t index, int32_t i_limit);
#endif /* _HEATER_H */

View File

@ -1 +0,0 @@
../temp.c

275
extruder/temp.c Normal file
View File

@ -0,0 +1,275 @@
#include "temp.h"
#include <stdlib.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
typedef enum {
TT_THERMISTOR,
TT_MAX6675,
TT_AD595,
TT_PT100,
TT_INTERCOM
} temp_types;
typedef enum {
PRESENT,
TCOPEN
} temp_flags_enum;
#define TEMP_C
#include "config.h"
#include "arduino.h"
#include "delay.h"
#include "debug.h"
#ifndef EXTRUDER
#include "sersendf.h"
#endif
#include "heater.h"
#ifdef GEN3
#include "intercom.h"
#endif
// this struct holds the runtime sensor data- read temperatures, targets, etc
struct {
temp_flags_enum temp_flags;
uint16_t last_read_temp;
uint16_t target_temp;
uint8_t temp_residency;
uint16_t next_read_time;
} temp_sensors_runtime[NUM_TEMP_SENSORS];
#ifdef TEMP_MAX6675
#endif
#ifdef TEMP_THERMISTOR
#include "analog.h"
#define NUMTEMPS 20
uint16_t temptable[NUMTEMPS][2] PROGMEM = {
{1, 841},
{54, 255},
{107, 209},
{160, 184},
{213, 166},
{266, 153},
{319, 142},
{372, 132},
{425, 124},
{478, 116},
{531, 108},
{584, 101},
{637, 93},
{690, 86},
{743, 78},
{796, 70},
{849, 61},
{902, 50},
{955, 34},
{1008, 3}
};
#endif
#ifdef TEMP_AD595
#include "analog.h"
#endif
void temp_init() {
uint8_t i;
for (i = 0; i < NUM_TEMP_SENSORS; i++) {
switch(temp_sensors[i].temp_type) {
#ifdef TEMP_MAX6675
// initialised when read
/* case TT_MAX6675:
break;*/
#endif
#ifdef TEMP_THERMISTOR
// handled by analog_init()
/* case TT_THERMISTOR:
break;*/
#endif
#ifdef TEMP_AD595
// handled by analog_init()
/* case TT_AD595:
break;*/
#endif
#ifdef GEN3
case TT_INTERCOM:
intercom_init();
update_send_cmd(0);
break;
#endif
}
}
}
void temp_sensor_tick() {
uint8_t i = 0;
for (; i < NUM_TEMP_SENSORS; i++) {
if (temp_sensors_runtime[i].next_read_time) {
temp_sensors_runtime[i].next_read_time--;
}
else {
uint16_t temp = 0;
//time to deal with this temp sensor
switch(temp_sensors[i].temp_type) {
#ifdef TEMP_MAX6675
case TT_MAX6675:
#ifdef PRR
PRR &= ~MASK(PRSPI);
#elif defined PRR0
PRR0 &= ~MASK(PRSPI);
#endif
SPCR = MASK(MSTR) | MASK(SPE) | MASK(SPR0);
// enable TT_MAX6675
WRITE(SS, 0);
// ensure 100ns delay - a bit extra is fine
delay(1);
// read MSB
SPDR = 0;
for (;(SPSR & MASK(SPIF)) == 0;);
temp = SPDR;
temp <<= 8;
// read LSB
SPDR = 0;
for (;(SPSR & MASK(SPIF)) == 0;);
temp |= SPDR;
// disable TT_MAX6675
WRITE(SS, 1);
temp_sensors_runtime[i].temp_flags = 0;
if ((temp & 0x8002) == 0) {
// got "device id"
temp_sensors_runtime[i].temp_flags |= PRESENT;
if (temp & 4) {
// thermocouple open
temp_sensors_runtime[i].temp_flags |= TCOPEN;
}
else {
temp = temp >> 3;
}
}
// this number depends on how frequently temp_sensor_tick is called. the MAX6675 can give a reading every 0.22s, so set this to about 250ms
temp_sensors_runtime[i].next_read_time = 25;
break;
#endif /* TEMP_MAX6675 */
#ifdef TEMP_THERMISTOR
case TT_THERMISTOR:
do {
uint8_t j;
//Read current temperature
temp = analog_read(temp_sensors[i].temp_pin);
//Calculate real temperature based on lookup table
for (j = 1; j < NUMTEMPS; j++) {
if (pgm_read_word(&(temptable[j][0])) > temp) {
// multiply by 4 because internal temp is stored as 14.2 fixed point
temp = pgm_read_word(&(temptable[j][1])) * 4 + (pgm_read_word(&(temptable[j][0])) - temp) * 4 * (pgm_read_word(&(temptable[j-1][1])) - pgm_read_word(&(temptable[j][1]))) / (pgm_read_word(&(temptable[j][0])) - pgm_read_word(&(temptable[j-1][0])));
break;
}
}
//Clamp for overflows
if (j == NUMTEMPS)
temp = temptable[NUMTEMPS-1][1] * 4;
temp_sensors_runtime[i].next_read_time = 0;
} while (0);
break;
#endif /* TEMP_THERMISTOR */
#ifdef TEMP_AD595
case TT_AD595:
temp = analog_read(temp_pin);
// convert
// >>8 instead of >>10 because internal temp is stored as 14.2 fixed point
temp = (temp * 500L) >> 8;
temp_sensors_runtime[i].next_read_time = 0;
break;
#endif /* TEMP_AD595 */
#ifdef TEMP_PT100
case TT_PT100:
#warning TODO: PT100 code
break
#endif /* TEMP_PT100 */
#ifdef GEN3
case TT_INTERCOM:
temp = get_read_cmd() << 2;
start_send();
temp_sensors_runtime[i].next_read_time = 0;
break;
#endif /* GEN3 */
}
temp_sensors_runtime[i].last_read_temp = temp;
if (labs(temp - temp_sensors_runtime[i].target_temp) < TEMP_HYSTERESIS) {
if (temp_sensors_runtime[i].temp_residency < TEMP_RESIDENCY_TIME)
temp_sensors_runtime[i].temp_residency++;
}
else {
temp_sensors_runtime[i].temp_residency = 0;
}
if (temp_sensors[i].heater_index < NUM_HEATERS) {
heater_tick(temp_sensors[i].heater_index, temp_sensors_runtime[i].last_read_temp, temp_sensors_runtime[i].target_temp);
}
}
}
}
uint8_t temp_achieved() {
uint8_t i, all_ok = 255;
for (i = 0; i < NUM_TEMP_SENSORS; i++) {
if (temp_sensors_runtime[i].temp_residency < TEMP_RESIDENCY_TIME)
all_ok = 0;
}
return all_ok;
}
void temp_set(uint8_t index, uint16_t temperature) {
temp_sensors_runtime[index].target_temp = temperature;
temp_sensors_runtime[index].temp_residency = 0;
#ifdef GEN3
if (temp_sensors[index].temp_type == TT_INTERCOM)
update_send_cmd(temperature >> 2);
#endif
}
uint16_t temp_get(uint8_t index) {
return temp_sensors_runtime[index].last_read_temp;
}
// extruder doesn't have sersendf_P
#ifndef EXTRUDER
void temp_print(uint8_t index) {
uint8_t c = 0;
c = (temp_sensors_runtime[index].last_read_temp & 3) * 25;
sersendf_P(PSTR("T: %u.%u\n"), temp_sensors_runtime[index].last_read_temp >> 2, c);
}
#endif

View File

@ -1 +0,0 @@
../temp.h

29
extruder/temp.h Normal file
View File

@ -0,0 +1,29 @@
#ifndef _TEMP_H
#define _TEMP_H
#include <stdint.h>
/*
NOTES
no point in specifying a port- all the different temp sensors we have must be on a particular port. The MAX6675 must be on the SPI, and the thermistor and AD595 must be on an analog port.
we still need to specify which analog pins we use in machine.h for the analog sensors however, otherwise the analog subsystem won't read them.
*/
#define temp_tick temp_sensor_tick
void temp_init(void);
void temp_sensor_tick(void);
uint8_t temp_achieved(void);
void temp_set(uint8_t index, uint16_t temperature);
uint16_t temp_get(uint8_t index);
void temp_print(uint8_t index);
uint16_t temp_read(uint8_t index);
#endif /* _TIMER_H */

View File

@ -1 +0,0 @@
../watchdog.c

47
extruder/watchdog.c Normal file
View File

@ -0,0 +1,47 @@
#include "watchdog.h"
#ifdef USE_WATCHDOG
#include <avr/wdt.h>
#include <avr/interrupt.h>
#include "arduino.h"
#include "serial.h"
volatile uint8_t wd_flag = 0;
// uint8_t mcusr_mirror __attribute__ ((section (".noinit")));
// void get_mcusr(void) __attribute__((naked)) __attribute__((section(".init3")));
// void get_mcusr(void) {
// mcusr_mirror = MCUSR;
// MCUSR = 0;
// wdt_disable();
// }
ISR(WDT_vect) {
// watchdog has tripped- no main loop activity for 0.5s, probably a bad thing
// if watchdog fires again, we will reset
// perhaps we should do something more intelligent in this interrupt?
wd_flag |= 1;
}
void wd_init() {
// check if we were reset by the watchdog
// if (mcusr_mirror & MASK(WDRF))
// serial_writestr_P(PSTR("Watchdog Reset!\n"));
// 0.25s timeout, interrupt and system reset
wdt_enable(WDTO_500MS);
WDTCSR |= MASK(WDIE);
}
void wd_reset() {
wdt_reset();
if (wd_flag) {
WDTCSR |= MASK(WDIE);
wd_flag &= ~1;
}
}
#endif /* USE_WATCHDOG */

View File

@ -1 +0,0 @@
../watchdog.h

22
extruder/watchdog.h Normal file
View File

@ -0,0 +1,22 @@
#ifndef _WATCHDOG_H
#define _WATCHDOG_H
#include "config.h"
#ifdef USE_WATCHDOG
// initialize
void wd_init(void) __attribute__ ((cold));
// reset timeout- must be called periodically or we reboot
void wd_reset(void);
// notable lack of disable function
#else /* USE_WATCHDOG */
#define wd_init() /* empty */
#define wd_reset() /* empty */
#endif /* USE_WATCHDOG */
#endif /* _WATCHDOG_H */

View File

@ -1 +0,0 @@
extruder/intercom.c

219
intercom.c Normal file
View File

@ -0,0 +1,219 @@
#include "intercom.h"
#include <avr/interrupt.h>
#include "config.h"
#include "delay.h"
#ifdef GEN3
#define INTERCOM_BAUD 57600
#define enable_transmit() do { WRITE(TX_ENABLE_PIN,1); WRITE(RX_ENABLE_PIN,0); } while(0)
#define disable_transmit() do { WRITE(TX_ENABLE_PIN,0); WRITE(RX_ENABLE_PIN,0); } while(0)
/*
Defines a super simple intercom interface using the RS485 modules
Host will say: START1 START2 PWM_CMD PWM_CHK
Extruder will reply: START1 START2 TMP_CMD TMP_CHK
CHK = 255-CMD, if they match do the work, if not, ignore this packet
in a loop
*/
#define START1 0xAA
#define START2 0x55
typedef enum {
SEND_START1,
SEND_START2,
SEND_CMD,
SEND_CHK,
SEND_DONE,
READ_START1,
READ_START2,
READ_CMD,
READ_CHK,
} intercom_state_e;
intercom_state_e state = READ_START1;
uint8_t cmd, chk, send_cmd, read_cmd;
void intercom_init(void)
{
#ifdef HOST
#if INTERCOM_BAUD > 38401
UCSR1A = MASK(U2X1);
UBRR1 = (((F_CPU / 8) / INTERCOM_BAUD) - 0.5);
#else
UCSR1A = 0;
UBRR1 = (((F_CPU / 16) / INTERCOM_BAUD) - 0.5);
#endif
UCSR1B = MASK(RXEN1) | MASK(TXEN1);
UCSR1C = MASK(UCSZ11) | MASK(UCSZ10);
UCSR1B |= MASK(RXCIE1) | MASK(TXCIE1);
#else
#if INTERCOM_BAUD > 38401
UCSR0A = MASK(U2X0);
UBRR0 = (((F_CPU / 8) / INTERCOM_BAUD) - 0.5);
#else
UCSR0A = 0;
UBRR0 = (((F_CPU / 16) / INTERCOM_BAUD) - 0.5);
#endif
UCSR0B = MASK(RXEN0) | MASK(TXEN0);
UCSR0C = MASK(UCSZ01) | MASK(UCSZ00);
UCSR0B |= MASK(RXCIE0) | MASK(TXCIE0);
#endif
}
void update_send_cmd(uint8_t new_send_cmd) {
send_cmd = new_send_cmd;
}
uint8_t get_read_cmd(void) {
return read_cmd;
}
static void write_byte(uint8_t val) {
#ifdef HOST
UDR1 = val;
#else
UDR0 = val;
#endif
}
void start_send(void) {
state = SEND_START1;
enable_transmit();
delay_us(15);
//Enable interrupts so we can send next characters
#ifdef HOST
UCSR1B |= MASK(UDRIE1);
#else
UCSR0B |= MASK(UDRIE0);
#endif
}
static void finish_send(void) {
state = READ_START1;
disable_transmit();
}
/*
Interrupts, UART 0 for mendel
*/
#ifdef HOST
ISR(USART1_RX_vect)
#else
ISR(USART_RX_vect)
#endif
{
static uint8_t c;
#ifdef HOST
c = UDR1;
UCSR1A &= ~MASK(FE1) & ~MASK(DOR1) & ~MASK(UPE1);
#else
c = UDR0;
UCSR0A &= ~MASK(FE0) & ~MASK(DOR0) & ~MASK(UPE0);
#endif
if (state >= READ_START1) {
switch(state) {
case READ_START1:
if (c == START1) state = READ_START2;
break;
case READ_START2:
if (c == START2) state = READ_CMD;
else state = READ_START1;
break;
case READ_CMD:
cmd = c;
state = READ_CHK;
break;
case READ_CHK:
chk = c;
if (chk == 255 - cmd) {
//Values are correct, do something useful
WRITE(DEBUG_LED,1);
read_cmd = cmd;
#ifdef EXTRUDER
start_send();
#endif
}
else
{
state = READ_START1;
}
break;
default:
break;
}
}
}
#ifdef HOST
ISR(USART1_TX_vect)
#else
ISR(USART_TX_vect)
#endif
{
if (state == SEND_DONE) {
finish_send();
#ifdef HOST
UCSR1B &= ~MASK(TXCIE1);
#else
UCSR0B &= ~MASK(TXCIE0);
#endif
}
}
#ifdef HOST
ISR(USART1_UDRE_vect)
#else
ISR(USART_UDRE_vect)
#endif
{
switch(state) {
case SEND_START1:
write_byte(START1);
state = SEND_START2;
break;
case SEND_START2:
write_byte(START2);
state = SEND_CMD;
break;
case SEND_CMD:
write_byte(send_cmd);
state = SEND_CHK;
break;
case SEND_CHK:
write_byte(255 - send_cmd);
state = SEND_DONE;
#ifdef HOST
UCSR1B &= ~MASK(UDRIE1);
UCSR1B |= MASK(TXCIE1);
#else
UCSR0B &= ~MASK(UDRIE0);
UCSR0B |= MASK(TXCIE0);
#endif
break;
default:
break;
}
}
#endif /* GEN3 */

View File

@ -1 +0,0 @@
extruder/intercom.h

17
intercom.h Normal file
View File

@ -0,0 +1,17 @@
#ifndef _INTERCOM_H
#define _INTERCOM_H
#include <stdint.h>
// initialise serial subsystem
void intercom_init(void);
//Update the message we are sending over intercom
void update_send_cmd(uint8_t new_send_cmd);
void start_send(void);
//Read the message we are receiving over intercom
uint8_t get_read_cmd(void);
#endif /* _INTERCOM_H */

View File

@ -1 +0,0 @@
func.sh

312
mendel_cmd Executable file
View File

@ -0,0 +1,312 @@
#!/bin/bash
#
# this file is designed to be sourced into your current shell like this:
#
# source ./func.sh
#
# and then used like this:
#
# $ mendel_cmd G1 X100
# $ mendel_cmd M250
#
# {X:4200,Y:0,Z:0,E:0,F:300,c:19334400}
# {X:4200,Y:0,Z:0,E:0,F:300,c:0}
# Q1/1E
# $ mendel_readsym_uint8 mb_head
# 1
# $ mendel_readsym_target startpoint
# X: 2100
# Y: 0
# Z: 0
# E: 0
# F: 300
# $ mendel_readsym_mb
# [0] {
# eX: 0 eY: 0 eZ: 0 eE: 0 eF: 0
# flags: 0
# dX: 0 dY: 0 dZ: 0 dE: 0
# cX: 0 cY: 0 cZ: 0 cE: 0
# ts: 0
# c: 0 ec: 0 n: 0
# }
# [HEAD,TAIL:1] {
# eX: 4200 eY: 0 eZ: 0 eE: 0 eF: 300
# flags: 120
# dX: 4200 dY: 0 dZ: 0 dE: 0
# cX: -2100 cY: -2100 cZ: -2100 cE: -2100
# ts: 4200
# c: 19334400 ec: 0 n: 0
# }
# [2] {
# eX: 0 eY: 0 eZ: 0 eE: 0 eF: 0
# flags: 0
# dX: 0 dY: 0 dZ: 0 dE: 0
# cX: 0 cY: 0 cZ: 0 cE: 0
# ts: 0
# c: 0 ec: 0 n: 0
# }
# [3] {
# eX: 0 eY: 0 eZ: 0 eE: 0 eF: 0
# flags: 0
# dX: 0 dY: 0 dZ: 0 dE: 0
# cX: 0 cY: 0 cZ: 0 cE: 0
# ts: 0
# c: 0 ec: 0 n: 0
# }
# [4] {
# eX: 0 eY: 0 eZ: 0 eE: 0 eF: 0
# flags: 0
# dX: 0 dY: 0 dZ: 0 dE: 0
# cX: 0 cY: 0 cZ: 0 cE: 0
# ts: 0
# c: 0 ec: 0 n: 0
# }
# [5] {
# eX: 0 eY: 0 eZ: 0 eE: 0 eF: 0
# flags: 0
# dX: 0 dY: 0 dZ: 0 dE: 0
# cX: 0 cY: 0 cZ: 0 cE: 0
# ts: 0
# c: 0 ec: 0 n: 0
# }
# [6] {
# eX: 0 eY: 0 eZ: 0 eE: 0 eF: 0
# flags: 0
# dX: 0 dY: 0 dZ: 0 dE: 0
# cX: 0 cY: 0 cZ: 0 cE: 0
# ts: 0
# c: 0 ec: 0 n: 0
# }
# [7] {
# eX: 0 eY: 0 eZ: 0 eE: 0 eF: 0
# flags: 0
# dX: 0 dY: 0 dZ: 0 dE: 0
# cX: 0 cY: 0 cZ: 0 cE: 0
# ts: 0
# c: 0 ec: 0 n: 0
# }
mendel_setup() {
stty 115200 raw ignbrk -hup -echo ixoff < /dev/arduino
}
mendel_reset() {
stty hup < /dev/arduino
stty hup < /dev/arduino
mendel_setup
}
mendel_talk() {
( cat <&3 & cat >&3; kill $! ; ) 3<>/dev/arduino
}
mendel_cmd() {
(
local IFS=$' \t\n'
local RSC=0
local cmd="$*"
echo "$cmd" >&3;
local REPLY=""
while ! [[ "$REPLY" =~ ^OK ]] && ! [[ "$REPLY" =~ ^ok ]]
do
read -u 3
echo "${REPLY##ok }"
if [[ "$REPLY" =~ ^RESEND ]] || [[ "$REPLY" =~ ^rs ]]
then
if [ "$RSC" -le 3 ]
then
echo "$cmd" >&3
RSC=$(( $RSC + 1 ))
else
REPLY="OK"
echo "Too many retries: aborting" >&2
fi
fi
done
) 3<>/dev/arduino;
}
mendel_cmd_hr() {
(
local IFS=$' \t\n'
local cmd="$*"
local RSC=0
echo "$cmd" >&3
echo "S> $cmd"
local REPLY=""
while ! [[ "$REPLY" =~ ^OK ]] && ! [[ "$REPLY" =~ ^ok ]]
do
read -u 3
echo "<R $REPLY"
if [[ "$REPLY" =~ ^RESEND ]] || [[ "$REPLY" =~ ^rs ]]
then
if [ "$RSC" -le 3 ]
then
echo "$cmd" >&3
echo "S> $cmd"
RSC=$(( $RSC + 1))
else
REPLY="OK"
echo "Too many retries: aborting" >&2
fi
fi
done
) 3<>/dev/arduino;
}
mendel_print() {
(
for F in "$@"
do
local IFS=$'\n'
for L in $(< $F)
do
mendel_cmd_hr "$L"
done
done
)
}
mendel_readsym() {
(
local IFS=$' \t\n'
local sym=$1
if [ -n "$sym" ]
then
if [[ "$sym" =~ ^(0?x?[0-9A-Fa-f]+)(:([0-9]+))?$ ]]
then
local ADDR=$(( ${BASH_REMATCH[1]} ))
local SIZE=$(( ${BASH_REMATCH[3]} ))
if [ "$SIZE" -le 1 ]
then
SIZE=1
fi
mendel_cmd "M253 S$ADDR P$SIZE"
else
make mendel.sym &>/dev/null
if egrep -q '\b'$sym'\b' mendel.sym
then
local ADDR=$(( $(egrep '\b'$sym'\b' mendel.sym | cut -d\ -f1) ))
local SIZE=$(egrep '\b'$sym'\b' mendel.sym | cut -d+ -f2)
mendel_cmd "M253 S$ADDR P$SIZE"
else
echo "unknown symbol: $sym"
fi
fi
else
echo "what symbol?" > /dev/fd/2
fi
)
}
mendel_readsym_uint8() {
local sym=$1
local val=$(mendel_readsym $sym)
perl -e 'printf "%u\n", eval "0x".$ARGV[0]' $val
}
mendel_readsym_int8() {
local sym=$1
local val=$(mendel_readsym $sym)
perl -e 'printf "%d\n", ((eval "0x".$ARGV[0]) & 0x7F) - (((eval "0x".$ARGV[0]) & 0x80)?0x80:0)' $val
}
mendel_readsym_uint16() {
local sym=$1
local val=$(mendel_readsym $sym)
perl -e '$ARGV[0] =~ m#(..)(..)# && printf "%u\n", eval "0x$2$1"' $val
}
mendel_readsym_int16() {
local sym=$1
local val=$(mendel_readsym $sym)
perl -e '$ARGV[0] =~ m#(..)(..)# && printf "%d\n", ((eval "0x$2$1") & 0x7FFF) - (((eval "0x$2$1") & 0x8000)?0x8000:0)' $val
}
mendel_readsym_uint32() {
local sym=$1
local val=$(mendel_readsym $sym)
perl -e '$ARGV[0] =~ m#(..)(..)(..)(..)# && printf "%u\n", eval "0x$4$3$2$1"' $val
}
mendel_readsym_int32() {
local sym=$1
local val=$(mendel_readsym $sym)
perl -e '$ARGV[0] =~ m#(..)(..)(..)(..)# && printf "%d\n", eval "0x$4$3$2$1"' $val
}
mendel_readsym_target() {
local sym=$1
local val=$(mendel_readsym "$sym")
if [ -n "$val" ]
then
perl -e '@a = qw/X Y Z E F/; $c = 0; while (length $ARGV[0]) { $ARGV[0] =~ s#^(..)(..)(..)(..)##; printf "%s: %d\n", $a[$c], eval "0x$4$3$2$1"; $c++; }' "$val"
fi
}
mendel_readsym_mb() {
local val=$(mendel_readsym movebuffer)
local mbhead=$(mendel_readsym mb_head)
local mbtail=$(mendel_readsym mb_tail)
perl - <<'ENDPERL' -- $val $mbhead $mbtail
$i = -1;
@a = qw/eX 4 eY 4 eZ 4 eE 4 eF 4 flags 9 dX 12 dY 4 dZ 4 dE 4 cX 12 cY 4 cZ 4 cE 4 ts 12 c 12 rs 4 sn 4 cm 4 n 4 rs 1/;
$c = 0;
$c = 1234567;
while (length $ARGV[1]) {
if ($c > ($#a / 2)) {
$i++;
$c = 0;
printf "\n}\n"
if ($i > 0);
printf "[%s%d] {\n", (($i == $ARGV[2])?"HEAD":"").(($ARGV[2] == $ARGV[3] && $ARGV[2] == $i)?",":"").(($i == $ARGV[3])?"TAIL":"").(($i == $ARGV[2] || $i == $ARGV[3])?":":""), $i
}
if ($a[$c * 2 + 1] & 8) {
printf "\n";
}
if (($a[$c * 2 + 1] & 7) == 4) {
$ARGV[1] =~ s#^(..)(..)(..)(..)##;
printf "\t%s: %d", $a[$c * 2], eval "0x$4$3$2$1";
}
elsif (($a[$c * 2 + 1] & 7) == 1) {
$ARGV[1] =~ s#^(..)##;
printf "\t%s: %d", $a[$c * 2], eval "0x$1";
}
$c++;
}
printf "\n}\n";
ENDPERL
}
mendel_heater_pid() {
local P=$(mendel_readsym_int16 heater_p)
local I=$(mendel_readsym_int16 heater_i)
local D=$(mendel_readsym_int16 heater_d)
local PF=$(mendel_readsym_int32 p_factor)
local IF=$(mendel_readsym_int32 i_factor)
local DF=$(mendel_readsym_int32 d_factor)
local O=$(mendel_readsym_uint8 0x27)
local T=$(mendel_cmd M105 | cut -d\ -f2 | cut -d/ -f1)
echo "P=$P pf=$PF r="$(($P * $PF))
echo "I=$I if=$IF r="$(($I * $IF))
echo "D=$D df=$DF r="$(($D * $DF))
echo "R="$(( $(($P * $PF)) + $(($I * $IF)) + $(($D * $DF)) )) / 1024
echo "R="$(( $(( $(($P * $PF)) + $(($I * $IF)) + $(($D * $DF)) )) / 1024 ))
echo "R="$(( $(( $(( $(($P * $PF)) + $(($I * $IF)) + $(($D * $DF)) )) / 1024 )) + 128 ))
echo "O=$O T=$T"
}
if [[ "$0" =~ ^mendel_(setup|reset|cmd|readsym|heater_pid) ]]
then
eval "$0" "$@"
fi
if [[ "$1" =~ ^mendel_(setup|reset|cmd|readsym|heater_pid) ]]
then
eval "$@"
fi