-
Notifications
You must be signed in to change notification settings - Fork 19
/
robot_diff_drive.ino
222 lines (166 loc) · 4.64 KB
/
robot_diff_drive.ino
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
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
#include "MPU6050_light.h" // https://www.arduino.cc/reference/en/libraries/mpu6050_light/
#include "Wire.h"
#include <Encoder.h> // https://www.arduino.cc/reference/en/libraries/encoder/
#include <PID_v1.h> // https://github.com/br3ttb/Arduino-PID-Library
// Motor Left connections
Encoder enc_A(3, 12);
const int enA = 10;
const int in1 = 7;
const int in2 = 6;
// Motor Right connections
Encoder enc_B(2, 11);
const int enB = 9;
const int in3 = 4;
const int in4 = 5;
double l_pwm = 0;
double r_pwm = 0;
double l_ticks_rate = 0;
double r_ticks_rate = 0;
double l_desired_rate = 0;
double r_desired_rate = 0;
double l_desired_rate_abs = 0;
double r_desired_rate_abs = 0;
int left_ticks = 0;
int right_ticks = 0;
int l_direction = 1;
int r_direction = 1;
int previousReading_left = 0;
int previousReading_right = 0;
MPU6050 mpu(Wire);
double kp_l = 0.1, ki_l = 0, kd_l = 0;
// Input Output SetPoint
PID l_PID(&l_ticks_rate, &l_pwm, &l_desired_rate_abs, kp_l, ki_l, kd_l, DIRECT);
PID r_PID(&r_ticks_rate, &r_pwm, &r_desired_rate_abs, kp_l, ki_l, kd_l, DIRECT);
const float interval = 25; //millis
void setup() {
Serial.begin(115200);
Wire.begin();
byte status = mpu.begin();
while (status != 0) { }
delay(2000);
mpu.calcOffsets(true, true);
motor_stop();
l_PID.SetMode(AUTOMATIC);
l_PID.SetOutputLimits(0, 255);
r_PID.SetMode(AUTOMATIC);
r_PID.SetOutputLimits(0, 255);
}
void loop() {
mpu.update();
double tstart = millis();
read_encoder();
send_all_data();
get_desired_wheel_velocities();
calc_wheel_pwm();
set_motor_pwm();
delay(50);
double tend = millis();
l_ticks_rate = (double)((left_ticks - previousReading_left) / (tend - tstart)) * 1000;
r_ticks_rate = (double)((right_ticks - previousReading_right) / (tend - tstart)) * 1000;
previousReading_left = left_ticks;
previousReading_right = right_ticks;
}
void read_encoder() {
left_ticks = enc_A.read();
right_ticks = enc_B.read();
}
void set_motor_pwm() {
if (l_desired_rate != 0) {
if (l_direction == 1) {
digitalWrite(in1, LOW);
digitalWrite(in2, HIGH);
analogWrite(enA, int(l_pwm));
} else {
digitalWrite(in1, HIGH);
digitalWrite(in2, LOW);
analogWrite(enA, int(abs(l_pwm)));
}
} else {
analogWrite(enA, 0);
}
if (r_desired_rate != 0) {
if (l_direction == 1) {
digitalWrite(in3, LOW);
digitalWrite(in4, HIGH);
analogWrite(enB, int(r_pwm));
} else {
digitalWrite(in3, HIGH);
digitalWrite(in4, LOW);
analogWrite(enB, int(abs(r_pwm)));
}
} else {
analogWrite(enB, 0);
}
}
void send_all_data() {
float imu_array[10];
imu_array[0] = mpu.getAccX() * 9.81;
imu_array[1] = -mpu.getAccY() * 9.81;
imu_array[2] = mpu.getAccZ() * 9.81;
imu_array[3] = mpu.getGyroX() * 0.0174533;
imu_array[4] = mpu.getGyroY() * 0.0174533;
imu_array[5] = mpu.getGyroZ() * 0.0174533;
imu_array[6] = mpu.getAngleX() * 0.0174533;
imu_array[7] = mpu.getAngleY() * 0.0174533;
imu_array[8] = mpu.getAngleZ() * 0.0174533;
imu_array[9] = 1;
// Left_ticks, Right_ticks, AccX, AccY, AccZ, GyrX, GyrY, GyrZ, QuX, QuY, QuZ, QuW
String main_str = "";
main_str = main_str + int(left_ticks) + "/" + int(-right_ticks);
for (int i = 0; i < 10; i++) {
main_str = main_str + "/" + imu_array[i];
}
main_str = main_str + "/";
Serial.println(main_str);
}
int* velocity_string_parse(String velocities) {
velocities.remove(-2);
int piviot = velocities.indexOf("/");
String l_velocity = velocities;
l_velocity.remove(piviot);
String r_velocity = "";
int i = piviot + 1;
while (velocities[i]) {
r_velocity = r_velocity + velocities[i];
i = i + 1;
}
static int arr[2];
arr[0] = l_velocity.toInt();
arr[1] = r_velocity.toInt();
return arr;
}
void get_desired_wheel_velocities() {
if (Serial.available() > 0) {
String velocities = Serial.readStringUntil('\n');
int* arr;
arr = velocity_string_parse(velocities);
l_desired_rate = arr[0];
r_desired_rate = arr[1];
if (l_desired_rate < 0) {
l_direction = -1;
} else {
l_direction = 1;
}
if (l_desired_rate < 0) {
l_direction = -1;
} else {
l_direction = 1;
}
l_desired_rate_abs = abs(l_desired_rate);
r_desired_rate_abs = abs(r_desired_rate);
}
}
void calc_wheel_pwm() {
// l_pwm = map(l_desired_rate, -3250, 3250, -255, 255);
// r_pwm = map(r_desired_rate, -3250, 3250, -255, 255);
l_PID.Compute();
r_PID.Compute();
}
void motor_stop() {
digitalWrite(in1, LOW);
digitalWrite(in2, LOW);
digitalWrite(in3, LOW);
digitalWrite(in4, LOW);
analogWrite(enA, 0);
analogWrite(enB, 0);
}