عبارة عن روبوت بشكل عنكبوت يمتلك ستة أرجل و حساس مسافات ليقوم بالتنقل ضمن أي مساحة و الالتفاف حول العوائق التي تواجهه
أجزاء الروبوت
لقد استخدمت أرديونو MEGA2560 R3 لأنه يحتوي على العديد من المنافذ و المخارج ولكن يمكنك استخدام أي لوحة أرديونو أخرى مع أي سي لتمديد المنافذ .
لكل ساق ، نحتاج إلى 3 محركات لذا لدينا:3X6=18 محرك
استخدمت محرك سيرفو إضافي لحساس المسافات حتى يستطيع الدوران و قياس المسافات بجميع الاتجاهات. نحتاج إلى تزويد الروبوت ببطارية 7.4 فولط و 2 أمبير ساعي لأن المحركات الكثيرة التي يستخدمها الروبوت تحتاج إلى طاقة كبيرة و لأن محرك السرفو يحتاج إلى 5 فولط فقط فإننا نحتاج إلى محول جهد تنازلي و يجب استخدام محولي حهد واحد من أجل المحركات و الآخر من أجل تغذية الأرديونو و يرجى عدم تغذية كل من الأرديونو و المحركات من نفس المحول لأن المحركات تستهلك جل طاقة المحول
كانت لدي مشكلة مع حساس المسافة حيث أنه كان يحصل على قراءات خاطئة فرغم أن المسافة أمامه تكون كبيرة فأنه يعطي فراءة 0 و بعد البحث وجدت حل باستخدام ترانزستور كمفتاح اغلاق فعندما بحصل الحساس على القراءة 0 أقوم بإغلاق الطاقة عنه عن طريق الترانزستور و فتحها من جديد ليعود الحساس للعمل بشكل صحيح . بهذه الطريقة تمكنت من رفع قدرة الحساس ليكون أدق حتى مستوى الميليمتر
شرح خوارزمية البرمجة
إذا حاولت بالطريقة التقليدية تحريك محركين باستخدام الأرديونو فأنه لن بتحرك المحرك الثاني إلا عند أكتمال حركة الأول و هذا ما لا نريده لأن حركة الروبوت تعتمد على حركة عدة محركات على التوازي فقمت بإنشاء غرض برمجي أمرر إليه المحركات على شكل خصائص و و كل محرك يحوي زاوية الوجهة المطلوبة و بعد ذلك اعطي الأمر للغرض بانشاء حركة فيقوم الغرض بتدوير المحركات بمقدار درجة واحدة لكل محرك و بسرعة أحددها له عن طريق متغير و عندما بصل أي محرك إلة زاوية الدوران المطلوبة بتوقف و تستمر باقي المحركات بالدوران حتى تنتهي كلها فيقوم الغرض بتحرير المترجم لتنفيذ باقي التعليمات
تعريف محرك:
spiderServo servobackleftC(ID,Revers,Pin);
إصلاح قيم دوران المحرك:
servobackleftC.fixValue=int value;
محركات السيرفو sg90 هي محركات ذات جودة متدنية نسبيا و لكنها رخيصة لذلك قمت بإنشاء خاصية للإصلاح دورانها و ذلك بزيادة درجة البدء بعدد طبيعي
تهيئة الأتصال مع المحرك:
servobackleftC.attachServo();
تحديد زاوية الدوران:
servobackleftB.newDegree=30;
servomidelleftB.newDegree=30;
servofrontleftB.newDegree=30;
servobackrightB.newDegree=30;
servomidelrightB.newDegree=30;
servofrontrightB.newDegree=30;
لتحديد زاوية الوجهة بزاوية 0 حتى 180 و هذه التعليمة لا تجعل المحرك يدور و يتم ذلك بالتعليمة التالية
تحريك المحرك:
spiderMove(speed);
هذه التعليمة ستجعل جميع المحركات ذات الزواية المنشئة سابقا تتحرك على التوازي
ملف Spider.ino :
/*
spiderServo.ino - controlling spider robot servo motors
*/
#include <spiderRobot.h>
#include <SoftwareSerial.h>
SoftwareSerial BTserial(0, 1);
char RecivedData;
#define trigPin 3 /* Arduino pin tied to trigger pin on the ultrasonic sensor.*/
#define echoPin 4 /* Arduino pin tied to echo pin on the ultrasonic sensor.*/
int Ultraswitchpin=5; /*Ultrasonic switch bin 255 off and 0 is on*/
int distance;
int duration;
/* declare servos*/
spiderServo servobackleftC(0,180,27);
spiderServo servobackleftB(1,0,25);
spiderServo servobackleftA(2,0,23);
spiderServo servomidelleftC(3,0,22);
spiderServo servomidelleftB(4,180,24);
spiderServo servomidelleftA(5,0,26);
spiderServo servofrontleftC(6,180,28);
spiderServo servofrontleftB(7,0,30);
spiderServo servofrontleftA(8,0,32);
spiderServo servoUltraSonic(9,180,34);
spiderServo servofrontrightA(10,180,36);
spiderServo servofrontrightB(11,180,38);
spiderServo servofrontrightC(12,0,40);
spiderServo servomidelrightA(13,180,42);
spiderServo servomidelrightB(14,0,44);
spiderServo servomidelrightC(15,180,46);
spiderServo servobackrightA(16,180,48);
spiderServo servobackrightB(17,180,50);
spiderServo servobackrightC(18,0,52);
spiderServo spiderservos[19];
/* end declar servos*/
int spee=5;
void setup() {
pinMode(trigPin, OUTPUT); /* Sets the trigPin as an Output*/
pinMode(echoPin, INPUT); /* Sets the echoPin as an Input*/
pinMode(Ultraswitchpin,OUTPUT);
BTserial.begin(38400);
//set servos array
servomidelrightB.fixValue=-10;
spiderservos[0]=servobackleftC;
spiderservos[1]=servobackleftB;
spiderservos[2]=servobackleftA;
spiderservos[3]=servomidelleftC;
spiderservos[4]=servomidelleftB;
spiderservos[5]=servomidelleftA;
spiderservos[6]=servofrontleftC;
spiderservos[7]=servofrontleftB;
spiderservos[8]=servofrontleftA;
spiderservos[9]=servoUltraSonic;
spiderservos[10]=servofrontrightA;
spiderservos[11]=servofrontrightB;
spiderservos[12]=servofrontrightC;
spiderservos[13]=servomidelrightA;
spiderservos[14]=servomidelrightB;
spiderservos[15]=servomidelrightC;
spiderservos[16]=servobackrightA;
spiderservos[17]=servobackrightB;
spiderservos[18]=servobackrightC;
/*end set servos array*/
Serial.begin(9600);
/*delay(1000);*/
servobackleftC.attachServo();
servomidelleftC.attachServo();
servofrontleftC.attachServo();
servobackrightC.attachServo();
servomidelrightC.attachServo();
servofrontrightC.attachServo();
servobackleftC.newDegree=120;
servomidelleftC.newDegree=120;
servofrontleftC.newDegree=120;
servobackrightC.newDegree=120;
servomidelrightC.newDegree=120;
servofrontrightC.newDegree=120;
spiderMove(spee);
servobackleftB.attachServo();
servomidelleftB.attachServo();
servofrontleftB.attachServo();
servobackrightB.attachServo();
servomidelrightB.attachServo();
servofrontrightB.attachServo();
servobackleftB.newDegree=30;
servomidelleftB.newDegree=30;
servofrontleftB.newDegree=30;
servobackrightB.newDegree=30;
servomidelrightB.newDegree=30;
servofrontrightB.newDegree=30;
spiderMove(spee);
servoUltraSonic.attachServo();
servobackleftA.attachServo();
servomidelleftA.attachServo();
servofrontleftA.attachServo();
servobackrightA.attachServo();
servomidelrightA.attachServo();
servofrontrightA.attachServo();
servoUltraSonic.newDegree=90;
servobackleftA.newDegree=45;
servomidelleftA.newDegree=90;
servofrontleftA.newDegree=90;
servobackrightA.newDegree=45;
servomidelrightA.newDegree=90;
servofrontrightA.newDegree=90;
spiderMove(spee);
servobackleftB.newDegree=60;
servomidelleftB.newDegree=60;
servofrontleftB.newDegree=60;
servobackrightB.newDegree=60;
servomidelrightB.newDegree=60;
servofrontrightB.newDegree=60;
spiderMove(spee);
servobackrightB.newDegree=40;
servobackrightC.newDegree=90;
spiderMove(spee);
servobackrightB.newDegree=75;
spiderMove(spee);
}
void loop() {
Ultrasonic();
if(distance>40)
{
servofrontleftA.newDegree=60;
servomidelrightA.newDegree=60;
servobackleftB.newDegree=90;
servobackleftC.newDegree=60;
servobackrightB.newDegree=40;
servobackrightC.newDegree=120;
servofrontrightB.newDegree=40;
servofrontrightA.newDegree=120;
servomidelleftB.newDegree=40;
servomidelleftA.newDegree=120;
spiderMove(spee);
servobackrightB.newDegree=60;
servofrontrightB.newDegree=60;
servomidelleftB.newDegree=60;
spiderMove(spee);
servofrontrightA.newDegree=60;
servomidelleftA.newDegree=60;
servobackrightB.newDegree=90;
servobackrightC.newDegree=60;
servobackleftB.newDegree=40;
servobackleftC.newDegree=120;
servofrontleftB.newDegree=40;
servofrontleftA.newDegree=120;
servomidelrightB.newDegree=40;
servomidelrightA.newDegree=120;
spiderMove(spee);
servobackleftB.newDegree=60;
servofrontleftB.newDegree=60;
servomidelrightB.newDegree=60;
spiderMove(spee);
}else{
if(distance>15){
servofrontleftA.newDegree=60;
servomidelrightA.newDegree=60;
servobackleftB.newDegree=90;
servobackleftC.newDegree=60;
servobackrightB.newDegree=40;
servobackrightC.newDegree=120;
servofrontrightB.newDegree=40;
servofrontrightA.newDegree=80;
servomidelleftB.newDegree=40;
servomidelleftA.newDegree=120;
spiderMove(spee);
servobackrightB.newDegree=60;
servofrontrightB.newDegree=60;
servomidelleftB.newDegree=60;
spiderMove(spee);
servofrontrightA.newDegree=60;
servomidelleftA.newDegree=60;
servobackrightB.newDegree=90;
servobackrightC.newDegree=60;
servobackleftB.newDegree=40;
servobackleftC.newDegree=120;
servofrontleftB.newDegree=40;
servofrontleftA.newDegree=120;
servomidelrightB.newDegree=40;
servomidelrightA.newDegree=80;
spiderMove(spee);
servobackleftB.newDegree=60;
servofrontleftB.newDegree=60;
servomidelrightB.newDegree=60;
spiderMove(spee);
}
}
}
spiderServo *newspiderservos(){
spiderservos[0]=servobackleftC;
spiderservos[1]=servobackleftB;
spiderservos[2]=servobackleftA;
spiderservos[3]=servomidelleftC;
spiderservos[4]=servomidelleftB;
spiderservos[5]=servomidelleftA;
spiderservos[6]=servofrontleftC;
spiderservos[7]=servofrontleftB;
spiderservos[8]=servofrontleftA;
spiderservos[9]=servoUltraSonic;
spiderservos[10]=servofrontrightA;
spiderservos[11]=servofrontrightB;
spiderservos[12]=servofrontrightC;
spiderservos[13]=servomidelrightA;
spiderservos[14]=servomidelrightB;
spiderservos[15]=servomidelrightC;
spiderservos[16]=servobackrightA;
spiderservos[17]=servobackrightB;
spiderservos[18]=servobackrightC;
return(spiderservos);
}
/*move all servos that their destination is changed*/
void spiderMove(int Speed)
{
spiderservos[0]=servobackleftC;
spiderservos[1]=servobackleftB;
spiderservos[2]=servobackleftA;
spiderservos[3]=servomidelleftC;
spiderservos[4]=servomidelleftB;
spiderservos[5]=servomidelleftA;
spiderservos[6]=servofrontleftC;
spiderservos[7]=servofrontleftB;
spiderservos[8]=servofrontleftA;
spiderservos[9]=servoUltraSonic;
spiderservos[10]=servofrontrightA;
spiderservos[11]=servofrontrightB;
spiderservos[12]=servofrontrightC;
spiderservos[13]=servomidelrightA;
spiderservos[14]=servomidelrightB;
spiderservos[15]=servomidelrightC;
spiderservos[16]=servobackrightA;
spiderservos[17]=servobackrightB;
spiderservos[18]=servobackrightC;
bool checkmove=false;
/*check all servos assigned to move if they finished their moves*/
while(!checkmove)
{
checkmove=true;
for (int i = 0; i < 19; ++i)
{
if (spiderservos[i].newDegree!=spiderservos[i].currentDegree)
{
spiderservos[i].turn(Speed);
checkmove=false;
}
}
}
servobackleftC=spiderservos[0];
servobackleftB=spiderservos[1];
servobackleftA=spiderservos[2];
servomidelleftC=spiderservos[3];
servomidelleftB=spiderservos[4];
servomidelleftA=spiderservos[5];
servofrontleftC=spiderservos[6];
servofrontleftB=spiderservos[7];
servofrontleftA=spiderservos[8];
servoUltraSonic=spiderservos[9];
servofrontrightA=spiderservos[10];
servofrontrightB=spiderservos[11];
servofrontrightC=spiderservos[12];
servomidelrightA=spiderservos[13];
servomidelrightB=spiderservos[14];
servomidelrightC=spiderservos[15];
servobackrightA=spiderservos[16];
servobackrightB=spiderservos[17];
servobackrightC=spiderservos[18];
}
void Ultrasonic(){
if(distance==0){
analogWrite(Ultraswitchpin,255);
analogWrite(Ultraswitchpin,0);
}else{
/* Clears the trigPin*/
analogWrite(Ultraswitchpin,0);
}
analogWrite(Ultraswitchpin,255);
analogWrite(Ultraswitchpin,0);
duration = pulseIn(echoPin, HIGH);
/* Calculating the distance*/
distance= duration*0.034/2;
/* Prints the distance on the Serial Monitor*/
Serial.print("Distance: ");
Serial.println(distance);
}
ملف spiderRobot.cpp :
/*
spiderServo.cpp - Library for controlling spider robot servo motors
*/
#include "Arduino.h"
#include "spiderRobot.h"
/*spider servo class*/
spiderServo :: spiderServo(int id,int opendegree,int pin)
{
Id=id;
openDegree=opendegree;
Pin=pin;
currentDegree=90;
newDegree=90;
turnDone=true;
fixValue=0;
}
spiderServo::spiderServo()
{
currentDegree=90;
newDegree=90;
turnDone=true;
fixValue=0;
}
void spiderServo::attachServo(){
servo.attach(Pin);
currentDegree=90;
newDegree=90;
turnDone=true;
}
/* turn servo with sudtom speed from old degree to new one and make turn done true after finish*/
void spiderServo::turn(int servoSpeed){
if (newDegree!=currentDegree && turnDone)
{
startmovingMillis=millis();
}
unsigned long currentMillis = millis();
if(openDegree==180)
{
if(newDegree>currentDegree)
{
turnDone=false;
if (currentMillis - startmovingMillis >= servoSpeed){
currentDegree++;
servo.write(currentDegree+fixValue);
startmovingMillis=millis();
if (newDegree==currentDegree )
{
turnDone=true;
}
}
}else{
if(newDegree<currentDegree){
turnDone=false;
if (currentMillis - startmovingMillis >= servoSpeed){
currentDegree--;
servo.write(currentDegree+fixValue);
if (newDegree==currentDegree )
{
turnDone=true;
}
startmovingMillis=millis();
}
}
}
}else{
if(180-newDegree>180-currentDegree)
{
turnDone=false;
if (currentMillis - startmovingMillis >= servoSpeed){
currentDegree--;
servo.write(180-currentDegree+fixValue);
if (newDegree==currentDegree )
{
turnDone=true;
}
startmovingMillis=millis();
}
}else{
if(180-newDegree<180-currentDegree){
turnDone=false;
if (currentMillis - startmovingMillis >= servoSpeed){
currentDegree++;
servo.write(180-currentDegree+fixValue);
if (newDegree==currentDegree )
{
turnDone=true;
}
startmovingMillis=millis();
}
}
}
}
}
ملف spiderRobot.h :
/*
spiderRobot.h - Library for controling spider robot
servo motors
*/
#ifndef spiderRobot_h
#define spiderRobot_h
#include "Arduino.h"
#include <Servo.h>
class spiderServo{
public:
int Id,openDegree,Pin, currentDegree,newDegree,fixValue;
bool turnDone;
spiderServo(int,int,int);
spiderServo();
void turn(int );
void attachServo();
private:
Servo servo;
long startmovingMillis;
};
#endif
تحميل البرنامج على الروبوت:
قم بفتح المسار التالي على حاسبك بعد تنصيب الأرديونو أي دي أي من هنا
document/arduino/libraries/
و انسخ ملفي السي بي بي و الأتش هنا
document/arduino/libraries/spiderRobot/
بعدها قم بتشغيل ملف inoو حمل البرنامج على روبوتك
أسلوب التسمية:
لكل ساق للروبوت يوجد ثلاث محركات و قمت باستخدام الطريقة التالية لتسمية المتغيرات لهذه المحركات:
"servo"+leg position+servo position
روابط
متابعة المشروع على Githubمعلومات أكثر حول القطع الميكانيكية على Thingiverse
أضف تعليق