Skip to content

Commit cc65181

Browse files
committed
Adding robot server
1 parent e2e64c4 commit cc65181

File tree

9 files changed

+340
-2
lines changed

9 files changed

+340
-2
lines changed

.gitignore

+2
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,4 @@
11
.DS_Store
22
node_modules
3+
.idea
4+
npm-debug.log

software/package.json

+8-1
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,13 @@
1717
"node":"0.x.x"
1818
},
1919
"dependencies":{
20-
"johnny-five":"0.7.x"
20+
"johnny-five":"0.7.x",
21+
"hapi": "8.4.0",
22+
"argparse": "~0.1.10",
23+
"path": "~0.4.9",
24+
"temp": "~0.5.0",
25+
"request": "~2.12.0",
26+
"johnny-five": "git://github.com/rwaldron/johnny-five.git",
27+
"xmlhttprequest" : "~1.5.0"
2128
}
2229
}

software/src/bot.js

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
five = require("johnny-five");
2-
ik = require("./ik");
2+
ik = require("./lib/kinematics");
33
board = new five.Board({
44
debug: false
55
});
File renamed without changes.

software/src/server/calibration.js

+29
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
var fs = require("fs");
2+
3+
module.exports.loadDataFromFilePath = function(filePath) {
4+
// Default Calibration
5+
module.exports.data = {
6+
restPoint : {
7+
x : 0,
8+
y : 0,
9+
z : -120
10+
},
11+
servo1 : {
12+
minimumAngle : 20,
13+
maximumAngle : 90
14+
},
15+
servo2 : {
16+
minimumAngle : 20,
17+
maximumAngle : 90
18+
},
19+
servo3 : {
20+
minimumAngle : 20,
21+
maximumAngle : 90
22+
}
23+
};
24+
25+
// Load Calibration Data
26+
if (fs.existsSync(filePath)) {
27+
module.exports.data = eval(fs.readFileSync(filePath, "utf8"));
28+
}
29+
};

software/src/server/dancer.js

+33
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,33 @@
1+
var method = Dancer.prototype;
2+
3+
function Dancer(robot) {
4+
var dancer = this;
5+
this._robot = robot;
6+
this._minAngle = 10;
7+
this._maxAngle = 20;
8+
this._range = this._maxAngle - this._minAngle;
9+
this._interval = null;
10+
}
11+
12+
method.startDancing = function() {
13+
var _dance = function() {
14+
var t1 = parseInt((Math.random() * this._range) + this._minAngle, 10);
15+
var t2 = parseInt((Math.random() * this._range) + this._minAngle, 10);
16+
var t3 = parseInt((Math.random() * this._range) + this._minAngle, 10);
17+
this._robot.setAngles(t1,t2,t3);
18+
}.bind(this);
19+
20+
if (!this._interval) {
21+
this._interval = setInterval(_dance, 250);
22+
}
23+
};
24+
25+
method.stopDancing = function() {
26+
if (this._interval) {
27+
clearInterval(this._interval);
28+
this._interval = null;
29+
}
30+
};
31+
32+
module.exports = {};
33+
module.exports.Dancer = Dancer;

software/src/server/parser.js

+32
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
var ArgumentParser = require('argparse').ArgumentParser;
2+
3+
// parse arguments
4+
var parser = new ArgumentParser({
5+
version: '0.0.1',
6+
addHelp:true,
7+
description: 'Tapster Server'
8+
});
9+
10+
parser.addArgument(
11+
[ '-c', '--calibration'], {
12+
help: 'file to load calibration data from'
13+
});
14+
15+
parser.addArgument(
16+
['-p', '--port'] , {
17+
defaultValue: 4242
18+
, required: false
19+
, type: 'int'
20+
, example: "4242"
21+
, help: 'port to listen on'
22+
});
23+
24+
parser.addArgument(
25+
['-a', '--address'], {
26+
defaultValue: '127.0.0.1'
27+
, required: false
28+
, example: "127.0.0.1"
29+
, help: 'IP Address to listen on'
30+
});
31+
32+
module.exports = parser;

software/src/server/robot.js

