Source

ArduinoProjects / Experimental / MicroHorse / MicroHorse.ino

// Sweep
// by BARRAGAN <http://barraganstudio.com> 
// This example code is in the public domain.

#include <NewPing.h>
#include <Servo.h> 
#include <MathTypes.h>
#include <MathUtil.h>
#include <Animation.h>

#define DEBUG_RESET 0
#define DEBUG_PRINT 1
#define ALLOW_PING 1

const float obstacleDistanceInches = 36.0f;

float steeringValue = 0.0f;
const float calibrationAngle = -10.0f;
const float pingAngleMax = 65.0f;
const float maxTurnAngle = pingAngleMax;
float pingCurrAngle = -pingAngleMax;
int pingCurrIndex = 0;
const float pingEstimatedServoRotationSpeed = 200.0f; //deg per second
float pingAngleMoveTime = pingAngleMax/pingEstimatedServoRotationSpeed;

const int pingNumDistArrayEntries = 32;
float pingDistArray[pingNumDistArrayEntries];
float pingDistArrayAngles[pingNumDistArrayEntries];  //Should be fine since memory seems to not be an issue yet

const float updateAnimSPF = 1.0f/60.0f;
  
Animation* upperLegServoAnimFR;
Animation* upperLegServoAnimFL;
Animation* upperLegServoAnimBR;
Animation* upperLegServoAnimBL;
Animation* lowerLegServoAnimFR;
Animation* lowerLegServoAnimFL;
Animation* lowerLegServoAnimBR;
Animation* lowerLegServoAnimBL;
Animation* pingAnim;

const float movementMin = 0.0f;
const float movementMax = 1.0f;

//const float movementDistCheckMax = 40.0f;

float overallMovementR = 1.0f;
float overallMovementL = 1.0f;

float animSpeedMin = 2.0f;
float animSpeedMax = 4.0f;
float animSpeed = 3.0f;

const float backLegOffset = 0.8f;

const float rightSideOffset = 3.5f*0.45f;

//Ping
Servo servoPingSensor;
int ultrasonicMaxDistanceCM = 400;
int ultraSoundSignal = 3; // Ultrasound signal pin
NewPing* sonar;

float pingAnimVal;
const Animation::AnimMode pingAnimMode = Animation::AnimMode_PingPong;
const int pingAnimNumValues = 2;
Animation::KeyFrame pingAnimValues[pingAnimNumValues] = {{0.0f,-70},{0.75f,70}};

const Animation::AnimMode upperLegMode = Animation::AnimMode_Wrap;
const Animation::AnimMode lowerLegMode = Animation::AnimMode_Wrap;

//Top

//Front
const int numUpperLegAnimValuesF = 4;
Animation::KeyFrame upperLegAnimValuesF[numUpperLegAnimValuesF] = {{0.0f,20},{1.0f,-60},{2.1f,-20},{3.5f,20}};

//Back
const int numUpperLegAnimValuesB = 4;
Animation::KeyFrame upperLegAnimValuesB[numUpperLegAnimValuesB] = {{0.0f,30},{1.0f,-50},{2.1f,10},{3.5f,30}};


//Bottom

//Front
const int numLowerLegAnimValuesF = 5;
Animation::KeyFrame lowerLegAnimValuesF[numLowerLegAnimValuesF] = {{0.0f,-5},{0.9f,90},{1.25f,-20},{2.0f,0},{3.5f,-5}};


//Back
const int numLowerLegAnimValuesB = 5;
Animation::KeyFrame lowerLegAnimValuesB[numLowerLegAnimValuesB] = {{0.0f,15},{0.6f,90},{1.7f,-20},{2.0f,0},{3.5f,15}};


Servo servoUpperFR;
Servo servoUpperFL;
Servo servoUpperBR;
Servo servoUpperBL;

Servo servoLowerFR;
Servo servoLowerFL;
Servo servoLowerBR;
Servo servoLowerBL;

