Control program for a four-legged 12 axis robot.

Dependencies:   CircularBuffer Servo Terminal mbed Radio

Revision:
6:0163f2737cc6
Parent:
5:475f67175510
Child:
7:aac5f901bd76
--- a/main.cpp	Sun Jan 13 02:59:48 2013 +0000
+++ b/main.cpp	Sun Jan 13 19:50:40 2013 +0000
@@ -3,39 +3,127 @@
 #include "Matrix.h"
 #include "CircularBuffer.h"
 #include "Radio.h"
-#include "commands.h"
+#include "Terminal.h"
 #include <cstring>
+#include <cmath>
 
+#define MAXSPEED 0.1f
+#define MAXTURN 1.0f
+#define STEPTIME 0.4f
 
+enum state_t
+{
+    walk,
+    step,
+    reset
+};
+
+enum legstate_t
+{
+    A,
+    B,
+    C,
+    D
+};
 
 CircularBuffer<float,16> dataLog;
-float radius, speed;
 RobotLeg legA(p26, p29, p30);
 RobotLeg legB(p13, p14, p15);
 RobotLeg legC(p12, p11, p8);
 RobotLeg legD(p23, p24, p25);
-Radio radio(p5, p6, p7, p17, p19, p20);
+Radio radio(p5, p6, p7, p19, p20, p17);
+Timer cycleTimer;
+state_t state;
+legstate_t legState;
+
+
+
+CmdHandler* log(Terminal* terminal, const char* input)
+{
+    int start = 0;
+    int end = 15;
+    char output[256];
+    
+    if (sscanf(input, "log %d %d", &start, &end) == 1)
+    {
+        // Print only one item
+        sprintf(output, "%4d: %f\n", start, dataLog[start]);
+        terminal->write(output);
+    }
+    else
+    {
+        // Print a range of items
+        for (int i = start; i <= end; i++)
+        {
+            sprintf(output, "%4d: %f\n", i, dataLog[i]);
+            terminal->write(output);
+        }
+    }  
+    
+    return NULL;
+}
+
+
+
+CmdHandler* read(Terminal* terminal, const char* input)
+{
+    char output[256];
+    uint32_t data;
+
+    data = radio.rx_controller;
+    sprintf(output, "%d%d%d%d%d%d%d%d %d%d%d%d%d%d%d%d %d%d%d%d%d%d%d%d %d%d%d%d%d%d%d%d : %4d %4d %4d %4d", 
+    (data>>31)&1, (data>>30)&1, (data>>29)&1, (data>>28)&1, (data>>27)&1, (data>>26)&1, (data>>25)&1, (data>>24)&1, 
+    (data>>23)&1, (data>>22)&1, (data>>21)&1, (data>>20)&1, (data>>19)&1, (data>>18)&1, (data>>17)&1, (data>>16)&1, 
+    (data>>15)&1, (data>>14)&1, (data>>13)&1, (data>>12)&1, (data>>11)&1, (data>>10)&1, (data>>9)&1, (data>>8)&1, 
+    (data>>7)&1, (data>>6)&1, (data>>5)&1, (data>>4)&1, (data>>3)&1, (data>>2)&1, (data>>1)&1, (data>>0)&1, 
+    (int8_t)((data>>24)&0xff), (int8_t)((data>>16)&0xff), (int8_t)((data>>8)&0xff), (int8_t)((data)&0xff));
+    terminal->write(output);
+
+    return NULL;
+}
+
+
+
+int deadzone(int input, int zone)
+{
+    if (input > zone) return input;
+    else if (input < -zone) return input;
+    else return 0;
+}
+
+
+
+void resetLegs()
+{
+    legA.reset(-0.5f);
+    legB.reset(0.0f);
+    legC.reset(0.5f);
+    legD.reset(1.0f);
+    cycleTimer.start();
+    state = reset;
+    legState = D;
+}
 
 
 
 int main()
 {
     Timer deltaTimer;
-    Timer cycleTimer;
-    float angle, arc;
+    float xaxis, yaxis, turnaxis, speed, angle;
     vector3 v;
     matrix4 T;
     matrix4 PA, QA;
     matrix4 PB, QB; 
     matrix4 PC, QC; 
-    matrix4 PD, QD; 
+    matrix4 PD, QD;
     Terminal terminal;
+    bool freeA, freeB, freeC, freeD;
     
     terminal.addCommand("log", &log);
-    terminal.addCommand("speed", &setspeed);
-    terminal.addCommand("radius", &setradius);
     terminal.addCommand("read", &read);
     
+    radio.reset();
+    
     // Set leg parameters
     legA.setDimensions(0.11f, 0.125f, -0.006f, 0.020f);
     legB.setDimensions(0.11f, 0.125f, -0.006f, 0.020f);
@@ -61,6 +149,12 @@
     legD.theta.calibrate(2000, 1000, 45.0f, -45.0f);
     legD.phi.calibrate(2000, 1000, 70.0f, -45.0f);
     legD.psi.calibrate(1000, 2000, 80.0f, -45.0f);
+    
+    // Initialize leg position deltas
+    legA.nDeltaPosition = vector3(0.0f, 0.01f, 0.0f);
+    legB.nDeltaPosition = vector3(0.0f, -0.01f, 0.0f);
+    legC.nDeltaPosition = vector3(0.0f, 0.01f, 0.0f);
+    legD.nDeltaPosition = vector3(0.0f, -0.01f, 0.0f);
 
     // Create matrices to change base from robot coordinates to leg coordinates
     QA.translate(vector3(0.1f, 0.1f, 0.0f));
@@ -76,17 +170,9 @@
     PD = QD.inverse();
 
     // Go to initial position
-    legA.reset(-0.5f);
-    legB.reset(0.0f);
-    legC.reset(0.5f);
-    legD.reset(1.0f);
-    
-    // Set radius and speed to go straight forward
-    radius = 0.0f; // meters
-    speed = 0.0f; // m/s
+    resetLegs();
     
     deltaTimer.start();
-    cycleTimer.start();
     
     /*
     // Dump debug info 
@@ -99,32 +185,110 @@
     
     while(true)
     {
-        // Get arc length of movement delta
-        arc = speed*deltaTimer.read();
-        dataLog.push(deltaTimer.read());
-        deltaTimer.reset();
-        
-        if (radius == 0)
-        {
-            angle = 0.0f;
-            v.x = 0.0f;
-            v.y = arc;
-            v.z = 0.0f;
-        }
-        else
+        switch (state)
         {
-            angle = -arc/radius;
-            v.x = radius*(1 - cos(-angle));
-            v.y = radius*sin(-angle);
-            v.z = 0.0f;
+        case walk:
+        case step:
+            // Read controller input
+            xaxis = 0.0078125f * deadzone((int8_t)((radio.rx_controller>>0)&0xff), 8); // Convert to +/-1.0f range
+            yaxis = -0.0078125f * deadzone((int8_t)((radio.rx_controller>>8)&0xff), 8);
+            turnaxis = -0.0078125f * deadzone((int8_t)((radio.rx_controller>>16)&0xff), 8);
+            
+            // Compute delta movement vector and delta angle
+            v.x = xaxis;
+            v.y = yaxis;
+            v.z = 0;
+            v = v * MAXSPEED * deltaTimer.read();
+            speed = sqrt(v.x*v.x + v.y*v.y);
+            angle = turnaxis * MAXTURN * deltaTimer.read();
+            dataLog.push(turnaxis);
+            deltaTimer.reset();
+            
+            // Compute movement transformation in robot coordinates
+            T.identity().rotateZ(angle).translate(v).inverse();
+            
+            // Update legs
+            freeA = legA.update(PA*T*QA);
+            freeB = legB.update(PB*T*QB);
+            freeC = legC.update(PC*T*QC);
+            freeD = legD.update(PD*T*QD);
+            
+            // Update state
+            switch (legState)
+            {
+            case A:
+                if (!freeB || !freeC || !freeD) resetLegs();
+                else if (!freeA || cycleTimer.read() > 0.055f / speed) // 0.055/speed is 1/4 the gait period (0.22m/speed/4)
+                {
+                    legA.reset(1.0f);
+                    legState = B;
+                }
+                break;
+            
+            case B:
+                if (!freeA || !freeC || !freeD) resetLegs();
+                else if (!freeB || cycleTimer.read() > 0.11f / speed)
+                {
+                    legB.reset(1.0f);
+                    legState = C;
+                }
+                break;
+            
+            case C:
+                if (!freeA || !freeB || !freeD) resetLegs();
+                else if (!freeC || cycleTimer.read() > 0.165f / speed)
+                {
+                    legC.reset(1.0f);
+                    legState = D;
+                }
+                break;
+            
+            case D:
+                if (!freeA || !freeB || !freeC) resetLegs();
+                else if (!freeD || cycleTimer.read() > 0.22f / speed)
+                {
+                    legD.reset(1.0f);
+                    legState = A;
+                    cycleTimer.reset();
+                }
+                break;
+            }
+            
+            break;
+            
+        case reset:
+            if (cycleTimer.read() < STEPTIME && legState != A)
+            {
+                legA.reset(-0.5f);
+                legState = A;
+            }
+            else if (cycleTimer.read() < STEPTIME * 2 && legState == A)
+            {
+                legB.reset(0.0f);
+                legState = B;
+            }
+            else if (cycleTimer.read() < STEPTIME * 3 && legState == B)
+            {
+                legC.reset(0.5f);
+                legState = C;
+            }
+            else if (cycleTimer.read() < STEPTIME * 4 && legState == C)
+            {
+                legD.reset(1.0f);
+                legState = D;
+            }
+            else if (cycleTimer.read() >= STEPTIME * 4 && legState == D)
+            {
+                state = walk;
+                legState = A;
+                cycleTimer.reset();
+            }
+            else
+            {
+                resetLegs();
+            }
+            
+            break;
         }
-        
-        // Compute movement transformation in robot coordinates
-        T.identity().rotateZ(angle).translate(v).inverse();
-    
-        legA.update(PA*T*QA);
-        legB.update(PB*T*QB);
-        legC.update(PC*T*QC);
-        legD.update(PD*T*QD);
     }
 }