-
Notifications
You must be signed in to change notification settings - Fork 3
/
Copy pathSocialPods.cpp
176 lines (151 loc) · 4.98 KB
/
SocialPods.cpp
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
//Basic Motion
#include<VarSpeedServo.h>
#include<SocialPods.h>
//======================================//
// Variables //
//======================================//
// Do Not Touch!!! //
int servoAngles[2][2][2] = {};
int calib[2][2][2] = {};
VarSpeedServo servo[2][2][2];
//======================================//
// Example Functions //
//======================================//
//reference : http://makezine.jp/blog/2016/12/robot-quadruped-arduino-program.html
void forward(int speed = 50, int loop = 1){
if(readServoAngle(F,R,S) != -30) armMoveTo(F,R,-30);
if(readServoAngle(R,R,S) != 30) armMoveTo(R,R, 30);
if(readServoAngle(F,L,S) != -15) armMoveTo(F,L,-15);
if(readServoAngle(R,L,S) != 15) armMoveTo(R,L, 15);
int count = 0;
while(count < loop){
armMove(F,R,30,speed);
servoMove(F,R,S,-15, false, speed);
servoMove(F,L,S,-15, false, speed);
servoMove(R,L,S,-15, false, speed);
servoMove(R,R,S,-15, true, speed);
armMove(R,L,30,speed);
armMove(F,L,30,speed);
servoMove(F,R,S,-15, false, speed);
servoMove(F,L,S,-15, false, speed);
servoMove(R,L,S,-15, false, speed);
servoMove(R,R,S,-15, true, speed);
armMove(R,R,30,speed);
count++;
}
}
void turnRight(int speed = 50){
int count = 0;
while( count < 3 ){
armMove(F,R,-30, speed);
armMove(F,L,30, speed);
armMove(R,L,30, speed);
armMove(R,R,-30, speed);
initializePose();
count++;
}
}
//======================================//
// Wrapper Function Definitions //
//======================================//
// Do Not Touch!!! //
//High Level Function
void initializePose(){
servoMoveTo(F,R,S,0, false);
servoMoveTo(F,R,C,0, false);
servoMoveTo(F,L,S,0, false);
servoMoveTo(F,L,C,0, false);
servoMoveTo(R,R,S,0, false);
servoMoveTo(R,R,C,0, false);
servoMoveTo(R,L,S,0, false);
servoMoveTo(R,L,C,0, true);
}
void armMove(int FR, int LR, int deltaAngle, int _speed = 50){
servoMoveTo(FR, LR, C, 30, true, _speed);
servoMove(FR, LR, S, deltaAngle, true, _speed);
servoMoveTo(FR, LR, C, 0, true, _speed);
}
void armMoveTo(int FR, int LR, int angle, int _speed = 50){
servoMoveTo(FR, LR, C, 30, true, _speed);
servoMoveTo(FR, LR, S, angle, true, _speed);
servoMoveTo(FR, LR, C, 0, true, _speed);
}
//Low Level Function
int readServoAngle(int FR, int LR, int SC){
if(SC == 0){
return servoAngles[FR][LR][SC]/(LR*2-1) - calib[FR][LR][SC];
} else if (SC == 1) {
return servoAngles[FR][LR][SC]/(((FR+LR)%2)*2-1) - calib[FR][LR][SC];
}
}
void servoMove(int FR, int LR, int SC, int deltaAngle, bool isWait = true, int _speed = 50) {
if(SC == 0){
servoAngles[FR][LR][SC] += deltaAngle*(LR*2-1);
} else if (SC == 1) {
servoAngles[FR][LR][SC] += deltaAngle*(((FR+LR)%2)*2-1);
}
// check angle range
if(servoAngles[FR][LR][SC] < -90) {
servoAngles[FR][LR][SC] = -90;
} else if (servoAngles[FR][LR][SC] > 90) {
servoAngles[FR][LR][SC] = 90;
}
servo[FR][LR][SC].write(DEFAULT_POS-servoAngles[FR][LR][SC], _speed, isWait);
}
void servoMove(int FR, int LR, int SC, int deltaAngle, int _speed) {
if(SC == 0){
servoAngles[FR][LR][SC] += deltaAngle*(LR*2-1);
} else if (SC == 1) {
servoAngles[FR][LR][SC] += deltaAngle*(((FR+LR)%2)*2-1);
}
// check angle range
if(servoAngles[FR][LR][SC] < -90) {
servoAngles[FR][LR][SC] = -90;
} else if (servoAngles[FR][LR][SC] > 90) {
servoAngles[FR][LR][SC] = 90;
}
servo[FR][LR][SC].write(DEFAULT_POS-servoAngles[FR][LR][SC], _speed);
}
void servoMoveTo(int FR, int LR, int SC, int angle, bool isWait = true, int _speed = 50) {
if(SC == 0){
servoAngles[FR][LR][SC] = angle*(LR*2-1) + calib[FR][LR][SC];
} else if (SC == 1) {
servoAngles[FR][LR][SC] = angle*(((FR+LR)%2)*2-1) + calib[FR][LR][SC];
}
// check angle range
if(servoAngles[FR][LR][SC] < -90) {
servoAngles[FR][LR][SC] = -90;
} else if (servoAngles[FR][LR][SC] > 90) {
servoAngles[FR][LR][SC] = 90;
}
if(SC == 0){
servo[FR][LR][SC].write(DEFAULT_POS-servoAngles[FR][LR][SC], _speed, isWait);
} else if (SC == 1) {
servo[FR][LR][SC].write(DEFAULT_POS-servoAngles[FR][LR][SC], _speed, isWait);
}
}
void servoMoveTo(int FR, int LR, int SC, int angle, int _speed) {
if(SC == 0){
servoAngles[FR][LR][SC] = angle*(LR*2-1) + calib[FR][LR][SC];
} else if (SC == 1) {
servoAngles[FR][LR][SC] = angle*(((FR+LR)%2)*2-1) + calib[FR][LR][SC];
}
// check angle range
if(servoAngles[FR][LR][SC] < -90) {
servoAngles[FR][LR][SC] = -90;
} else if (servoAngles[FR][LR][SC] > 90) {
servoAngles[FR][LR][SC] = 90;
}
if(SC == 0){
servo[FR][LR][SC].write(DEFAULT_POS-servoAngles[FR][LR][SC], _speed);
} else if (SC == 1) {
servo[FR][LR][SC].write(DEFAULT_POS-servoAngles[FR][LR][SC], _speed);
}
}
void calibrateTo(int FR , int LR, int SC, int calib_value){
if(SC == 0){
calib[FR][LR][SC] = calib_value*(LR*2-1);
} else if (SC == 1) {
calib[FR][LR][SC] = calib_value*(((FR+LR)%2)*2-1);
}
}