续前言

四足机器人开发之一(食材篇)

四足机器人开发之二(开发环境篇)

原理

参考文献:60元成本打造esp8266四足机器人

PWM

因为使用了pca9685舵机驱动板,所以这里使用的是Adafruit_PWMServoDriver库驱动sg90舵机,原理是通过PWM来控制舵机角度,动作主要是靠PWM来写的

舵机0-180度对应的PWM数值写在表格里了,这里取的是近似值,自己进行微调也可以

角度 PWM数值
0 100
45 190
90 280
135 370
180 510

舵机号

图中的舵机号与代码中的舵机号是对应的,比如代码中的 pwm.setPWM(4, 0, 370) ,就是将4号脚置于135度

舵机角度

蓝色角度对应的是4、5、6、7脚,黄色对应的是0、1、2、3脚

这里的角度范围表示舵机能运动的范围以及最大角度

比如当4、6号脚为0度时向上,而5、7脚0度时向下,反之当4、6号脚为180度时向下,而5、7脚180度时向上

操作界面

操作页面有用小程序的也有用软件的,这里使用的是网页

用esp8266作为网络服务器,按钮使用html写的

原理就这么简单,期待最后的组装篇~

代码

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
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
#include <ESP8266WiFi.h>
#include <Wire.h>
#include <Adafruit_PWMServoDriver.h>

Adafruit_PWMServoDriver pwm = Adafruit_PWMServoDriver();

const char* ssid = "WIFI名称";
const char* password = "WIFI密码";

WiFiServer server(80); //http的服务端口

void setup() {
pinMode(16, OUTPUT); //用于连接Wi-Fi的LED指示灯
digitalWrite(16, LOW);
Serial.begin(115200);
pwm.begin();
pwm.setPWMFreq(60); //伺服电机以60hz刷新率工作
delay(1000);

//连接到无线网络
Serial.println();
Serial.println();
Serial.print("Connecting to ");
Serial.println(ssid);

WiFi.begin(ssid, password);

while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print("-");
}
Serial.println("");
Serial.println("WiFi connected");

//启动服务器
server.begin();
Serial.println("Server started");

//打印IP地址
Serial.print("Use this URL to connect: ");
Serial.print("http://");
Serial.print(WiFi.localIP());
Serial.println("/");

digitalWrite(16, HIGH);
}

void loop() {
//检查客户端是否已连接
WiFiClient client = server.available();
if (!client) {
return;
}

//等到客户端发送一些数据
Serial.println("new client");
while (!client.available()) {
delay(1);
}

//阅读请求的第一行
String request = client.readStringUntil('\r');
Serial.println(request);
client.flush();

//匹配请求
if (request.indexOf("/S") != -1) {
sleep();
}
if (request.indexOf("/W") != -1) {
normal();
}
if (request.indexOf("/F") != -1) {
normal();
forward();
forward();
forward();
forward();
}
if (request.indexOf("/B") != -1) {
normal();
backward();
backward();
backward();
backward();
}
if (request.indexOf("/L") != -1) {
normal();
left();
left();
}
if (request.indexOf("/R") != -1) {
normal();
right();
right();
}
if (request.indexOf("/H") != -1) {
normal();
hello();
}
if (request.indexOf("/C") != -1) {
normal();
come();
}
//返回响应
client.println("HTTP/1.1 200 OK");
client.println("Content-Type: text/html");
client.println(""); // do not forget this one
client.println("<!DOCTYPE HTML>");
client.println("<html>");
client.println("<head>");
client.println("<style>");
client.println(".button{");
/*----------网页设计----------*/
client.println("background-color: #4CAF50; /* GREEN */");
client.println("width: 48%;");
client.println("border: none;");
client.println("color: white;");
client.println("padding: 50px 40px;");
client.println("text-align: center;");
client.println("text-decoration: none;");
client.println("display: inline-block;");
client.println("font-size: 50px;");
client.println("margin: 4px 2px;");
client.println("cursor: pointer;");
client.println("border-radius: 12px;");
client.println("}");

client.println("</style>");
client.println("</head>");
client.println("<body bgcolor=black>");

client.println("<button class=\"button\" onclick=\"window.location.href='/F';\">前进</button>");
client.println("<button class=\"button\" onclick=\"window.location.href='/B';\">后退</button>");
client.println("<br></br>");
client.println("<button class=\"button\" onclick=\"window.location.href='/L';\">左转</button>");
client.println("<button class=\"button\" onclick=\"window.location.href='/R';\">右转</button>");
client.println("<br></br>");
client.println("<button class=\"button\" onclick=\"window.location.href='/S';\">睡觉</button>");
client.println("<button class=\"button\" onclick=\"window.location.href='/W';\">正常</button>");
client.println("<br></br>");
client.println("<button class=\"button\" onclick=\"window.location.href='/H';\">你好</button>");
client.println("<button class=\"button\" onclick=\"window.location.href='/C';\">来啊</button>");
client.println("</body>");
client.println("</html>");

delay(1);
Serial.println("Client disconnected");
Serial.println("");
}

/*----------动作函数----------*/

// | 7 | | 6 |
// ----- ----- ----- -----
// | 3 | | 2 |
// ----- -----
// | 1 | | 0 |
// ----- ----- ----- -----
// | 5 | | 4 |

