diff --git a/Marlin/Makefile b/Marlin/Makefile index 00799bbef..27cc5a7c5 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -163,6 +163,9 @@ MCU ?= at90usb1286 else ifeq ($(HARDWARE_MOTHERBOARD),81) HARDWARE_VARIANT ?= Teensy MCU ?= at90usb1286 +else ifeq ($(HARDWARE_MOTHERBOARD),811) +HARDWARE_VARIANT ?= Teensy +MCU ?= at90usb1286 else ifeq ($(HARDWARE_MOTHERBOARD),82) HARDWARE_VARIANT ?= Teensy MCU ?= at90usb646 @@ -287,7 +290,7 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \ SdFile.cpp SdVolume.cpp planner.cpp stepper.cpp \ temperature.cpp cardreader.cpp configuration_store.cpp \ watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \ - vector_3.cpp qr_solve.cpp buzzer.cpp + dac_mcp4728.cpp vector_3.cpp qr_solve.cpp buzzer.cpp ifeq ($(LIQUID_TWI2), 0) CXXSRC += LiquidCrystal.cpp else diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 0ad9d8454..04a371c78 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -68,6 +68,10 @@ #include #endif +#if ENABLED(DAC_STEPPER_CURRENT) + #include "stepper_dac.h" +#endif + /** * Look here for descriptions of G-codes: * - http://linuxcnc.org/handbook/gcode/g-code.html @@ -203,6 +207,8 @@ * M605 - Set dual x-carriage movement mode: S [ X R ] * M907 - Set digital trimpot motor current using axis codes. * M908 - Control digital trimpot directly. + * M909 - DAC_STEPPER_CURRENT: Print digipot/DAC current value + * M910 - DAC_STEPPER_CURRENT: Commit digipot/DAC value to external EEPROM via I2C * M350 - Set microstepping mode. * M351 - Toggle MS1 MS2 pins directly. * @@ -5724,21 +5730,44 @@ inline void gcode_M907() { // for each additional extruder (named B,C,D,E..., channels 4,5,6,7...) for (int i = NUM_AXIS; i < DIGIPOT_I2C_NUM_CHANNELS; i++) if (code_seen('B' + i - (NUM_AXIS))) digipot_i2c_set_current(i, code_value()); #endif + #if ENABLED(DAC_STEPPER_CURRENT) + if (code_seen('S')) { + float dac_percent = code_value(); + for (uint8_t i = 0; i <= 4; i++) dac_current_percent(i, dac_percent); + } + for (uint8_t i = 0; i < NUM_AXIS; i++) if (code_seen(axis_codes[i])) dac_current_percent(i, code_value()); + #endif } -#if HAS_DIGIPOTSS +#if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT) /** * M908: Control digital trimpot directly (M908 P S) */ inline void gcode_M908() { - digitalPotWrite( - code_seen('P') ? code_value() : 0, - code_seen('S') ? code_value() : 0 - ); + #if HAS_DIGIPOTSS + digitalPotWrite( + code_seen('P') ? code_value() : 0, + code_seen('S') ? code_value() : 0 + ); + #endif + #ifdef DAC_STEPPER_CURRENT + dac_current_raw( + code_seen('P') ? code_value_long() : -1, + code_seen('S') ? code_value_short() : 0 + ); + #endif } -#endif // HAS_DIGIPOTSS + #if ENABLED(DAC_STEPPER_CURRENT) // As with Printrbot RevF + + inline void gcode_M909() { dac_print_values(); } + + inline void gcode_M910() { dac_commit_eeprom(); } + + #endif + +#endif // HAS_DIGIPOTSS || DAC_STEPPER_CURRENT #if HAS_MICROSTEPS @@ -6438,11 +6467,25 @@ void process_next_command() { gcode_M907(); break; - #if HAS_DIGIPOTSS + #if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT) + case 908: // M908 Control digital trimpot directly. gcode_M908(); break; - #endif // HAS_DIGIPOTSS + + #if ENABLED(DAC_STEPPER_CURRENT) // As with Printrbot RevF + + case 909: // M909 Print digipot/DAC current value + gcode_M909(); + break; + + case 910: // M910 Commit digipot/DAC value to external EEPROM + gcode_M910(); + break; + + #endif + + #endif // HAS_DIGIPOTSS || DAC_STEPPER_CURRENT #if HAS_MICROSTEPS diff --git a/Marlin/boards.h b/Marlin/boards.h index 3f83e6fe1..f364172ce 100644 --- a/Marlin/boards.h +++ b/Marlin/boards.h @@ -40,6 +40,7 @@ #define BOARD_TEENSYLU 8 // Teensylu #define BOARD_RUMBA 80 // Rumba #define BOARD_PRINTRBOARD 81 // Printrboard (AT90USB1286) +#define BOARD_PRINTRBOARD_REVF 811 // Printrboard Revision F (AT90USB1286) #define BOARD_BRAINWAVE 82 // Brainwave (AT90USB646) #define BOARD_SAV_MKI 83 // SAV Mk-I (AT90USB1286) #define BOARD_TEENSY2 84 // Teensy++2.0 (AT90USB1286) - CLI compile: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84 make diff --git a/Marlin/dac_mcp4728.cpp b/Marlin/dac_mcp4728.cpp new file mode 100644 index 000000000..b7035bfc7 --- /dev/null +++ b/Marlin/dac_mcp4728.cpp @@ -0,0 +1,115 @@ +/* + + mcp4728.cpp - Arduino library for MicroChip MCP4728 I2C D/A converter + For implementation details, please take a look at the datasheet http://ww1.microchip.com/downloads/en/DeviceDoc/22187a.pdf + For discussion and feedback, please go to http://arduino.cc/forum/index.php/topic,51842.0.html +*/ + + +/* _____PROJECT INCLUDES_____________________________________________________ */ +#include "dac_mcp4728.h" + +#if ENABLED(DAC_STEPPER_CURRENT) + +// Used Global variables +uint16_t mcp4728_values[4]; + +/* +Begin I2C, get current values (input register and eeprom) of mcp4728 +*/ +void mcp4728_init() { + Wire.begin(); + Wire.requestFrom(int(DAC_DEV_ADDRESS), 24); + while(Wire.available()) { + int deviceID = Wire.receive(); + int hiByte = Wire.receive(); + int loByte = Wire.receive(); + + int isEEPROM = (deviceID & 0B00001000) >> 3; + int channel = (deviceID & 0B00110000) >> 4; + if (isEEPROM != 1) { + mcp4728_values[channel] = word((hiByte & 0B00001111), loByte); + } + } +} + +/* +Write input resister value to specified channel using fastwrite method. +Channel : 0-3, Values : 0-4095 +*/ +uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value) { + mcp4728_values[channel] = value; + return mcp4728_fastWrite(); +} +/* +Write all input resistor values to EEPROM using SequencialWrite method. +This will update both input register and EEPROM value +This will also write current Vref, PowerDown, Gain settings to EEPROM +*/ +uint8_t mcp4728_eepromWrite() { + Wire.beginTransmission(DAC_DEV_ADDRESS); + Wire.send(SEQWRITE); + for (uint8_t channel=0; channel <= 3; channel++) { + Wire.send(DAC_STEPPER_VREF << 7 | 0 << 5 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[channel])); + Wire.send(lowByte(mcp4728_values[channel])); + } + return Wire.endTransmission(); +} + +/* + Write Voltage reference setting to all input regiters +*/ +uint8_t mcp4728_setVref_all(uint8_t value) { + Wire.beginTransmission(DAC_DEV_ADDRESS); + Wire.send(VREFWRITE | value << 3 | value << 2 | value << 1 | value); + return Wire.endTransmission(); +} +/* + Write Gain setting to all input regiters +*/ +uint8_t mcp4728_setGain_all(uint8_t value) { + Wire.beginTransmission(DAC_DEV_ADDRESS); + Wire.send(GAINWRITE | value << 3 | value << 2 | value << 1 | value); + return Wire.endTransmission(); +} + +/* + Return Input Regiter value +*/ +uint16_t mcp4728_getValue(uint8_t channel) { return mcp4728_values[channel]; } + +/* +// Steph: Might be useful in the future +// Return Vout +uint16_t mcp4728_getVout(uint8_t channel) { + uint32_t vref = 2048; + uint32_t vOut = (vref * mcp4728_values[channel] * (_DAC_STEPPER_GAIN + 1)) / 4096; + if (vOut > defaultVDD) vOut = defaultVDD; + return vOut; +} +*/ + +/* +FastWrite input register values - All DAC ouput update. refer to DATASHEET 5.6.1 +DAC Input and PowerDown bits update. +No EEPROM update +*/ +uint8_t mcp4728_fastWrite() { + Wire.beginTransmission(DAC_DEV_ADDRESS); + for (uint8_t channel=0; channel <= 3; channel++) { + Wire.send(highByte(mcp4728_values[channel])); + Wire.send(lowByte(mcp4728_values[channel])); + } + return Wire.endTransmission(); +} + +/* +Common function for simple general commands +*/ +uint8_t mcp4728_simpleCommand(byte simpleCommand) { + Wire.beginTransmission(GENERALCALL); + Wire.send(simpleCommand); + return Wire.endTransmission(); +} + +#endif // DAC_STEPPER_CURRENT diff --git a/Marlin/dac_mcp4728.h b/Marlin/dac_mcp4728.h new file mode 100644 index 000000000..53664d4d6 --- /dev/null +++ b/Marlin/dac_mcp4728.h @@ -0,0 +1,44 @@ +/** +Arduino library for MicroChip MCP4728 I2C D/A converter. +*/ + +#ifndef mcp4728_h +#define mcp4728_h + +#include "Configuration.h" +#include "Configuration_adv.h" + +#if ENABLED(DAC_STEPPER_CURRENT) +#include "WProgram.h" +#include "Wire.h" +//#include + +#define defaultVDD 5000 +#define BASE_ADDR 0x60 +#define RESET 0B00000110 +#define WAKE 0B00001001 +#define UPDATE 0B00001000 +#define MULTIWRITE 0B01000000 +#define SINGLEWRITE 0B01011000 +#define SEQWRITE 0B01010000 +#define VREFWRITE 0B10000000 +#define GAINWRITE 0B11000000 +#define POWERDOWNWRITE 0B10100000 +#define GENERALCALL 0B0000000 +#define GAINWRITE 0B11000000 + +// This is taken from the original lib, makes it easy to edit if needed +#define DAC_DEV_ADDRESS (BASE_ADDR | 0x00) + +void mcp4728_init(); +uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value); +uint8_t mcp4728_eepromWrite(); +uint8_t mcp4728_setVref_all(uint8_t value); +uint8_t mcp4728_setGain_all(uint8_t value); +uint16_t mcp4728_getValue(uint8_t channel); +uint8_t mcp4728_fastWrite(); +uint8_t mcp4728_simpleCommand(byte simpleCommand); + +#endif +#endif + diff --git a/Marlin/pins.h b/Marlin/pins.h index 6d97df2ac..9df3caba1 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -77,6 +77,8 @@ #include "pins_RUMBA.h" #elif MB(PRINTRBOARD) #include "pins_PRINTRBOARD.h" +#elif MB(PRINTRBOARD_REVF) + #include "pins_PRINTRBOARD_REVF.h" #elif MB(BRAINWAVE) #include "pins_BRAINWAVE.h" #elif MB(BRAINWAVE_PRO) diff --git a/Marlin/pins_PRINTRBOARD_REVF.h b/Marlin/pins_PRINTRBOARD_REVF.h new file mode 100644 index 000000000..976ea505f --- /dev/null +++ b/Marlin/pins_PRINTRBOARD_REVF.h @@ -0,0 +1,134 @@ +/** + * Printrboard pin assignments (AT90USB1286) + * Requires the Teensyduino software with Teensy++ 2.0 selected in Arduino IDE! + * http://www.pjrc.com/teensy/teensyduino.html + * See http://reprap.org/wiki/Printrboard for more info + */ + +#ifndef __AVR_AT90USB1286__ + #error Oops! Make sure you have 'Teensy++ 2.0' selected from the 'Tools -> Boards' menu. +#endif + +#if ENABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) // use Teensyduino Teensy++2.0 pin assignments instead of Marlin traditional. + #error These Printrboard assignments depend on traditional Marlin assignments, not AT90USBxx_TEENSYPP_ASSIGNMENTS in fastio.h +#endif + +#define LARGE_FLASH true + +#define X_STEP_PIN 0 +#define X_DIR_PIN 1 +#define X_ENABLE_PIN 39 + +#define Y_STEP_PIN 2 +#define Y_DIR_PIN 3 +#define Y_ENABLE_PIN 38 + +#define Z_STEP_PIN 4 +#define Z_DIR_PIN 5 +#define Z_ENABLE_PIN 23 + +#define E0_STEP_PIN 6 +#define E0_DIR_PIN 7 +#define E0_ENABLE_PIN 19 + +#define HEATER_0_PIN 21 // Extruder +#define HEATER_1_PIN 46 +#define HEATER_2_PIN 47 +#define HEATER_BED_PIN 20 + +// If soft or fast PWM is off then use Teensyduino pin numbering, Marlin +// fastio pin numbering otherwise +#if ENABLED(FAN_SOFT_PWM) || ENABLED(FAST_PWM_FAN) + #define FAN_PIN 22 +#else + #define FAN_PIN 16 +#endif + +#define X_STOP_PIN 35 +#define Y_STOP_PIN 12 +#define Z_STOP_PIN 36 + +#define TEMP_0_PIN 1 // Extruder / Analog pin numbering +#define TEMP_BED_PIN 0 // Bed / Analog pin numbering + +#if ENABLED(FILAMENT_SENSOR) + #define FILWIDTH_PIN 2 +#endif + +#define TEMP_1_PIN -1 +#define TEMP_2_PIN -1 + +////LCD Pin Setup//// + +#define SDPOWER -1 +#define SDSS 20 // Teensylu pin mapping +#define LED_PIN -1 +#define PS_ON_PIN -1 +#define KILL_PIN -1 +#define ALARM_PIN -1 + +// uncomment to enable an I2C based DAC like on the Printrboard REVF +#define DAC_STEPPER_CURRENT +// Number of channels available for DAC, For Printrboar REVF there are 4 +#define DAC_STEPPER_ORDER {3,2,1,0} + +#define DAC_STEPPER_SENSE 0.11 +#define DAC_STEPPER_ADDRESS 0 +#define DAC_STEPPER_MAX 3520 +#define DAC_STEPPER_VREF 1 //internal Vref, gain 1x = 2.048V +#define DAC_STEPPER_GAIN 0 + +#if DISABLED(SDSUPPORT) + // these pins are defined in the SD library if building with SD support + #define SCK_PIN 9 + #define MISO_PIN 11 + #define MOSI_PIN 10 +#endif + +#if ENABLED(ULTRA_LCD) + #define BEEPER_PIN -1 + + #define LCD_PINS_RS 9 + #define LCD_PINS_ENABLE 8 + #define LCD_PINS_D4 7 + #define LCD_PINS_D5 6 + #define LCD_PINS_D6 5 + #define LCD_PINS_D7 4 + + #define BTN_EN1 16 + #define BTN_EN2 17 + #define BTN_ENC 18//the click + + #define BLEN_C 2 + #define BLEN_B 1 + #define BLEN_A 0 + + #define SD_DETECT_PIN -1 + + //encoder rotation values + #define encrot0 0 + #define encrot1 2 + #define encrot2 3 + #define encrot3 1 +#endif + +#if ENABLED(VIKI2) || ENABLED(miniVIKI) + #define BEEPER_PIN 32 //FastIO + // Pins for DOGM SPI LCD Support + #define DOGLCD_A0 42 //Non-FastIO + #define DOGLCD_CS 43 //Non-FastIO + #define LCD_SCREEN_ROT_180 + + //The encoder and click button (FastIO Pins) + #define BTN_EN1 26 + #define BTN_EN2 27 + #define BTN_ENC 47 //the click switch + + #define SDSS 45 + #define SD_DETECT_PIN -1 // FastIO (Manual says 72 I'm not certain cause I can't test) + + #if ENABLED(TEMP_STAT_LEDS) + #define STAT_LED_RED 12 //Non-FastIO + #define STAT_LED_BLUE 10 //Non-FastIO + #endif +#endif diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index 7f24a16ca..4c5f16eee 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -30,6 +30,7 @@ #include "language.h" #include "cardreader.h" #include "speed_lookuptable.h" + #if HAS_DIGIPOTSS #include #endif @@ -1181,19 +1182,18 @@ void quickStop() { #endif //BABYSTEPPING -// From Arduino DigitalPotControl example -void digitalPotWrite(int address, int value) { - #if HAS_DIGIPOTSS +#if HAS_DIGIPOTSS + + // From Arduino DigitalPotControl example + void digitalPotWrite(int address, int value) { digitalWrite(DIGIPOTSS_PIN, LOW); // take the SS pin low to select the chip SPI.transfer(address); // send in the address and value via SPI: SPI.transfer(value); digitalWrite(DIGIPOTSS_PIN, HIGH); // take the SS pin high to de-select the chip: //delay(10); - #else - UNUSED(address); - UNUSED(value); - #endif -} + } + +#endif //HAS_DIGIPOTSS // Initialize Digipot Motor Current void digipot_init() { @@ -1232,7 +1232,7 @@ void digipot_current(uint8_t driver, int current) { #else UNUSED(driver); UNUSED(current); -#endif + #endif } void microstep_init() { diff --git a/Marlin/stepper.h b/Marlin/stepper.h index 1dfe79bfc..a582ae14c 100644 --- a/Marlin/stepper.h +++ b/Marlin/stepper.h @@ -62,7 +62,9 @@ extern block_t* current_block; // A pointer to the block currently being traced void quickStop(); -void digitalPotWrite(int address, int value); +#if HAS_DIGIPOTSS + void digitalPotWrite(int address, int value); +#endif void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2); void microstep_mode(uint8_t driver, uint8_t stepping); void digipot_init(); diff --git a/Marlin/stepper_dac.cpp b/Marlin/stepper_dac.cpp new file mode 100644 index 000000000..6b8ae8f3c --- /dev/null +++ b/Marlin/stepper_dac.cpp @@ -0,0 +1,87 @@ +/* + stepper_dac.cpp - To set stepper current via DAC + + Part of Marlin + + Copyright (c) 2016 MarlinFirmware + + Marlin is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Marlin is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Marlin. If not, see . +*/ + +#include "Marlin.h" + +#if ENABLED(DAC_STEPPER_CURRENT) + + #include "stepper_dac.h" + + bool dac_present = false; + const uint8_t dac_order[NUM_AXIS] = DAC_STEPPER_ORDER; + + int dac_init() { + mcp4728_init(); + + if (mcp4728_simpleCommand(RESET)) return -1; + + dac_present = true; + + mcp4728_setVref_all(DAC_STEPPER_VREF); + mcp4728_setGain_all(DAC_STEPPER_GAIN); + + return 0; + } + + void dac_current_percent(uint8_t channel, float val) { + if (!dac_present) return; + + NOMORE(val, 100); + + mcp4728_analogWrite(dac_order[channel], val * DAC_STEPPER_MAX / 100); + mcp4728_simpleCommand(UPDATE); + } + + void dac_current_raw(uint8_t channel, uint16_t val) { + if (!dac_present) return; + + NOMORE(val, DAC_STEPPER_MAX); + + mcp4728_analogWrite(dac_order[channel], val); + mcp4728_simpleCommand(UPDATE); + } + + static float dac_perc(int8_t n) { return 100.0 * mcp4728_getValue(dac_order[n]) / DAC_STEPPER_MAX; } + static float dac_amps(int8_t n) { return ((2.048 * mcp4728_getValue(dac_order[n])) / 4096.0) / (8.0 * DAC_STEPPER_SENSE); } + + void dac_print_values() { + if (!dac_present) return; + + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM("Stepper current values in % (Amps):"); + SERIAL_ECHO_START; + SERIAL_ECHOPAIR(" X:", dac_perc(0)); + SERIAL_ECHOPAIR(" (", dac_amps(0)); + SERIAL_ECHOPAIR(") Y:", dac_perc(1)); + SERIAL_ECHOPAIR(" (", dac_amps(1)); + SERIAL_ECHOPAIR(") Z:", dac_perc(2)); + SERIAL_ECHOPAIR(" (", dac_amps(2)); + SERIAL_ECHOPAIR(") E:", dac_perc(3)); + SERIAL_ECHOPAIR(" (", dac_amps(3)); + SERIAL_ECHOLN(")"); + } + + void dac_commit_eeprom() { + if (!dac_present) return; + mcp4728_eepromWrite(); + } + +#endif // DAC_STEPPER_CURRENT diff --git a/Marlin/stepper_dac.h b/Marlin/stepper_dac.h new file mode 100644 index 000000000..9fcf97c60 --- /dev/null +++ b/Marlin/stepper_dac.h @@ -0,0 +1,33 @@ +/* + stepper_dac.h - To set stepper current via DAC + + Part of Marlin + + Copyright (c) 2016 MarlinFirmware + + Marlin is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Marlin is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Marlin. If not, see . +*/ + +#ifndef STEPPER_DAC_H +#define STEPPER_DAC_H + +#include "dac_mcp4728.h" + +int dac_init(); +void dac_current_percent(uint8_t channel, float val); +void dac_current_raw(uint8_t channel, uint16_t val); +void dac_print_values(); +void dac_commit_eeprom(); + +#endif // STEPPER_DAC_H