Machine Learning Hopping Robot

Posted on 23/12/2018 by demej00
Steps completed / 2
Press to mark a step as
completed or click here to complete all
Components you will need
Select missing items to add them
to the cart or select all
Introduction

This project is about putting a two servo leg on a training carousel, putting a counterweight on it so that it can simulate movement in a low gravity environment, and then letting it learn to hop, crawl, scoot around in a circle. Quite interesting to watch it learn to move - always comes up with a novel way to propel itself.


I decided to take the two servo leg off my crawling robot and stick it on a carousel so that it could move around in a circle and endlessly try new random behaviors to see which movement would propel it the best. Most work was spent on building a simple carousel (I call it the horse trainer) which was built out of my usual materials: fishing pole sections, 3mm hobby plywood, epoxy, hotglue and bamboo cutting boards. Had to buy a slip ring (pretty cheap here in China) to power the servos and make an encoder wheel which is really a hatchet-job but functional for the time being.

Anyway, it works quite nicely, is endlessly entertaining and I never seem to get tired of watching it learn a new movement gait.

The encoder wheel is very crude and so I have commissioned someone to laser cut me one out of thin aluminum sheet for 15 bucks. The problem with the old wheel is that the slots are not even and there are not enough slots in the wheel (currently about 50) so that if I train the robot for 100 episodes, it may come up with 5 having the same maximum distance so my new wheel will have 80 very nicely and evenly cut slots. Looking forward to trying it out with the accurately spaced laser cut encoder wheel.

I simulate moon gravity by setting the counterweight so that the leg weighs about 6 and half grams (earth weight of leg is 40 grams). I noticed that when I set the weight of the leg to it's actual 40 grams and let it train on a smooth floor, it has developed a scooting gait like it is scooting around on it's bum. 

Here is my fantasy: build a four legged robot, hitch it a ride to the moon and toss it out on the surface and let it evolve it's own moon hopping gait. Give it a brain, perhaps one of those cool neuromorphic chips, a camera, an emotion chip to let it whoop and hollar and some solar cells for power. That would be really neat.

Where to go next: of course, I have to add another two servo leg to this one and see if it will teach itself to walk without predetermining any special setup criteria - just random selection.

 

 

New encoder wheel that should improve performance.


//Machine learnng hopping Robot using Simple Reinforcement Learning 
//by: jim demello


// Servo setup:  the servos must be oriented so that if the arm is rotating counter-clockwise to the left of the servo, then up is 0 degrees
//               and down is 180 degrees, for both servos. Then when the arm is in it's highest postion, servo 1 (the servo closest to the
//               body of the robot, will be at 0 degrees and servo 2 will be at 40 degrees.)
// Sonar:        the ultrasonic module should be placed facing the rear of the robot as it measures movement of the robot away from some
//               solid structure like a wall.
// TODO:         1. smooth servo arm movements (simultaneous moves) - done
//               2. lower servo starting positions - done
//               3. try using wheel encoder rather than ultrasonic module for greater precision and so that robot does not have to
//               measure distance from another object - done
// goal:         move between two arm positions that produce the greatest distance, without using arrays to store results.
// algorithm:    this is a positive reinforcement unsupervised learning algorithm
//               It chooses random servo positions for two arm positions - 
//               and then moves the arm from the first to the second position, gets distance from encoder wheel annd it keeps the arm positions that produce the greatest distance. 
//               Uses interrupt to keep count of encoder wheel clicks 

#include <Servo.h>
void interpolate2Servos(int,int,int,int,int,int);
int encoderValue=0; void count(void);
Servo servo1,servo2;
#ifdef __arm__
// should use uinstd.h to define sbrk but Due causes a conflict
extern "C" char* sbrk(int incr);
#else  // __ARM__
extern char *__brkval;
#endif  // __arm__
 
int freeMemory() {  // this routine reports on free ram space
  char top;
#ifdef __arm__
  return &top - reinterpret_cast<char*>(sbrk(0));
#elif defined(CORE_TEENSY) || (ARDUINO > 103 && ARDUINO != 151)
  return &top - __brkval;
#else  // __arm__
  return __brkval ? &top - __brkval : &top - __malloc_heap_start;
#endif  // __arm__
}

float distance;
float sonarTime;

int TRIGGER=7,ECHO=8; // sonar pins
   
//int state=0;
//int numberSuccesses = 0;

int episodes = 0;
  int spos1 = 0; // servo1 position
  int spos2 = 0; // servo2 position
  int spos3 = 0; // servo1 position
  int spos4 =0;  // servo2 position
  int spos1High =0; // servo1 highest position 
  int spos2High =0;
  int spos3High =0;
  int spos4High =0;
  int distanceHigh=0;
 
  float distDifference=0,distPrevious=0,distCurrent=0;
   
void setup (){ 
   Serial.begin(9600);
   attachInterrupt(digitalPinToInterrupt(2),count,FALLING); // set interrupt
   encoderValue=0;
  servo1.attach( 6, 600, 2400 );
  servo2.attach( 9, 600, 2400 );
  //myServo(servo1,0,1,8,1); //  set servos to zero position
  //delay(1000);
  //myServo(servo2,0,1,8,1);
  delay(100);
  interpolate2Servos(  1,90,2,90,20,10); // initial servo positions

  randomSeed(analogRead(0)); // get real random number seed
 
  //distPrevious = getDistance(); //get initial distance
  //Serial.println(distPrevious);
  delay(1000);
 // exit(0);  // exit here to just test sonar
  } // end setup
  

