-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathInMoov2 hand_Myo.ino
313 lines (237 loc) · 8.84 KB
/
InMoov2 hand_Myo.ino
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
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
//This is based on the MiniBot project, MiniBlue.pde from Zagros Robotics, Inc
//Modified by Elizabeth Greene ([email protected]) 30 August 2013 for the inMoov Prosthetics project
//Modified by Gaël Langevin ([email protected]) 13/11/2014 for the inMoov Prosthetics project
//Todo: set PWM pulse on pins 2 to 11
#include <MyoController.h>
#define DOUBLETAP_PIN 12
MyoController myo = MyoController();
int r_motor_Rotthumb_n = 2; //Arduino pin to motor Controller Ain1
int r_motor_Rotthumb_p = 3; //Arduino pin tomotor Controller Ain2
int r_motor_Thumb_n = 4; //Arduino pin to motor Controller Bin1
int r_motor_Thumb_p = 5; //Arduino pin to motor Controller Bin2
int r_motor_Index_n = 6; //Arduino pin to motor Controller Ain1
int r_motor_Index_p = 7; //Arduino pin to motor Controller Ain2
int r_motor_Majeure_n = 8; //Arduino pin to motor Controller Bin1
int r_motor_Majeure_p = 9; //Arduino pin to motor Controller Bin2
int r_motor_Pinky_n = 10; //Arduino pin to motor Controller Ain1
int r_motor_Pinky_p = 11; //Arduino pin to motor Controller Ain2
int incomingByte = 0; // for incoming serial data
//This value sets the maximum speed of the motor. It's a value between 1 and 255.
//64 is 1/4 speed, 128 is 1/2 speed, 255 is full speed
int maxSpeed = 250;
int halfSpeed = 150;
int minSpeed = 128;
//These are the values you determined to be the limit for the minimum and maximum finger positions.
int potLimitLowRotthumb = 50; //RotThumb extend
int potLimitHighRotthumb = 800; //RotThumb retract
int potLimitLowThumb = 125; //Thumb extend
int potLimitHighThumb = 400; //Thumb retract
int potLimitLowIndex = 0; //Index extend
int potLimitHighIndex = 620; //Index retract
int potLimitLowMajeure = 130; //Majeure extend
int potLimitHighMajeure = 550; //Majeure retract
int potLimitLowPinky = 170; //Pinky extend
int potLimitHighPinky = 400; //Pinky retract
int speedDesired;
unsigned long safeDelay = (5 * 1000);
unsigned long lastMillis;
int rotthumbPot;
int rotthumbDesired;
int deltaRotthumb;
int rotthumbPos;
int thumbPot;
int thumbDesired;
int deltaThumb;
int thumbPos;
int indexPot;
int indexDesired;
int deltaIndex;
int indexPos;
int majeurePot;
int majeureDesired;
int deltaMajeure;
int majeurePos;
int pinkyPot;
int pinkyDesired;
int deltaPinky;
int pinkyPos;
void setup()
{
pinMode(DOUBLETAP_PIN, OUTPUT);
pinMode(13, OUTPUT);
pinMode(r_motor_Rotthumb_n, OUTPUT); //Set control pins to be outputs
pinMode(r_motor_Rotthumb_p, OUTPUT);
pinMode(r_motor_Thumb_n, OUTPUT); //Set control pins to be outputs
pinMode(r_motor_Thumb_p, OUTPUT);
pinMode(r_motor_Index_n, OUTPUT); //Set control pins to be outputs
pinMode(r_motor_Index_p, OUTPUT);
pinMode(r_motor_Majeure_n, OUTPUT); //Set control pins to be outputs
pinMode(r_motor_Majeure_p, OUTPUT);
pinMode(r_motor_Pinky_n, OUTPUT); //Set control pins to be outputs
pinMode(r_motor_Pinky_p, OUTPUT);
stopMotors();
Serial.begin(115200);
myo.initMyo();
//Serial.println("c = close hand ");
//Serial.println("o = open hand ");
//Serial.println("g = intermediate position of hand ");
}
void loop()
{
rotthumbPot = analogRead(A2);
thumbPot = analogRead(A3);
indexPot = analogRead(A4);
majeurePot = analogRead(A5);
pinkyPot = analogRead(A6);
actualPosition(rotthumbPot,thumbPot,indexPot,majeurePot,pinkyPot);
myo.updatePose();
if (Serial.available() > 0) {
// read the incoming byte:
incomingByte = Serial.read();
switch (incomingByte,myo.getCurrentPose()) {
case rest:
digitalWrite(DOUBLETAP_PIN,LOW);
incomingByte='*';
break;
case fist:
moveHand(90,0,90,90,90, maxSpeed);
//Serial.println("Closing");
incomingByte='*';
safeDelay = (5 * 150);
lastMillis = millis();
break;
case fingersSpread:
moveHand(0,0,0,0,0, maxSpeed);
//Serial.println("Opening");
incomingByte='*';
safeDelay = (5 * 150);
lastMillis = millis();
break;
case waveIn:
moveHand(90,25,40,0,0, maxSpeed);
//Serial.println("Pinch Fingers");
incomingByte='*';
safeDelay = (5 * 150);
lastMillis = millis();
break;
case waveOut:
moveHand(30,50,0,60,160, maxSpeed);
//Serial.println("Typing Finger");
incomingByte='*';
safeDelay = (5 * 150);
lastMillis = millis();
break;
case doubleTap:
digitalWrite(DOUBLETAP_PIN,HIGH);
break;}
delay(100);
}
if ((millis()-lastMillis) < safeDelay){
check();
delay(1);
digitalWrite(13,LOW);}
else {
stopMotors();
digitalWrite(13,HIGH);
delay(1);
}
}
void actualPosition(int rotthumbPot, int thumPot, int indexPot, int majeurePot, int pinkyPot){
rotthumbPos = map(rotthumbPot,potLimitLowRotthumb,potLimitHighRotthumb,0,90);
thumbPos = map(thumbPot,potLimitLowThumb,potLimitHighThumb,0,90);
indexPos = map(indexPot,potLimitLowIndex,potLimitHighIndex,0,90);
majeurePos = map(majeurePot,potLimitLowMajeure,potLimitHighMajeure,0,90);
pinkyPos = map(pinkyPot,potLimitLowPinky,potLimitHighPinky,0,90);
}
void moveHand(int rotthumb, int thumb, int index, int majeure, int pinky, int val){
rotthumbDesired = rotthumb;
thumbDesired = thumb;
indexDesired = index;
majeureDesired = majeure;
pinkyDesired = pinky;
speedDesired = val;
}
void stopMotors(){
digitalWrite(r_motor_Rotthumb_n, LOW); //set both motors off for start-up
digitalWrite(r_motor_Rotthumb_p, LOW);
digitalWrite(r_motor_Thumb_n, LOW); //set both motors off for start-up
digitalWrite(r_motor_Thumb_p, LOW);
digitalWrite(r_motor_Index_n, LOW); //set both motors off for start-up
digitalWrite(r_motor_Index_p, LOW);
digitalWrite(r_motor_Majeure_n, LOW); //set both motors off for start-up
digitalWrite(r_motor_Majeure_p, LOW);
digitalWrite(r_motor_Pinky_n, LOW); //set both motors off for start-up
digitalWrite(r_motor_Pinky_p, LOW);
}
void check(){
deltaRotthumb = (rotthumbDesired - rotthumbPos);
if (abs(deltaRotthumb) > 10) {
if (deltaRotthumb >0){
analogWrite(r_motor_Rotthumb_n,speedDesired);
digitalWrite(r_motor_Rotthumb_p, LOW);
}
else {
analogWrite(r_motor_Rotthumb_p,speedDesired);
digitalWrite(r_motor_Rotthumb_n, LOW);
}}
else {
digitalWrite(r_motor_Rotthumb_n, LOW);
digitalWrite(r_motor_Rotthumb_p, LOW);
}
deltaThumb = (thumbDesired - thumbPos);
if (abs(deltaThumb) > 10) {
if (deltaThumb >0){
analogWrite(r_motor_Thumb_n,speedDesired);
digitalWrite(r_motor_Thumb_p, LOW);
}
else {
analogWrite(r_motor_Thumb_p,speedDesired);
digitalWrite(r_motor_Thumb_n, LOW);
}}
else {
digitalWrite(r_motor_Thumb_n, LOW);
digitalWrite(r_motor_Thumb_p, LOW);
}
deltaIndex = (indexDesired - indexPos);
if (abs(deltaIndex) > 10) {
if (deltaIndex >0){
analogWrite(r_motor_Index_n,speedDesired);
digitalWrite(r_motor_Index_p, LOW);
}
else {
analogWrite(r_motor_Index_p,speedDesired);
digitalWrite(r_motor_Index_n, LOW);
}}
else {
digitalWrite(r_motor_Index_n, LOW);
digitalWrite(r_motor_Index_p, LOW);
}
deltaMajeure = (majeureDesired - majeurePos);
if (abs(deltaMajeure) > 10) {
if (deltaMajeure >0){
analogWrite(r_motor_Majeure_n,speedDesired);
digitalWrite(r_motor_Majeure_p, LOW);
}
else {
analogWrite(r_motor_Majeure_p,speedDesired);
digitalWrite(r_motor_Majeure_n, LOW);
}}
else {
digitalWrite(r_motor_Majeure_n, LOW);
digitalWrite(r_motor_Majeure_p, LOW);
}
deltaPinky = (pinkyDesired - pinkyPos);
if (abs(deltaPinky) > 10) {
if (deltaPinky>0){
analogWrite(r_motor_Pinky_n,speedDesired);
digitalWrite(r_motor_Pinky_p, LOW);
}
else {
analogWrite(r_motor_Pinky_p,speedDesired);
digitalWrite(r_motor_Pinky_n, LOW);
}}
else {
digitalWrite(r_motor_Pinky_n, LOW);
digitalWrite(r_motor_Pinky_p, LOW);
}
}