float lastTimeMillis = 0.0f;
void setup() 
{ 
#if DEBUG_PRINT
  Serial.begin(9600);
#endif

  for(int i=0; i<pingNumDistArrayEntries; ++i)
  {
    pingDistArray[i] = 0.0f;
    
    const float t = (float)i/(float)(pingNumDistArrayEntries-1);
    pingDistArrayAngles[i] = Lerp(-pingAngleMax,pingAngleMax,t);
   
#if DEBUG_PRINT
    Serial.print(i);
    Serial.print(": ");
    Serial.println(pingDistArrayAngles[i]);
#endif
  }

  sonar = new NewPing(ultraSoundSignal,ultraSoundSignal,ultrasonicMaxDistanceCM);
  
  //Create animations
  pingAnim = new Animation(pingAnimValues,pingAnimNumValues,pingAnimMode);
  
  //Left legs
  upperLegServoAnimFL = new Animation(upperLegAnimValuesF,numUpperLegAnimValuesF,upperLegMode);
  lowerLegServoAnimFL = new Animation(lowerLegAnimValuesF,numLowerLegAnimValuesF,lowerLegMode);
  upperLegServoAnimBL = new Animation(upperLegAnimValuesB,numUpperLegAnimValuesB,upperLegMode);
  lowerLegServoAnimBL = new Animation(lowerLegAnimValuesB,numLowerLegAnimValuesB,lowerLegMode);
  
  //Right legs
  upperLegServoAnimFR = new Animation(upperLegAnimValuesF,numUpperLegAnimValuesF,upperLegMode);
  lowerLegServoAnimFR = new Animation(lowerLegAnimValuesF,numLowerLegAnimValuesF,lowerLegMode);
  upperLegServoAnimBR = new Animation(upperLegAnimValuesB,numUpperLegAnimValuesB,upperLegMode);
  lowerLegServoAnimBR = new Animation(lowerLegAnimValuesB,numLowerLegAnimValuesB,lowerLegMode);

  //Right legs
  upperLegServoAnimFR->currT += rightSideOffset;
  lowerLegServoAnimFR->currT += rightSideOffset;
  upperLegServoAnimBR->currT += rightSideOffset;
  lowerLegServoAnimBR->currT += rightSideOffset;
  
  //Left legs
  upperLegServoAnimBL->currT += backLegOffset;
  lowerLegServoAnimBL->currT += backLegOffset;

  //Right legs
  upperLegServoAnimBR->currT += backLegOffset;
  lowerLegServoAnimBR->currT += backLegOffset;
  
  servoUpperFR.attach(4);
  servoUpperFL.attach(5);
  servoUpperBR.attach(6);
  servoUpperBL.attach(7);
  
  servoLowerFR.attach(8);
  servoLowerFL.attach(9);
  servoLowerBR.attach(10);
  servoLowerBL.attach(11);
  
  servoPingSensor.attach(12);
  
  //pinMode(ultraSoundSignal,OUTPUT);

  //Init time
  lastTimeMillis = millis();
} 

float animUpdateTimer = 0.0f;

void UpdatePing(float timeDelta)
{
  bool reachedEnd = false;
  
  //If we should be at the next angle, change to the next index and do a ping
  pingAngleMoveTime -= timeDelta;
  if(pingAngleMoveTime < 0.0f)
  {
    //Do a ping at the current angle
    const float distance = sonar->ping_in();
    
    pingDistArray[pingCurrIndex] = distance;
    
/*#if DEBUG_PRINT
    Serial.print("Angle: ");
    Serial.print(pingCurrAngle);
    Serial.print("Distance (inches): ");
    Serial.println(distance);
#endif*/
    
    const float lastAngle = pingCurrAngle;
    
    //Switch to next angle
    if(pingCurrIndex == pingNumDistArrayEntries-1)
    {
      reachedEnd = true;
      
      //Get next angle
      pingCurrAngle = -pingAngleMax;
    }
    else
    {
      //Increment index
      ++pingCurrIndex;
      
      //Get next angle
      pingCurrAngle = pingDistArrayAngles[pingCurrIndex];
    }

    //Set timer based on the amount of turning to do
    pingAngleMoveTime = abs(pingCurrAngle-lastAngle)/pingEstimatedServoRotationSpeed;
    
    //Write to servo
    servoPingSensor.write(-pingCurrAngle+calibrationAngle+90.0f);
    
    //Finished a scan so update movement!
    if(reachedEnd)
    {
      pingCurrIndex = 0;
      
      int bestNonObstacleCount = 0;
      int countIndexStart = 0;
      int currNonObstacleCount = 0;
      float desiredAngle = 0.0f;
      
      for(int i=0; i<pingNumDistArrayEntries; ++i)
      {
        //If we find an obstacle or we reach the end of the array...
        if(pingDistArray[i] < obstacleDistanceInches
          || i == (pingNumDistArrayEntries-1))
        { 
          //If this is the widest open area we've found
          //so far...
          if(currNonObstacleCount > bestNonObstacleCount)
          {
            //Save the best!
             bestNonObstacleCount = currNonObstacleCount;
             
             //Save the angle in the center of this hopefully huge open area
             const int desiredIndex = (countIndexStart+i)/2;
             desiredAngle = pingDistArrayAngles[desiredIndex];
          }
          
          //Set up for net run
          countIndexStart = i+1;        
          currNonObstacleCount = 0;
        }
        else
        {
          //No obstacles.  Yay!
          ++currNonObstacleCount;
        }
      }
      
#if DEBUG_PRINT
      Serial.print("Turn to this angle: ");
      Serial.print(desiredAngle);
      Serial.print(", Steering value: ");
      steeringValue = ClampF(desiredAngle/maxTurnAngle,-1.0f,1.0f);
      Serial.println(steeringValue);
#endif
  
      overallMovementL = steeringValue*0.5f+0.5f;
      overallMovementR = 1.0f-overallMovementL;
      
      const float moveDiff = 1.0f-abs(overallMovementL-overallMovementR);
      const float maxMove = MaxF(overallMovementL,overallMovementR);
      
      //animSpeed = Lerp(animSpeedMin,animSpeedMax,moveDiff);
      
      overallMovementL /= maxMove;
      overallMovementR /= maxMove;
    
      overallMovementL = Lerp(movementMin,movementMax,overallMovementL);
      overallMovementR = Lerp(movementMin,movementMax,overallMovementR);
  
/*#if DEBUG_PRINT
      Serial.print("Left: ");
      Serial.print(overallMovementL);
      Serial.print(", Right: ");
      Serial.print(overallMovementR);
      Serial.print(", Anim Speed: ");
      Serial.println(animSpeed);
#endif*/
    }
  }
}


