抱歉,您的浏览器无法访问本站
本页面需要浏览器支持(启用)JavaScript
了解详情 >

HTML 部分:

引入 semantic-ui, jquery 和 joy.js

1
2
3
4
5
6
7
8
9
10
11
12
<head>
<meta charset="UTF-8">
<title>Tourmaline</title>
</meta>
<meta name="viewport" content="width=device-width, initial-scale=0.5, minimum-scale=1.0, maximum-scale=4.0">
</meta>
<link rel="stylesheet" type="text/css" href="https://unpkg.com/semantic-ui@2.4.2/dist/semantic.min.css">
<script src="https://code.jquery.com/jquery-3.1.1.min.js"
integrity="sha256-hVVnYaiADRTO2PzUGmuLJr8BLUSjGIZsDYGmIJLv2b8=" crossorigin="anonymous"></script>
<script src="https://unpkg.com/semantic-ui@2.4.2/dist/semantic.min.js"></script>
<script src="joy.min.js"></script>
</head>
1
2
3
4
<script>
car_server = "http://10.80.165.58";
update_time = 2000;//2000毫秒更新一次
</script>

一些数据

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
<div class="ui container">
<div class="ui fluid segment">
<div class="ui top attached label">小车状态</div>

<div class="ui three cards">
<div class="card">
<div class="content">
<div class="header">电池</div>
<div class="ui indicating progress" id="battery">
<div class="bar">
</div>
<div class="label" id="battery_label"></div>
</div>
</div>
</div>
<div class="card">
<div class="content">
<div class="header">是否倾斜</div>
<div class="description" id="lean">

</div>
</div>
</div>
<div class="card">
<div class="content">
<div class="header">是否有人</div>
<div class="description" id="human">

</div>
</div>
</div>
</div>
</div>
<div class="ui fluid segment">
<div class="ui top attached label">操控杆</div>
<div id="joyDiv" style="width:200px;height:200px;margin-bottom:20px;"></div>
</div>
<div class="ui fluid segment">
<div class="ui top attached label">步骤</div>
<div class="ui two cards">
<div class="card">
<div class="ui vertical steps" id="steps">
<!-- <div class="step">
<i class="arrow alternate circle up icon"></i>
<div class="content">
<div class="title">前进</div>
<div class="description">x=100,y=100,t=1s</div>
</div>
</div>
<div class="step">
<i class="arrow alternate circle down icon"></i>
<div class="content">
<div class="title">后退</div>
<div class="description">x=-100,y=-100,t=1s</div>
</div>
</div>
<div class="step">
<i class="stop circle icon"></i>
<div class="content">
<div class="title">暂停</div>
<div class="description">x=0,y=0,t=1s</div>
</div>
</div>
<div class="step">
<i class="arrow circle right icon"></i>
<div class="content">
<div class="title">右转</div>
<div class="description">x=100,y=-100,t=1s</div>
</div>
</div>
<div class="step">
<i class="arrow circle left icon"></i>
<div class="content">
<div class="title">左转</div>
<div class="description">x=-100,y=100,t=1s</div>
</div>
</div> -->
</div>
</div>
<div class="card">
<div class="ui form">
<div class="field">
<label>JSON 数据</label>
<textarea style="font-family:consolas;tab-size: 4;height:353px">
[
{
"cmd": "forward",
"x": 100,
"y": 100,
"t": 1
},
{
"cmd": "backward",
"x": -100,
"y": -100,
"t": 1
},
{
"cmd": "left",
"x": -100,
"y": 100,
"t": 1
},
{
"cmd": "right",
"x": 100,
"y": -100,
"t": 1
},
{
"cmd": "stop",
"x": 100,
"y": -100,
"t": 1
},
{
"cmd": "not full speed",
"x": 50,
"y": 50,
"t": 1
}
]
</textarea>
</div>
<div class="ui horizontal buttons">
<div class="ui button" onclick="apply()">
应用
</div>
<div class="ui button" onclick="activate()">
执行
</div>
</div>
<div class="ui checkbox">
<input type="checkbox" id="repeat">
<label>循环</label>
</div>
</div>
</div>
</div>
</div>
</div>

