-
Notifications
You must be signed in to change notification settings - Fork 33
/
Copy pathCytronMotorDriver.cpp
78 lines (69 loc) · 1.62 KB
/
CytronMotorDriver.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
#include "CytronMotorDriver.h"
CytronMD::CytronMD(MODE mode, uint8_t pin1, uint8_t pin2)
{
_mode = mode;
_pin1 = pin1;
_pin2 = pin2;
pinMode(_pin1, OUTPUT);
pinMode(_pin2, OUTPUT);
digitalWrite(_pin1, LOW);
digitalWrite(_pin2, LOW);
}
void CytronMD::setSpeed(int16_t speed)
{
// Make sure the speed is within the limit.
if (speed > 255)
{
speed = 255;
}
else if (speed < -255)
{
speed = -255;
}
// Set the speed and direction.
switch (_mode)
{
case PWM_DIR:
if (speed >= 0)
{
#if defined(ARDUINO_ARCH_ESP32)
ledcWrite(_pin1, speed);
#else
analogWrite(_pin1, speed);
#endif
digitalWrite(_pin2, LOW);
}
else
{
#if defined(ARDUINO_ARCH_ESP32)
ledcWrite(_pin1, -speed);
#else
analogWrite(_pin1, -speed);
#endif
digitalWrite(_pin2, HIGH);
}
break;
case PWM_PWM:
if (speed >= 0)
{
#if defined(ARDUINO_ARCH_ESP32)
ledcWrite(_pin1, speed);
ledcWrite(_pin2, 0);
#else
analogWrite(_pin1, speed);
analogWrite(_pin2, 0);
#endif
}
else
{
#if defined(ARDUINO_ARCH_ESP32)
ledcWrite(_pin1, 0);
ledcWrite(_pin2, -speed);
#else
analogWrite(_pin1, 0);
analogWrite(_pin2, -speed);
#endif
}
break;
}
}