Browse Source

Add support for Printrboard RevF

The PrintrBoard Rev F utilizes a mcp4728 DAC to set motor current. Printrbot's implementation utilizes 2 new M-codes to set and write the DAC settings to the DAC EEPROM: `M909` (Read DAC) and `M910` (Write DAC). `M907` is re-used to set value, `M908` for direct control.

The Pins file for the RevF board is included.
Stephanie 8 years ago
parent
commit
6843b78f99
7 changed files with 365 additions and 2 deletions
  1. 4
    1
      Marlin/Makefile
  2. 1
    0
      Marlin/boards.h
  3. 115
    0
      Marlin/dac_mcp4728.cpp
  4. 44
    0
      Marlin/dac_mcp4728.h
  5. 2
    0
      Marlin/pins.h
  6. 134
    0
      Marlin/pins_PRINTRBOARD_REVF.h
  7. 65
    1
      Marlin/stepper.cpp

+ 4
- 1
Marlin/Makefile View File

@@ -163,6 +163,9 @@ MCU              ?= at90usb1286
163 163
 else ifeq  ($(HARDWARE_MOTHERBOARD),81)
164 164
 HARDWARE_VARIANT ?= Teensy
165 165
 MCU              ?= at90usb1286
166
+else ifeq  ($(HARDWARE_MOTHERBOARD),811)
167
+HARDWARE_VARIANT ?= Teensy
168
+MCU              ?= at90usb1286
166 169
 else ifeq  ($(HARDWARE_MOTHERBOARD),82)
167 170
 HARDWARE_VARIANT ?= Teensy
168 171
 MCU              ?= at90usb646
@@ -287,7 +290,7 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp	\
287 290
 	SdFile.cpp SdVolume.cpp planner.cpp stepper.cpp \
288 291
 	temperature.cpp cardreader.cpp configuration_store.cpp \
289 292
 	watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
290
-	vector_3.cpp qr_solve.cpp buzzer.cpp
293
+	dac_mcp4728.cpp vector_3.cpp qr_solve.cpp buzzer.cpp
291 294
 ifeq ($(LIQUID_TWI2), 0)
292 295
 CXXSRC += LiquidCrystal.cpp
293 296
 else

+ 1
- 0
Marlin/boards.h View File

@@ -40,6 +40,7 @@
40 40
 #define BOARD_TEENSYLU          8    // Teensylu
41 41
 #define BOARD_RUMBA             80   // Rumba
42 42
 #define BOARD_PRINTRBOARD       81   // Printrboard (AT90USB1286)
43
+#define BOARD_PRINTRBOARD_REVF  811  // Printrboard Revision F (AT90USB1286)
43 44
 #define BOARD_BRAINWAVE         82   // Brainwave (AT90USB646)
44 45
 #define BOARD_SAV_MKI           83   // SAV Mk-I (AT90USB1286)
45 46
 #define BOARD_TEENSY2           84   // Teensy++2.0 (AT90USB1286) - CLI compile: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84  make

+ 115
- 0
Marlin/dac_mcp4728.cpp View File

