Browse Source

Merge pull request #4159 from thinkyhead/rc_rigidbot_diff

Rigidbot V2 support - has MCP4728 digipot
Scott Lahteine 9 years ago
parent
commit
ee876dcd7a

+ 1
- 0
Marlin/boards.h View File

@@ -40,6 +40,7 @@
40 40
 #define BOARD_RAMPS_13_SF       38   // RAMPS 1.3 (Power outputs: Spindle, Controller Fan)
41 41
 #define BOARD_FELIX2            37   // Felix 2.0+ Electronics Board (RAMPS like)
42 42
 #define BOARD_RIGIDBOARD        42   // Invent-A-Part RigidBoard
43
+#define BOARD_RIGIDBOARD_V2     52   // Invent-A-Part RigidBoard V2
43 44
 #define BOARD_RAMPS_14_EFB      43   // RAMPS 1.4 (Power outputs: Hotend, Fan, Bed)
44 45
 #define BOARD_RAMPS_14_EEB      44   // RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Bed)
45 46
 #define BOARD_RAMPS_14_EFF      45   // RAMPS 1.4 (Power outputs: Hotend, Fan0, Fan1)

+ 11
- 11
Marlin/dac_mcp4728.cpp View File

@@ -43,9 +43,9 @@ void mcp4728_init() {
43 43
   Wire.begin();
44 44
   Wire.requestFrom(int(DAC_DEV_ADDRESS), 24);
45 45
   while(Wire.available()) {
46
-    int deviceID = Wire.receive();
47
-    int hiByte = Wire.receive();
48
-    int loByte = Wire.receive();
46
+    int deviceID = Wire.read();
47
+    int hiByte = Wire.read();
48
+    int loByte = Wire.read();
49 49
 
50 50
     int isEEPROM = (deviceID & 0B00001000) >> 3;
51 51
     int channel = (deviceID & 0B00110000) >> 4;
@@ -70,10 +70,10 @@ uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value) {
70 70
  */
71 71
 uint8_t mcp4728_eepromWrite() {
72 72
   Wire.beginTransmission(DAC_DEV_ADDRESS);
73
-  Wire.send(SEQWRITE);
73
+  Wire.write(SEQWRITE);
74 74
   for (uint8_t channel=0; channel <= 3; channel++) {
75
-    Wire.send(DAC_STEPPER_VREF << 7 | 0 << 5 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[channel]));
76
-    Wire.send(lowByte(mcp4728_values[channel]));
75
+    Wire.write(DAC_STEPPER_VREF << 7 | 0 << 5 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[channel]));
76
+    Wire.write(lowByte(mcp4728_values[channel]));
77 77
   }
78 78
   return Wire.endTransmission();
79 79
 }