void loop() 
{ 
  //Get current time in seconds
  const float currTimeMillis = millis();
  const float timeDelta = (currTimeMillis-lastTimeMillis)/1000.0f;
  lastTimeMillis = currTimeMillis;
  
#if ALLOW_PING
  UpdatePing(timeDelta);
#endif
  
  animUpdateTimer -= timeDelta;
  if(animUpdateTimer < 0.0f)
  {
    animUpdateTimer += updateAnimSPF;
    
    UpdateAnims(updateAnimSPF);
  }
} 

inline void UpdateAnims(float timeDelta)
{
  upperLegServoAnimFR->animSpeed = animSpeed;
  lowerLegServoAnimFR->animSpeed = animSpeed;
  upperLegServoAnimBR->animSpeed = animSpeed;
  lowerLegServoAnimBR->animSpeed = animSpeed;
  upperLegServoAnimFL->animSpeed = animSpeed;
  lowerLegServoAnimFL->animSpeed = animSpeed;
  upperLegServoAnimBL->animSpeed = animSpeed;
  lowerLegServoAnimBL->animSpeed = animSpeed; 
  
  //Update animations
  //Right legs
  upperLegServoAnimFR->Update(timeDelta); 
  lowerLegServoAnimFR->Update(timeDelta);
  upperLegServoAnimBR->Update(timeDelta); 
  lowerLegServoAnimBR->Update(timeDelta);
  
  //Left legs
  upperLegServoAnimFL->Update(timeDelta);
  lowerLegServoAnimFL->Update(timeDelta);
  upperLegServoAnimBL->Update(timeDelta);
  lowerLegServoAnimBL->Update(timeDelta);  
  
  float topFrontRightAnimVal =  upperLegServoAnimFR->CalcAnimVal();
  float topFrontLeftAnimVal = -upperLegServoAnimFL->CalcAnimVal();
  float topBackRightAnimVal =  upperLegServoAnimBR->CalcAnimVal();
  float topBackLeftAnimVal = -upperLegServoAnimBL->CalcAnimVal();
  
  float bottomFrontRightAnimVal =  lowerLegServoAnimFR->CalcAnimVal();
  float bottomFrontLeftAnimVal = -lowerLegServoAnimFL->CalcAnimVal();
  float bottomBackRightAnimVal =  lowerLegServoAnimBR->CalcAnimVal();
  float bottomBackLeftAnimVal = -lowerLegServoAnimBL->CalcAnimVal();
  
   //Right legs
  topFrontRightAnimVal *= overallMovementR;
  bottomFrontRightAnimVal *= overallMovementR;
  topBackRightAnimVal *= overallMovementR;
  bottomBackRightAnimVal *= overallMovementR;
  
  //Left legs
  topFrontLeftAnimVal *= overallMovementL;
  bottomFrontLeftAnimVal *= overallMovementL;
  topBackLeftAnimVal *= overallMovementL;
  bottomBackLeftAnimVal *= overallMovementL;
  
  //TODO: bake these into the animations at startup
  
  //Right legs
  topFrontRightAnimVal += 90.0f;
  bottomFrontRightAnimVal += 90.0f;
  topBackRightAnimVal += 90.0f;
  bottomBackRightAnimVal += 90.0f;
  
  //Left legs
  topFrontLeftAnimVal += 90.0f;
  bottomFrontLeftAnimVal += 90.0f;
  topBackLeftAnimVal += 90.0f;
  bottomBackLeftAnimVal += 90.0f;  
  
 #if !DEBUG_RESET
   //Set servo values from animations
  servoUpperFR.write(topFrontRightAnimVal);
  servoLowerFR.write(bottomFrontRightAnimVal);
  servoUpperBR.write(topBackRightAnimVal);
  servoLowerBR.write(bottomBackRightAnimVal);
  
  servoUpperFL.write(topFrontLeftAnimVal);
  servoLowerFL.write(bottomFrontLeftAnimVal);
  servoUpperBL.write(topBackLeftAnimVal);
  servoLowerBL.write(bottomBackLeftAnimVal);
 #endif
}
Tip: Filter by directory path e.g. /media app.js to search for public/media/app.js.
Tip: Use camelCasing e.g. ProjME to search for ProjectModifiedEvent.java.
Tip: Filter by extension type e.g. /repo .js to search for all .js files in the /repo directory.
Tip: Separate your search with spaces e.g. /ssh pom.xml to search for src/ssh/pom.xml.
Tip: Use ↑ and ↓ arrow keys to navigate and return to view the file.
Tip: You can also navigate files with Ctrl+j (next) and Ctrl+k (previous) and view the file with Ctrl+o.
Tip: You can also navigate files with Alt+j (next) and Alt+k (previous) and view the file with Alt+o.