结构主体

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
var is_step_on = false;
var joy = new JoyStick('joyDiv');
function updateSpeed(speedX, speedY) {
$.get(`${car_server}/go?left=${joy.GetX()}&right=${joy.GetY()}`);
}
function apply() {
var json = JSON.parse($('textarea').val());
$("#steps").empty();
for (var i = 0; i < json.length; i++) {
var step = json[i];
var icon = "";
switch (step.cmd) {
case "forward":
icon = "arrow alternate circle up icon";
break;
case "backward":
icon = "arrow alternate circle down icon";
break;
case "stop":
icon = "stop circle icon";
break;
case "right":
icon = "arrow circle right icon";
break;
case "left":
icon = "arrow circle left icon";
break;
default:
icon = "question circle icon";
break;
}
$("#steps").append(`
<div class="step">
<i class="${icon}"></i>
<div class="content">
<div class="title">${step.cmd}</div>
<div class="description">x=${step.x},y=${step.y},t=${step.t}s</div>
</div>
</div>
`);
}
}

更新steps

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
function sleep(time) {
return new Promise((resolve) => {
setTimeout(() => {
resolve();
}, time);
});
}
//指示小车行动
async function activate() {
is_step_on = true;
var json = JSON.parse($('textarea').val());
for (var i = 0; i < json.length; i++) {
console.log(i);
// console.log($('#repeat').checkbox('is checked'));
var step = json[i];
$.get(`${car_server}/go?left=${step.x}&right=${step.y}`);
//等待t秒
await sleep(step.t * 1000);
if (i==json.length-1 && $('#repeat').is(':checked')) {
i = -1;
}
}
//停止
$.get(`${car_server}/go?left=0&right=0`);
is_step_on=false;
}
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
function updateStatus() {
// console.log(joy.GetX(), joy.GetY());
// $("#battery").progress({
// percent: 870 / 10
// });
// $("#battery_label").text(870 / 10 + "%");
$.get(car_server + "/battery", function (data) {
$("#battery").progress({
percent: data.battery / 10
});
$("#battery_label").text(data.battery / 10 + "%");
});
if (!is_step_on) updateSpeed(joy.GetX(), joy.GetY());
}
// Create JoyStick object into the DIV 'joyDiv'
apply();
updateStatus();
setInterval(function () { updateStatus() }, update_time);

更新status

control.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
#include <Wire.h>
// #include <cstdio>

#define I2C_ADDR 0x34

#define ADC_BAT_ADDR 0
#define MOTOR_TYPE_ADDR 20 //编码电机类型设置
#define MOTOR_ENCODER_POLARITY_ADDR 21 //设置编码方向极性,
//如果发现电机转速根本不受控制,要么最快速度转动,要么停止。可以将此地址的值重新设置一下
//范围0或1,默认0
#define MOTOR_FIXED_PWM_ADDR 31 //固定PWM控制,属于开环控制,范围(-100~100)
//#define SERVOS_ADDR_CMD 40
#define MOTOR_FIXED_SPEED_ADDR 51 //固定转速控制,属于闭环控制,
//单位:脉冲数每10毫秒,范围(根据具体的编码电机来,受编码线数,电压大小,负载大小等影响,一般在±50左右)

#define MOTOR_ENCODER_TOTAL_ADDR 60 //4个编码电机各自的总脉冲值
//如果已知电机每转一圈的脉冲数为U,又已知轮子的直径D,那么就可以通过脉冲计数的方式得知每个轮子行进的距离
//比如读到电机1的脉冲总数为P,那么行进的距离为(P/U) * (3.14159*D)
//对于不同的电机可以自行测试每圈的脉冲数U,可以手动旋转10圈读出脉冲数,然后取平均值得出


//电机类型具体值
#define MOTOR_TYPE_WITHOUT_ENCODER 0
#define MOTOR_TYPE_TT 1
#define MOTOR_TYPE_N20 2
#define MOTOR_TYPE_JGB 3 //磁环每转是44个脉冲 减速比:90 默认