@@ -0,0 +1,115 @@
1
+/*
2
+
3
+  mcp4728.cpp - Arduino library for MicroChip MCP4728 I2C D/A converter
4
+  For implementation details, please take a look at the datasheet http://ww1.microchip.com/downloads/en/DeviceDoc/22187a.pdf
5
+  For discussion and feedback, please go to http://arduino.cc/forum/index.php/topic,51842.0.html
6
+*/
7
+
8
+
9
+/* _____PROJECT INCLUDES_____________________________________________________ */
10
+#include "dac_mcp4728.h"
11
+
12
+#if ENABLED(DAC_STEPPER_CURRENT)
13
+
14
+// Used Global variables
15
+uint16_t     mcp4728_values[4];
16
+
17
+/*
18
+Begin I2C, get current values (input register and eeprom) of mcp4728
19
+*/
20
+void mcp4728_init() {
21
+  Wire.begin();
22
+  Wire.requestFrom(int(DAC_DEV_ADDRESS), 24);
23
+  while(Wire.available()) {
24
+    int deviceID = Wire.receive();
25
+    int hiByte = Wire.receive();
26
+    int loByte = Wire.receive();
27
+
28
+    int isEEPROM = (deviceID & 0B00001000) >> 3;
29
+    int channel = (deviceID & 0B00110000) >> 4;
30
+    if (isEEPROM != 1) {
31
+      mcp4728_values[channel] = word((hiByte & 0B00001111), loByte);
32
+    }
33
+  }
34
+}
35
+
36
+/*
37
+Write input resister value to specified channel using fastwrite method.
38
+Channel : 0-3, Values : 0-4095
39
+*/
40
+uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value) {
41
+  mcp4728_values[channel] = value;
42
+  return mcp4728_fastWrite();
43
+}
44
+/*
45
+Write all input resistor values to EEPROM using SequencialWrite method.
46
+This will update both input register and EEPROM value
47
+This will also write current Vref, PowerDown, Gain settings to EEPROM
48
+*/
49
+uint8_t mcp4728_eepromWrite() {
50
+  Wire.beginTransmission(DAC_DEV_ADDRESS);
51
+  Wire.send(SEQWRITE);
52
+  for (uint8_t channel=0; channel <= 3; channel++) {
53
+    Wire.send(DAC_STEPPER_VREF << 7 | 0 << 5 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[channel]));
54
+    Wire.send(lowByte(mcp4728_values[channel]));
55
+  }
56
+  return Wire.endTransmission();
57
+}
58
+
59
+/*
60
+  Write Voltage reference setting to all input regiters
61
+*/
62
+uint8_t mcp4728_setVref_all(uint8_t value) {
63
+  Wire.beginTransmission(DAC_DEV_ADDRESS);
64
+  Wire.send(VREFWRITE | value << 3 | value << 2 | value << 1 | value);
65
+  return Wire.endTransmission();
66
+}
67
+/*
68
+  Write Gain setting to all input regiters
69
+*/
70
+uint8_t mcp4728_setGain_all(uint8_t value) {
71
+  Wire.beginTransmission(DAC_DEV_ADDRESS);
72
+  Wire.send(GAINWRITE | value << 3 | value << 2 | value << 1 | value);
73
+  return Wire.endTransmission();
74
+}
75
+
76
+/*
77
+  Return Input Regiter value
78
+*/
79
+uint16_t mcp4728_getValue(uint8_t channel) { return mcp4728_values[channel]; }
80
+
81
+/*
82
+// Steph: Might be useful in the future
83
+// Return Vout
84
+uint16_t mcp4728_getVout(uint8_t channel) {
85
+  uint32_t vref = 2048;
86
+  uint32_t vOut = (vref * mcp4728_values[channel] * (_DAC_STEPPER_GAIN + 1)) / 4096;
87
+  if (vOut > defaultVDD) vOut = defaultVDD;
88
+  return vOut;
89
+}
90
+*/
91
+
92
+/*
93
+FastWrite input register values - All DAC ouput update. refer to DATASHEET 5.6.1
94
+DAC Input and PowerDown bits update.
95
+No EEPROM update
96
+*/
97
+uint8_t mcp4728_fastWrite() {
98
+  Wire.beginTransmission(DAC_DEV_ADDRESS);
99
+  for (uint8_t channel=0; channel <= 3; channel++) {
100
+    Wire.send(highByte(mcp4728_values[channel]));
101
+    Wire.send(lowByte(mcp4728_values[channel]));
102
+  }
103
+  return Wire.endTransmission();
104
+}
105
+
106
+/*
107
+Common function for simple general commands
108
+*/
109
+uint8_t mcp4728_simpleCommand(byte simpleCommand) {
110
+  Wire.beginTransmission(GENERALCALL);
111
+  Wire.send(simpleCommand);
112
+  return Wire.endTransmission();
113
+}
114
+
115
+#endif // DAC_STEPPER_CURRENT

+ 44
- 0
Marlin/dac_mcp4728.h View File

