summaryrefslogtreecommitdiff
path: root/lib/motors/motors.cpp
blob: 843de224bea1d63eb116ef3af6a6dbfa461ff7b0 (plain)
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
#include <Arduino.h>
#include "settings.h"
#include "motors.h"

#define RIGHT_CHANNEL 4
#define LEFT_CHANNEL 5

#define MOTOR_FREQ 5000
#define MOTOR_RES 10

int MOTORS::scaleSpeed(int speed)
{
    return map(speed, 0, 100, 0, (1 << MOTOR_RES) - 1);
}

MOTORS::MOTORS()
{
}

void MOTORS::stop()
{
    ledcWrite(RIGHT_CHANNEL, 0);
    ledcWrite(LEFT_CHANNEL, 0);
}

void MOTORS::rightStop()
{
    ledcWrite(RIGHT_CHANNEL, 0);
}

void MOTORS::leftStop()
{
    ledcWrite(LEFT_CHANNEL, 0);
}

void MOTORS::init()
{
    ledcSetup(LEFT_CHANNEL, MOTOR_FREQ, MOTOR_RES);
    ledcAttachPin(EN34, LEFT_CHANNEL);

    ledcSetup(RIGHT_CHANNEL, MOTOR_FREQ, MOTOR_RES);
    ledcAttachPin(EN12, RIGHT_CHANNEL);

    pinMode(IN1, OUTPUT);
    pinMode(IN2, OUTPUT);
    pinMode(IN3, OUTPUT);
    pinMode(IN4, OUTPUT);
}

void MOTORS::leftBackward(int speed, int duration)
{
    digitalWrite(IN1, HIGH);
    digitalWrite(IN2, LOW);
    ledcWrite(RIGHT_CHANNEL, scaleSpeed(speed));

    if (duration > 0)
    {
        delay(duration);
        stop();
    }
}

void MOTORS::leftForward(int speed, int duration)
{
    digitalWrite(IN1, LOW);
    digitalWrite(IN2, HIGH);
    ledcWrite(RIGHT_CHANNEL, scaleSpeed(speed));

    if (duration > 0)
    {
        delay(duration);
        stop();
    }
}

void MOTORS::rightBackward(int speed, int duration)
{
    digitalWrite(IN3, HIGH);
    digitalWrite(IN4, LOW);
    ledcWrite(LEFT_CHANNEL, scaleSpeed(speed));
    ledcWrite(RIGHT_CHANNEL, 0);

    if (duration > 0)
    {
        delay(duration);
        stop();
    }
}

void MOTORS::rightForward(int speed, int duration)
{
    digitalWrite(IN3, LOW);
    digitalWrite(IN4, HIGH);
    ledcWrite(LEFT_CHANNEL, scaleSpeed(speed));
    ledcWrite(RIGHT_CHANNEL, 0);

    if (duration > 0)
    {
        delay(duration);
        stop();
    }
}

void MOTORS::forward(int speed, int duration)
{
    leftForward(speed);
    rightForward(speed);
    if (duration > 0)
    {
        delay(duration);
        stop();
    }
}

void MOTORS::backward(int speed, int duration)
{
    leftBackward(speed);
    rightBackward(speed);
    if (duration > 0)
    {
        delay(duration);
        stop();
    }
}

void MOTORS::leftTurn(int speed, int duration)
{
    leftForward(speed);
    rightBackward(speed);
    if (duration > 0)
    {
        delay(duration);
        stop();
    }
}

void MOTORS::rightTurn(int speed, int duration)
{
    leftBackward(speed);
    rightForward(speed);
    if (duration > 0)
    {
        delay(duration);
        stop();
    }
}