电机类型与基本数据

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
u8 data[20];
bool WireWriteByte(uint8_t val) {
Wire.beginTransmission(I2C_ADDR);
Wire.write(val);
if (Wire.endTransmission() != 0) {
return false;
}
return true;
}
bool WireWriteDataArray(uint8_t reg, uint8_t *val, unsigned int len) {
unsigned int i;

Wire.beginTransmission(I2C_ADDR);
Wire.write(reg);
for (i = 0; i < len; i++) {
Wire.write(val[i]);
}
if (Wire.endTransmission() != 0) {
return false;
}
return true;
}
bool WireReadDataByte(uint8_t reg, uint8_t &val) {
if (!WireWriteByte(reg)) {
return false;
}
Wire.requestFrom(I2C_ADDR, 1);
while (Wire.available()) {
val = Wire.read();
}
return true;
}
int WireReadDataArray(uint8_t reg, uint8_t *val, unsigned int len) {
unsigned char i = 0;
/* Indicate which register we want to read from */
if (!WireWriteByte(reg)) {
return -1;
}
/* Read block data */
Wire.requestFrom(I2C_ADDR, len);
while (Wire.available()) {
if (i >= len) {
return -1;
}
val[i] = Wire.read();
i++;
}
return i;
}

I2C通讯

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
#include <ESP8266WiFi.h>
#include <WiFiClient.h>
#include <ESP8266WebServer.h>
#include <cstring>

// #ifndef STASSID
// #define STASSID "blablabla"
// #define STAPSK "blablabla"
// #endif
#include <password.h>


const char *ssid = STASSID;
const char *password = STAPSK;

ESP8266WebServer server(80);

初始 ESP8266WebServer

1
2
3
4
5
6
7
8
9
10
11
uint8_t MotorType = MOTOR_TYPE_JGB;
uint8_t MotorEncoderPolarity = 0;

void SetupMotor() {
Wire.begin();
// printf_begin();
delay(200);
WireWriteDataArray(MOTOR_TYPE_ADDR, &MotorType, 1);
delay(5);
WireWriteDataArray(MOTOR_ENCODER_POLARITY_ADDR, &MotorEncoderPolarity, 1);
}

初始化马达,指定类型与极性。

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
void handleNotFound() {
String message = "File Not Found\n\n";
message += "URI: ";
message += server.uri();
message += "\nMethod: ";
message += (server.method() == HTTP_GET) ? "GET" : "POST";
message += "\nArguments: ";
message += server.args();
message += "\n";
for (uint8_t i = 0; i < server.args(); i++) {
message += " " + server.argName(i) + ": " + server.arg(i) + "\n";
}
server.send(404, "text/plain", message);
}

float getVoltage() {
int v = analogRead(A0);
float volt = v * (5.0 / 1024.0) * 2;
return volt;
}

void handleBattery() {
float vol = getVoltage() - 2.0;
char s[30] = "{\"battery\":xxx}";
s[11] = ((int)vol) % 10 + '0';
s[12] = ((int)(vol * 10)) % 10 + '0';
s[13] = ((int)(vol * 100)) % 10 + '0';
server.send(200, "application/json", s);
}
uint8_t p[2] = { 0, 0 };
int32_t EncodeTotal[4];
void handleMovement() {
String LeftSpeed = server.arg("left");
String RightSpeed = server.arg("right");
Serial.println(LeftSpeed);
Serial.println(RightSpeed);
p[0] = LeftSpeed.toInt();
p[1] = RightSpeed.toInt();
WireWriteDataArray(MOTOR_FIXED_SPEED_ADDR, p, 2);
server.send(200, "text/plain", "ok");
}

接受http请求

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
void SetupServer() {
Serial.begin(115200);
WiFi.mode(WIFI_STA);
WiFi.begin(ssid, password);

// Wait for connection
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print(".");
}
Serial.println("");
Serial.print("Connected to ");
Serial.println(ssid);
Serial.print("IP address: ");
Serial.println(WiFi.localIP());

server.enableCORS(true);
server.on("/battery", handleBattery);
server.on("/go", handleMovement);

server.begin();
Serial.println("HTTP server started");
}

初始化服务器。

1
2
3
4
5
6
7
8
void setup() {
SetupServer();
SetupMotor();
}

void loop() {
server.handleClient();
}

评论