-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathindex.js
161 lines (127 loc) · 3.34 KB
/
index.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
var express = require('express')
, app = express()
, path = require('path')
, http = require('http').Server(app)
, socketIO = require('socket.io')(http)
, five = require('johnny-five')
, tessel = require('tessel-io')
, ip = require('ip')
, PORT = 3000
, board = new five.Board({
io: new tessel()
})
;
function emitUserCount(socketIO) {
socketIO.sockets.emit('user:count', socketIO.engine.clientsCount);
console.log('Total users: ', socketIO.engine.clientsCount);
}
app.use(express.static(path.join(__dirname + '/public')));
// index route
app.get('/', function (req, res, next) {
res.sendFile(path.join(__dirname + '/public/index.html'))
});
// variable input controller route
app.get('/controller', function (req, res, next) {
res.sendFile(path.join(__dirname + '/public/controller.html'))
});
// board ready event
board.on('ready', function (err) {
if (err) {
board.reset();
return;
}
function checkForZeroUsers(socketIO) {
if (socketIO.engine.clientsCount === 0) {
stop();
}
}
console.log('board connected! Johnny-Five ready to go.')
// setup motors
var motor1 = new five.Motor({
pins: {
pwm: 'A5',
dir: 'A6'
},
invertPWM: true
})
, motor2 = new five.Motor({
pins: {
pwm: 'B5',
dir: 'B6'
},
invertPWM: true
});
function forward(_speed) {
var speed = _speed ? _speed : 255;
// motor 1 is reversed
motor1.reverse(speed);
motor2.forward(speed);
}
function reverse(_speed) {
var speed = _speed ? _speed : 255;
// motor 1 is reversed
motor1.forward(speed);
motor2.reverse(speed);
}
function spinLeft(_speed) {
var speed = _speed ? _speed : 255 * .8;
// motor 1 is reversed
motor1.forward(speed);
motor2.forward(speed);
}
function spinRight(_speed) {
var speed = _speed ? _speed : 255 * .8;
// motor 1 is reversed
motor1.reverse(speed);
motor2.reverse(speed);
}
function stop() {
motor1.stop();
motor2.stop();
}
// SocketIO events
socketIO.on('connection', function (socket) {
//console.log('New connection!');
emitUserCount(socketIO);
socket.on('forward', forward);
socket.on('reverse', reverse);
socket.on('spinLeft', spinLeft);
socket.on('spinRight', spinRight);
// nipplejs variable input events
socket.on('leftMotor', function (input) {
//console.log('leftMotor: ' + input.force);
// INVERTED DIRECTIONS FOR THIS MOTOR
if (input.direction === 'forward') {
motor1.reverse(input.force);
} else {
motor1.forward(input.force);
}
});
socket.on('rightMotor', function (input) {
//console.log('rightMotor: ' + input.force);
if (input.direction === 'forward') {
motor2.forward(input.force);
} else {
motor2.reverse(input.force);
}
});
socket.on('stop', function (motor) {
//console.log('STOP!');
if (!motor) {
stop();
} else if (motor === 'leftMotor') {
motor1.stop();
} else {
motor2.stop();
}
});
socket.on('disconnect', function() {
checkForZeroUsers(socketIO);
emitUserCount(socketIO);
});
});
// set the app to listen on PORT
http.listen(PORT);
// log the address and port
console.log('Up and running on ' + ip.address() + ':' + PORT);
});