+82
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,82 @@
1+
var kinematics = require("./../lib/kinematics");
2+
var method = Robot.prototype;
3+
4+
function Robot(servo1, servo2, servo3, calibration) {
5+
this._servo1 = servo1;
6+
this._servo2 = servo2;
7+
this._servo3 = servo3;
8+
this._calibration = calibration;
9+
}
10+
11+
var sin = function(degree) {
12+
return Math.sin(Math.PI * (degree/180));
13+
};
14+
15+
var cos = function(degree) {
16+
return Math.cos(Math.PI * (degree/180));
17+
};
18+
19+
var mapNumber = function (num, in_min , in_max , out_min , out_max ) {
20+
return ( num - in_min ) * ( out_max - out_min ) / ( in_max - in_min ) + out_min;
21+
};
22+
23+
var rotate = function(x,y) {
24+
var theta = -60;
25+
var x1 = x * cos(theta) - y * sin(theta);
26+
var y1 = y * cos(theta) + x * sin(theta);
27+
return [x1,y1]
28+
};
29+
30+
var reflect = function(x,y) {
31+
var theta = 0;
32+
var x1 = x;
33+
var y1 = x * sin(2*theta) - y * cos(2*theta);
34+
return [x1,y1]
35+
};
36+
37+
38+
method.getAngles = function() {
39+
return [this._servo1.last.degrees, this._servo2.last.degrees, this._servo3.last.degrees];
40+
};
41+
42+
method.setAngles = function(t1,t2,t3) {
43+
console.log("Setting Angles:" + [t1,t2,t3]);
44+
t1 = isNaN(t1) ? this._calibration.servo1.minimumAngle : t1;
45+
t2 = isNaN(t2) ? this._calibration.servo1.minimumAngle : t2;
46+
t3 = isNaN(t3) ? this._calibration.servo1.minimumAngle : t3;
47+
this._servo1.to(t1);
48+
this._servo2.to(t2);
49+
this._servo3.to(t3);
50+
};
51+
52+
method.getPosition = function() {
53+
var angles = this.getAngles();
54+
return kinematics.forward(angles[0], angles[1], angles[2]);
55+
};
56+
57+
method.setPosition = function(x, y, z) {
58+
var reflected = reflect(x,y);
59+
var rotated = rotate(reflected[0],reflected[1]);
60+
var angles = kinematics.inverse(rotated[0], rotated[1], z);
61+
var t1 = mapNumber(angles[1], 0 , 90 , this._calibration.servo1.minimumAngle , this._calibration.servo1.maximumAngle);
62+
var t2 = mapNumber(angles[2], 0 , 90 , this._calibration.servo2.minimumAngle , this._calibration.servo2.maximumAngle);
63+
var t3 = mapNumber(angles[3], 0 , 90 , this._calibration.servo3.minimumAngle , this._calibration.servo3.maximumAngle);
64+
this.setAngles(t1,t2,t3);
65+
};
66+
67+
method.reset = function() {
68+
this.setPosition(calibration.restPoint.x, calibration.restPoint, calibration.restPoint.z);
69+
};
70+
71+
method.getPositionForAngles = function(t1,t2,t3) {
72+
var points = kinematics.forward(t1,t2,t3);
73+
return [points[1], points[2], points[3]];
74+
};
75+
76+
method.getAnglesForPosition = function(x,y,z) {
77+
var angles = kinematics.inverse(x,y,z);
78+
return [angles[1], angles[2], angles[3]];
79+
};
80+
81+
module.exports = {};
82+
module.exports.Robot = Robot;

software/src/server/server.js

