-
Notifications
You must be signed in to change notification settings - Fork 0
/
MotorDriverL298N.cpp
77 lines (40 loc) · 1.28 KB
/
MotorDriverL298N.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
#include "MotorDriverL298N.h"
MotorDriverL298N::MotorDriverL298N(int pwm_pin, int in1_pin, int in2_pin, int pwm_resolution){
this->pwm_limit = pow(2,pwm_resolution);
this->pwm_resolution = pwm_resolution;
this->IN1 = in1_pin;
this->IN2 = in2_pin;
this->EN = pwm_pin;
}
void MotorDriverL298N::begin(){
pinMode(this->IN1, OUTPUT);
pinMode(this->IN2, OUTPUT);
pinMode(this->EN, OUTPUT);
analogWriteResolution(this->pwm_resolution);
}
void MotorDriverL298N::setDeadzone(int deadzone){
this->deadzone = deadzone;
}
int MotorDriverL298N::setLimits(int value, int limit){
if(value > limit)
value = limit;
if(value < -limit)
value = -limit;
return value;
}
void MotorDriverL298N::setPWM(int pwm_value){
pwm_value = setLimits(pwm_value, this->pwm_limit);
analogWrite(this->EN, abs(pwm_value));
if(pwm_value > this->deadzone){
digitalWrite(this->IN1, HIGH);
digitalWrite(this->IN2, LOW);
}
else if(pwm_value < -this->deadzone){
digitalWrite(this->IN1, LOW);
digitalWrite(this->IN2, HIGH);
}
else{
digitalWrite(this->IN1, LOW);
digitalWrite(this->IN2, LOW);
}
}