@@ -83,7 +83,7 @@ uint8_t mcp4728_eepromWrite() {
83 83
  */
84 84
 uint8_t mcp4728_setVref_all(uint8_t value) {
85 85
   Wire.beginTransmission(DAC_DEV_ADDRESS);
86
-  Wire.send(VREFWRITE | value << 3 | value << 2 | value << 1 | value);
86
+  Wire.write(VREFWRITE | value << 3 | value << 2 | value << 1 | value);
87 87
   return Wire.endTransmission();
88 88
 }
89 89
 /**
@@ -91,7 +91,7 @@ uint8_t mcp4728_setVref_all(uint8_t value) {
91 91
  */
92 92
 uint8_t mcp4728_setGain_all(uint8_t value) {
93 93
   Wire.beginTransmission(DAC_DEV_ADDRESS);
94
-  Wire.send(GAINWRITE | value << 3 | value << 2 | value << 1 | value);
94
+  Wire.write(GAINWRITE | value << 3 | value << 2 | value << 1 | value);
95 95
   return Wire.endTransmission();
96 96
 }
97 97
 
@@ -120,8 +120,8 @@ uint16_t mcp4728_getVout(uint8_t channel) {
120 120
 uint8_t mcp4728_fastWrite() {
121 121
   Wire.beginTransmission(DAC_DEV_ADDRESS);
122 122
   for (uint8_t channel=0; channel <= 3; channel++) {
123
-    Wire.send(highByte(mcp4728_values[channel]));
124
-    Wire.send(lowByte(mcp4728_values[channel]));
123
+    Wire.write(highByte(mcp4728_values[channel]));
124
+    Wire.write(lowByte(mcp4728_values[channel]));
125 125
   }
126 126
   return Wire.endTransmission();
127 127
 }
@@ -131,7 +131,7 @@ uint8_t mcp4728_fastWrite() {
131 131
  */
132 132
 uint8_t mcp4728_simpleCommand(byte simpleCommand) {
133 133
   Wire.beginTransmission(GENERALCALL);
134
-  Wire.send(simpleCommand);
134
+  Wire.write(simpleCommand);
135 135
   return Wire.endTransmission();
136 136
 }
137 137
 

+ 3
- 3
Marlin/dac_mcp4728.h View File

@@ -31,9 +31,7 @@
31 31
 #include "Configuration_adv.h"
32 32
 
33 33
 #if ENABLED(DAC_STEPPER_CURRENT)
34
-#include "WProgram.h"
35 34
 #include "Wire.h"
36
-//#include <Wire.h>
37 35
 
38 36
 #define defaultVDD 5000
39 37
 #define BASE_ADDR 0x60
@@ -50,7 +48,9 @@
50 48
 #define GAINWRITE 0B11000000
51 49
 
52 50
 // This is taken from the original lib, makes it easy to edit if needed
53
-#define DAC_DEV_ADDRESS (BASE_ADDR | 0x00)
51
+// DAC_OR_ADDRESS defined in pins_BOARD.h  file
52
+#define DAC_DEV_ADDRESS (BASE_ADDR | DAC_OR_ADDRESS)
53
+
54 54
 
55 55
 void mcp4728_init();
56 56
 uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value);

+ 4
- 1
Marlin/example_configurations/RigidBot/Configuration.h View File

@@ -117,8 +117,11 @@
117 117
 
118 118
 // The following define selects which electronics board you have.
119 119
 // Please choose the name from boards.h that matches your setup
120
+// for Rigidbot version 1 : #define MOTHERBOARD BOARD_RIGIDBOARD
121
+// for Rigidbot Version 2 : #define MOTHERBOARD BOARD_RIGIDBOARD_V2
122
+
120 123
 #ifndef MOTHERBOARD
121
-  #define MOTHERBOARD BOARD_RIGIDBOARD
124
+  #define MOTHERBOARD BOARD_RIGIDBOARD_V2
122 125
 #endif
123 126
 
124 127
 // Optional custom name for your RepStrap or other custom machine

+ 2
- 0
Marlin/pins.h View File

@@ -129,6 +129,8 @@
129 129
   #include "pins_MKS_BASE.h"
130 130
 #elif MB(RIGIDBOARD)
131 131
   #include "pins_RIGIDBOARD.h"
132
+#elif MB(RIGIDBOARD_V2)
133
+  #include "pins_RIGIDBOARD_V2.h"
132 134
 #elif MB(MEGACONTROLLER)
133 135
   #include "pins_MEGACONTROLLER.h"
134 136
 #elif MB(BQ_ZUM_MEGA_3D)

+ 1
- 0
Marlin/pins_PRINTRBOARD_REVF.h View File

@@ -89,6 +89,7 @@
89 89
 #define DAC_STEPPER_MAX   3520
90 90
 #define DAC_STEPPER_VREF     1 //internal Vref, gain 1x = 2.048V
91 91
 #define DAC_STEPPER_GAIN     0
92
+#define DAC_OR_ADDRESS    0x00
92 93
 
93 94
 #if DISABLED(SDSUPPORT)
94 95
   // these pins are defined in the SD library if building with SD support

+ 40
- 0
Marlin/pins_RIGIDBOARD_V2.h View File

@@ -0,0 +1,40 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * RIGIDBOARD V2 Arduino Mega with RAMPS v1.4 pin assignments
25
+ */
26
+
27
+#include "pins_RIGIDBOARD.h"
28
+
29
+// I2C based DAC like on the Printrboard REVF
30
+#define DAC_STEPPER_CURRENT
31
+// Channels available for DAC, For Rigidboard there are 4
32
+#define DAC_STEPPER_ORDER {0,1,2,3}
33
+
34
+#define DAC_STEPPER_SENSE    0.11
35
+#define DAC_STEPPER_ADDRESS  0
36
+#define DAC_STEPPER_MAX   5000
37
+#define DAC_STEPPER_VREF     1 //internal Vref, gain 1x = 2.048V
38
+#define DAC_STEPPER_GAIN     0
39
+#define DAC_DISABLE_PIN     42 //  set low to enable DAC
40
+#define DAC_OR_ADDRESS    0x01

+ 5
- 0
Marlin/stepper_dac.cpp View File

@@ -51,6 +51,11 @@
51 51
   const uint8_t dac_order[NUM_AXIS] = DAC_STEPPER_ORDER;
52 52
 
53 53
   int dac_init() {
54
+    #if PIN_EXISTS(DAC_DISABLE)
55
+      pinMode(DAC_DISABLE_PIN, OUTPUT);
56
+      digitalWrite(DAC_DISABLE_PIN, LOW);  // set pin low to enable DAC
57
+    #endif
58
+
54 59
     mcp4728_init();
55 60
 
56 61
     if (mcp4728_simpleCommand(RESET)) return -1;

Loading…
Cancel
Save