@@ -0,0 +1,44 @@
1
+/**
2
+Arduino library for MicroChip MCP4728 I2C D/A converter.
3
+*/
4
+
5
+#ifndef mcp4728_h
6
+#define mcp4728_h
7
+
8
+#include "Configuration.h"
9
+#include "Configuration_adv.h"
10
+
11
+#if ENABLED(DAC_STEPPER_CURRENT)
12
+#include "WProgram.h"
13
+#include "Wire.h"
14
+//#include <Wire.h>
15
+
16
+#define defaultVDD 5000
17
+#define BASE_ADDR 0x60
18
+#define RESET 0B00000110
19
+#define WAKE 0B00001001
20
+#define UPDATE 0B00001000
21
+#define MULTIWRITE 0B01000000
22
+#define SINGLEWRITE 0B01011000
23
+#define SEQWRITE 0B01010000
24
+#define VREFWRITE 0B10000000
25
+#define GAINWRITE 0B11000000
26
+#define POWERDOWNWRITE 0B10100000
27
+#define GENERALCALL 0B0000000
28
+#define GAINWRITE 0B11000000
29
+
30
+// This is taken from the original lib, makes it easy to edit if needed
31
+#define DAC_DEV_ADDRESS (BASE_ADDR | 0x00)
32
+
33
+void mcp4728_init();
34
+uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value);
35
+uint8_t mcp4728_eepromWrite();
36
+uint8_t mcp4728_setVref_all(uint8_t value);
37
+uint8_t mcp4728_setGain_all(uint8_t value);
38
+uint16_t mcp4728_getValue(uint8_t channel);
39
+uint8_t mcp4728_fastWrite();
40
+uint8_t mcp4728_simpleCommand(byte simpleCommand);
41
+
42
+#endif
43
+#endif
44
+

+ 2
- 0
Marlin/pins.h View File

@@ -77,6 +77,8 @@
77 77
   #include "pins_RUMBA.h"
78 78
 #elif MB(PRINTRBOARD)
79 79
   #include "pins_PRINTRBOARD.h"
80
+#elif MB(PRINTRBOARD_REVF)
81
+  #include "pins_PRINTRBOARD_REVF.h"
80 82
 #elif MB(BRAINWAVE)
81 83
   #include "pins_BRAINWAVE.h"
82 84
 #elif MB(BRAINWAVE_PRO)

+ 134
- 0
Marlin/pins_PRINTRBOARD_REVF.h View File

