-
Notifications
You must be signed in to change notification settings - Fork 0
/
L298NX2.cpp
336 lines (254 loc) · 5.51 KB
/
L298NX2.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
/*
L298N.cpp - Libreria per gestire i movimenti di un motore DC con il modulo L298N
Autore: Andrea Lombardo
Sito web: http://www.lombardoandrea.com
*/
#include "L298NX2.h"
#include "L298N.h"
#define DEBUG 0
typedef void (*CallBackFunction)();
L298NX2::L298NX2(uint8_t pinEnable_A,
uint8_t pinIN1_A,
uint8_t pinIN2_A,
uint8_t pinEnable_B,
uint8_t pinIN1_B,
uint8_t pinIN2_B) : _motorA(pinEnable_A,
pinIN1_A,
pinIN2_A),
_motorB(pinEnable_B,
pinIN1_B,
pinIN2_B)
{
_canMove = true;
_lastMs = 0;
}
L298NX2::L298NX2(uint8_t pinIN1_A,
uint8_t pinIN2_A,
uint8_t pinIN1_B,
uint8_t pinIN2_B) : _motorA(pinIN1_A,
pinIN2_A),
_motorB(
pinIN1_B,
pinIN2_B)
{
_canMove = true;
_lastMs = 0;
}
void trace(String msg)
{
if (DEBUG)
{
Serial.println(msg);
}
}
//Motor A
void L298NX2::setSpeedA(unsigned short pwmVal)
{
_motorA.setSpeed(pwmVal);
}
unsigned short L298NX2::getSpeedA()
{
return _motorA.getSpeed();
}
void L298NX2::forwardA()
{
_motorA.forward();
}
void L298NX2::backwardA()
{
_motorA.backward();
}
void L298NX2::runA(L298N::Direction direction)
{
_motorA.run(direction);
}
void L298NX2::runForA(unsigned long delay_A, L298N::Direction direction_A)
{
trace("runForA(d, d)");
_motorA.runFor(delay_A, direction_A);
}
void L298NX2::runForA(unsigned long delay_A, L298N::Direction direction_A, CallBackFunction callback_A)
{
trace("runForA(d, d, c)");
_motorA.runFor(delay_A, direction_A, callback_A);
}
void L298NX2::forwardForA(unsigned long delay, CallBackFunction callback)
{
this->runForA(delay, L298N::FORWARD, callback);
}
void L298NX2::forwardForA(unsigned long delay)
{
this->runForA(delay, L298N::FORWARD);
}
void L298NX2::backwardForA(unsigned long delay, CallBackFunction callback)
{
this->runForA(delay, L298N::BACKWARD, callback);
}
void L298NX2::backwardForA(unsigned long delay)
{
this->runForA(delay, L298N::BACKWARD);
}
void L298NX2::stopA()
{
_motorA.stop();
}
void L298NX2::resetA()
{
_motorA.reset();
}
boolean L298NX2::isMovingA()
{
return _motorA.isMoving();
}
L298N::Direction L298NX2::getDirectionA()
{
return _motorA.getDirection();
}
/*
*/
//Motor B
void L298NX2::setSpeedB(unsigned short pwmVal)
{
_motorB.setSpeed(pwmVal);
}
unsigned short L298NX2::getSpeedB()
{
return _motorB.getSpeed();
}
void L298NX2::forwardB()
{
_motorB.forward();
}
void L298NX2::backwardB()
{
_motorB.backward();
}
void L298NX2::runB(L298N::Direction direction)
{
_motorB.run(direction);
}
void L298NX2::runForB(unsigned long delay_B, L298N::Direction direction_B)
{
_motorB.runFor(delay_B, direction_B);
}
void L298NX2::runForB(unsigned long delay_B, L298N::Direction direction_B, CallBackFunction callback_B)
{
_motorB.runFor(delay_B, direction_B, callback_B);
}
void L298NX2::forwardForB(unsigned long delay, CallBackFunction callback)
{
this->runForB(delay, L298N::FORWARD, callback);
}
void L298NX2::forwardForB(unsigned long delay)
{
this->runForB(delay, L298N::FORWARD);
}
void L298NX2::backwardForB(unsigned long delay, CallBackFunction callback)
{
this->runForB(delay, L298N::BACKWARD, callback);
}
void L298NX2::backwardForB(unsigned long delay)
{
this->runForB(delay, L298N::BACKWARD);
}
void L298NX2::stopB()
{
_motorB.stop();
}
void L298NX2::resetB()
{
_motorB.reset();
}
boolean L298NX2::isMovingB()
{
return _motorB.isMoving();
}
L298N::Direction L298NX2::getDirectionB()
{
return _motorB.getDirection();
}
/*
*/
// Both
void L298NX2::setSpeed(unsigned short pwmVal)
{
_motorA.setSpeed(pwmVal);
_motorB.setSpeed(pwmVal);
}
void L298NX2::forward()
{
_motorA.forward();
_motorB.forward();
}
void L298NX2::backward()
{
_motorA.backward();
_motorB.backward();
}
void L298NX2::run(uint8_t direction)
{
_motorA.run(direction);
_motorB.run(direction);
}
//Timing and callback
void L298NX2::runFor(unsigned long delay, L298N::Direction direction, CallBackFunction callback)
{
if ((_lastMs == 0) && _canMove)
{
_lastMs = millis();
switch (direction)
{
case L298N::FORWARD:
this->forward();
break;
case L298N::BACKWARD:
this->backward();
break;
case L298N::STOP:
default:
this->stop();
break;
}
}
if (((millis() - _lastMs) > delay) && _canMove)
{
this->stop();
_lastMs = 0;
_canMove = false;
callback();
}
}
void L298NX2::runFor(unsigned long delay, L298N::Direction direction)
{
this->runFor(delay, direction, fakeCallback);
}
void L298NX2::forwardFor(unsigned long delay, CallBackFunction callback)
{
this->runFor(delay, L298N::FORWARD, callback);
}
void L298NX2::forwardFor(unsigned long delay)
{
this->runFor(delay, L298N::FORWARD);
}
void L298NX2::backwardFor(unsigned long delay, CallBackFunction callback)
{
this->runFor(delay, L298N::BACKWARD, callback);
}
void L298NX2::backwardFor(unsigned long delay)
{
this->runFor(delay, L298N::BACKWARD);
}
void L298NX2::stop()
{
_motorA.stop();
_motorB.stop();
}
void L298NX2::reset()
{
_canMove = true;
_motorA.reset();
_motorB.reset();
}
void L298NX2::fakeCallback()
{
}