-
Notifications
You must be signed in to change notification settings - Fork 2
Expand file tree
/
Copy pathwebui.js
More file actions
251 lines (227 loc) · 8.18 KB
/
webui.js
File metadata and controls
251 lines (227 loc) · 8.18 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
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
var twist;
var cmdvel;
var publishImmediately = true;
var robot_IP;
var manager;
var manager1;
var manager2;
var teleop;
var ros;
/**
* Sends ROS messages with velocity for the robot.
* @param {*} linear
* @param {*} angular
*/
function moveAction(linear, angular) {
if (linear !== undefined && angular !== undefined) {
twist.linear.x = linear;
twist.angular.z = angular;
} else {
twist.linear.x = 0;
twist.angular.z = 0;
}
cmdVel.publish(twist);
}
/**
* Creates velocity message publisher.
*/
function initVelocityPublisher() {
//Initilize message with zero values.
twist = new ROSLIB.Message({
linear: {
x: 0,
y: 0,
z: 0
},
angular: {
x: 0,
y: 0,
z: 0
}
});
// Initialize topic object.
cmdVel = new ROSLIB.Topic({
ros: ros,
name: '/cmd_vel',
messageType: 'geometry_msgs/Twist'
})
// Register publisher within ROS system
cmdVel.advertise();
}
/**
* Creates keyboard controller object.
*/
function initTeleopKeyboard() {
// Use WASD to drive the robot.
// Check if the controller was already created
if(teleop == null) {
//Initialize the teleop.
teleop = new KEYBOARDTELEOP.Teleop({
ros: ros,
topic: '/cmd_vel'
});
}
// Add event listener for the slider movement.
robotSpeedRange = document.getElementById("robot-speed");
robotSpeedRange.oninput = function () {
teleop.scale = robotSpeedRange.value / 100;
}
}
/**
* Creates the joystick object.
*/
function createJoystick() {
// Check if the joystick was already created.
if (manager == null) {
joystickContainer = document.getElementById('joystick');
// Configuring joystick.
// Refer to https://yoannmoinet.github.io/nipplejs/ to adjust.
var options = {
zone: joystickContainer,
position: {left: 50 + '%', top: 105 + 'px'},
mode: 'static',
size: 200,
color: '#0066ff',
restJoystick: true
};
manager = nipplejs.create(options);
// Add event listener for the joystick movement.
manager.on('move', function(evt, nipple) {
// nipplejs returns direction in screen coordinates
// Rotate to correct i.e. dragging towards screen will move bot forward.
var direction = nipple.angle.degree - 90;
if(direction > 180) {
direction = -(450 - nipple.angle.degree);
}
// Convert angles to radians and scale the speeds.
// Adjust to make the bot faster/slower.
var lin = Math.cos(direction / 57.29) * nipple.distance * 0.005;
var ang = Math.sin(direction / 57.29) * nipple.distance * 0.05;
// nipplejs triggers events when the joystick moves at each pixel.
// Therefore this must be delayed lest too many consecutive message
// publications will occur. Events triggered <50ms after last publication will be dropped.
if(publishImmediately) {
publishImmediately = false;
moveAction(lin, ang);
setTimeout(function () {
publishImmediately = true;
}, 50);
}
});
// Create event listener for joystick release - send stop message.
manager.on('end', function() {
moveAction(0,0);
});
}
}
function createJoystick1() {
// Check if the joystick was already created.
if (manager1 == null) {
joystickContainer = document.getElementById('joystick1');
// Configuring joystick.
// Refer to https://yoannmoinet.github.io/nipplejs/ to adjust.
var options = {
zone: joystickContainer,
position: {left: 50 + '%', top: 105 + 'px'},
mode: 'static',
size: 200,
color: '#006921',
restJoystick: true
};
manager1 = nipplejs.create(options);
// Add event listener for the joystick movement.
manager1.on('move', function(evt, nipple) {
// nipplejs returns direction in screen coordinates
// Rotate to correct i.e. dragging towards screen will move bot forward.
var direction = nipple.angle.degree - 90;
if(direction > 180) {
direction = -(450 - nipple.angle.degree);
}
// Convert angles to radians and scale the speeds.
// Adjust to make the bot faster/slower.
var lin = Math.cos(direction / 57.29) * nipple.distance * 0.005;
var ang = Math.sin(direction / 57.29) * nipple.distance * 0.05;
// nipplejs triggers events when the joystick moves at each pixel.
// Therefore this must be delayed lest too many consecutive message
// publications will occur. Events triggered <50ms after last publication will be dropped.
if(publishImmediately) {
publishImmediately = false;
moveAction(lin, ang);
setTimeout(function () {
publishImmediately = true;
}, 50);
}
});
// Create event listener for joystick release - send stop message.
manager1.on('end', function() {
moveAction(0,0);
});
}
}
function createJoystick2() {
// Check if the joystick was already created.
if (manager2 == null) {
joystickContainer = document.getElementById('joystick2');
// Configuring joystick.
// Refer to https://yoannmoinet.github.io/nipplejs/ to adjust.
var options = {
zone: joystickContainer,
position: {left: 50 + '%', top: 105 + 'px'},
mode: 'static',
size: 200,
color: '#002169',
restJoystick: true
};
manager2 = nipplejs.create(options);
// Add event listener for the joystick movement.
manager2.on('move', function(evt, nipple) {
// nipplejs returns direction in screen coordinates
// Rotate to correct i.e. dragging towards screen will move bot forward.
var direction = nipple.angle.degree - 90;
if(direction > 180) {
direction = -(450 - nipple.angle.degree);
}
// Convert angles to radians and scale the speeds.
// Adjust to make the bot faster/slower.
var lin = Math.cos(direction / 57.29) * nipple.distance * 0.005;
var ang = Math.sin(direction / 57.29) * nipple.distance * 0.05;
// nipplejs triggers events when the joystick moves at each pixel.
// Therefore this must be delayed lest too many consecutive message
// publications will occur. Events triggered <50ms after last publication will be dropped.
if(publishImmediately) {
publishImmediately = false;
moveAction(lin, ang);
setTimeout(function () {
publishImmediately = true;
}, 50);
}
});
// Create event listener for joystick release - send stop message.
manager2.on('end', function() {
moveAction(0,0);
});
}
}
window.onload = function () {
// Determine robot address automatically then:
// robot_IP = location.hostname;
// Else set robot address statically:
robot_IP = "10.5.10.117";
// Initialize handle for rosbridge_websocket
ros = new ROSLIB.Ros({
url: "ws://" + robot_IP + ":9090"
});
initVelocityPublisher();
// Get handle for video placeholder.
video = document.getElementById('video');
// Populate video source
video.src = "http://" + robot_IP + ":8080/stream?topic=/camera/rgb/image_raw&type=mjpeg&quality=80";
// Commented out video.onload since inital testing will be done without camera.
//video.onload = function () {
// Joystick and keyboard controls will be available ONLY WHEN VIDEO IS loaded.
createJoystick();
createJoystick1();
createJoystick2();
initTeleopKeyboard();
//};
}