@@ -0,0 +1,134 @@
1
+/**
2
+ * Printrboard pin assignments (AT90USB1286)
3
+ * Requires the Teensyduino software with Teensy++ 2.0 selected in Arduino IDE!
4
+ * http://www.pjrc.com/teensy/teensyduino.html
5
+ * See http://reprap.org/wiki/Printrboard for more info
6
+ */
7
+
8
+#ifndef __AVR_AT90USB1286__
9
+  #error Oops!  Make sure you have 'Teensy++ 2.0' selected from the 'Tools -> Boards' menu.
10
+#endif
11
+
12
+#if ENABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS)  // use Teensyduino Teensy++2.0 pin assignments instead of Marlin traditional.
13
+  #error These Printrboard assignments depend on traditional Marlin assignments, not AT90USBxx_TEENSYPP_ASSIGNMENTS in fastio.h
14
+#endif
15
+
16
+#define LARGE_FLASH        true
17
+
18
+#define X_STEP_PIN          0
19
+#define X_DIR_PIN           1
20
+#define X_ENABLE_PIN       39
21
+
22
+#define Y_STEP_PIN          2
23
+#define Y_DIR_PIN           3
24
+#define Y_ENABLE_PIN       38
25
+
26
+#define Z_STEP_PIN          4
27
+#define Z_DIR_PIN           5
28
+#define Z_ENABLE_PIN       23
29
+
30
+#define E0_STEP_PIN         6
31
+#define E0_DIR_PIN          7
32
+#define E0_ENABLE_PIN      19
33
+
34
+#define HEATER_0_PIN       21  // Extruder
35
+#define HEATER_1_PIN       46
36
+#define HEATER_2_PIN       47
37
+#define HEATER_BED_PIN     20
38
+
39
+// If soft or fast PWM is off then use Teensyduino pin numbering, Marlin
40
+// fastio pin numbering otherwise
41
+#if ENABLED(FAN_SOFT_PWM) || ENABLED(FAST_PWM_FAN)
42
+  #define FAN_PIN          22
43
+#else
44
+  #define FAN_PIN          16
45
+#endif
46
+
47
+#define X_STOP_PIN         35
48
+#define Y_STOP_PIN         12
49
+#define Z_STOP_PIN         36
50
+
51
+#define TEMP_0_PIN          1  // Extruder / Analog pin numbering
52
+#define TEMP_BED_PIN        0  // Bed / Analog pin numbering
53
+
54
+#if ENABLED(FILAMENT_SENSOR)
55
+  #define FILWIDTH_PIN      2
56
+#endif
57
+
58
+#define TEMP_1_PIN         -1
59
+#define TEMP_2_PIN         -1
60
+
61
+////LCD Pin Setup////
62
+
63
+#define SDPOWER            -1
64
+#define SDSS               20 // Teensylu pin mapping
65
+#define LED_PIN            -1
66
+#define PS_ON_PIN          -1
67
+#define KILL_PIN           -1
68
+#define ALARM_PIN          -1
69
+
70
+// uncomment to enable an I2C based DAC like on the Printrboard REVF
71
+#define DAC_STEPPER_CURRENT
72
+// Number of channels available for DAC, For Printrboar REVF there are 4
73
+#define DAC_STEPPER_ORDER 	{3,2,1,0}
74
+
75
+#define DAC_STEPPER_SENSE 0.11
76
+#define DAC_STEPPER_ADDRESS	0
77
+#define DAC_STEPPER_MAX 	3520
78
+#define DAC_STEPPER_VREF 	1 //internal Vref, gain 1x = 2.048V
79
+#define DAC_STEPPER_GAIN	0
80
+
81
+#if DISABLED(SDSUPPORT)
82
+  // these pins are defined in the SD library if building with SD support
83
+  #define SCK_PIN           9
84
+  #define MISO_PIN         11
85
+  #define MOSI_PIN         10
86
+#endif
87
+
88
+#if ENABLED(ULTRA_LCD)
89
+  #define BEEPER_PIN -1
90
+
91
+  #define LCD_PINS_RS 9
92
+  #define LCD_PINS_ENABLE 8
93
+  #define LCD_PINS_D4 7
94
+  #define LCD_PINS_D5 6
95
+  #define LCD_PINS_D6 5
96
+  #define LCD_PINS_D7 4
97
+
98
+  #define BTN_EN1   16
99
+  #define BTN_EN2   17
100
+  #define BTN_ENC   18//the click
101
+
102
+  #define BLEN_C 2
103
+  #define BLEN_B 1
104
+  #define BLEN_A 0
105
+
106
+  #define SD_DETECT_PIN -1
107
+
108
+  //encoder rotation values
109
+  #define encrot0 0
110
+  #define encrot1 2
111
+  #define encrot2 3
112
+  #define encrot3 1
113
+#endif
114
+
115
+#if ENABLED(VIKI2) || ENABLED(miniVIKI)
116
+  #define BEEPER_PIN 32 //FastIO
117
+  // Pins for DOGM SPI LCD Support
118
+  #define DOGLCD_A0  42 //Non-FastIO
119
+  #define DOGLCD_CS  43 //Non-FastIO
120
+  #define LCD_SCREEN_ROT_180
121
+
122
+  //The encoder and click button (FastIO Pins)
123
+  #define BTN_EN1 26
124
+  #define BTN_EN2 27
125
+  #define BTN_ENC 47  //the click switch
126
+
127
+  #define SDSS 45
128
+  #define SD_DETECT_PIN -1 // FastIO (Manual says 72 I'm not certain cause I can't test)
129
+
130
+  #if ENABLED(TEMP_STAT_LEDS)
131
+    #define STAT_LED_RED      12 //Non-FastIO
132
+    #define STAT_LED_BLUE     10 //Non-FastIO
133
+  #endif
134
+#endif

