Spiderroboter mit sechs Füße und einem Ultraschallsensor, um zu erkennen, ob sich etwas vor ihm befindet, so dass er sich dreht und nicht mit dem Ding zusammenstößt.
Robot parts
Ich benutzte Arduino MEGA2560 R3, weil es viele IO-Ports enthält, aber Sie können jedes andere Arduino-Board mit einem erweiterten IC verwenden, um die IO-Ports zu erweitern.
Für jedes Bein benötigen wir 3 Servomotoren, also haben wir: 3 x 6 = 18 Servomotoren
Ich habe ein Servo mehr für den Ultraschall-Sensor verwendet, so dass es nach links und rechts drehen kann, um das Ziel in alle Richtungen zu bekommen. wir brauchen 7,4 v lipo akku mit 2000 mah wegen der leistung, die die servos brauchen und weil der arduino und der servo nur 5 v benötigen wir müssen DC-DC-konverter einen für die arduino board und der zweite ist für die servomotoren und Bitte verbinden Sie den Arduino und den Servo nicht mit dem gleichen DC-DC-konverter, da Servomotoren viel Energie verbrauchen, die der DC-DC-konverter zur Verfügung stellt.
Ich hatte vorher ein Problem mit dem Ultraschallsensor, der Ultraschallsensor bekommt nicht immer den richtigen Wert und manchmal wird der Abstand 0, auch wenn es nicht so ist. Nach der Forschung fand ich eine Lösung mit dem 2N3906 Transistor, der mit dem Stromzweig von Ultraschall verbunden war Was ich gemacht habe, ist, nach 0 Abstand Lesung benutze ich den Transistor als Schalter, um die Stromversorgung des Ultraschallsensors zu schließen und es wieder zu öffnen, damit es zurückgesetzt wird, dann wird es versuchen, wieder zu arbeiten. auf diese Weise konnte ich die Entfernung um Millimeter erreichen.
Code Erklärung
Wenn Sie versuchen, zwei Servomotoren nacheinander um 90 Grad mit Schrittgeschwindigkeit zu bewegen, beginnt der zweite Servo sich zu bewegen, nachdem der erste seine Bewegungen beendet hat und wir eine Bewegung für den Roboter schaffen müssen, um viele Servos in demselben zu bewegen Zeit, ich meine parallele Bewegungen. Ich habe ein Objekt namens Move erstellt, das die Servos enthält, die bewegt werden müssen, mit einem Gradwert und einer Geschwindigkeit für jeden von ihnen, dann bewegen sich alle Servos zusammen mit einem Grad für jeden und wenn einer von ihnen den Zielgrad erreicht es wird anhalten und warten, bis andere Servos beendet sind. Wenn alle Servos ihre Bewegung beendet haben, wird das Move-Objekt ausgeführt, dann können wir neue Bewegungen machen und so weiter.
Servo deklaration:
spiderServo servobackleftC(ID,Revers,Pin);
Korrektur der Servowerte:
servobackleftC.fixValue=int value;
Servomotoren sg90 sind keine hochwertigen Servos, aber sie sind billig, also müssen Sie vielleicht den Wert für einige von ihnen Korrekturen
Servo anbauen:
servobackleftC.attachServo();
Zielwert einstellen:
servobackleftB.newDegree=30;
servomidelleftB.newDegree=30;
servofrontleftB.newDegree=30;
servobackrightB.newDegree=30;
servomidelrightB.newDegree=30;
servofrontrightB.newDegree=30;
Wenn Sie den neuen Zielgrad für die Servos und diesen Befehl einstellen, werden sie nicht bewegt. Es wird nur der neue Zielwert für viele Servos gesetzt, dann werden sie im nächsten Befehl parallel verschoben
Servos bewegen:
spiderMove(speed);
Dieser Befehl bewirkt, dass sich alle letzten Servos parallel bewegen und die Parametergeschwindigkeit beträgt, z. B. 5, sodass die Geschwindigkeit in 5 Millisekunden ein Grad beträgt
Spider.ino Datei:
/*
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 Datei:
/*
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 Datei:
/*
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
Softwareeinrichtung:
Sie müssen zunächst Arduino IDE einrichten (Hier), dann müssen Sie spiderRobot.h und spiderRobot.cpp zur Arduino-Bibliothek hinzufügen
document/arduino/libraries/
es wird so sein
document/arduino/libraries/spiderRobot/
Innerhalb des letzten Pfades sollte es zwei Dateien Spider Robot.h und Spider Robot.cpp und Examples Ordner enthalten, der spiderRobot.ino enthält und Sie können es verwenden, um den Code auf Ihr Arduino hochzuladen
Hardware-Setup:
Für jedes Bein des Spinnenroboters gibt es drei Servos. In der Code-Deklaration habe ich jedes Servo mit diesem Schema benannt:
"servo"+leg position+servo position
Links
Folgen Sie dem Projekt auf GithubMehr Details über 3D Teile in Thingiverse
Es gibt 1 Kommentar
Super
Sehr geehrter Herr Osman, mit viele Interesse hab ich deine Webseite gelesen, das war aber sehr schön geordnet, geeignet style und alles. Was empfähle ich, um deine Ideen in dieser Webseite zu alle in Europa zu erreichen, SIO und Google Ich hab deine Webseite erreicht durch Twitter Es wäre besser wenn durch Google search klappt Viele grüße False