void doTraining() {  
  Serial.println("Do doTraining...");
  episodes = 50;  
  for (int episode=0;episode<episodes;episode++) // for N expisodes
  {
            spos1 = random(160); // get random servo positions
            spos2 = random(160);
            spos3 = random(160);
            spos4 = random(160);
        
            interpolate2Servos(  1,spos1,2,spos2,20,50); // set leg in first position, move to this position slowly
            encoderValue=0; // set encoder value to 0 after leg is in first position
            interpolate2Servos(  1,spos3,2,spos4,20,20); // move to second leg position, move faster
           
            Serial.print(" episode = ");Serial.print(episode);
            Serial.print(" spos1 = ");Serial.print(spos1);
            Serial.print(" spos2 = ");Serial.print(spos2);
            Serial.print(" spos3 = ");Serial.print(spos3);
            Serial.print(" spos4 = ");Serial.print(spos4);
            Serial.print(" distance = ");Serial.println(encoderValue);

             if ( encoderValue > distanceHigh) { // if current distancee is greater than highest then replace postions
               spos1High = spos1; // servo position 1
               spos2High = spos2; // servo position 2
               spos3High = spos3; // servo position 3
               spos4High = spos4; // servo position 4
               distanceHigh = encoderValue;
           
               }
         
}  // end each episode

    Serial.print("spos1High = ");Serial.println(spos1High);
    Serial.println(" ");
  
} // end doTraining

void doLearnedBehavior() {
     Serial.println("Do Learned behavior... ");
     myServo(servo1,0,1,8);
     myServo(servo2,0,1,8);
     delay(2000);
     
     for (int i=0;i<300;i++) {
       Serial.print(" spos1High= "); Serial.print(spos1High);
       Serial.print(" spos2High = ");Serial.print(spos2High);
       Serial.print(" spos3High = ");Serial.print(spos3High);
       Serial.print(" spos4High = ");Serial.println(spos4High);
     
  //     myServo(servo1,spos1High,1,7);
  //     myServo(servo2,spos2High,1,7);
       interpolate2Servos(  1,spos1High,2,spos2High,20,50);
       //delay(500);
  //     myServo(servo1,spos3High,1,7);
  //     myServo(servo2,spos4High,1,7);
       interpolate2Servos(  1,spos3High,2,spos4High,20,20);
  } // doLearned
  
} // end loop

void loop(){  // main loop reads success table and performs actions
   int freespace = freeMemory();  Serial.print("free memory= "); Serial.println(freespace);
   doTraining();     // trial and error training with distance reinforcement
   freespace = freeMemory();  Serial.print("free memory= "); Serial.println(freespace);
   
   doLearnedBehavior(); // do longest step 10 times to make robot crawl
   
   myServo(servo1,0,1,8); // park servos
   myServo(servo2,0,1,8);
 
   Serial.print("end program ");
   delay(2000);
   exit(0);  // quit program
    
} // end main loop

void myServo(Servo servo,int newAngle,int angleInc,int incDelay) {
  int curAngle = 0;
  curAngle = servo.read();
 
  if (curAngle < newAngle) {
   for(int angle=curAngle;angle < newAngle;angle += angleInc) {
         servo.write(angle);
         delay(incDelay);   }
   }
   else if (curAngle > newAngle) {
      for(int angle=curAngle;angle > newAngle;angle -= angleInc) {
          servo.write(angle);
          delay(incDelay);   }
   }
   } // end of myServo function

   
int servoRead(int servoNumber) {
  int servoCurrent;
  
  if (servoNumber== 1) {   servoCurrent = servo1.read(); }
  if (servoNumber== 2) {   servoCurrent = servo2.read(); }
  
  return servoCurrent;
}

void servoWrite(int servoNumber, int offset) {
                
   if (servoNumber==1) { servo1.write(offset);                  }
   if (servoNumber==2) { servo2.write(offset); }
 
}
   
   void interpolate2Servos(    int servo1,int servo1Position,
                               int servo2,int servo2Position,
                               int numberSteps,int timeDelay){
     int servo1Current,servo2Current;
        
     servo1Current = servoRead(servo1);
     servo2Current = servoRead(servo2);
         
            
     int cOffset = (servo1Position - servo1Current);  cOffset = abs(cOffset)/numberSteps;
     int dOffset = (servo2Position - servo2Current);  dOffset = abs(dOffset)/numberSteps; 
    
     int cOffsetTotal=0,dOffsetTotal=0;
    
     cOffsetTotal = servo1Current;
     dOffsetTotal = servo2Current;
     
      for (int x=0; x<numberSteps;x++) {
        if (servo1Position > servo1Current) { cOffsetTotal = cOffsetTotal + cOffset; }
        else                                { cOffsetTotal = cOffsetTotal - cOffset; }
        if (servo2Position > servo2Current) { dOffsetTotal = dOffsetTotal + dOffset; }
        else                                { dOffsetTotal = dOffsetTotal - dOffset; }
       
        if (servo1Position != servo1Current) servoWrite(servo1,cOffsetTotal);
        if (servo2Position != servo2Current) servoWrite(servo2,dOffsetTotal);
              
    //    Serial.print(" a and b Offset  "); Serial.print(aOffsetTotal);  Serial.print(" ");Serial.println( bOffsetTotal); delay(10);
        delay(timeDelay);
   }// end for
    //////////////////////////////////////
    // take care of modulo remainders //
    /////////////////////////////////////
      
        if (servo1Position != servo1Current) servoWrite(servo1,servo1Position);
        if (servo2Position != servo2Current) servoWrite(servo2,servo2Position);
     
     }
void count() // interrupt routine to count encoder values

{

encoderValue++;

}

LikedLike this to see more

Spread the word

Flag this post

Thanks for helping to keep our community civil!


Notify staff privately
It's Spam
This post is an advertisement, or vandalism. It is not useful or relevant to the current topic.

You flagged this as spam. Undo flag.Flag Post