Sorfware for Lexy ( Hexapode )

Dependencies:   mbed BLE_API X_NUCLEO_IDB0XA1 MODSERIAL

LIB/Hexapod.h

Committer:
Essenceia
Date:
2016-08-20
Revision:
3:13bd725bd47b
Parent:
1:8bab9152933e

File content as of revision 3:13bd725bd47b:

#ifndef HEXAPOD_H
#define HEXAPOD_H
#include <math.h>
#include "Bezier.h"
#ifndef PI
#define PI 3.14159265
#endif
#define DEGTORAD 0.01745329251
#define RADTODEG 57.2957795131
#define MAX_SPEED 1.5
#define SS_DURATION 2.0
#define TURN_TOL 0.005
#define MAXITER 300
// position tolerance in cm
#define TOLERANCE 0.1
// angle to move things away from bounds by, in radians
#define ANGEPS 0.01

// in turning value per second
#define TURN_SLEW 0.8
#define SPEED_SLEW 0.4

using namespace std;

/* servo IDs:
 *           back
 *  06 10 08 ---- 07 09 11 
 *  12 16 14 ---- 13 15 17
 *  18 04 02 ---- 01 03 05
 *           front
 *
 * convert to index:
 *  (LEG 5) 17 16 15 ---- 06 07 08 (LEG 2)
 *  (LEG 4) 14 13 12 ---- 03 04 05 (LEG 1)
 *  (LEG 3) 11 10 09 ---- 00 01 02 (LEG 0)
 *
 * tibia, femur, coxa ---- coxa, femur, tibia
 *
 * limits (ignoring intersection with other limbs):
 *  coxa: 245 - 75
 *  femur: 250 - 55
 *  tibia: 215 - 40
 */

/* Coordinate system:
 *  Origin is bottom of main chassis, center horizontally
 *    Z OO==> Y
 *      ||
 *      \/ X
 */

enum Groups {GROUP_ALL, GROUP_TIBIA, GROUP_FEMUR, GROUP_COXA, 
            GROUP_RIGHT, GROUP_LEFT, 
            GROUP_FRONT, GROUP_MIDDLE, GROUP_BACK};

class hexapod
{
public:
    // both sets of angles are relative to leg root and leg angle
    float servoangle[18]; // in degrees, 0 to 300 or so (subject to more constraint)
    float angle[18]; // in radians, direction and offset corrected
    bool changed[18];
    // hexapod body
    float length[3]; // length of coxa, femur, tibia
    float femurangle, tibiaangle;
    float coxaangle; // rajout personnel en fonction de la configuration de lexy
    float angleub[3], anglelb[3]; // angle bounds
    float legpos[6][3]; // root of leg in xyz
    float legpos1[6][3]; // default resting position of leg
    float legang[6]; // root angle of leg

    // for walking
    float time, speed;
    float smoothspeed, fdf;
    float turning, smoothturning;
    float standheight;
    float sweepmodifier, speedmodifier, maxsweep;

    // for safestand
    float sstime;
    bool ssrunning;
    float ssx0[6], ssy0[6], ssz0[6]; // initial positions

    // dead-reckoning
    float dr_xpos, dr_ypos, dr_ang;

    bool debug;

    // for walking
    Bezier b_walk_up, b_walk_down;

    hexapod (bool debugflag = false);

    void safeStand ();
    void step (float dt);
    void setAngles ();
    void setServoAngles ();
    bool IKSolve (int leg, float *target);
    void FKSolve (int leg, float *angles, float *pos);
    void stand ();
    void sit ();

};
#endif