-
Notifications
You must be signed in to change notification settings - Fork 0
/
server.js
274 lines (256 loc) · 7.43 KB
/
server.js
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
var express = require("express");
var app = express();
var http = require('http');
app.listen(8000);
var Gopigo = require('node-gopigo').Gopigo
var Commands = Gopigo.commands
var Robot = Gopigo.robot
var ultrasonicPin = 15
//var irreceiverPin = 8
// Control timeout
var cachedAction = ""
var timer = -1
setInterval(function() {
timer = timer - 1;
if (timer == 0) {
handleAnswer("x");
}
}, 1);
// Continuous move
app.get('/moveContinuous', function(req, res){
res.send('done');
timer = 200;
robot.motion.setLeftSpeed(req.query.leftSpeed);
robot.motion.setRightSpeed(req.query.rightSpeed);
handleAnswer(req.query.action);
});
// Step move
app.get('/moveWithSteps', function(req, res){
res.send('done');
timer = 10000;
robot.motion.setSpeed(200);
robot.encoders.targeting(1, 1, req.query.steps)
handleAnswer(req.query.action);
console.log(req.query.steps);
});
app.get('/stop', function(req, res){
timer = 1;
console.log("from /stop");
res.send('done');
});
// Control gopigo car move with steps.
// n1=1 n2=0 n3=15 act = d --> turn left for 90 degree
// n1=0 n2=1 n3=15 act = a --> turn right for 90 degree
robot = new Robot({
minVoltage: 5.5,
criticalVoltage: 1.2,
debug: true,
ultrasonicSensorPin: ultrasonicPin,
//IRReceiverSensorPin: irreceiverPin
})
robot.on('init', function onInit(res) {
if (res) {
console.log('GoPiGo Ready!')
// askForCommand()
} else {
console.log('Something went wrong during the init.')
}
})
robot.on('error', function onError(err) {
console.log('Something went wrong')
console.log(err)
})
robot.on('free', function onFree() {
console.log('GoPiGo is free to go')
})
robot.on('halt', function onHalt() {
console.log('GoPiGo is halted')
})
robot.on('close', function onClose() {
console.log('GoPiGo is going to sleep')
})
robot.on('reset', function onReset() {
console.log('GoPiGo is resetting')
})
robot.on('normalVoltage', function onNormalVoltage(voltage) {
console.log('Voltage is ok ['+voltage+']')
})
robot.on('lowVoltage', function onLowVoltage(voltage) {
console.log('(!!) Voltage is low ['+voltage+']')
})
robot.on('criticalVoltage', function onCriticalVoltage(voltage) {
console.log('(!!!) Voltage is critical ['+voltage+']')
})
robot.init()
function handleAnswer(answer) {
if (timer < 0) {
return
}
var message = ''
switch (answer) {
case 'help':
console.log('')
console.log('reset => performs a reset of LEDs and servo motor')
console.log('left led on => turn left led on')
console.log('left led off => turn left led off')
console.log('right led on => turn right led on')
console.log('right led off => turn right led off')
console.log('move forward => moves the GoPiGo forward')
console.log('move backward => moves the GoPiGo backward')
console.log('turn left => turns the GoPiGo to the left')
console.log('turn right => turns the GoPiGo to the right')
console.log('stop => stops the GoPiGo')
console.log('increase speed => increases the motors speed')
console.log('decrease speed => decreases the motors speed')
console.log('voltage => returns the voltage value')
console.log('servo test => performs a servo test')
console.log('ultrasonic distance => returns the distance from an object')
console.log('move forward with PID => moves the GoPiGo forward with PID')
console.log('move backward with PID => moves the GoPiGo backward with PID')
console.log('rotate left => rotates the GoPiGo to the left')
console.log('rotate right => rotates the GoPiGo to the right')
console.log('set encoder targeting => sets the encoder targeting')
console.log('firmware version => returns the firmware version')
console.log('board revision => returns the board revision')
console.log('ir receive => returns the data from the IR receiver')
console.log('exit => exits from this test')
console.log('')
break
case 'reset':
robot.reset()
break
case 'left led on':
var res = robot.ledLeft.on()
console.log('Left led on::'+res)
break
case 'left led off':
var res = robot.ledLeft.off()
console.log('Left led off::'+res)
break
case 'right led on':
var res = robot.ledRight.on()
console.log('Right led on::'+res)
break
case 'right led off':
var res = robot.ledRight.off()
console.log('Right led off::'+res)
break
case 'move forward':
case 'w':
var res = robot.motion.forward(false)
console.log('Moving forward::' + res)
break
case 'turn left':
case 'a':
var res = robot.motion.left()
console.log('Turning left::' + res)
break
case 'turn right':
case 'd':
var res = robot.motion.right()
console.log('Turning right::' + res)
break
case 'move backward':
case 's':
var res = robot.motion.backward(false)
console.log('Moving backward::' + res)
break
case 'stop':
case 'x':
var res = robot.motion.stop()
console.log('Stop::' + res)
break
case 'increase speed':
case 't':
var res = robot.motion.increaseSpeed()
console.log('Increasing speed::' + res)
break
case 'decrease speed':
case 'g':
var res = robot.motion.decreaseSpeed()
console.log('Decreasing speed::' + res)
break
case 'voltage':
case 'v':
var res = robot.board.getVoltage()
console.log('Voltage::' + res + ' V')
break
case 'servo test':
case 'b':
robot.servo.move(0)
console.log('Servo in position 0')
robot.board.wait(1000)
robot.servo.move(180)
console.log('Servo in position 180')
robot.board.wait(1000)
robot.servo.move(90)
console.log('Servo in position 90')
break
case 'exit':
case 'z':
robot.close()
process.exit()
break
case 'ultrasonic distance':
case 'u':
var res = robot.ultraSonicSensor.getDistance()
console.log('Ultrasonic Distance::' + res + ' cm')
break
case 'ir receive':
var res = robot.IRReceiverSensor.read()
console.log('IR Receiver data::')
console.log(res)
break
case 'l':
// TODO
break
case 'move forward with pid':
case 'i':
var res = robot.motion.forward(true)
console.log('Moving forward::' + res)
break
case 'move backward with pid':
case 'k':
var res = robot.motion.backward(true)
console.log('Moving backward::' + res)
break
case 'rotate left':
case 'n':
var res = robot.motion.leftWithRotation()
console.log('Rotating left::' + res)
break
case 'rotate right':
case 'm':
var res = robot.motion.rightWithRotation()
console.log('Rotating right::' + res)
break
case 'set encoder targeting':
case 'y':
var res = robot.encoders.targeting(1, 1, 18)
console.log('Setting encoder targeting:1:1:18::' + res)
break
case 'firmware version':
case 'f':
var res = robot.board.version()
console.log('Firmware version::' + res)
break
case 'board revision':
var res = robot.board.revision()
console.log('Board revision::' + res)
break
}
// robot.board.wait(1000)
// askForCommand()
};
var options = {
host: 'www.monash.edu.au',
port: 80,
path: '/'
};
setInterval(function() {
http.get(options, function(res) {
// console.log(Math.random());
}).on('error', function(e) {
// console.log("Got error: " + e.message);
});
}, 1000);