+ 65
- 1
Marlin/stepper.cpp View File

@@ -30,6 +30,7 @@
30 30
 #include "language.h"
31 31
 #include "cardreader.h"
32 32
 #include "speed_lookuptable.h"
33
+#include "dac_mcp4728.h"
33 34
 #if HAS_DIGIPOTSS
34 35
   #include <SPI.h>
35 36
 #endif
@@ -1224,9 +1225,72 @@ void digipot_current(uint8_t driver, int current) {
1224 1225
   #else
1225 1226
     UNUSED(driver);
1226 1227
     UNUSED(current);
1227
-#endif
1228
+  #endif
1228 1229
 }
1229 1230
 
1231
+#if ENABLED(DAC_STEPPER_CURRENT)
1232
+
1233
+  bool dac_present = false;
1234
+  const uint8_t dac_order[NUM_AXIS] = DAC_STEPPER_ORDER;
1235
+
1236
+  int dac_init() {
1237
+    mcp4728_init();
1238
+
1239
+    if (mcp4728_simpleCommand(RESET)) return -1;
1240
+
1241
+    dac_present = true;
1242
+
1243
+    mcp4728_setVref_all(DAC_STEPPER_VREF);
1244
+    mcp4728_setGain_all(DAC_STEPPER_GAIN);
1245
+
1246
+    return 0;
1247
+  }
1248
+
1249
+  void dac_current_percent(uint8_t channel, float val) {
1250
+    if (!dac_present) return;
1251
+
1252
+    NOMORE(val, 100);
1253
+
1254
+    mcp4728_analogWrite(dac_order[channel], val * DAC_STEPPER_MAX / 100);
1255
+    mcp4728_simpleCommand(UPDATE);
1256
+  }
1257
+
1258
+  void dac_current_raw(uint8_t channel, uint16_t val) {
1259
+    if (!dac_present) return;
1260
+
1261
+    NOMORE(val, DAC_STEPPER_MAX);
1262
+
1263
+    mcp4728_analogWrite(dac_order[channel], val);
1264
+    mcp4728_simpleCommand(UPDATE);
1265
+  }
1266
+
1267
+  static float dac_perc(int8_t n) { return 100.0 * mcp4728_getValue(dac_order[n]) / DAC_STEPPER_MAX; }
1268
+  static float dac_amps(int8_t n) { return ((2.048 * mcp4728_getValue(dac_order[n])) / 4096.0) / (8.0 * DAC_STEPPER_SENSE); }
1269
+
1270
+  void dac_print_values() {
1271
+    if (!dac_present) return;
1272
+
1273
+    SERIAL_ECHO_START;
1274
+    SERIAL_ECHOLNPGM("Stepper current values in % (Amps):");
1275
+    SERIAL_ECHO_START;
1276
+    SERIAL_ECHOPAIR(" X:",  dac_perc(0));
1277
+    SERIAL_ECHOPAIR(" (",   dac_amps(0));
1278
+    SERIAL_ECHOPAIR(") Y:", dac_perc(1));
1279
+    SERIAL_ECHOPAIR(" (",   dac_amps(1));
1280
+    SERIAL_ECHOPAIR(") Z:", dac_perc(2));
1281
+    SERIAL_ECHOPAIR(" (",   dac_amps(2));
1282
+    SERIAL_ECHOPAIR(") E:", dac_perc(3));
1283
+    SERIAL_ECHOPAIR(" (",   dac_amps(3));
1284
+    SERIAL_ECHOLN(")");
1285
+  }
1286
+
1287
+  void dac_commit_eeprom() {
1288
+    if (!dac_present) return;
1289
+    mcp4728_eepromWrite();
1290
+  }
1291
+
1292
+#endif // DAC_STEPPER_CURRENT
1293
+
1230 1294
 void microstep_init() {
1231 1295
   #if HAS_MICROSTEPS_E1
1232 1296
     pinMode(E1_MS1_PIN, OUTPUT);

Loading…
Cancel
Save