// Pins
enum {
- ENABLE_X_PIN = PORT_A << 3,
+ RESERVED_0_PIN = PORT_A << 3,
ENABLE_Y_PIN,
ENABLE_Z_PIN,
ENABLE_A_PIN,
SPI_MOSI_PIN,
STEP_X_PIN = PORT_D << 3,
- SPI_CS_X_PIN,
+ RESERVED_1_PIN,
SPI_CS_A_PIN,
SPI_CS_Z_PIN,
SPIN_PWM_PIN,
STEP_Y_PIN = PORT_E << 3,
SPI_CS_Y_PIN,
DIR_X_PIN,
- DIR_Y_PIN,
+ SPI_CS_X_PIN,
STEP_A_PIN,
SWITCH_2_PIN,
- DIR_Z_PIN,
- DIR_A_PIN,
+ ENABLE_X_PIN,
+ FAULT_X_PIN,
STEP_Z_PIN = PORT_F << 3,
RS485_RW_PIN,
FAULT_PIN,
ESTOP_PIN,
- FAULT_X_PIN,
+ RESERVED_2_PIN,
FAULT_Y_PIN,
FAULT_Z_PIN,
FAULT_A_PIN,
};
-
-#if 0
-enum {
- STEP_X_PIN = PORT_A << 3,
- DIR_X_PIN,
- ENABLE_X_PIN,
- SPI_CS_X_PIN,
- FAULT_X_PIN,
- FAULT_PIN,
- MIN_X_PIN,
- MAX_X_PIN,
-
- SPIN_PWM_PIN = PORT_B << 3,
- SPIN_DIR_PIN,
- MIN_Y_PIN,
- MAX_Y_PIN,
- RS485_RE_PIN,
- RS485_DE_PIN,
- SPIN_ENABLE_PIN,
- BOOT_PIN,
-
- SDA_PIN = PORT_C << 3,
- SCL_PIN,
- SERIAL_RX_PIN,
- SERIAL_TX_PIN,
- SERIAL_CTS_PIN,
- SPI_CLK_PIN,
- SPI_MOSI_PIN,
- SPI_MISO_PIN,
-
- STEP_A_PIN = PORT_D << 3,
- DIR_A_PIN,
- ENABLE_A_PIN,
- SPI_CS_A_PIN,
- FAULT_A_PIN,
- ESTOP_PIN,
- RS485_RO_PIN,
- RS485_DI_PIN,
-
- STEP_Z_PIN = PORT_E << 3,
- DIR_Z_PIN,
- ENABLE_Z_PIN,
- SPI_CS_Z_PIN,
- FAULT_Z_PIN,
- SWITCH_1_PIN,
- MIN_Z_PIN,
- MAX_Z_PIN,
-
- STEP_Y_PIN = PORT_F << 3,
- DIR_Y_PIN,
- ENABLE_Y_PIN,
- SPI_CS_Y_PIN,
- FAULT_Y_PIN,
- SWITCH_2_PIN,
- MIN_A_PIN,
- MAX_A_PIN,
-};
-#endif
+#define SPI_SS_PIN SERIAL_CTS_PIN // Needed for SPI configuration
// Compile-time settings
// Motor settings. See motor.c
-#define MOTOR_CURRENT 0.8 // 1.0 is full power
-#define MOTOR_IDLE_CURRENT 0.1 // 1.0 is full power
+#define MOTOR_CURRENT 0.3 // 1.0 is full power
+#define MOTOR_IDLE_CURRENT 0.01 // 1.0 is full power
+#define MOTOR_STALL_THRESHOLD 0 // 0 -> 1 is least -> most sensitive
#define MOTOR_MICROSTEPS 16
#define MOTOR_POWER_MODE MOTOR_POWERED_ONLY_WHEN_MOVING
-#define MOTOR_IDLE_TIMEOUT 2 // secs, motor off after this time
+#define MOTOR_IDLE_TIMEOUT 0.25 // secs, motor off after this time
#define M1_MOTOR_MAP AXIS_X
#define M1_STEP_ANGLE 1.8
*/
// Timer assignments - see specific modules for details
+// TCC1 free
#define TIMER_STEP TCC0 // Step timer (see stepper.h)
-#define TIMER_TMC2660 TCC1 // TMC2660 timer (see tmc2660.h)
#define TIMER_PWM TCD1 // PWM timer (see pwm_spindle.c)
#define M1_TIMER TCD0
#define MIN_SEGMENT_USEC 2500.0 // minimum segment time
-// TMC2660 driver settings
-#define TMC2660_OVF_vect TCC1_OVF_vect
-#define TMC2660_SPI_SS_PIN SERIAL_CTS_PIN
-#define TMC2660_SPI_SCK_PIN SPI_CLK_PIN
-#define TMC2660_SPI_MISO_PIN SPI_MISO_PIN
-#define TMC2660_SPI_MOSI_PIN SPI_MOSI_PIN
-#define TMC2660_TIMER TIMER_TMC2660
-#define TMC2660_TIMER_ENABLE TC_CLKSEL_DIV64_gc
-#define TMC2660_POLL_RATE 0.001 // sec. Must be in (0, 1]
-#define TMC2660_STABILIZE_TIME 0.01 // sec. Must be at least 1ms
-
-
// Huanyang settings
#define HUANYANG_PORT USARTD1
#define HUANYANG_DRE_vect USARTD1_DRE_vect
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics firmware.
+
+ Copyright (c) 2015 - 2016 Buildbotics LLC
+ 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 "drv8711.h"
+#include "status.h"
+#include "motor.h"
+
+#include <avr/interrupt.h>
+#include <util/delay.h>
+
+#include <string.h>
+#include <stdlib.h>
+#include <stdio.h>
+
+
+#define DRIVERS 1
+#define COMMANDS 4
+
+
+#define DRV8711_WORD_BYTE_PTR(WORD, LOW) \
+ (((uint8_t *)&(WORD)) + ((LOW) ? 0 : 1))
+
+
+typedef struct {
+ uint8_t status;
+
+ bool active;
+ float idle_current;
+ float drive_current;
+ float stall_threshold;
+
+ uint8_t mode; // microstepping mode
+
+ uint8_t cs_pin;
+ uint8_t fault_pin;
+} drv8711_driver_t;
+
+
+static drv8711_driver_t drivers[MOTORS] = {
+ {.cs_pin = SPI_CS_X_PIN, .fault_pin = FAULT_X_PIN},
+ {.cs_pin = SPI_CS_Y_PIN, .fault_pin = FAULT_Y_PIN},
+ {.cs_pin = SPI_CS_Z_PIN, .fault_pin = FAULT_Z_PIN},
+ {.cs_pin = SPI_CS_A_PIN, .fault_pin = FAULT_A_PIN},
+};
+
+
+typedef struct {
+ uint8_t *read;
+ bool callback;
+ uint8_t disable_cs_pin;
+
+ uint8_t cmd;
+ uint8_t driver;
+ bool low_byte;
+
+ uint8_t ncmds;
+ uint16_t commands[DRIVERS][COMMANDS];
+ uint16_t responses[DRIVERS];
+} spi_t;
+
+static spi_t spi = {0};
+
+
+static void _driver_check_status(int driver) {
+ uint8_t status = drivers[driver].status;
+ uint8_t mflags = 0;
+
+ if (status & DRV8711_STATUS_OTS_bm) mflags |= MOTOR_FLAG_OVER_TEMP_bm;
+ if (status & DRV8711_STATUS_AOCP_bm) mflags |= MOTOR_FLAG_OVER_CURRENT_bm;
+ if (status & DRV8711_STATUS_BOCP_bm) mflags |= MOTOR_FLAG_OVER_CURRENT_bm;
+ if (status & DRV8711_STATUS_APDF_bm) mflags |= MOTOR_FLAG_DRIVER_FAULT_bm;
+ if (status & DRV8711_STATUS_BPDF_bm) mflags |= MOTOR_FLAG_DRIVER_FAULT_bm;
+ if (status & DRV8711_STATUS_UVLO_bm) mflags |= MOTOR_FLAG_UNDER_VOLTAGE_bm;
+ if (status & DRV8711_STATUS_STD_bm) mflags |= MOTOR_FLAG_STALLED_bm;
+ if (status & DRV8711_STATUS_STDLAT_bm) mflags |= MOTOR_FLAG_STALLED_bm;
+
+ if (mflags) motor_error_callback(driver, mflags);
+}
+
+
+static float _driver_get_current(int driver) {
+ drv8711_driver_t *drv = &drivers[driver];
+ return drv->active ? drv->drive_current : drv->idle_current;
+}
+
+
+static uint8_t _spi_next_command(uint8_t cmd) {
+ // Process status responses
+ for (int driver = 0; driver < DRIVERS; driver++) {
+ uint16_t command = spi.commands[driver][cmd];
+
+ if (DRV8711_CMD_IS_READ(command) &&
+ DRV8711_CMD_ADDR(command) == DRV8711_STATUS_REG) {
+ uint8_t status = spi.responses[driver];
+
+ if (status != drivers[driver].status) {
+ drivers[driver].status = status;
+ _driver_check_status(driver);
+ }
+ }
+ }
+
+ // Next command
+ if (++cmd == spi.ncmds) {
+ cmd = 0; // Wrap around
+
+ for (int driver = 0; driver < DRIVERS; driver++)
+ motor_driver_callback(driver);
+ }
+
+ // Prep next command
+ for (int driver = 0; driver < DRIVERS; driver++) {
+ uint16_t *command = &spi.commands[driver][cmd];
+
+ switch (DRV8711_CMD_ADDR(*command)) {
+ case DRV8711_TORQUE_REG: // Update motor current setting
+ *command = (*command & 0xff00) |
+ (uint8_t)round(0xff * _driver_get_current(driver));
+ break;
+
+ case DRV8711_CTRL_REG: // Set microsteps
+ *command = (*command & 0xff87) | (drivers[driver].mode << 3);
+ break;
+
+ default: break;
+ }
+ }
+
+ return cmd;
+}
+
+
+static void _spi_send() {
+ // Flush any status errors (TODO check for errors)
+ uint8_t x = SPIC.STATUS;
+ x = x;
+
+ // Disable CS
+ if (spi.disable_cs_pin) {
+ OUTCLR_PIN(spi.disable_cs_pin); // Set low (inactive)
+ _delay_us(1);
+ spi.disable_cs_pin = 0;
+ }
+
+ // Schedule next CS disable or enable next CS now
+ if (spi.low_byte) spi.disable_cs_pin = drivers[spi.driver].cs_pin;
+ else {
+ OUTSET_PIN(drivers[spi.driver].cs_pin); // Set high (active)
+ _delay_us(1);
+ }
+
+ // Read
+ if (spi.read) {
+ *spi.read = SPIC.DATA;
+ spi.read = 0;
+ }
+
+ // Callback, passing current command index, and get next command index
+ if (spi.callback) {
+ spi.cmd = _spi_next_command(spi.cmd);
+ spi.callback = false;
+ }
+
+ // Write byte and prep next read
+ SPIC.DATA =
+ *DRV8711_WORD_BYTE_PTR(spi.commands[spi.driver][spi.cmd], spi.low_byte);
+ spi.read = DRV8711_WORD_BYTE_PTR(spi.responses[spi.driver], spi.low_byte);
+
+ // Check if WORD complete, go to next driver & check if command finished
+ if (spi.low_byte && ++spi.driver == DRIVERS) {
+ spi.driver = 0; // Wrap around
+ spi.callback = true; // Call back after last byte is read
+ }
+
+ // Next byte
+ spi.low_byte = !spi.low_byte;
+}
+
+
+static void _init_spi_commands() {
+ // Setup SPI command sequence
+ for (int driver = 0; driver < DRIVERS; driver++) {
+ uint16_t *commands = spi.commands[driver];
+ spi.ncmds = 0;
+
+ // Enable motor
+ commands[spi.ncmds++] =
+ DRV8711_WRITE(DRV8711_CTRL_REG, DRV8711_CTRL_ENBL_bm |
+ DRV8711_CTRL_EXSTALL_bm);
+
+ // Set current
+ commands[spi.ncmds++] =
+ DRV8711_WRITE(DRV8711_TORQUE_REG, DRV8711_TORQUE_SMPLTH_100);
+
+ // Read status
+ commands[spi.ncmds++] = DRV8711_READ(DRV8711_STATUS_REG);
+
+ // Clear status
+ commands[spi.ncmds++] = DRV8711_WRITE(DRV8711_STATUS_REG, 0);
+ }
+
+ if (COMMANDS < spi.ncmds)
+ STATUS_ERROR(STAT_INTERNAL_ERROR,
+ "SPI command buffer overflow increase COMMANDS in %s",
+ __FILE__);
+
+ _spi_send(); // Kick it off
+}
+
+
+ISR(SPIC_INT_vect) {
+ _spi_send();
+}
+
+
+void _fault_isr(int motor) {}
+
+
+ISR(PORT_1_FAULT_ISR_vect) {_fault_isr(0);}
+ISR(PORT_2_FAULT_ISR_vect) {_fault_isr(1);}
+ISR(PORT_3_FAULT_ISR_vect) {_fault_isr(2);}
+ISR(PORT_4_FAULT_ISR_vect) {_fault_isr(3);}
+
+
+void drv8711_init() {
+ // Configure motors
+ for (int i = 0; i < MOTORS; i++) {
+ drivers[i].idle_current = MOTOR_IDLE_CURRENT;
+ drivers[i].drive_current = MOTOR_CURRENT;
+ drivers[i].stall_threshold = MOTOR_STALL_THRESHOLD;
+
+ drv8711_disable(i);
+ }
+
+ // Setup pins
+ // Must set the SS pin either in/high or any/output for master mode to work
+ // Note, this pin is also used by the USART as the CTS line
+ DIRSET_PIN(SPI_SS_PIN); // Output
+ OUTSET_PIN(SPI_CLK_PIN); // High
+ DIRSET_PIN(SPI_CLK_PIN); // Output
+ DIRCLR_PIN(SPI_MISO_PIN); // Input
+ OUTSET_PIN(SPI_MOSI_PIN); // High
+ DIRSET_PIN(SPI_MOSI_PIN); // Output
+
+ for (int i = 0; i < DRIVERS; i++) {
+ uint8_t cs_pin = drivers[i].cs_pin;
+ uint8_t fault_pin = drivers[i].fault_pin;
+
+ OUTSET_PIN(cs_pin); // High
+ DIRSET_PIN(cs_pin); // Output
+ OUTCLR_PIN(fault_pin); // Input
+
+ // Fault interrupt
+ //PINCTRL_PIN(fault_pin) = PORT_ISC_RISING_gc;
+ //PORT(fault_pin)->INT1MASK = BM(fault_pin); // INT1
+ //PORT(fault_pin)->INTCTRL |= PORT_INT1LVL_HI_gc;
+ }
+
+ // Configure SPI
+ PR.PRPC &= ~PR_SPI_bm; // Disable power reduction
+ SPIC.CTRL = SPI_ENABLE_bm | SPI_MASTER_bm | SPI_MODE_0_gc |
+ SPI_PRESCALER_DIV16_gc; // enable, big endian, master, mode, clock div
+ PORT(SPI_CLK_PIN)->REMAP = PORT_SPI_bm; // Swap SCK and MOSI
+ SPIC.INTCTRL = SPI_INTLVL_LO_gc; // interupt level
+
+ _init_spi_commands();
+}
+
+
+void drv8711_enable(int driver) {
+ if (driver < 0 || DRIVERS <= driver) return;
+ drivers[driver].active = true;
+}
+
+
+void drv8711_disable(int driver) {
+ if (driver < 0 || DRIVERS <= driver) return;
+ drivers[driver].active = false;
+}
+
+
+void drv8711_set_microsteps(int driver, uint16_t msteps) {
+ if (driver < 0 || DRIVERS <= driver) return;
+ switch (msteps) {
+ case 1: case 2: case 4: case 8: case 16: case 32: case 64: case 128: case 256:
+ break;
+ default: return; // Invalid
+ }
+
+ drivers[driver].mode = round(logf(msteps) / logf(2));
+}
+
+
+float get_drive_power(int driver) {
+ if (driver < 0 || DRIVERS <= driver) return 0;
+ return drivers[driver].drive_current;
+}
+
+
+void set_drive_power(int driver, float value) {
+ if (driver < 0 || DRIVERS <= driver || value < 0 || 1 < value) return;
+ drivers[driver].drive_current = value;
+}
+
+
+float get_idle_power(int driver) {
+ if (driver < 0 || DRIVERS <= driver) return 0;
+ return drivers[driver].idle_current;
+}
+
+
+void set_idle_power(int driver, float value) {
+ if (driver < 0 || DRIVERS <= driver || value < 0 || 1 < value) return;
+ drivers[driver].idle_current = value;
+}
+
+
+float get_current_power(int driver) {
+ if (driver < 0 || DRIVERS <= driver) return 0;
+ return _driver_get_current(driver);
+}
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics firmware.
+
+ Copyright (c) 2015 - 2016 Buildbotics LLC
+ 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 "config.h"
+#include "status.h"
+
+#include <stdint.h>
+#include <stdbool.h>
+
+enum {
+ DRV8711_CTRL_REG,
+ DRV8711_TORQUE_REG,
+ DRV8711_OFF_REG,
+ DRV8711_BLANK_REG,
+ DRV8711_DECAY_REG,
+ DRV8711_STALL_REG,
+ DRV8711_DRIVE_REG,
+ DRV8711_STATUS_REG,
+};
+
+
+enum {
+ DRV8711_CTRL_ENBL_bm = 1 << 0,
+ DRV8711_CTRL_RDIR_bm = 1 << 1,
+ DRV8711_CTRL_RSTEP_bm = 1 << 2,
+ DRV8711_CTRL_MODE_1 = 0 << 3,
+ DRV8711_CTRL_MODE_2 = 1 << 3,
+ DRV8711_CTRL_MODE_4 = 2 << 3,
+ DRV8711_CTRL_MODE_8 = 3 << 3,
+ DRV8711_CTRL_MODE_16 = 4 << 3,
+ DRV8711_CTRL_MODE_32 = 5 << 3,
+ DRV8711_CTRL_MODE_64 = 6 << 3,
+ DRV8711_CTRL_MODE_128 = 7 << 3,
+ DRV8711_CTRL_MODE_256 = 8 << 3,
+ DRV8711_CTRL_EXSTALL_bm = 1 << 7,
+ DRV8711_CTRL_ISGAIN_5 = 0 << 8,
+ DRV8711_CTRL_ISGAIN_10 = 1 << 8,
+ DRV8711_CTRL_ISGAIN_20 = 2 << 8,
+ DRV8711_CTRL_ISGAIN_40 = 3 << 8,
+ DRV8711_CTRL_DTIME_400 = 0 << 10,
+ DRV8711_CTRL_DTIME_450 = 1 << 10,
+ DRV8711_CTRL_DTIME_650 = 2 << 10,
+ DRV8711_CTRL_DTIME_850 = 3 << 10,
+};
+
+
+enum {
+ DRV8711_TORQUE_SMPLTH_50 = 0 << 8,
+ DRV8711_TORQUE_SMPLTH_100 = 1 << 8,
+ DRV8711_TORQUE_SMPLTH_200 = 2 << 8,
+ DRV8711_TORQUE_SMPLTH_300 = 3 << 8,
+ DRV8711_TORQUE_SMPLTH_400 = 4 << 8,
+ DRV8711_TORQUE_SMPLTH_600 = 5 << 8,
+ DRV8711_TORQUE_SMPLTH_800 = 6 << 8,
+ DRV8711_TORQUE_SMPLTH_1000 = 7 << 8,
+};
+
+
+enum {
+ DRV8711_OFF_PWMMODE_bm = 1 << 8,
+};
+
+
+enum {
+ DRV8711_BLANK_ABT_bm = 1 << 8,
+};
+
+
+enum {
+ DRV8711_DECAY_DECMOD_SLOW = 0 << 8,
+ DRV8711_DECAY_DECMOD_OPT = 1 << 8,
+ DRV8711_DECAY_DECMOD_FAST = 2 << 8,
+ DRV8711_DECAY_DECMOD_MIXED = 3 << 8,
+ DRV8711_DECAY_DECMOD_AUTO_OPT = 4 << 8,
+ DRV8711_DECAY_DECMOD_AUTO_MIXED = 5 << 8,
+};
+
+
+enum {
+ DRV8711_STALL_SDCNT_1 = 0 << 8,
+ DRV8711_STALL_SDCNT_2 = 1 << 8,
+ DRV8711_STALL_SDCNT_4 = 2 << 8,
+ DRV8711_STALL_SDCNT_8 = 3 << 8,
+ DRV8711_STALL_VDIV_32 = 0 << 10,
+ DRV8711_STALL_VDIV_16 = 1 << 10,
+ DRV8711_STALL_VDIV_8 = 2 << 10,
+ DRV8711_STALL_VDIV_4 = 3 << 10,
+};
+
+
+enum {
+ DRV8711_DRIVE_OCPTH_250 = 0 << 0,
+ DRV8711_DRIVE_OCPTH_500 = 1 << 0,
+ DRV8711_DRIVE_OCPTH_750 = 2 << 0,
+ DRV8711_DRIVE_OCPTH_1000 = 3 << 0,
+ DRV8711_DRIVE_OCPDEG_1 = 0 << 2,
+ DRV8711_DRIVE_OCPDEG_2 = 1 << 2,
+ DRV8711_DRIVE_OCPDEG_4 = 2 << 2,
+ DRV8711_DRIVE_OCPDEG_8 = 3 << 2,
+ DRV8711_DRIVE_TDRIVEN_250 = 0 << 4,
+ DRV8711_DRIVE_TDRIVEN_500 = 1 << 4,
+ DRV8711_DRIVE_TDRIVEN_1000 = 2 << 4,
+ DRV8711_DRIVE_TDRIVEN_2000 = 3 << 4,
+ DRV8711_DRIVE_TDRIVEP_250 = 0 << 6,
+ DRV8711_DRIVE_TDRIVEP_500 = 1 << 6,
+ DRV8711_DRIVE_TDRIVEP_1000 = 2 << 6,
+ DRV8711_DRIVE_TDRIVEP_2000 = 3 << 6,
+ DRV8711_DRIVE_IDRIVEN_100 = 0 << 8,
+ DRV8711_DRIVE_IDRIVEN_200 = 1 << 8,
+ DRV8711_DRIVE_IDRIVEN_300 = 2 << 8,
+ DRV8711_DRIVE_IDRIVEN_400 = 3 << 8,
+ DRV8711_DRIVE_IDRIVEP_50 = 0 << 10,
+ DRV8711_DRIVE_IDRIVEP_100 = 1 << 10,
+ DRV8711_DRIVE_IDRIVEP_150 = 2 << 10,
+ DRV8711_DRIVE_IDRIVEP_200 = 3 << 10,
+};
+
+enum {
+ DRV8711_STATUS_OTS_bm = 1 << 0,
+ DRV8711_STATUS_AOCP_bm = 1 << 1,
+ DRV8711_STATUS_BOCP_bm = 1 << 2,
+ DRV8711_STATUS_APDF_bm = 1 << 3,
+ DRV8711_STATUS_BPDF_bm = 1 << 4,
+ DRV8711_STATUS_UVLO_bm = 1 << 5,
+ DRV8711_STATUS_STD_bm = 1 << 6,
+ DRV8711_STATUS_STDLAT_bm = 1 << 7,
+};
+
+
+#define DRV8711_READ(ADDR) ((1 << 15) | ((ADDR) << 12))
+#define DRV8711_WRITE(ADDR, DATA) (((ADDR) << 12) | ((DATA) & 0xfff))
+#define DRV8711_CMD_ADDR(CMD) (((CMD) >> 12) & 7)
+#define DRV8711_CMD_IS_READ(CMD) ((1 << 15) & (CMD))
+
+
+void drv8711_init();
+void drv8711_enable(int driver);
+void drv8711_disable(int driver);
+void drv8711_set_microsteps(int driver, uint16_t msteps);
#include "motor.h"
#include "switch.h"
#include "usart.h"
-#include "tmc2660.h"
+#include "drv8711.h"
#include "vars.h"
#include "rtc.h"
#include "report.h"
hardware_init(); // hardware setup - must be first
usart_init(); // serial port
i2c_init(); // i2c port
- tmc2660_init(); // motor drivers
+ drv8711_init(); // motor drivers
stepper_init(); // steppers
motor_init(); // motors
switch_init(); // switches
STAT_MSG(INTERNAL_ERROR, "Internal error")
STAT_MSG(MOTOR_STALLED, "Motor stalled")
-STAT_MSG(MOTOR_OVERTEMP_WARN, "Motor over temperature warning")
-STAT_MSG(MOTOR_OVERTEMP, "Motor over temperature")
-STAT_MSG(MOTOR_SHORTED, "Motor shorted")
+STAT_MSG(MOTOR_OVER_TEMP, "Motor over temperature")
+STAT_MSG(MOTOR_OVER_CURRENT, "Motor over temperature")
+STAT_MSG(MOTOR_DRIVER_FAULT, "Motor driver fault")
+STAT_MSG(MOTOR_UNDER_VOLTAGE, "Motor under voltage")
STAT_MSG(PREP_LINE_MOVE_TIME_INFINITE, "Move time is infinite")
STAT_MSG(PREP_LINE_MOVE_TIME_NAN, "Move time is NAN")
#include "rtc.h"
#include "report.h"
#include "stepper.h"
-#include "tmc2660.h"
+#include "drv8711.h"
#include "estop.h"
#include "gcode_state.h"
#include "util.h"
.polarity = M2_POLARITY,
.power_mode = M2_POWER_MODE,
.step_pin = STEP_Y_PIN,
- .dir_pin = DIR_Y_PIN,
+ .dir_pin = RESERVED_2_PIN, // TODO
.enable_pin = ENABLE_Y_PIN,
.timer = &M2_TIMER,
.dma = &M2_DMA_CH,
.polarity = M3_POLARITY,
.power_mode = M3_POWER_MODE,
.step_pin = STEP_Z_PIN,
- .dir_pin = DIR_Z_PIN,
+ .dir_pin = RESERVED_2_PIN, // TODO
.enable_pin = ENABLE_Z_PIN,
.timer = &M3_TIMER,
.dma = &M3_DMA_CH,
.polarity = M4_POLARITY,
.power_mode = M4_POWER_MODE,
.step_pin = STEP_A_PIN,
- .dir_pin = DIR_A_PIN,
+ .dir_pin = RESERVED_2_PIN, // TODO
.enable_pin = ENABLE_A_PIN,
.timer = (TC0_t *)&M4_TIMER,
.dma = &M4_DMA_CH,
// IO pins
DIRSET_PIN(m->step_pin); // Output
DIRSET_PIN(m->dir_pin); // Output
- OUTSET_PIN(m->enable_pin); // High (disabled)
+ OUTCLR_PIN(m->enable_pin); // Low (disabled)
DIRSET_PIN(m->enable_pin); // Output
// Setup motor timer
m->dma->CTRLA =
DMA_CH_REPEAT_bm | DMA_CH_SINGLE_bm | DMA_CH_BURSTLEN_1BYTE_gc;
m->dma->CTRLA |= DMA_CH_ENABLE_bm;
+
+ drv8711_set_microsteps(motor, m->microsteps);
}
}
void motor_enable(int motor, bool enable) {
- if (enable) OUTCLR_PIN(motors[motor].enable_pin); // Active low
+ if (enable) OUTSET_PIN(motors[motor].enable_pin); // Active high
else {
- OUTSET_PIN(motors[motor].enable_pin);
+ OUTCLR_PIN(motors[motor].enable_pin);
motors[motor].power_state = MOTOR_IDLE;
}
}
}
+int motor_get_microsteps(int motor) {return motors[motor].microsteps;}
int32_t motor_get_encoder(int motor) {return motors[motor].encoder;}
void motor_reset(int motor) {
motors[motor].flags = 0;
- tmc2660_reset(motor);
}
static void _deenergize(int motor) {
if (motors[motor].power_state == MOTOR_ACTIVE) {
motors[motor].power_state = MOTOR_IDLE;
- tmc2660_disable(motor);
+ drv8711_disable(motor);
}
}
static void _energize(int motor) {
if (motors[motor].power_state == MOTOR_IDLE && !motor_error(motor)) {
motors[motor].power_state = MOTOR_ENERGIZING;
- tmc2660_enable(motor);
+ drv8711_enable(motor);
}
// Reset timeout, regardless
motor_t *m = &motors[motor];
if (m->power_state == MOTOR_IDLE) m->flags &= ~MOTOR_FLAG_ENABLED_bm;
- else {
+ else if (!estop_triggered()) {
m->power_state = MOTOR_ACTIVE;
m->flags |= MOTOR_FLAG_ENABLED_bm;
+ motor_enable(motor, true);
}
report_request();
if (motor_error(motor)) {
if (m->flags & MOTOR_FLAG_STALLED_bm) ALARM(STAT_MOTOR_STALLED);
- if (m->flags & MOTOR_FLAG_OVERTEMP_WARN_bm) ALARM(STAT_MOTOR_OVERTEMP_WARN);
- if (m->flags & MOTOR_FLAG_OVERTEMP_bm) ALARM(STAT_MOTOR_OVERTEMP);
- if (m->flags & MOTOR_FLAG_SHORTED_bm) ALARM(STAT_MOTOR_SHORTED);
+ if (m->flags & MOTOR_FLAG_OVER_TEMP_bm) ALARM(STAT_MOTOR_OVER_TEMP);
+ if (m->flags & MOTOR_FLAG_OVER_CURRENT_bm) ALARM(STAT_MOTOR_OVER_CURRENT);
+ if (m->flags & MOTOR_FLAG_DRIVER_FAULT_bm) ALARM(STAT_MOTOR_DRIVER_FAULT);
+ if (m->flags & MOTOR_FLAG_UNDER_VOLTAGE_bm) ALARM(STAT_MOTOR_UNDER_VOLTAGE);
}
}
// a negative bias in the uint32_t conversion that results in long-term
// negative drift.
int32_t travel = round(target) - m->position + error;
- uint32_t ticks_per_step = travel ? labs(clocks / travel) : 0;
+ uint32_t ticks_per_step = travel ? labs(clocks / 2 / travel) : 0;
m->position = round(target);
// Setup the direction, compensating for polarity.
}
motors[motor].microsteps = value;
+ drv8711_set_microsteps(motor, value);
}
first = false;
}
- if (MOTOR_FLAG_OVERTEMP_WARN_bm & flags) {
+ if (MOTOR_FLAG_OVER_TEMP_bm & flags) {
if (!first) printf_P(PSTR(", "));
- printf_P(PSTR("temp warn"));
+ printf_P(PSTR("over temp"));
first = false;
}
- if (MOTOR_FLAG_OVERTEMP_bm & flags) {
+ if (MOTOR_FLAG_OVER_CURRENT_bm & flags) {
if (!first) printf_P(PSTR(", "));
- printf_P(PSTR("over temp"));
+ printf_P(PSTR("over current"));
first = false;
}
- if (MOTOR_FLAG_SHORTED_bm & flags) {
+ if (MOTOR_FLAG_DRIVER_FAULT_bm & flags) {
if (!first) printf_P(PSTR(", "));
- printf_P(PSTR("short"));
+ printf_P(PSTR("fault"));
first = false;
}
- if (MOTOR_FLAG_OPEN_LOAD_bm & flags) {
+ if (MOTOR_FLAG_UNDER_VOLTAGE_bm & flags) {
if (!first) printf_P(PSTR(", "));
- printf_P(PSTR("open"));
+ printf_P(PSTR("uvlo"));
first = false;
}
typedef enum {
MOTOR_FLAG_ENABLED_bm = 1 << 0,
MOTOR_FLAG_STALLED_bm = 1 << 1,
- MOTOR_FLAG_OVERTEMP_WARN_bm = 1 << 2,
- MOTOR_FLAG_OVERTEMP_bm = 1 << 3,
- MOTOR_FLAG_SHORTED_bm = 1 << 4,
- MOTOR_FLAG_OPEN_LOAD_bm = 1 << 5,
- MOTOR_FLAG_ERROR_bm = (//MOTOR_FLAG_STALLED_bm | TODO revisit this
- MOTOR_FLAG_SHORTED_bm |
- MOTOR_FLAG_OVERTEMP_WARN_bm |
- MOTOR_FLAG_OVERTEMP_bm)
+ MOTOR_FLAG_OVER_TEMP_bm = 1 << 2,
+ MOTOR_FLAG_OVER_CURRENT_bm = 1 << 3,
+ MOTOR_FLAG_DRIVER_FAULT_bm = 1 << 4,
+ MOTOR_FLAG_UNDER_VOLTAGE_bm = 1 << 5,
+ MOTOR_FLAG_ERROR_bm = (//MOTOR_FLAG_STALLED_bm |
+ MOTOR_FLAG_OVER_TEMP_bm |
+ MOTOR_FLAG_OVER_CURRENT_bm |
+ MOTOR_FLAG_DRIVER_FAULT_bm |
+ MOTOR_FLAG_UNDER_VOLTAGE_bm)
} motor_flags_t;
int motor_get_axis(int motor);
float motor_get_steps_per_unit(int motor);
float motor_get_units_per_step(int motor);
+int motor_get_microsteps(int motor);
int32_t motor_get_encoder(int motor);
void motor_set_encoder(int motor, float encoder);
int32_t motor_get_error(int motor);
#include <avr/io.h>
-enum {PORT_A, PORT_B, PORT_C, PORT_D, PORT_E, PORT_F};
+enum {PORT_A = 1, PORT_B, PORT_C, PORT_D, PORT_E, PORT_F};
extern PORT_t *pin_ports[];
-#define PORT(PIN) pin_ports[PIN >> 3]
+#define PORT(PIN) pin_ports[(PIN >> 3) - 1]
#define BM(PIN) (1 << (PIN & 7))
#define DIRSET_PIN(PIN) PORT(PIN)->DIRSET = BM(PIN)
#include "planner.h"
#include "stepper.h"
#include "rtc.h"
-#include "tmc2660.h"
#include "state.h"
#include "config.h"
cal.stalled = false;
cal.reverse = false;
- tmc2660_set_stallguard_threshold(cal.motor, 8);
+ //tmc2660_set_stallguard_threshold(cal.motor, 8);
cal.wait = rtc_get_time() + CAL_WAIT_TIME;
break;
float mm = (float)steps / motor_get_steps_per_unit(cal.motor);
STATUS_DEBUG("%"PRIi32" steps %0.2f mm", steps, mm);
- tmc2660_set_stallguard_threshold(cal.motor, 63);
+ //tmc2660_set_stallguard_threshold(cal.motor, 63);
mp_set_cycle(CYCLE_MACHINING); // Default cycle
+++ /dev/null
-/******************************************************************************\
-
- This file is part of the Buildbotics firmware.
-
- Copyright (c) 2015 - 2016 Buildbotics LLC
- 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 "tmc2660.h"
-#include "status.h"
-#include "motor.h"
-#include "rtc.h"
-#include "cpp_magic.h"
-#include "machine.h"
-#include "plan/calibrate.h"
-
-#include <avr/io.h>
-#include <avr/interrupt.h>
-#include <avr/pgmspace.h>
-
-#include <string.h>
-#include <stdlib.h>
-#include <stdio.h>
-
-
-#define REGS 5
-
-
-typedef struct {
- bool wrote_data;
- bool configured;
- uint32_t next_cmd;
- uint32_t stabilizing;
-
- uint16_t sguard;
- uint8_t flags;
- uint8_t reg_valid;
- uint32_t regs[REGS];
-
- float idle_current;
- float drive_current;
-
- uint8_t cs_pin;
- uint8_t fault_pin;
-} tmc2660_driver_t;
-
-
-static const uint32_t reg_addrs[] = {
- TMC2660_DRVCTRL_ADDR,
- TMC2660_CHOPCONF_ADDR,
- TMC2660_SMARTEN_ADDR,
- TMC2660_DRVCONF_ADDR,
- TMC2660_SGCSCONF_ADDR,
-};
-
-
-static tmc2660_driver_t drivers[MOTORS] = {
- {.cs_pin = SPI_CS_X_PIN, .fault_pin = FAULT_X_PIN},
- {.cs_pin = SPI_CS_Y_PIN, .fault_pin = FAULT_Y_PIN},
- {.cs_pin = SPI_CS_Z_PIN, .fault_pin = FAULT_Z_PIN},
- {.cs_pin = SPI_CS_A_PIN, .fault_pin = FAULT_A_PIN},
-};
-
-
-typedef struct {
- volatile uint8_t driver;
- volatile bool read;
- volatile uint8_t byte;
- volatile uint32_t out;
- volatile uint32_t in;
-} spi_t;
-
-static spi_t spi = {0};
-
-
-
-static bool _driver_stabilized(tmc2660_driver_t *drv) {
- return !drv->stabilizing || rtc_expired(drv->stabilizing);
-}
-
-
-static void _report_error_flags(int driver) {
- tmc2660_driver_t *drv = &drivers[driver];
-
- if (!_driver_stabilized(drv)) return;
-
- uint8_t dflags = drv->flags;
- uint8_t mflags = 0;
-
- if ((TMC2660_DRVSTATUS_SHORT_TO_GND_A | TMC2660_DRVSTATUS_SHORT_TO_GND_B) &
- dflags) mflags |= MOTOR_FLAG_SHORTED_bm;
-
- if (TMC2660_DRVSTATUS_OVERTEMP_WARN & dflags)
- mflags |= MOTOR_FLAG_OVERTEMP_WARN_bm;
-
- if (TMC2660_DRVSTATUS_OVERTEMP & dflags) mflags |= MOTOR_FLAG_OVERTEMP_bm;
-
- if ((TMC2660_DRVSTATUS_OPEN_LOAD_A | TMC2660_DRVSTATUS_OPEN_LOAD_A) & dflags)
- mflags |= MOTOR_FLAG_OPEN_LOAD_bm;
-
- if (IN_PIN(drv->fault_pin)) mflags |= MOTOR_FLAG_STALLED_bm;
-
- if (mflags) motor_error_callback(driver, mflags);
-}
-
-
-static void _spi_cs(int driver, bool enable) {
- if (enable) OUTCLR_PIN(drivers[driver].cs_pin);
- else OUTSET_PIN(drivers[driver].cs_pin);
-}
-
-
-static void _spi_next();
-
-
-static void _spi_send() {
- // Flush any status errors (TODO check for errors)
- uint8_t x = SPIC.STATUS;
- x = x;
-
- // Read
- if (!spi.byte) spi.in = 0;
- else spi.in = spi.in << 8 | SPIC.DATA;
-
- // Write
- if (spi.byte < 3) SPIC.DATA = 0xff & (spi.out >> ((2 - spi.byte++) * 8));
- else {
- // SPI transfer complete
- spi.byte = 0;
- _spi_next();
- }
-}
-
-
-static void _driver_write(int driver) {
- tmc2660_driver_t *drv = &drivers[driver];
-
- _spi_cs(spi.driver, true); // Select driver
- spi.out = drv->next_cmd;
- drv->wrote_data = true;
- _spi_send(); // Start transfer
-}
-
-
-// Returns true if the current driver has more data to send
-static bool _driver_read(int driver) {
- tmc2660_driver_t *drv = &drivers[driver];
-
- _spi_cs(spi.driver, false); // Deselect driver
-
- // Read response
- bool read_response = drv->wrote_data;
- if (drv->wrote_data) {
- drv->wrote_data = false;
-
- // Read bits [23, 4]
- drv->sguard = (spi.in >> 14) & 0x3ff;
- drv->flags = spi.in >> 4;
-
- //calibrate_set_stallguard(driver, drv->sguard);
-
- // Write driver 0 stallguard to DAC
- //if (driver == 0 && (DACB.STATUS & DAC_CH0DRE_bm))
- // DACB.CH0DATA = drv->sguard << 2;
-
- _report_error_flags(driver);
- }
-
- // Check if regs have changed
- for (int i = 0; i < REGS; i++)
- if (!(drv->reg_valid & (1 << i))) {
- // Reg changed, update driver
- drv->reg_valid |= 1 << i;
- drv->next_cmd = reg_addrs[i] | drv->regs[i];
- //drv->stabilizing = rtc_get_time() + TMC2660_STABILIZE_TIME * 1000;
- drv->configured = false;
-
- return true;
- }
-
- // Update motor
- if (!drv->configured && _driver_stabilized(drv)) {
- motor_driver_callback(driver);
- drv->configured = true;
-
- // Enable motor when first fully configured
- motor_enable(driver, true);
- }
-
- // Switch back to monitoring
- drv->next_cmd = TMC2660_DRVCTRL_ADDR | drv->regs[TMC2660_DRVCTRL];
-
- // Write command now if we didn't read a response above
- return !read_response;
-}
-
-
-static void _spi_next() {
- bool has_move = _driver_read(spi.driver);
-
- //if (!has_move) drivers[spi.driver].reg_valid = 0;
-
- if (!has_move && ++spi.driver == MOTORS) {
- spi.driver = 0;
- TMC2660_TIMER.CTRLA = TMC2660_TIMER_ENABLE;
- return;
- }
-
- _driver_write(spi.driver); // Write
-}
-
-
-ISR(SPIC_INT_vect) {
- _spi_send();
-}
-
-
-ISR(TMC2660_OVF_vect) {
- TMC2660_TIMER.CTRLA = 0; // Disable clock
- _spi_next();
-}
-
-
-void _fault_isr(int motor) {
- if (_driver_stabilized(&drivers[motor]))
- motor_error_callback(motor, MOTOR_FLAG_STALLED_bm);
-}
-
-
-ISR(PORT_1_FAULT_ISR_vect) {_fault_isr(0);}
-ISR(PORT_2_FAULT_ISR_vect) {_fault_isr(1);}
-ISR(PORT_3_FAULT_ISR_vect) {_fault_isr(2);}
-ISR(PORT_4_FAULT_ISR_vect) {_fault_isr(3);}
-
-
-void tmc2660_init() {
- // Configure motors
- for (int i = 0; i < MOTORS; i++) {
- drivers[i].idle_current = MOTOR_IDLE_CURRENT;
- drivers[i].drive_current = MOTOR_CURRENT;
-
- uint32_t mstep = 0;
- switch (MOTOR_MICROSTEPS) {
- case 1: mstep = TMC2660_DRVCTRL_MRES_1; break;
- case 2: mstep = TMC2660_DRVCTRL_MRES_2; break;
- case 4: mstep = TMC2660_DRVCTRL_MRES_4; break;
- case 8: mstep = TMC2660_DRVCTRL_MRES_8; break;
- case 16: mstep = TMC2660_DRVCTRL_MRES_16; break;
- case 32: mstep = TMC2660_DRVCTRL_MRES_32; break;
- case 64: mstep = TMC2660_DRVCTRL_MRES_64; break;
- case 128: mstep = TMC2660_DRVCTRL_MRES_128; break;
- case 256: mstep = TMC2660_DRVCTRL_MRES_256; break;
- default: break; // Invalid
- }
-
- drivers[i].regs[TMC2660_DRVCTRL] = TMC2660_DRVCTRL_DEDGE | mstep |
- (MOTOR_MICROSTEPS == 16 ? TMC2660_DRVCTRL_INTPOL : 0);
-
- drivers[i].regs[TMC2660_CHOPCONF] = TMC2660_CHOPCONF_TBL_16 |
- TMC2660_CHOPCONF_HEND(3) | TMC2660_CHOPCONF_HSTART(7) |
- TMC2660_CHOPCONF_TOFF(4);
- //drivers[i].regs[TMC2660_CHOPCONF] = TMC2660_CHOPCONF_TBL_36 |
- // TMC2660_CHOPCONF_CHM | TMC2660_CHOPCONF_HEND(7) |
- // TMC2660_CHOPCONF_FASTD(6) | TMC2660_CHOPCONF_TOFF(7);
-
- drivers[i].regs[TMC2660_SMARTEN] = TMC2660_SMARTEN_SEIMIN |
- TMC2660_SMARTEN_SE(350, 450);
- drivers[i].regs[TMC2660_SMARTEN] = 0; // Disable CoolStep
-
- drivers[i].regs[TMC2660_SGCSCONF] = TMC2660_SGCSCONF_SFILT |
- TMC2660_SGCSCONF_THRESH(63);
-
- drivers[i].regs[TMC2660_DRVCONF] = TMC2660_DRVCONF_RDSEL_SG;
-
- tmc2660_disable(i);
- }
-
- // Setup pins
- // Must set the SS pin either in/high or any/output for master mode to work
- // Note, this pin is also used by the USART as the CTS line
- DIRSET_PIN(TMC2660_SPI_SS_PIN); // Output
- OUTSET_PIN(TMC2660_SPI_SCK_PIN); // High
- DIRSET_PIN(TMC2660_SPI_SCK_PIN); // Output
- DIRCLR_PIN(TMC2660_SPI_MISO_PIN); // Input
- OUTSET_PIN(TMC2660_SPI_MOSI_PIN); // High
- DIRSET_PIN(TMC2660_SPI_MOSI_PIN); // Output
-
- for (int driver = 0; driver < MOTORS; driver++) {
- uint8_t cs_pin = drivers[driver].cs_pin;
- uint8_t fault_pin = drivers[driver].fault_pin;
-
- OUTSET_PIN(cs_pin); // High
- DIRSET_PIN(cs_pin); // Output
- OUTCLR_PIN(fault_pin); // Input
-
- PINCTRL_PIN(fault_pin) = PORT_ISC_RISING_gc;
- PORT(fault_pin)->INT1MASK = BM(fault_pin); // INT1
- PORT(fault_pin)->INTCTRL |= PORT_INT1LVL_HI_gc;
- }
-
- // Configure SPI
- PR.PRPC &= ~PR_SPI_bm; // Disable power reduction
- SPIC.CTRL = SPI_ENABLE_bm | SPI_MASTER_bm | SPI_MODE_3_gc | SPI_CLK2X_bm |
- SPI_PRESCALER_DIV16_gc; // enable, big endian, master, mode 3, clock/8
- PORT(TMC2660_SPI_SCK_PIN)->REMAP = PORT_SPI_bm; // Swap SCK and MOSI
- SPIC.INTCTRL = SPI_INTLVL_LO_gc; // interupt level
-
- // Configure timer
- PR.PRPC &= ~PR_TC1_bm; // Disable power reduction
- TMC2660_TIMER.PER = F_CPU / 64 * TMC2660_POLL_RATE;
- TMC2660_TIMER.INTCTRLA = TC_OVFINTLVL_LO_gc; // overflow interupt level
- TMC2660_TIMER.CTRLA = TMC2660_TIMER_ENABLE;
-
- // Configure DAC channel 0 for output
- //DACB.CTRLA = DAC_CH0EN_bm | DAC_ENABLE_bm;
- //DACB.CTRLB = DAC_CHSEL_SINGLE_gc;
- //DACB.CTRLC = DAC_REFSEL_AVCC_gc;
-}
-
-
-static void _set_reg(int motor, int reg, uint32_t value) {
- tmc2660_driver_t *drv = &drivers[motor];
-
- if (drv->regs[reg] == value) return;
-
- drv->regs[reg] = value;
- drv->reg_valid &= ~(1 << reg);
- drv->configured = false;
-}
-
-
-static uint32_t _get_reg(int motor, int reg) {
- return drivers[motor].regs[reg];
-}
-
-
-static float _get_current(int motor) {
- return (_get_reg(motor, TMC2660_SGCSCONF) & 31) / 31.0;
-}
-
-
-static void _set_current(int motor, float value) {
- if (value < 0 || 1 < value) return;
-
- uint32_t reg =
- (_get_reg(motor, TMC2660_SGCSCONF) & ~31) | (uint8_t)(value * 31.0);
- _set_reg(motor, TMC2660_SGCSCONF, reg);
-}
-
-
-uint8_t tmc2660_flags(int motor) {
- return motor < MOTORS ? drivers[motor].flags : 0;
-}
-
-
-void tmc2660_reset(int driver) {
- drivers[driver].reg_valid = 0;
-}
-
-
-bool tmc2660_ready(int motor) {
- return drivers[motor].configured;
-}
-
-
-void tmc2660_enable(int driver) {
- tmc2660_reset(driver);
- _set_current(driver, drivers[driver].drive_current);
-}
-
-
-void tmc2660_disable(int driver) {
- _set_current(driver, drivers[driver].idle_current);
-}
-
-
-void tmc2660_set_stallguard_threshold(int driver, int8_t threshold) {
- uint32_t value =
- _get_reg(driver, TMC2660_SGCSCONF) & ~TMC2660_SGCSCONF_THRESH_bm;
- value |= TMC2660_SGCSCONF_THRESH(threshold);
- _set_reg(driver, TMC2660_SGCSCONF, value);
-}
-
-
-float get_power_level(int driver) {
- return drivers[driver].drive_current;
-}
-
-
-void set_power_level(int driver, float value) {
- drivers[driver].drive_current = value;
-}
-
-
-float get_idle_level(int driver) {
- return drivers[driver].idle_current;
-}
-
-
-void set_idle_level(int driver, float value) {
- drivers[driver].idle_current = value;
-}
-
-
-float get_current_level(int driver) {
- return _get_current(driver);
-}
-
-
-void set_current_level(int driver, float value) {
- _set_current(driver, value);
-}
-
-
-uint16_t get_sg_value(int driver) {
- return drivers[driver].sguard;
-}
-
-
-int8_t get_stallguard(int driver) {
- uint8_t x = (_get_reg(driver, TMC2660_SGCSCONF) & 0x7f00) >> 8;
- return (x & (1 << 6)) ? (x & 0xc0) : x;
-}
-
-
-void set_stallguard(int driver, int8_t value) {
- if (value < -64 || 63 < value) return;
-
- _set_reg(driver, TMC2660_SGCSCONF,
- (_get_reg(driver, TMC2660_SGCSCONF) & ~0x7f00) |
- TMC2660_SGCSCONF_THRESH(value));
-}
+++ /dev/null
-/******************************************************************************\
-
- This file is part of the Buildbotics firmware.
-
- Copyright (c) 2015 - 2016 Buildbotics LLC
- 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 "config.h"
-#include "status.h"
-
-#include <stdint.h>
-#include <stdbool.h>
-
-
-void tmc2660_init();
-uint8_t tmc2660_status(int driver);
-void tmc2660_reset(int driver);
-bool tmc2660_ready(int driver);
-void tmc2660_enable(int driver);
-void tmc2660_disable(int driver);
-void tmc2660_set_stallguard_threshold(int driver, int8_t threshold);
-
-
-#define TMC2660_DRVCTRL 0
-#define TMC2660_DRVCTRL_ADDR (0UL << 18)
-#define TMC2660_DRVCTRL_PHA (1UL << 17)
-#define TMC2660_DRVCTRL_CA(x) (((int32_t)x & 0xff) << 9)
-#define TMC2660_DRVCTRL_PHB (1UL << 8)
-#define TMC2660_DRVCTRL_CB(x) (((int32_t)x & 0xff) << 0)
-#define TMC2660_DRVCTRL_INTPOL (1UL << 9)
-#define TMC2660_DRVCTRL_DEDGE (1UL << 8)
-#define TMC2660_DRVCTRL_MRES_256 (0UL << 0)
-#define TMC2660_DRVCTRL_MRES_128 (1UL << 0)
-#define TMC2660_DRVCTRL_MRES_64 (2UL << 0)
-#define TMC2660_DRVCTRL_MRES_32 (3UL << 0)
-#define TMC2660_DRVCTRL_MRES_16 (4UL << 0)
-#define TMC2660_DRVCTRL_MRES_8 (5UL << 0)
-#define TMC2660_DRVCTRL_MRES_4 (6UL << 0)
-#define TMC2660_DRVCTRL_MRES_2 (7UL << 0)
-#define TMC2660_DRVCTRL_MRES_1 (8UL << 0)
-
-#define TMC2660_CHOPCONF 1
-#define TMC2660_CHOPCONF_ADDR (4UL << 17)
-#define TMC2660_CHOPCONF_TBL_16 (0UL << 15)
-#define TMC2660_CHOPCONF_TBL_24 (1UL << 15)
-#define TMC2660_CHOPCONF_TBL_36 (2UL << 15)
-#define TMC2660_CHOPCONF_TBL_54 (3UL << 15)
-#define TMC2660_CHOPCONF_CHM (1UL << 14)
-#define TMC2660_CHOPCONF_RNDTF (1UL << 13)
-#define TMC2660_CHOPCONF_FDM_COMP (0UL << 12)
-#define TMC2660_CHOPCONF_FDM_TIMER (1UL << 12)
-#define TMC2660_CHOPCONF_HDEC_16 (0UL << 11)
-#define TMC2660_CHOPCONF_HDEC_32 (1UL << 11)
-#define TMC2660_CHOPCONF_HDEC_48 (2UL << 11)
-#define TMC2660_CHOPCONF_HDEC_64 (3UL << 11)
-#define TMC2660_CHOPCONF_HEND(x) ((((int32_t)x + 3) & 0xf) << 7)
-#define TMC2660_CHOPCONF_SWO(x) ((((int32_t)x + 3) & 0xf) << 7)
-#define TMC2660_CHOPCONF_HSTART(x) ((((int32_t)x - 1) & 7) << 4)
-#define TMC2660_CHOPCONF_FASTD(x) ((((int32_t)x & 8) << 11) | ((x & 7) << 4))
-#define TMC2660_CHOPCONF_TOFF_TBL (1 << 0)
-#define TMC2660_CHOPCONF_TOFF(x) (((int32_t)x & 0xf) << 0)
-
-#define TMC2660_SMARTEN 2
-#define TMC2660_SMARTEN_ADDR (5UL << 17)
-#define TMC2660_SMARTEN_SEIMIN (1UL << 15)
-#define TMC2660_SMARTEN_SEDN_32 (0UL << 13)
-#define TMC2660_SMARTEN_SEDN_8 (1UL << 13)
-#define TMC2660_SMARTEN_SEDN_2 (2UL << 13)
-#define TMC2660_SMARTEN_SEDN_1 (3UL << 13)
-#define TMC2660_SMARTEN_SEUP_1 (0UL << 5)
-#define TMC2660_SMARTEN_SEUP_2 (1UL << 5)
-#define TMC2660_SMARTEN_SEUP_4 (2UL << 5)
-#define TMC2660_SMARTEN_SEUP_8 (3UL << 5)
-#define TMC2660_SMARTEN_SE(MIN, MAX) \
- (((uint32_t)(MIN / 32) & 0xf) | \
- (((uint32_t)(MAX / 32 - MIN / 32 - 1) & 0xf) << 8))
-
-#define TMC2660_SGCSCONF 4
-#define TMC2660_SGCSCONF_ADDR (6UL << 17)
-#define TMC2660_SGCSCONF_SFILT (1UL << 16)
-#define TMC2660_SGCSCONF_THRESH_bm 0x7f00
-#define TMC2660_SGCSCONF_THRESH(x) (((int32_t)x & 0x7f) << 8)
-#define TMC2660_SGCSCONF_CS(x) (((int32_t)x & 0x1f) << 0)
-#define TMC2660_SGCSCONF_CS_NONE (31UL << 0)
-
-#define TMC2660_DRVCONF 3
-#define TMC2660_DRVCONF_ADDR (7UL << 17)
-#define TMC2660_DRVCONF_TST (1UL << 16)
-#define TMC2660_DRVCONF_SLPH_MIN (0UL << 14)
-#define TMC2660_DRVCONF_SLPH_MIN_TC (1UL << 14)
-#define TMC2660_DRVCONF_SLPH_MED_TC (2UL << 14)
-#define TMC2660_DRVCONF_SLPH_MAX (3UL << 14)
-#define TMC2660_DRVCONF_SLPL_MIN (0UL << 12)
-#define TMC2660_DRVCONF_SLPL_MED (2UL << 12)
-#define TMC2660_DRVCONF_SLPL_MAX (3UL << 12)
-#define TMC2660_DRVCONF_DISS2G (1UL << 10)
-#define TMC2660_DRVCONF_TS2G_3_2 (0UL << 8)
-#define TMC2660_DRVCONF_TS2G_1_6 (1UL << 8)
-#define TMC2660_DRVCONF_TS2G_1_2 (2UL << 8)
-#define TMC2660_DRVCONF_TS2G_0_8 (3UL << 8)
-#define TMC2660_DRVCONF_SDOFF (1UL << 7)
-#define TMC2660_DRVCONF_VSENSE (1UL << 6)
-#define TMC2660_DRVCONF_RDSEL_MSTEP (0UL << 4)
-#define TMC2660_DRVCONF_RDSEL_SG (1UL << 4)
-#define TMC2660_DRVCONF_RDSEL_SGCS (2UL << 4)
-
-#define TMC2660_DRVSTATUS_STANDSTILL (1UL << 7)
-#define TMC2660_DRVSTATUS_OPEN_LOAD_B (1UL << 6)
-#define TMC2660_DRVSTATUS_OPEN_LOAD_A (1UL << 5)
-#define TMC2660_DRVSTATUS_SHORT_TO_GND_B (1UL << 4)
-#define TMC2660_DRVSTATUS_SHORT_TO_GND_A (1UL << 3)
-#define TMC2660_DRVSTATUS_OVERTEMP_WARN (1UL << 2)
-#define TMC2660_DRVSTATUS_OVERTEMP (1UL << 1)
-#define TMC2660_DRVSTATUS_STALLED (1UL << 0)
// Type names
static const char bool_name [] PROGMEM = "<bool>";
#define TYPE_NAME(TYPE) static const char TYPE##_name [] PROGMEM = "<" #TYPE ">"
-MAP(TYPE_NAME, SEMI, flags_t, string, pstring, float, int8_t, uint8_t, uint16_t,
+MAP(TYPE_NAME, SEMI, flags_t, string, pstring, float, uint8_t, uint16_t,
int32_t);
// int8
+#if 0
static void var_print_int8_t(int8_t x) {
printf_P(PSTR("%"PRIi8), x);
}
static void eeprom_update_int8_t(int8_t *addr, int8_t value) {
eeprom_update_byte((uint8_t *)addr, value);
}
-
+#endif
// uint8
static void var_print_uint8_t(uint8_t x) {
VAR(polarity, "po", uint8_t, MOTORS, 1, 1, "Normal or reversed")
VAR(power_mode, "pm", uint8_t, MOTORS, 1, 1, "Motor power mode")
-VAR(power_level, "pl", float, MOTORS, 1, 1, "Motor drive current")
-VAR(idle_level, "il", float, MOTORS, 1, 1, "Motor idle current")
-VAR(current_level, "cl", float, MOTORS, 1, 1, "Motor current now")
-VAR(stallguard, "th", int8_t, MOTORS, 1, 1, "StallGuard threshold")
-VAR(sg_value, "sg", uint16_t, MOTORS, 0, 0, "StallGuard reading")
+VAR(drive_power, "dp", float, MOTORS, 1, 1, "Motor drive power")
+VAR(idle_power, "ip", float, MOTORS, 1, 1, "Motor idle power")
+VAR(current_power, "cp", float, MOTORS, 0, 0, "Motor power now")
VAR(status_flags, "mf", uint8_t, MOTORS, 0, 0, "Motor status flags")
VAR(status_strings, "ms", flags_t, MOTORS, 0, 0, "Motor status strings")