-
Notifications
You must be signed in to change notification settings - Fork 0
/
Bluetooth_Serial.ino
257 lines (226 loc) · 7.4 KB
/
Bluetooth_Serial.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
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
void Blue_Serial_Rec() {
if (BlueSerial.available() > 0 )
{
char c;
while ((BlueSerial.available() > 0) && (g_command_ready == false)) {
c = (char)BlueSerial.read();
if (c == ';') {
g_command_ready = true;
}
else {
g_command += c;
}
}
if (g_command_ready) {
char tmp_str[200] = "";
g_command.toCharArray(tmp_str, 40);
strcat(tmp_str, ";");
BlueSerial.write(tmp_str); // ECHO
Serial.print(F("ECHO:"));
Serial.println(tmp_str);
Serial.print(g_command); //end of line and function exit
if (g_command == "L0") {
digitalWrite(13, LOW);
}
else if (g_command == "L1") {
digitalWrite(13, HIGH);
}
else if (g_command == "FILM") {
if (servo_step == -1) servo_step = 0;
servo_counter = 0;
}
else if (g_command == "mode_PID") {
send_angle = true;
mode = MODE_PID;
}
else if (g_command == "mode_test") {
mode = MODE_TEST;
motors_off();
}
else if (g_command == "mode_wheel") {
motor1_speed_out = 0;
motor2_speed_out = 0;
mode = MODE_WHEEL;
motors_runing = true;
}
else if (g_command == "angle_stop") {
send_angle = false;
}
else if (g_command == "motors_off") {
motors_runing = false;
}
else if (g_command == "motors_on") {
motors_runing = true;
}
else if (g_command == "set_angle") {
Setpoint = Input;
send_angle = true;
mode = MODE_PID;
}
// A one-parameter command...
else if (g_command.startsWith("servo1")) {
int pos = g_command.indexOf(" ");
if (pos == -1) {
Serial.println(F("Error: Command 'read_page' expects an int operand"));
} else {
int page = (word)g_command.substring(pos).toInt();
Serial.print(F("word="));
Serial.print(page);
Serial.println(F(";"));
uint16_t pulselen = map (page, 0 , 180, 0, 4095);
Serial.print(F("pulselen:")); Serial.println(pulselen);
PWM_module.setPWM(SERVO_UP_DOWN, 0, pulselen);
previousMillis = currentMillis; //for servo detach later
}
}
else if (g_command.startsWith("servo2")) {
int pos = g_command.indexOf(" ");
if (pos == -1) {
Serial.println(F("Error: Command 'read_page' expects an int operand"));
} else {
int page = (word)g_command.substring(pos).toInt();
Serial.print(F("word="));
Serial.print(page);
Serial.println(F(";"));
uint16_t pulselen = map (page, 0 , 180, 400, 600);
PWM_module.setPWM(SERVO_LEFT_RIGHT, 0, pulselen);
previousMillis = currentMillis; //for detach later
}
}
else if (g_command.startsWith("motor1")) {
int pos = g_command.indexOf(" ");
if (pos == -1) {
Serial.println(F("Error: Command 'read_page' expects an int operand"));
} else {
int page;
byte idx = (word)g_command.indexOf('-');
if (idx != 0 and idx != 255) {
page = (-1) * (word)g_command.substring(idx + 1).toInt();
} else {
page = (word)g_command.substring(pos).toInt();
}
motor1_speed_out = page; //map(page,-255, 255, MIN_MOTOR_1, motorR_max_speed);
motors_runing = true;
}
}
else if (g_command.startsWith("motor2")) {
int pos = g_command.indexOf(" ");
if (pos == -1) {
Serial.println(F("Error: Command 'read_page' expects an int operand"));
} else {
int page;
byte idx = (word)g_command.indexOf('-');
if (idx != 0 and idx != 255) {
page = (-1) * (word)g_command.substring(idx + 1).toInt();
} else {
page = (word)g_command.substring(pos).toInt();
}
motor2_speed_out = page; //map(page,-255, 255, MIN_MOTOR_1, motorR_max_speed);
motors_runing = true;
}
}
else if (g_command.startsWith("MAX_SPEED")) {
int pos = g_command.indexOf(" ");
if (pos == -1) {
Serial.println(F("Error(MAX_SPEED): Command 'read_page' expects an int operand"));
} else {
int page = (word)g_command.substring(pos).toInt();
set_motors_max(page, page);
}
}
else if (g_command.startsWith("P")) {
String str_pid;
int pos = g_command.indexOf(" ");
if (pos == -1) {
Serial.println(F("Error(PIDconst): Command 'read_page' expects an int operand"));
} else {
str_pid = g_command.substring(pos);
}
send_angle = true;
mode = MODE_PID;
String st1 = getValue(str_pid, ',', 0);
String st2 = getValue(str_pid, ',', 1);
String st3 = getValue(str_pid, ',', 2);
if (isNumeric(st1) && isNumeric(st2) && isNumeric(st3)) {
double Kp_val = st1.toDouble();
double Kd_val = st2.toDouble();
double Ki_val = st3.toDouble();
kp = Kp_val / 10.0;
kd = Kd_val / 10.0;
ki = Ki_val / 10.0;
PID_obj.setGains(kp, ki, kd);
PID_obj.reset();
}
}
else if (g_command.startsWith("wheel")) {
int pos1 = g_command.indexOf("(");
int pos2 = g_command.indexOf(",");
int pos3 = g_command.indexOf(")");
if (pos1 == -1) {
Serial.println(F("Error(wheel): Command 'read_page' expects an int operand"));
} else {
wheel_x = (word)g_command.substring(pos1 + 1, pos2).toInt();
wheel_y = (word)g_command.substring(pos2 + 1, pos3).toInt();
mode = MODE_WHEEL;
}
}
done:
g_command = "";
g_command_ready = false;
Serial.println();
}
}
}
void Blue_Serial_Send(byte mode, float data_1, float data_2, float data_3, float data_4) {
char tmp_str[40] = "";
char res[8]; // Buffer big enough for 7-character float
if (mode == MODE_ONE_ANGLE) {
strcat(tmp_str, "angle,");
dtostrf(data_1, 6, 2, res); //w
strcat(tmp_str, res);
strcat(tmp_str, ",END");
} else if (mode == MODE_ANGLE_SETPOINT) {
strcat(tmp_str, "angle,");
dtostrf(data_1, 6, 2, res); //w
strcat(tmp_str, res);
strcat(tmp_str, ",setpoint,");
dtostrf(data_2, 6, 2, res); //w
strcat(tmp_str, res);
strcat(tmp_str, ",END");
}
else {
if (!debug_sent_bt_data) {
#ifdef OUTPUT_READABLE_QUATERNION
strcat(tmp_str, "QUAT,");
dtostrf(data_1, 6, 2, res); //w
strcat(tmp_str, res);
strcat(tmp_str, ",");
dtostrf(data_2, 6, 2, res); //x
strcat(tmp_str, res);
strcat(tmp_str, ",");
dtostrf(data_3, 6, 2, res); //y
strcat(tmp_str, res);
strcat(tmp_str, ",");
dtostrf(data_4, 6, 2, res); //z
strcat(tmp_str, res);
strcat(tmp_str, ",END");
Serial.print(F("str:"));
Serial.println(tmp_str);
#endif
#ifdef OUTPUT_READABLE_EULER
strcat(tmp_str, "ANGLE,");
dtostrf(data_1, 6, 2, res); //euler[0] * 180 / M_PI
strcat(tmp_str, res);
strcat(tmp_str, ",");
dtostrf(data_2, 6, 2, res); //euler[1] * 180 / M_PI
strcat(tmp_str, res);
strcat(tmp_str, ",");
dtostrf(data_3, 6, 2, res); //euler[2] * 180 / M_PI
strcat(tmp_str, res);
strcat(tmp_str, ",END");
// print only relevant angle
#endif
}
}
BlueSerial.write(tmp_str);
}