-
Notifications
You must be signed in to change notification settings - Fork 17
Expand file tree
/
Copy pathESP32MotorControl.cpp
More file actions
executable file
·346 lines (230 loc) · 7.5 KB
/
ESP32MotorControl.cpp
File metadata and controls
executable file
·346 lines (230 loc) · 7.5 KB
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
/*****************************************
* Library : ESP32MotorControl - Library for dual motor driver carrier for Arduino.
* Programmer: Joao Lopes
* Comments : This library is to use with dual motors ICs, as DRV8833, DRV8825 and L298.
* And uses the MCPWM for control motors
* Versions :
* ------ ---------- -------------------------
* 0.1.0 2018-12-26 First beta
*****************************************/
/*
* Source for ESP32MotorControl
*
* Copyright (C) 2018 Joao Lopes https://github.com/JoaoLopesF/ESP32MotorControl
*
* This program 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, version 3.
*
* This program 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 this program. If not, see <http://www.gnu.org/licenses/>.
*
* This file contains the code for ESP32MotorControl library.
*
*/
/*
* TODO list:
* - Port to L298
*/
/*
* TODO known issues:
*/
////// Includes
#include "Arduino.h"
#include "ESP32MotorControl.h"
#include <stdio.h>
#include "esp_system.h"
#include "esp_attr.h"
#include "driver/mcpwm.h"
#include "soc/mcpwm_reg.h"
#include "soc/mcpwm_struct.h"
///// Defines
// debug
//#define debug(fmt, ...)
#define debug(fmt, ...) Serial.printf("%s: " fmt "\r\n", __func__, ##__VA_ARGS__)
///// Methods
///// Driver with 4 pins: DRV88nn, DRV8833, DRV8825, etc.
// Attach one motor
void ESP32MotorControl::attachMotor(uint8_t gpioIn1, uint8_t gpioIn2)
{
attachMotors(gpioIn1, gpioIn2, 0, 0);
}
// Attach two motors
void ESP32MotorControl::attachMotors(uint8_t gpioIn1, uint8_t gpioIn2, uint8_t gpioIn3, uint8_t gpioIn4)
{
// debug
debug("init MCPWM Motor 0");
// Attach motor 0 input pins.
// Set MCPWM unit 0
mcpwm_gpio_init(MCPWM_UNIT_0, MCPWM0A, gpioIn1);
mcpwm_gpio_init(MCPWM_UNIT_0, MCPWM0B, gpioIn2);
// Indicate the motor 0 is attached.
this->mMotorAttached[0] = true;
// Attach motor 1 input pins.
if (!(gpioIn3 == 0 && gpioIn4 ==0)) {
debug("init MCPWM Motor 1");
// Set MCPWM unit 1
mcpwm_gpio_init(MCPWM_UNIT_1, MCPWM1A, gpioIn3);
mcpwm_gpio_init(MCPWM_UNIT_1, MCPWM1B, gpioIn4);
// Indicate the motor 1 is attached.
this->mMotorAttached[1] = true;
}
// Initial MCPWM configuration
debug ("Configuring Initial Parameters of MCPWM...");
mcpwm_config_t pwm_config;
pwm_config.frequency = 1000; //frequency,
pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 0
pwm_config.cmpr_b = 0; //duty cycle of PWMxb = 0
pwm_config.counter_mode = MCPWM_UP_COUNTER;
pwm_config.duty_mode = MCPWM_DUTY_MODE_0;
mcpwm_init(MCPWM_UNIT_0, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings
mcpwm_init(MCPWM_UNIT_1, MCPWM_TIMER_1, &pwm_config); //Configure PWM1A & PWM1B with above settings
debug ("MCPWM initialized");
}
// Motor full forward
void ESP32MotorControl::motorFullForward(uint8_t motor)
{
if (!isMotorValid(motor)) {
return;
}
// Full forward
if (motor == 0) {
mcpwm_set_signal_low(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B);
mcpwm_set_signal_high(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A);
} else {
mcpwm_set_signal_low(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_B);
mcpwm_set_signal_high(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_A);
}
mMotorSpeed[motor] = 100; // Save it
mMotorForward[motor] = true;
debug ("Motor %u full forward", motor);
}
// Motor set speed forward
void ESP32MotorControl::motorForward(uint8_t motor, uint8_t speed)
{
if (!isMotorValid(motor)) {
return;
}
if (speed == 100) { // Full speed
motorFullForward(motor);
} else {
// Set speed -> PWM duty 0-100
if (motor == 0) {
mcpwm_set_signal_low(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B);
mcpwm_set_duty(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A, speed);
mcpwm_set_duty_type(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A, MCPWM_DUTY_MODE_0); //call this each time, if operator was previously in low/high state
} else {
mcpwm_set_signal_low(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_B);
mcpwm_set_duty(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_A, speed);
mcpwm_set_duty_type(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_A, MCPWM_DUTY_MODE_0); //call this each time, if operator was previously in low/high state
}
mMotorSpeed[motor] = speed; // Save it
mMotorForward[motor] = true;
debug("Motor %u forward speed %u", motor, speed);
}
}
void ESP32MotorControl::motorFullReverse(uint8_t motor)
{
if (!isMotorValid(motor)) {
return;
}
// Full forward
if (motor == 0) {
mcpwm_set_signal_low(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A);
mcpwm_set_signal_high(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B);
} else {
mcpwm_set_signal_low(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_A);
mcpwm_set_signal_high(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_B);
}
mMotorSpeed[motor] = 100; // Save it
mMotorForward[motor] = false;
debug ("Motor %u full reverse", motor);
}
// Motor set speed reverse
void ESP32MotorControl::motorReverse(uint8_t motor, uint8_t speed)
{
if (!isMotorValid(motor)) {
return;
}
if (speed == 100) { // Full speed
motorFullReverse(motor);
} else {
// Set speed -> PWM duty 0-100
if (motor == 0) {
mcpwm_set_signal_low(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A);
mcpwm_set_duty(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B, speed);
mcpwm_set_duty_type(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B, MCPWM_DUTY_MODE_0); //call this each time, if operator was previously in low/high state
} else {
mcpwm_set_signal_low(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_A);
mcpwm_set_duty(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_B, speed);
mcpwm_set_duty_type(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_B, MCPWM_DUTY_MODE_0); //call this each time, if operator was previously in low/high state
}
mMotorSpeed[motor] = speed; // Save it
mMotorForward[motor] = false;
debug("Motor %u reverse speed %u", motor, speed);
}
}
// Motor stop
void ESP32MotorControl::motorStop(uint8_t motor)
{
if (!isMotorValid(motor)) {
return;
}
// Motor stop
if (motor == 0) {
mcpwm_set_signal_low(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A);
mcpwm_set_signal_low(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B);
} else {
mcpwm_set_signal_low(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_A);
mcpwm_set_signal_low(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_B);
}
mMotorSpeed[motor] = 0; // Save it
mMotorForward[motor] = true; // For stop
debug("Motor %u stop", motor);
}
// Motors stop
void ESP32MotorControl::motorsStop()
{
motorStop(0);
motorStop(1);
debug("Motors stop");
}
// Get motor speed
uint8_t ESP32MotorControl::getMotorSpeed(uint8_t motor) {
if (!isMotorValid(motor)) {
return false;
}
return mMotorSpeed[motor];
}
// Is motor in forward ?
boolean ESP32MotorControl::isMotorForward(uint8_t motor) {
if (!isMotorValid(motor)) {
return false;
}
if (isMotorStopped(motor)) {
return false;
} else {
return mMotorForward[motor];
}
}
// Is motor stopped ?
boolean ESP32MotorControl::isMotorStopped(uint8_t motor) {
if (!isMotorValid(motor)) {
return true;
}
return (mMotorSpeed[motor] == 0);
}
//// Privates
// Is motor valid ?
boolean ESP32MotorControl::isMotorValid(uint8_t motor) {
if (motor > 1) {
return false;
}
return mMotorAttached[motor];
}
///// End