-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathL298N.cpp
91 lines (85 loc) · 1.92 KB
/
L298N.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
/*
* L298N library, using to drive L298N to control motors
* Copyright (C) 2017 Liu Chaoyang
*
* 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, either version 3 of the License, or
* (at your option) any later version.
*
* 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/>.
**/
#include "L298N.h"
void L298N::initMotorController()
{
pinMode(ena, OUTPUT);
pinMode(enb, OUTPUT);
pinMode(in1, OUTPUT);
pinMode(in2, OUTPUT);
pinMode(in3, OUTPUT);
pinMode(in4, OUTPUT);
}
void L298N::setMotorSpeed(int i, int spd)
{
if (spd > MAX_PWM)
{
spd = MAX_PWM;
}
if (spd < -MAX_PWM)
{
spd = -MAX_PWM;
}
if (i == LEFT)
{// left wheel
if (spd >= 0)
{
// Go forward
digitalWrite(in2, HIGH);
digitalWrite(in1, LOW);
analogWrite(ena, spd);
}
else
{
// Go backward
digitalWrite(in1, HIGH);
digitalWrite(in2, LOW);
analogWrite(ena, -spd);
}
}
else
{// right wheel
if (spd >= 0)
{
// Go forward
digitalWrite(in4, HIGH);
digitalWrite(in3, LOW);
analogWrite(enb, spd);
}
else
{
// Go backward
digitalWrite(in3, HIGH);
digitalWrite(in4, LOW);
analogWrite(enb, -spd);
}
}
}
void L298N::setMotorSpeeds(int leftSpeed, int rightSpeed)
{
setMotorSpeed(LEFT, leftSpeed);
setMotorSpeed(RIGHT, rightSpeed);
}
void L298N::stopMotor(int i)
{
setMotorSpeed(i, 0);
}
void L298N::stopMotors()
{
setMotorSpeeds(0, 0);
}