-
Notifications
You must be signed in to change notification settings - Fork 9
/
experiment14b.js
43 lines (38 loc) · 1.25 KB
/
experiment14b.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
// Draws a diamond
var PEN_DOWN = PEN_DOWN_VALUE_HERE; // motors[2] when pen touches paper
var PEN_UP = PEN_UP_VALUE_HERE; // motors[2] when pen is away from paper
var OFFSET_LEFT = 0.1; // offset to make left servo horizontal
var OFFSET_RIGHT = -0.1; // offset to make right servo horizontal
var motors = [0,0,PEN_UP];
function updateServos() {
getNewPosition();
digitalPulse(B3, 1, E.clip(1.5+(motors[0]+OFFSET_LEFT), 1, 2));
digitalPulse(B3, 1, 0); // wait for pulse
digitalPulse(B4, 1, E.clip(1.5-(motors[1]+OFFSET_RIGHT), 1, 2));
digitalPulse(B4, 1, 0); // wait for pulse
digitalPulse(B5, 1, E.clip(1.5+motors[2], 1, 2)); // Pen
}
var pos = 0;
var size = 0.1;
function getNewPosition() {
// increment pos slowly between 0 and 1
pos += 0.002;
if (pos > 1) pos = 0;
// Multiply by 4, for each edge of the square
var sq = pos*4;
// Now set the position for each edge:
if (sq<1) { // top edge
motors[0] = (sq-0.5)*2*size;
motors[1] = -size;
} else if (sq<2) { // right edge
motors[0] = size;
motors[1] = (sq-1.5)*2*size;
} else if (sq<3) { // bottom edge
motors[0] = (2.5-sq)*2*size;
motors[1] = size;
} else { // left edge
motors[0] = -size;
motors[1] = (3.5-sq)*2*size;
}
}
setInterval(updateServos, 20);