+153
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,153 @@
1+
#! /usr/local/bin/node
2+
var application_root = __dirname
3+
, parser = require("./parser")
4+
, Hapi = require("hapi")
5+
, path = require("path")
6+
, five = require("johnny-five")
7+
, calibration = require("./calibration")
8+
, Robot = require("./robot").Robot
9+
, Dancer = require("./dancer").Dancer;
10+
11+
args = parser.parseArgs();
12+
calibration.loadDataFromFilePath(args.calibration);
13+
14+
var board = new five.Board({ debug: false});
15+
board.on("ready", function() {
16+
var servo1 = five.Servo({
17+
pin: 9,
18+
range: [0,90]
19+
});
20+
21+
var servo2 = five.Servo({
22+
pin: 10,
23+
range: [0,90]
24+
});
25+
26+
var servo3 = five.Servo({
27+
pin: 11,
28+
range: [0,90]
29+
});
30+
31+
servo1.on("error", function() {
32+
console.log(arguments);
33+
});
34+
servo2.on("error", function() {
35+
console.log(arguments);
36+
});
37+
servo3.on("error", function() {
38+
console.log(arguments);
39+
});
40+
41+
// Initialize Objects
42+
var robot = new Robot(servo1,servo2,servo3,calibration.data);
43+
var dancer = new Dancer(robot);
44+
45+
// Move to starting point
46+
robot.setPosition(calibration.data.restPoint.x, calibration.data.restPoint.y, calibration.data.restPoint.z);
47+
48+
// create a server with a host and port
49+
var server = new Hapi.Server();
50+
server.connection({
51+
host: args.address,
52+
port: args.port
53+
});
54+
55+
server.route({
56+
method: 'GET',
57+
path:'/status',
58+
handler: function (request, reply) {
59+
console.log("GET " + request.path + ": ");
60+
reply('\"OK\"');
61+
}
62+
});
63+
64+
server.route({
65+
method: 'POST',
66+
path:'/reset',
67+
handler: function (request, reply) {
68+
console.log("GET " + request.path + ": ");
69+
robot.reset();
70+
reply(robot.getAngles());
71+
}
72+
});
73+
74+
server.route({
75+
method: 'POST',
76+
path:'/dance',
77+
handler: function (request, reply) {
78+
console.log("GET " + request.path + ": ");
79+
dancer.startDancing();
80+
reply('\"Dancing!\"');
81+
}
82+
});
83+
84+
server.route({
85+
method: 'POST',
86+
path:'/stopDancing',
87+
handler: function (request, reply) {
88+
console.log("GET " + request.path + ": ");
89+
dancer.stopDancing();
90+
reply('\"No more dancing.\"');
91+
}
92+
});
93+
94+
server.route({
95+
method: 'POST',
96+
path:'/setAngles',
97+
handler: function (request, reply) {
98+
console.log("POST " + request.path + ": ");
99+
var theta1 = parseFloat(request.payload.theta1);
100+
var theta2 = parseFloat(request.payload.theta2);
101+
var theta3 = parseFloat(request.payload.theta3);
102+
robot.setAngles(theta1, theta2, theta3);
103+
return reply("\"OK\"");
104+
}
105+
});
106+
107+
server.route({
108+
method: 'POST',
109+
path:'/setPosition',
110+
handler: function (request, reply) {
111+
console.log("POST " + request.path + ": ");
112+
var x = parseFloat(request.payload.x);
113+
var y = parseFloat(request.payload.y);
114+
var z = parseFloat(request.payload.z);
115+
robot.setPosition(x, y, z);
116+
return reply("\"OK\"");
117+
}
118+
});
119+
120+
server.route({
121+
method: 'GET',
122+
path:'/angles',
123+
handler: function (request, reply) {
124+
console.log("GET " + request.path + ": ");
125+
return reply(robot.getAngles());
126+
}
127+
});
128+
129+
server.route({
130+
method: 'GET',
131+
path:'/position',
132+
handler: function (request, reply) {
133+
console.log("GET " + request.path + ": ");
134+
return reply(robot.getPosition());
135+
}
136+
});
137+
138+
server.route({
139+
method: 'GET',
140+
path:'/anglesForPosition/x/{x}/y/{y}/z/{z}',
141+
handler: function (request, reply) {
142+
console.log("GET " + req.path + ": ");
143+
var x = parseFloat(request.params.x);
144+
var y = parseFloat(request.params.y);
145+
var z = parseFloat(request.params.z);
146+
return reply(robot.getAnglesForPosition(x,y,z));
147+
}
148+
});
149+
150+
server.start();
151+
console.log("Robot listening on port " + args.port);
152+
153+
});

0 commit comments

Comments
 (0)