פרויקט זרוע רובוטית יכול להיות דבר מעולה שניתן ללמוד ממנו רבות והתוצר הסופי שימושי ונחמד, לבנות זרוע רובוטית מאפס יכול להיות משימה לא פשוטה ולקנות ערכה מוכנה בד"כ יעלה מאוד יקר.
לפני זמן מה מצאתי שקיימת זרוע צעצוע מאוד זולה וזמינה ברשת של חברה בשם – OWI.
זוהי זרוע מאוד פשוטה ללא כל בקר עם 5 מנועי DC פשוטים ושלט חוטי ללא כל אמצעי בקרה על מיקום כל מפרק של הזרוע.
היה לי מכר שביקר בארצות הברית לכן כל הזרוע עלתה לי 29$ כולל משלוח.
למי שאין מכר בחו"ל הזרועה כולל משלוח זמינה ב EBAY באזור ה 350 שקל כולל משלוח, ישנם כמה חנויות אינטרנטיות שמוכרות את הזרוע בארץ אך המחיר משמעותית יקר יותר.
המטרה – לחבר את המנועים של הזרוע לבקר ארדואינו, להוסיף דרך לקרוא את המיקום של כל מפרק ,להוסיף מצלמה ולתת לכל זה ממשק אינטרנטי.
רכיבים לפרויקט:
ערכת זרוע .
לוח ארדואינו (אני השתמשתי ב dumiliannov כי זה מה שהיה לי זמין).
לוח הרחבה(מגן) (ציוד הקפי משלים לארדואינו) בקר מנועים של adafruit (קיימים העתקים לא מקוריים בחניות סיניות בעלות נמוכה יותר שם אני קניתי).
בקר זוג מנועים רגיל כמו זה (היה לי בקר כזה שאחת היציאות שלו תקולה ולכן הוא יכול לשלוט רק על מנוע אחד אך זה הספיק – הסבר בהמשך ).
כל פוטנציומטר מחובר לפין אנלוגי שעל גבי הלוח הרחבה:
בנוסף ישנה מצלמה שפרקתי ממחשב נייד וחיברתי לה מחבר USB והיא ממוקמת ע"ג החלק העליון.
הארדואינו והמצלמה מחוברים למחשב המריץ וינדוס XP ע"ג מחשב קטן שמחובר לחלק התחתון של השולחן ושמשמש כשרת.
על המחשב הזה יש 2 תוכנות שרצות כ- service :
1. YAWCAM – תוכנה לשידור תזרים של פריימים ממצלמת הרשת שמחוברת למחשב .
2. node.js יחד עם socket.ioexpress ו- serial . כל הקונפיגורציה הזאת כדי שיהיה ניתן לשלוט על הראדואינו בזמן אמת דרך אפליקציית javascript.
ישנם סליידרים לכל מפרק שמזיזים את הזרוע בהתאם לקריאה מהפוטנציומטרים ובנוסף ישנם כפתורים לכל מפרק שמזיזים את הזרוע ללא קשר לקריאה מהפוטנציומטרים.
ישנה גם אפשרות לשלוח לארדואינו מסר ב SERIAL וכפתור לקריאת החיישן האולטרסוני ולשליטה על נורת הלד.
מתחת לסטרים של המצלמה ישנו אלמנט של serial output terminal שלשם מוזרמת כל תכולת המסרים שמגיעים מהSERIAL של הארדואינו.
כל הקבצים הסטטיים (קבצי JS CSS HTML IMAGES) יושבים על שרת WEB חיצוני והקישור למצלמה ולnodejs נעשה ישירות למחשב שמשמש כשרת כשהפורטים אליו פתוחים בפיירוול הביתי.
קוד הארדואינו:
//*************************************************************
//OWI Arm controller
//Include potenciometers for position.
//By Vardi Michael
//iot.org.il
//*************************************************************
#include
#include
#define PING_PIN A5 // Arduino pin tied to both trigger and echo pins on the ultrasonic sensor.
#define MAX_DISTANCE 300 // Maximum distance we want to ping for (in centimeters). Maximum sensor distance is rated at 400-500cm.
NewPing sonar(PING_PIN, PING_PIN, MAX_DISTANCE); // NewPing setup of pin and maximum distance.
int tempPing=0;
AF_DCMotor motor1(1); // Instantiate all the motors
AF_DCMotor motor2(2);
AF_DCMotor motor3(3);
AF_DCMotor motor4(4);
int LED=2; //pin for LED
int gripperA=9; //pin for gripper close
int gripperB=10; //pin for gripper open
AF_DCMotor motorArray[]={motor1,motor2,motor3,motor4}; //put all motors in an array.
//function to drive all motors take 3 params - motor number,motor speed and motor direction( 1 or 2 to represent forward/backward).
void motorDrive (int motor,int motorSpeed,int motorDirection,int motorDuration)
{
digitalWrite(gripperA, LOW);//turn off gripper motor
digitalWrite(gripperB, LOW);
if(motor-1>3)//motor-1 >3 in the motors array mean its only gripper motor(ordenarry motor controller and not arduino motor shield).
{
if(motorDirection>1) //1 mean forward and >1 mean backwards
digitalWrite(gripperA, HIGH);
else
digitalWrite(gripperB, HIGH);
delay(motorDuration);
digitalWrite(gripperA, LOW);
digitalWrite(gripperB, LOW);
}
else
{
if(motorDirection>1)
{
motorArray[motor-1].setSpeed(motorSpeed); // set the speed up to 255
motorArray[motor-1].run(BACKWARD);
}
else
{
motorArray[motor-1].setSpeed(motorSpeed); // set the speed to 100/255
motorArray[motor-1].run(FORWARD);
}
delay(motorDuration);
motorArray[motor-1].setSpeed(0);
motorArray[motor-1].run(RELEASE);
motorArray[motor-1].setSpeed(0);
}
}
//function to drive all motors to potentiometer position reading value;
int motorDrivePosition (int posit,int motor)
{
digitalWrite(gripperA, LOW);//turn off gripper motor
digitalWrite(gripperB, LOW);
int tempPositionVal = analogRead(motor-1);
int delta=tempPositionVal-posit;
while(abs(delta)>40)
{
if((motor-1)>3)//motor-1 >3 in the motors array mean its only gripper motor(ordenarry motor controller and not arduino motor shield).
{
if(tempPositionVal<posit) //1 mean forward and >1 mean backwards
{
digitalWrite(gripperA, HIGH);
delay(10);
digitalWrite(gripperA, LOW);
}
else if(tempPositionVal>posit)
{
digitalWrite(gripperB, HIGH);
delay(10);
digitalWrite(gripperB, LOW);
}
}
else if(motor==1)
{
if(tempPositionVal>posit)
{
motorArray[motor-1].setSpeed(255); // set the speed up to 255
motorArray[motor-1].run(BACKWARD);
delay(10);
motorArray[motor-1].setSpeed(0);
motorArray[motor-1].run(RELEASE);
motorArray[motor-1].setSpeed(0);
}
else if(tempPositionVal<posit) { motorArray[motor-1].setSpeed(255); // set the speed to 100/255 motorArray[motor-1].run(FORWARD); delay(10); motorArray[motor-1].setSpeed(0); motorArray[motor-1].run(RELEASE); motorArray[motor-1].setSpeed(0); } } else if(motor>1&&motor<5)
{
if(tempPositionVal<posit) { motorArray[motor-1].setSpeed(255); // set the speed up to 255 motorArray[motor-1].run(BACKWARD); delay(10); motorArray[motor-1].setSpeed(0); motorArray[motor-1].run(RELEASE); motorArray[motor-1].setSpeed(0); } else if(tempPositionVal>posit)
{
motorArray[motor-1].setSpeed(255); // set the speed to 100/255
motorArray[motor-1].run(FORWARD);
delay(10);
motorArray[motor-1].setSpeed(0);
motorArray[motor-1].run(RELEASE);
motorArray[motor-1].setSpeed(0);
}
}
tempPositionVal = analogRead(motor-1);
delta=tempPositionVal-posit;
}
Serial.println(tempPositionVal);
if(motor-1>3)
{
digitalWrite(gripperA, LOW);
digitalWrite(gripperB, LOW);
}
else
{
motorArray[motor-1].setSpeed(0);
motorArray[motor-1].run(RELEASE);
motorArray[motor-1].setSpeed(0);
}
}
//function to "expload" string from serial with delimiting and return desired value
String getValue(String data, char separator, int index)
{
int found = 0;
int strIndex[] = {0, -1};
int maxIndex = data.length()-1;
for(int i=0; i<=maxIndex && found<=index; i++) { if(data.charAt(i)==separator || i==maxIndex) { found++; strIndex[0] = strIndex[1]+1; strIndex[1] = (i == maxIndex) ? i+1 : i; } } return found>index ? data.substring(strIndex[0], strIndex[1]) : "";
}
void setup()
{
Serial.begin(9600); // set up Serial library at 9600 bps
motor1.setSpeed(100); // set the speed to 100/255
motor2.setSpeed(100); // do the same for the others...
motor3.setSpeed(100);
motor4.setSpeed(100);
//Setup gripper
pinMode(gripperA, OUTPUT); //Initiates Motor gripper Channel A pin
pinMode(gripperB, OUTPUT); //Initiates Motor gripper Channel B pin
pinMode(LED, OUTPUT); //Initiates lED pin
}
void loop()
{
//handel the serial communication...reading a string from serial
delay(50); // Wait 50ms between pings (about 20 pings/sec). 29ms should be the shortest delay between pings.
unsigned int uS = sonar.ping(); // Send ping, get ping time in microseconds (uS).
if(abs(tempPing-(uS / US_ROUNDTRIP_CM))>5)
{
Serial.print("ping;");
Serial.println(uS / US_ROUNDTRIP_CM); // Convert ping time to distance and print result (0 = outside set distance range, no ping echo)
}
tempPing=uS / US_ROUNDTRIP_CM;
String content = "";
char character;
while(Serial.available())
{
character = Serial.read();
content.concat(character);
delay (1);
}
if (content != "")
{
if(content =="ping")
{
Serial.print("ping;");
Serial.println(uS / US_ROUNDTRIP_CM); // Convert ping time to distance and print result (0 = outside set distance range, no ping echo)
}
else if(content =="ledon")
{
digitalWrite(LED, HIGH);
}
else if(content =="ledoff")
{
digitalWrite(LED, LOW);
}
else if(getValue(content,';',0) =="cp")//get current motors position report
{
int valtemp = analogRead(getValue(content,';',1).toInt()-1) ; // read the input pin 0
Serial.println(valtemp); // report the new readings
delay(10);
}
else if(getValue(content,';',0) =="pos")//drive motor to position of potentiometer
{
motorDrivePosition(getValue(content,';',1).toInt(),getValue(content,';',2).toInt());
}
else//call for motorDrive function according to string from serial
motorDrive(getValue(content,';',0).toInt(),getValue(content,';',1).toInt(),getValue(content,';',2).toInt(),getValue(content,';',3).toInt());
}
}