#include "config.h"
#include "stepper.h"
#include "spindle.h"
-#include "gpio.h"
+#include "coolant.h"
#include "switch.h"
#include "hardware.h"
#include "util.h"
// Sub-system inits
cm_spindle_init();
+ coolant_init();
}
static void _exec_mist_coolant_control(float *value, float *flag) {
- cm.gm.mist_coolant = value[0];
-
- if (cm.gm.mist_coolant) gpio_set_bit_on(MIST_COOLANT_BIT);
- else gpio_set_bit_off(MIST_COOLANT_BIT);
+ coolant_set_mist(cm.gm.mist_coolant = value[0]);
}
static void _exec_flood_coolant_control(float *value, float *flag) {
cm.gm.flood_coolant = value[0];
- if (cm.gm.flood_coolant) gpio_set_bit_on(FLOOD_COOLANT_BIT);
- else {
- gpio_set_bit_off(FLOOD_COOLANT_BIT);
- float vect[] = {}; // turn off mist coolant
- _exec_mist_coolant_control(vect, vect); // M9 special function
- }
+ coolant_set_flood(value[0]);
+ if (!value[0]) coolant_set_mist(false); // M9 special function
}
// Spindle settings
-#define SPINDLE_TYPE SPINDLE_TYPE_HUANYANG
-#define SPINDLE_PWM_FREQUENCY 100 // in Hz
-#define SPINDLE_CW_SPEED_LO 1000 // in RPM (arbitrary units)
-#define SPINDLE_CW_SPEED_HI 2000
-#define SPINDLE_CW_PHASE_LO 0.125 // phase [0..1]
-#define SPINDLE_CW_PHASE_HI 0.2
-#define SPINDLE_CCW_SPEED_LO 1000
-#define SPINDLE_CCW_SPEED_HI 2000
-#define SPINDLE_CCW_PHASE_LO 0.125
-#define SPINDLE_CCW_PHASE_HI 0.2
-#define SPINDLE_PWM_PHASE_OFF 0.1
+#define SPINDLE_TYPE SPINDLE_TYPE_PWM
+#define SPINDLE_PWM_FREQUENCY 100 // in Hz
+#define SPINDLE_MIN_RPM 1000
+#define SPINDLE_MAX_RPM 24000
+#define SPINDLE_MIN_DUTY 0.05
+#define SPINDLE_MAX_DUTY 0.99
+#define SPINDLE_POLARITY 0 // 0 = normal, 1 = reverse
+
+#define SPINDLE_PWM_PORT PORTD
+#define SPINDLE_PWM_PIN_bm (1 << 5)
+#define SPINDLE_DIR_PORT PORTB
+#define SPINDLE_DIR_PIN_bm (1 << 1)
+#define SPINDLE_ENABLE_PORT PORTB
+#define SPINDLE_ENABLE_PIN_bm (1 << 6)
// Gcode defaults
#define PORT_OUT_Z PORT_MOTOR_3
#define PORT_OUT_A PORT_MOTOR_4
-#define MOTOR_PORT_DIR_gm 0x2f // pin dir settings
-
// Motor control port
#define STEP_BIT_bm (1 << 0)
#define DIRECTION_BIT_bm (1 << 1)
#define SPINDLE_BIT 0 // spindle on/off
#define SPINDLE_DIR 1 // spindle direction, 1=CW, 0=CCW
#define SPINDLE_PWM 2 // spindle PWMs output bit
-#define MIST_COOLANT_BIT 2 // coolant on/off
-#define FLOOD_COOLANT_BIT 1 // coolant on/off
+
+#define MIST_PORT PORTE
+#define MIST_PIN_bm (1 << 5)
+#define FLOOD_PORT PORTF
+#define FLOOD_PIN_bm (1 << 5)
/* Interrupt usage:
*
// Timer assignments - see specific modules for details
#define TIMER_STEP TCC0 // Step timer (see stepper.h)
#define TIMER_TMC2660 TCC1 // TMC2660 timer (see tmc2660.h)
-#define TIMER_PWM1 TCD1 // PWM timer #1 (see pwm.c)
-#define TIMER_PWM2 TCD1 // PWM timer #2 (see pwm.c)
+#define TIMER_PWM TCD1 // PWM timer (see pwm_spindle.c)
#define M1_TIMER TCE1
#define M2_TIMER TCF0
#include "stepper.h"
#include "motor.h"
#include "switch.h"
-#include "pwm.h"
#include "usart.h"
#include "tmc2660.h"
#include "vars.h"
stepper_init(); // steppers
motor_init(); // motors
switch_init(); // switches
- pwm_init(); // PWM drivers
planner_init(); // motion planning
canonical_machine_init(); // gcode machine
vars_init(); // configuration variables
for (int motor = 0; motor < MOTORS; motor++) {
motor_t *m = &motors[motor];
+ // IO pins
+ m->port->DIRSET = STEP_BIT_bm; // Output
+ m->port->DIRSET = DIRECTION_BIT_bm; // Output
+ m->port->OUTSET = MOTOR_ENABLE_BIT_bm; // High (disabled)
+ m->port->DIRSET = MOTOR_ENABLE_BIT_bm; // Output
+
// Setup motor timer
m->timer->CTRLB = TC_WGMODE_FRQ_gc | TC1_CCAEN_bm;
+++ /dev/null
-/******************************************************************************\
-
- This file is part of the Buildbotics firmware.
-
- Copyright (c) 2015 - 2016 Buildbotics LLC
- Copyright (c) 2012 - 2015 Alden S. Hart, Jr.
- All rights reserved.
-
- This file ("the software") is free software: you can redistribute it
- and/or modify it under the terms of the GNU General Public License,
- version 2 as published by the Free Software Foundation. You should
- have received a copy of the GNU General Public License, version 2
- along with the software. If not, see <http://www.gnu.org/licenses/>.
-
- The software 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
- Lesser General Public License for more details.
-
- You should have received a copy of the GNU Lesser General Public
- License along with the software. If not, see
- <http://www.gnu.org/licenses/>.
-
- For information regarding this software email:
- "Joseph Coffland" <joseph@buildbotics.com>
-
-\******************************************************************************/
-
-#include "pwm.h"
-
-#include "config.h"
-#include "hardware.h"
-#include "gpio.h"
-
-#include <string.h>
-
-
-typedef struct {
- TC1_t *timer; // assumes TC1 flavor timers used for PWM channels
-} pwm_t;
-
-
-pwm_t pwm[PWMS] = {
- {.timer = &TIMER_PWM1},
- {.timer = &TIMER_PWM2}
-};
-
-
-/* Initialize pwm channels
- *
- * Notes:
- * - Whatever level interrupts you use must be enabled in main()
- * - init assumes PWM1 output bit (D5) has been set to output previously
- * (stepper.c)
- */
-void pwm_init() {
- return; // Don't init PWM for now. TODO fix this
-
- gpio_set_bit_off(SPINDLE_PWM);
-
- pwm[PWM_1].timer->CTRLB = PWM1_CTRLB;
- pwm[PWM_2].timer->CTRLB = PWM2_CTRLB;
-}
-
-
-/* Set PWM channel frequency
- *
- * @param channel PWM channel
- * @param freq PWM frequency in Khz as a float
- *
- * Assumes 32MHz clock.
- * Doesn't turn time on until duty cycle is set
- */
-stat_t pwm_set_freq(uint8_t chan, float freq) {
- if (PWMS <= chan) return STAT_NO_SUCH_DEVICE;
- if (PWM_MAX_FREQ < freq) return STAT_INPUT_EXCEEDS_MAX_VALUE;
- if (freq < PWM_MIN_FREQ) return STAT_INPUT_LESS_THAN_MIN_VALUE;
-
- // Set period and optimal prescaler value
- float prescale = F_CPU / 65536 / freq;
- if (prescale <= 1) {
- pwm[chan].timer->PER = F_CPU / freq;
- pwm[chan].timer->CTRLA = TC_CLKSEL_DIV1_gc;
-
- } else if (prescale <= 2) {
- pwm[chan].timer->PER = F_CPU / 2 / freq;
- pwm[chan].timer->CTRLA = TC_CLKSEL_DIV2_gc;
-
- } else if (prescale <= 4) {
- pwm[chan].timer->PER = F_CPU / 4 / freq;
- pwm[chan].timer->CTRLA = TC_CLKSEL_DIV4_gc;
-
- } else if (prescale <= 8) {
- pwm[chan].timer->PER = F_CPU / 8 / freq;
- pwm[chan].timer->CTRLA = TC_CLKSEL_DIV8_gc;
-
- } else {
- pwm[chan].timer->PER = F_CPU / 64 / freq;
- pwm[chan].timer->CTRLA = TC_CLKSEL_DIV64_gc;
- }
-
- return STAT_OK;
-}
-
-
-/*
- * Set PWM channel duty cycle
- *
- * @param channel PWM channel
- * @param duty PWM duty cycle from 0% to 100%
- *
- * Setting duty cycle to 0 disables the PWM channel with output low
- * Setting duty cycle to 100 disables the PWM channel with output high
- * Setting duty cycle between 0 and 100 enables PWM channel
- *
- * The frequency must have been set previously
- */
-stat_t pwm_set_duty(uint8_t chan, float duty) {
- if (duty < 0) return STAT_INPUT_LESS_THAN_MIN_VALUE;
- if (duty > 1) return STAT_INPUT_EXCEEDS_MAX_VALUE;
-
- // Ffrq = Fper / 2N(CCA + 1)
- // Fpwm = Fper / N(PER + 1)
- float period_scalar = pwm[chan].timer->PER;
- pwm[chan].timer->CCB = period_scalar * duty + 1;
-
- return STAT_OK;
-}
+++ /dev/null
-/******************************************************************************\
-
- This file is part of the Buildbotics firmware.
-
- Copyright (c) 2015 - 2016 Buildbotics LLC
- Copyright (c) 2010 - 2015 Alden S. Hart, Jr.
- All rights reserved.
-
- This file ("the software") is free software: you can redistribute it
- and/or modify it under the terms of the GNU General Public License,
- version 2 as published by the Free Software Foundation. You should
- have received a copy of the GNU General Public License, version 2
- along with the software. If not, see <http://www.gnu.org/licenses/>.
-
- The software 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
- Lesser General Public License for more details.
-
- You should have received a copy of the GNU Lesser General Public
- License along with the software. If not, see
- <http://www.gnu.org/licenses/>.
-
- For information regarding this software email:
- "Joseph Coffland" <joseph@buildbotics.com>
-
-\******************************************************************************/
-
-#pragma once
-
-
-#include "status.h"
-
-#include <stdint.h>
-
-
-enum {
- PWM_1,
- PWM_2,
-};
-
-
-void pwm_init();
-stat_t pwm_set_freq(uint8_t channel, float freq);
-stat_t pwm_set_duty(uint8_t channel, float duty);
#include "pwm_spindle.h"
#include "config.h"
-#include "gpio.h"
-#include "hardware.h"
-#include "pwm.h"
typedef struct {
- float frequency; // base frequency for PWM driver, in Hz
- float cw_speed_lo; // minimum clockwise spindle speed [0..N]
- float cw_speed_hi; // maximum clockwise spindle speed
- float cw_phase_lo; // pwm phase at minimum CW spindle speed, clamped [0..1]
- float cw_phase_hi; // pwm phase at maximum CW spindle speed, clamped [0..1]
- float ccw_speed_lo; // minimum counter-clockwise spindle speed [0..N]
- float ccw_speed_hi; // maximum counter-clockwise spindle speed
- float ccw_phase_lo; // pwm phase at minimum CCW spindle speed, clamped [0..1]
- float ccw_phase_hi; // pwm phase at maximum CCW spindle speed, clamped
- float phase_off; // pwm phase when spindle is disabled
+ uint16_t freq; // base frequency for PWM driver, in Hz
+ float min_rpm;
+ float max_rpm;
+ float min_duty;
+ float max_duty;
+ bool reverse;
+ bool enable_invert;
} spindle_t;
static spindle_t spindle = {
- .frequency = SPINDLE_PWM_FREQUENCY,
- .cw_speed_lo = SPINDLE_CW_SPEED_LO,
- .cw_speed_hi = SPINDLE_CW_SPEED_HI,
- .cw_phase_lo = SPINDLE_CW_PHASE_LO,
- .cw_phase_hi = SPINDLE_CW_PHASE_HI,
- .ccw_speed_lo = SPINDLE_CCW_SPEED_LO,
- .ccw_speed_hi = SPINDLE_CCW_SPEED_HI,
- .ccw_phase_lo = SPINDLE_CCW_PHASE_LO,
- .ccw_phase_hi = SPINDLE_CCW_PHASE_HI,
- .phase_off = SPINDLE_PWM_PHASE_OFF,
+ .freq = SPINDLE_PWM_FREQUENCY,
+ .min_rpm = SPINDLE_MIN_RPM,
+ .max_rpm = SPINDLE_MAX_RPM,
+ .min_duty = SPINDLE_MIN_DUTY,
+ .max_duty = SPINDLE_MAX_DUTY,
+ .reverse = SPINDLE_POLARITY,
+ .enable_invert = false,
};
-/// return PWM phase (duty cycle) for dir and speed
-static float _get_spindle_pwm(cmSpindleMode_t mode, float speed) {
- float speed_lo;
- float speed_hi;
- float phase_lo;
- float phase_hi;
-
- switch (mode) {
- case SPINDLE_CW:
- speed_lo = spindle.cw_speed_lo;
- speed_hi = spindle.cw_speed_hi;
- phase_lo = spindle.cw_phase_lo;
- phase_hi = spindle.cw_phase_hi;
- break;
-
- case SPINDLE_CCW:
- speed_lo = spindle.ccw_speed_lo;
- speed_hi = spindle.ccw_speed_hi;
- phase_lo = spindle.ccw_phase_lo;
- phase_hi = spindle.ccw_phase_hi;
- break;
-
- default: return spindle.phase_off;
+static void _spindle_set_pwm(cmSpindleMode_t mode, float speed) {
+ if (mode == SPINDLE_OFF || speed < spindle.min_rpm) {
+ TIMER_PWM.CTRLA = 0;
+ return;
}
- // Clamp spindle speed to lo/hi range
- if (speed < speed_lo) speed = speed_lo;
- if (speed > speed_hi) speed = speed_hi;
+ // Clamp speed
+ if (spindle.max_rpm < speed) speed = spindle.max_rpm;
- // Normalize speed to [0..1]
- speed = (speed - speed_lo) / (speed_hi - speed_lo);
- return speed * (phase_hi - phase_lo) + phase_lo;
+ // Set clock period and optimal prescaler value
+ float prescale = F_CPU / 65536.0 / spindle.freq;
+ if (prescale <= 1) {
+ TIMER_PWM.PER = F_CPU / spindle.freq;
+ TIMER_PWM.CTRLA = TC_CLKSEL_DIV1_gc;
+
+ } else if (prescale <= 2) {
+ TIMER_PWM.PER = F_CPU / 2 / spindle.freq;
+ TIMER_PWM.CTRLA = TC_CLKSEL_DIV2_gc;
+
+ } else if (prescale <= 4) {
+ TIMER_PWM.PER = F_CPU / 4 / spindle.freq;
+ TIMER_PWM.CTRLA = TC_CLKSEL_DIV4_gc;
+
+ } else if (prescale <= 8) {
+ TIMER_PWM.PER = F_CPU / 8 / spindle.freq;
+ TIMER_PWM.CTRLA = TC_CLKSEL_DIV8_gc;
+
+ } else if (prescale <= 64) {
+ TIMER_PWM.PER = F_CPU / 64 / spindle.freq;
+ TIMER_PWM.CTRLA = TC_CLKSEL_DIV64_gc;
+
+ } else TIMER_PWM.CTRLA = 0;
+
+ // Map RPM to duty cycle
+ float duty = (speed - spindle.min_rpm) / (spindle.max_rpm - spindle.min_rpm) *
+ (spindle.max_duty - spindle.min_duty) + spindle.min_duty;
+
+ TIMER_PWM.CCB = TIMER_PWM.PER * duty;
}
-void pwm_spindle_init() {
- if (spindle.frequency < 0) spindle.frequency = 0;
+static void _spindle_set_enable(bool enable) {
+ if (enable ^ spindle.enable_invert)
+ SPINDLE_ENABLE_PORT.OUTSET = SPINDLE_ENABLE_PIN_bm;
+ else SPINDLE_ENABLE_PORT.OUTCLR = SPINDLE_ENABLE_PIN_bm;
+}
+
- pwm_set_freq(PWM_1, spindle.frequency);
- pwm_set_duty(PWM_1, spindle.phase_off);
+static void _spindle_set_dir(bool forward) {
+ if (forward ^ spindle.reverse) SPINDLE_DIR_PORT.OUTCLR = SPINDLE_DIR_PIN_bm;
+ else SPINDLE_DIR_PORT.OUTSET = SPINDLE_DIR_PIN_bm;
}
-void pwm_spindle_set(cmSpindleMode_t mode, float speed) {
- switch (mode) {
- case SPINDLE_CW:
- gpio_set_bit_on(SPINDLE_BIT);
- gpio_set_bit_off(SPINDLE_DIR);
- break;
-
- case SPINDLE_CCW:
- gpio_set_bit_on(SPINDLE_BIT);
- gpio_set_bit_on(SPINDLE_DIR);
- break;
-
- default:
- gpio_set_bit_off(SPINDLE_BIT); // failsafe: any error causes stop
- }
+void pwm_spindle_init() {
+ // Configure IO
+ SPINDLE_PWM_PORT.DIRSET = SPINDLE_PWM_PIN_bm; // PWM Output
+ _spindle_set_dir(true);
+ SPINDLE_DIR_PORT.DIRSET = SPINDLE_DIR_PIN_bm; // Dir Output
+ _spindle_set_enable(false);
+ SPINDLE_ENABLE_PORT.DIRSET = SPINDLE_ENABLE_PIN_bm; // Enable output
+
+ // Configure clock
+ TIMER_PWM.CTRLB = TC1_CCBEN_bm | TC_WGMODE_SINGLESLOPE_gc;
+}
- // PWM spindle control
- pwm_set_duty(PWM_1, _get_spindle_pwm(mode, speed));
+
+void pwm_spindle_set(cmSpindleMode_t mode, float speed) {
+ _spindle_set_dir(mode == SPINDLE_CW);
+ _spindle_set_pwm(mode, speed);
+ _spindle_set_enable(mode != SPINDLE_OFF && TIMER_PWM.CTRLA);
}
PORT_t *port = drivers[driver].port;
port->OUTSET = CHIP_SELECT_BIT_bm; // High
- port->OUTSET = MOTOR_ENABLE_BIT_bm; // High (disabled)
- port->DIR = MOTOR_PORT_DIR_gm; // Pin directions
+ port->DIRSET = CHIP_SELECT_BIT_bm; // Output
+ port->DIRCLR = FAULT_BIT_bm; // Input
port->PIN4CTRL = PORT_ISC_RISING_gc;
port->INT1MASK = FAULT_BIT_bm; // INT1