forked from adafruit/Adafruit_Motor_Shield_V2_Library
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Adafruit_MotorShield.cpp
397 lines (343 loc) · 10.1 KB
/
Adafruit_MotorShield.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
/******************************************************************
This is the library for the Adafruit Motor Shield V2 for Arduino.
It supports DC motors & Stepper motors with microstepping as well
as stacking-support. It is *not* compatible with the V1 library!
It will only work with https://www.adafruit.com/products/1483
Adafruit invests time and resources providing this open
source code, please support Adafruit and open-source hardware
by purchasing products from Adafruit!
Written by Limor Fried/Ladyada for Adafruit Industries.
BSD license, check license.txt for more information.
All text above must be included in any redistribution.
******************************************************************/
#if (ARDUINO >= 100)
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#include <Wire.h>
#include "Adafruit_MotorShield.h"
#include <Adafruit_PWMServoDriver.h>
#if defined(ARDUINO_SAM_DUE)
#define WIRE Wire1
#else
#define WIRE Wire
#endif
#if (MICROSTEPS == 8)
uint8_t microstepcurve[] = {0, 50, 98, 142, 180, 212, 236, 250, 255};
#elif (MICROSTEPS == 16)
uint8_t microstepcurve[] = {0, 25, 50, 74, 98, 120, 141, 162, 180, 197, 212, 225, 236, 244, 250, 253, 255};
#endif
Adafruit_MotorShield::Adafruit_MotorShield(uint8_t addr) {
_addr = addr;
_pwm = Adafruit_PWMServoDriver(_addr);
}
void Adafruit_MotorShield::begin(uint16_t freq) {
// init PWM w/_freq
WIRE.begin();
_pwm.begin();
_freq = freq;
_pwm.setPWMFreq(_freq); // This is the maximum PWM frequency
for (uint8_t i=0; i<16; i++)
_pwm.setPWM(i, 0, 0);
}
void Adafruit_MotorShield::setPWM(uint8_t pin, uint16_t value) {
if (value > 4095) {
_pwm.setPWM(pin, 4096, 0);
} else
_pwm.setPWM(pin, 0, value);
}
void Adafruit_MotorShield::setPin(uint8_t pin, boolean value) {
if (value == LOW)
_pwm.setPWM(pin, 0, 0);
else
_pwm.setPWM(pin, 4096, 0);
}
Adafruit_DCMotor *Adafruit_MotorShield::getMotor(uint8_t num) {
if (num > 4) return NULL;
num--;
if (dcmotors[num].motornum == 0) {
// not init'd yet!
dcmotors[num].motornum = num;
dcmotors[num].MC = this;
uint8_t pwm, in1, in2;
if (num == 0) {
pwm = 8; in2 = 9; in1 = 10;
} else if (num == 1) {
pwm = 13; in2 = 12; in1 = 11;
} else if (num == 2) {
pwm = 2; in2 = 3; in1 = 4;
} else if (num == 3) {
pwm = 7; in2 = 6; in1 = 5;
}
dcmotors[num].PWMpin = pwm;
dcmotors[num].IN1pin = in1;
dcmotors[num].IN2pin = in2;
}
return &dcmotors[num];
}
Adafruit_StepperMotor *Adafruit_MotorShield::getStepper(uint16_t steps, uint8_t num) {
if (num > 2) return NULL;
num--;
if (steppers[num].steppernum == 0) {
// not init'd yet!
steppers[num].steppernum = num;
steppers[num].revsteps = steps;
steppers[num].MC = this;
uint8_t pwma, pwmb, ain1, ain2, bin1, bin2;
if (num == 0) {
pwma = 8; ain2 = 9; ain1 = 10;
pwmb = 13; bin2 = 12; bin1 = 11;
} else if (num == 1) {
pwma = 2; ain2 = 3; ain1 = 4;
pwmb = 7; bin2 = 6; bin1 = 5;
}
steppers[num].PWMApin = pwma;
steppers[num].PWMBpin = pwmb;
steppers[num].AIN1pin = ain1;
steppers[num].AIN2pin = ain2;
steppers[num].BIN1pin = bin1;
steppers[num].BIN2pin = bin2;
}
return &steppers[num];
}
/******************************************
MOTORS
******************************************/
Adafruit_DCMotor::Adafruit_DCMotor(void) {
MC = NULL;
motornum = 0;
PWMpin = IN1pin = IN2pin = 0;
}
void Adafruit_DCMotor::run(uint8_t cmd) {
switch (cmd) {
case FORWARD:
MC->setPin(IN2pin, LOW); // take low first to avoid 'break'
MC->setPin(IN1pin, HIGH);
break;
case BACKWARD:
MC->setPin(IN1pin, LOW); // take low first to avoid 'break'
MC->setPin(IN2pin, HIGH);
break;
case RELEASE:
MC->setPin(IN1pin, LOW);
MC->setPin(IN2pin, LOW);
break;
}
}
void Adafruit_DCMotor::setSpeed(uint8_t speed) {
MC->setPWM(PWMpin, speed*16);
}
/******************************************
STEPPERS
******************************************/
Adafruit_StepperMotor::Adafruit_StepperMotor(void) {
revsteps = steppernum = currentstep = 0;
}
/*
uint16_t steps, Adafruit_MotorShield controller) {
revsteps = steps;
steppernum = 1;
currentstep = 0;
if (steppernum == 1) {
latch_state &= ~_BV(MOTOR1_A) & ~_BV(MOTOR1_B) &
~_BV(MOTOR2_A) & ~_BV(MOTOR2_B); // all motor pins to 0
// enable both H bridges
pinMode(11, OUTPUT);
pinMode(3, OUTPUT);
digitalWrite(11, HIGH);
digitalWrite(3, HIGH);
// use PWM for microstepping support
MC->setPWM(1, 255);
MC->setPWM(2, 255);
} else if (steppernum == 2) {
latch_state &= ~_BV(MOTOR3_A) & ~_BV(MOTOR3_B) &
~_BV(MOTOR4_A) & ~_BV(MOTOR4_B); // all motor pins to 0
// enable both H bridges
pinMode(5, OUTPUT);
pinMode(6, OUTPUT);
digitalWrite(5, HIGH);
digitalWrite(6, HIGH);
// use PWM for microstepping support
// use PWM for microstepping support
MC->setPWM(3, 255);
MC->setPWM(4, 255);
}
}
*/
void Adafruit_StepperMotor::setSpeed(uint16_t rpm) {
//Serial.println("steps per rev: "); Serial.println(revsteps);
//Serial.println("RPM: "); Serial.println(rpm);
usperstep = 60000000 / ((uint32_t)revsteps * (uint32_t)rpm);
}
void Adafruit_StepperMotor::release(void) {
MC->setPin(AIN1pin, LOW);
MC->setPin(AIN2pin, LOW);
MC->setPin(BIN1pin, LOW);
MC->setPin(BIN2pin, LOW);
MC->setPWM(PWMApin, 0);
MC->setPWM(PWMBpin, 0);
}
void Adafruit_StepperMotor::step(uint16_t steps, uint8_t dir, uint8_t style) {
uint32_t uspers = usperstep;
uint8_t ret = 0;
if (style == INTERLEAVE) {
uspers /= 2;
}
else if (style == MICROSTEP) {
uspers /= MICROSTEPS;
steps *= MICROSTEPS;
#ifdef MOTORDEBUG
Serial.print("steps = "); Serial.println(steps, DEC);
#endif
}
while (steps--) {
//Serial.println("step!"); Serial.println(uspers);
ret = onestep(dir, style);
delayMicroseconds(uspers);
}
}
uint8_t Adafruit_StepperMotor::onestep(uint8_t dir, uint8_t style) {
uint8_t a, b, c, d;
uint8_t ocrb, ocra;
ocra = ocrb = 255;
// next determine what sort of stepping procedure we're up to
if (style == SINGLE) {
if ((currentstep/(MICROSTEPS/2)) % 2) { // we're at an odd step, weird
if (dir == FORWARD) {
currentstep += MICROSTEPS/2;
}
else {
currentstep -= MICROSTEPS/2;
}
} else { // go to the next even step
if (dir == FORWARD) {
currentstep += MICROSTEPS;
}
else {
currentstep -= MICROSTEPS;
}
}
} else if (style == DOUBLE) {
if (! (currentstep/(MICROSTEPS/2) % 2)) { // we're at an even step, weird
if (dir == FORWARD) {
currentstep += MICROSTEPS/2;
} else {
currentstep -= MICROSTEPS/2;
}
} else { // go to the next odd step
if (dir == FORWARD) {
currentstep += MICROSTEPS;
} else {
currentstep -= MICROSTEPS;
}
}
} else if (style == INTERLEAVE) {
if (dir == FORWARD) {
currentstep += MICROSTEPS/2;
} else {
currentstep -= MICROSTEPS/2;
}
}
if (style == MICROSTEP) {
if (dir == FORWARD) {
currentstep++;
} else {
// BACKWARDS
currentstep--;
}
currentstep += MICROSTEPS*4;
currentstep %= MICROSTEPS*4;
ocra = ocrb = 0;
if ( (currentstep >= 0) && (currentstep < MICROSTEPS)) {
ocra = microstepcurve[MICROSTEPS - currentstep];
ocrb = microstepcurve[currentstep];
} else if ( (currentstep >= MICROSTEPS) && (currentstep < MICROSTEPS*2)) {
ocra = microstepcurve[currentstep - MICROSTEPS];
ocrb = microstepcurve[MICROSTEPS*2 - currentstep];
} else if ( (currentstep >= MICROSTEPS*2) && (currentstep < MICROSTEPS*3)) {
ocra = microstepcurve[MICROSTEPS*3 - currentstep];
ocrb = microstepcurve[currentstep - MICROSTEPS*2];
} else if ( (currentstep >= MICROSTEPS*3) && (currentstep < MICROSTEPS*4)) {
ocra = microstepcurve[currentstep - MICROSTEPS*3];
ocrb = microstepcurve[MICROSTEPS*4 - currentstep];
}
}
currentstep += MICROSTEPS*4;
currentstep %= MICROSTEPS*4;
#ifdef MOTORDEBUG
Serial.print("current step: "); Serial.println(currentstep, DEC);
Serial.print(" pwmA = "); Serial.print(ocra, DEC);
Serial.print(" pwmB = "); Serial.println(ocrb, DEC);
#endif
MC->setPWM(PWMApin, ocra*16);
MC->setPWM(PWMBpin, ocrb*16);
// release all
uint8_t latch_state = 0; // all motor pins to 0
//Serial.println(step, DEC);
if (style == MICROSTEP) {
if ((currentstep >= 0) && (currentstep < MICROSTEPS))
latch_state |= 0x03;
if ((currentstep >= MICROSTEPS) && (currentstep < MICROSTEPS*2))
latch_state |= 0x06;
if ((currentstep >= MICROSTEPS*2) && (currentstep < MICROSTEPS*3))
latch_state |= 0x0C;
if ((currentstep >= MICROSTEPS*3) && (currentstep < MICROSTEPS*4))
latch_state |= 0x09;
} else {
switch (currentstep/(MICROSTEPS/2)) {
case 0:
latch_state |= 0x1; // energize coil 1 only
break;
case 1:
latch_state |= 0x3; // energize coil 1+2
break;
case 2:
latch_state |= 0x2; // energize coil 2 only
break;
case 3:
latch_state |= 0x6; // energize coil 2+3
break;
case 4:
latch_state |= 0x4; // energize coil 3 only
break;
case 5:
latch_state |= 0xC; // energize coil 3+4
break;
case 6:
latch_state |= 0x8; // energize coil 4 only
break;
case 7:
latch_state |= 0x9; // energize coil 1+4
break;
}
}
#ifdef MOTORDEBUG
Serial.print("Latch: 0x"); Serial.println(latch_state, HEX);
#endif
if (latch_state & 0x1) {
// Serial.println(AIN2pin);
MC->setPin(AIN2pin, HIGH);
} else {
MC->setPin(AIN2pin, LOW);
}
if (latch_state & 0x2) {
MC->setPin(BIN1pin, HIGH);
// Serial.println(BIN1pin);
} else {
MC->setPin(BIN1pin, LOW);
}
if (latch_state & 0x4) {
MC->setPin(AIN1pin, HIGH);
// Serial.println(AIN1pin);
} else {
MC->setPin(AIN1pin, LOW);
}
if (latch_state & 0x8) {
MC->setPin(BIN2pin, HIGH);
// Serial.println(BIN2pin);
} else {
MC->setPin(BIN2pin, LOW);
}
return currentstep;
}