-
Notifications
You must be signed in to change notification settings - Fork 2
Expand file tree
/
Copy pathPropulsion.cpp
More file actions
160 lines (136 loc) · 3.31 KB
/
Propulsion.cpp
File metadata and controls
160 lines (136 loc) · 3.31 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
//
//
//
#include "Propulsion.h"
Propulsion::Propulsion()
:motorL(4, 5, 2, 4.0, 2.5), motorR(7, 6, 3, 4.0, 2.5), sumError(0), progress(0), allowSpeedControll(true)
{
}
void Propulsion::setForwards(int distance = 0)
{
motorL.setDirection(true);
motorR.setDirection(true);
motorL.setDistance(distance); // distance = 0 corresponds to infinity, distance in #pulses
motorR.setDistance(distance);
}
void Propulsion::setBackwards(int distance = 0)
{
motorL.setDirection(false);
motorR.setDirection(false);
motorL.setDistance(distance); // distance = 0 corresponds to infinity, distance in #pulses
motorR.setDistance(distance);
}
void Propulsion::setSpeed(int speed)
{
motorL.setSpeed(speed);
motorR.setSpeed(speed);
}
void Propulsion::setAllowSpeedControl(bool allowSpeedControll)
{
this->allowSpeedControll = allowSpeedControll;
}
bool Propulsion::getAllowSpeedControll()
{
return allowSpeedControll;
}
bool Propulsion::drive()
{
bool resultL = false;
bool resultR = false;
if (motorL.getSpeed() == 0 && motorR.getSpeed() == 0)
{
reset();
return false;
}
if (motorL.getDistance() - int(motorL.getPointerToEncoder()->getEncoderTicks()) <=
min(140, motorL.getSpeed() * 15) && motorL.getDistance() != 0)
{
if (motorL.getDistance() - int(motorL.getPointerToEncoder()->getEncoderTicks()) <= 0)
{
motorL.setSpeed(0);
resultL = true;
}
else
{
motorL.setSpeed(2);
}
}
if (motorR.getDistance() - int(motorR.getPointerToEncoder()->getEncoderTicks()) <=
min(140, motorR.getSpeed() * 15) && motorR.getDistance() != 0)
{
if (motorR.getDistance() - int(motorR.getPointerToEncoder()->getEncoderTicks()) <= 0)
{
motorR.setSpeed(0);
resultR = true;
}
else
{
motorR.setSpeed(2);
}
}
int PWML = motorL.calcPWM_val();
int PWMR = motorR.calcPWM_val();
int error = int(motorL.getPointerToEncoder()->getEncoderTicks() -
motorR.getPointerToEncoder()->getEncoderTicks());
sumError = sumError + error;
int prevError = int(motorL.getPointerToEncoder()->getPrevEncoderTicks() -
motorR.getPointerToEncoder()->getPrevEncoderTicks());
int boost = (KP * error) + (KD * (error - prevError))
+ (KI * sumError);
PWML = PWML - boost;
PWMR = PWMR + boost;
motorL.setPWM_val(PWML);
motorR.setPWM_val(PWMR);
return resultL && resultR;
}
void Propulsion::setLeftRotation(int distance)
{
motorL.setDirection(true);
motorR.setDirection(false);
motorL.setDistance(distance); // distance = 0 corresponds to infinity, distance in #pulses
motorR.setDistance(distance);
}
void Propulsion::setRightRotation(int distance)
{
motorL.setDirection(false);
motorR.setDirection(true);
motorL.setDistance(distance); // distance = 0 corresponds to infinity, distance in #pulses
motorR.setDistance(distance);
}
Motor* Propulsion::getPointerToMotorL()
{
return motorL.getPointer();
}
Motor* Propulsion::getPointerToMotorR()
{
return motorR.getPointer();
}
void Propulsion::resetSumError()
{
sumError = 0;
}
void Propulsion::reset()
{
getPointerToMotorL()->reset();
getPointerToMotorR()->reset();
sumError = 0;
allowSpeedControll = true;
}
void Propulsion::stopMotors()
{
motorL.setPWM_val(0);
motorR.setPWM_val(0);
//Not finished
}
void Propulsion::setProgress(int progress)
{
this->progress = progress;
}
int Propulsion::getProgress()
{
return progress;
}
void Propulsion::incrementProgress()
{
progress++;
}