Spider robot with six feet and an ultrasonic sensor to detect if there is something in front of him so it will turn and try to not crash with that thing.
Robot parts
I used Arduino MEGA2560 R3 because it contains many IO ports but you can use any other Arduino board with an extending IC to extend the IO ports.
for each leg, we need 3 servo motors so we have: 3 X 6 = 18 Servo motors
I used one servo more for the ultrasonic sensor so it can turn left and right to get the destination in all directions. we need 7.4 v lipo battery with 2000 mah because of the power that the servos need and because the Arduino and the servo need only 5 v we need to use DC-DC converters one for the Arduino board and the second is for the servo motors and please don't connect the Arduino and the servo to the same DC-DC converter because servo motors take a lot of power that DC-DC converter provides.
I had a problem before with ultrasonic sensor which is, the ultrasonic sensor not always get the right reading and sometimes it gets distance 0 even it is not so after research I found a solution using the 2N3906 transistor which connected to the power leg of ultrasonic and what I made is, after 0 distance reading I use the transistor as a switch to close the power to the ultrasonic sensor and open it again so it will reset then it will try to read again. by this way, I could get distance by millimeters.
Code explanation
If you try to make two servo motors move 90 degree one by one using step speed then the second servo will start moving after the first finished its moves and what we need to create a movement for the robot is, to move many servos in the same time, I mean parallel moves. I created an object called Move which contains the servos, that need to be moved, with a degree value and speed for each of them then all servos will be moving together with one degree for each one and when any one of them reach the destination degree it will stop and wait for other servos to finish then when all servos finish their move the Move object will be done then we can make new move and so.
Servo declaration:
spiderServo servobackleftC(ID,Revers,Pin);
Fix Servo values:
servobackleftC.fixValue=int value;
Servo motors sg90 are not high-quality servos but they are cheap so maybe you need to fix the value for some of them
Attach Servo:
servobackleftC.attachServo();
This command will attach the servo motor
Set destination value:
servobackleftB.newDegree=30;
servomidelleftB.newDegree=30;
servofrontleftB.newDegree=30;
servobackrightB.newDegree=30;
servomidelrightB.newDegree=30;
servofrontrightB.newDegree=30;
Setting the new destination degree for the servos and this command will not make them move.It is just to set the new destinations value for many servos then in the next command they will move parallel
Moving Servos:
spiderMove(speed);
This command will make all last Servos move parallel and it takes parameter speed for example 5 so the speed will be one degree in 5 milliseconds
Spider.ino file:
/*
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 file:
/*
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 file:
/*
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
Software Setup:
You need to setup Arduino IDE first (Here) then you need to add spiderRobot.h and spiderRobot.cpp to Arduino library
document/arduino/libraries/
so it will be like this
document/arduino/libraries/spiderRobot/
inside the last path, it should be to files spiderRobot.h and spiderRobot.cpp and examples folder which contains spiderRobot.ino and you can use it to upload the code to your Arduino
Hardware Setup:
For each leg of the spider robot, there are three servos. in the code declaration I named each servo using this schema:
"servo"+leg position+servo position
Links
Follow the project on GithubMore details about 3d parts in Thingiverse
Add your comment