void sleep()
{
pwm.setPWM(4, 0, 280);
delay(100);
pwm.setPWM(5, 0, 280);
delay(100);
pwm.setPWM(6, 0, 280);
delay(100);
pwm.setPWM(7, 0, 280);
delay(100);
pwm.setPWM(0, 0, 510);
delay(100);
pwm.setPWM(1, 0, 100);
delay(100);
pwm.setPWM(2, 0, 100);
delay(100);
pwm.setPWM(3, 0, 510);
}

void normal()
{
pwm.setPWM(0, 0, 370);
delay(100);
pwm.setPWM(1, 0, 190);
delay(100);
pwm.setPWM(2, 0, 190);
delay(100);
pwm.setPWM(3, 0, 370);
delay(100);
pwm.setPWM(4, 0, 510);
delay(100);
pwm.setPWM(7, 0, 100);
delay(100);
pwm.setPWM(6, 0, 510);
delay(100);
pwm.setPWM(5, 0, 100);
}

void left()
{
pwm.setPWM(4, 0, 370);
delay(100);
pwm.setPWM(0, 0, 510);
delay(100);
pwm.setPWM(4, 0, 510);
delay(100);
pwm.setPWM(6, 0, 370);
delay(100);
pwm.setPWM(2, 0, 280);
delay(100);
pwm.setPWM(6, 0, 510);
delay(100);
pwm.setPWM(7, 0, 190);
delay(100);
pwm.setPWM(3, 0, 510);
delay(100);
pwm.setPWM(7, 0, 100);
delay(100);
pwm.setPWM(5, 0, 190);
delay(100);
pwm.setPWM(1, 0, 280);
delay(100);
pwm.setPWM(5, 0, 100);
delay(100);
pwm.setPWM(0, 0, 370);
pwm.setPWM(2, 0, 190);
pwm.setPWM(3, 0, 370);
pwm.setPWM(1, 0, 190);
}

void right()
{
pwm.setPWM(5, 0, 190);
delay(100);
pwm.setPWM(1, 0, 100);
delay(100);
pwm.setPWM(5, 0, 100);
delay(100);
pwm.setPWM(7, 0, 190);
delay(100);
pwm.setPWM(3, 0, 280);
delay(100);
pwm.setPWM(7, 0, 100);
delay(100);
pwm.setPWM(6, 0, 370);
delay(100);
pwm.setPWM(2, 0, 100);
delay(100);
pwm.setPWM(6, 0, 510);
delay(100);
pwm.setPWM(4, 0, 370);
delay(100);
pwm.setPWM(0, 0, 190);
delay(100);
pwm.setPWM(4, 0, 510);
delay(100);
pwm.setPWM(1, 0, 190);
pwm.setPWM(3, 0, 370);
pwm.setPWM(2, 0, 190);
pwm.setPWM(0, 0, 370);
}

void forward()
{
pwm.setPWM(5, 0, 190);
delay(50);
pwm.setPWM(1, 0, 100);
delay(50);
pwm.setPWM(5, 0, 100);
delay(50);
pwm.setPWM(4, 0, 370);
delay(50);
pwm.setPWM(0, 0, 510);
delay(50);
pwm.setPWM(4, 0, 510);
delay(50);
pwm.setPWM(6, 0, 370);
delay(50);
pwm.setPWM(2, 0, 280);
delay(50);
pwm.setPWM(6, 0, 510);
delay(50);
pwm.setPWM(7, 0, 190);
delay(50);
pwm.setPWM(3, 0, 280);
delay(50);
pwm.setPWM(7, 0, 100);
delay(50);
pwm.setPWM(0, 0, 370);
pwm.setPWM(1, 0, 190);
pwm.setPWM(2, 0, 190);
pwm.setPWM(3, 0, 370);
}

void backward()
{
pwm.setPWM(7, 0, 190);
delay(50);
pwm.setPWM(3, 0, 510);
delay(50);
pwm.setPWM(7, 0, 100);
delay(50);
pwm.setPWM(6, 0, 370);
delay(50);
pwm.setPWM(2, 0, 100);
delay(50);
pwm.setPWM(6, 0, 510);
delay(50);
pwm.setPWM(5, 0, 190);
delay(50);
pwm.setPWM(1, 0, 280);
delay(50);
pwm.setPWM(5, 0, 100);
delay(50);
pwm.setPWM(4, 0, 370);
delay(50);
pwm.setPWM(0, 0, 280);
delay(50);
pwm.setPWM(4, 0, 510);
delay(50);
pwm.setPWM(3, 0, 370);
pwm.setPWM(2, 0, 190);
pwm.setPWM(1, 0, 190);
pwm.setPWM(0, 0, 370);
}

void hello()
{
pwm.setPWM(0, 0, 510);
delay(100);
pwm.setPWM(4, 0, 100);
delay(500);
pwm.setPWM(4, 0, 190);
delay(500);
pwm.setPWM(4, 0, 100);
delay(500);
pwm.setPWM(4, 0, 190);
delay(500);
pwm.setPWM(4, 0, 100);
delay(500);
pwm.setPWM(4, 0, 510);
}

void come()
{
pwm.setPWM(0, 0, 280);
delay(100);
pwm.setPWM(4, 0, 100);
delay(500);
pwm.setPWM(4, 0, 190);
delay(500);
pwm.setPWM(4, 0, 100);
delay(500);
pwm.setPWM(4, 0, 190);
delay(500);
pwm.setPWM(4, 0, 100);
delay(500);
pwm.setPWM(4, 0, 510);
}