Library to control a 3DOF robotic leg. Specify an [x,y,z] co-ordinate and the library will solve the inverse kinematic equations to calculate the required servo pulse widths to position the foot at the target location.

Dependencies:   Utils

Leg.h

Committer:
eencae
Date:
2015-05-25
Revision:
6:a91d18a26ba3
Parent:
5:1190596b8842

File content as of revision 6:a91d18a26ba3:

/**
@file Leg.h

@brief Header file containing member functions and variables

*/

#ifndef LEG_H
#define LEG_H

#include "mbed.h"
#include "Utils.h"

/**
@brief mbed library for controlling a 3DOF robotic leg such as though found on the Lynxmotion MAH3-R Hexapod.
@brief The library solves the inverse kinematic equations of the leg to position the foot at a
@brief specified [X,Y,Z] cordinate.

@see http://www.lynxmotion.com/c-157-mah3-r.aspx

@brief Revision 0.1

@author Craig A. Evans
@date   May 2015
 *
 * Example:
 * @code

#include "mbed.h"
#include "Leg.h"

Serial serial(USBTX,USBRX);
Leg leg(p21,p22,p23);

int main()
{
    serial.baud(115200);

    leg.set_link_lengths(28.0,58.0,125.0);  // set leg dimensions

    Timer t;  // timer for calculation (~80 us on LPC1768)
    t.start();
    vector_t angles = leg.solve_inverse_kinematics(80.0,0.0,-100.0);  // solve IK equations
    t.stop();

    serial.printf("\nSolution time = %f us\n",1e6*t.read());

    leg.move(angles);  // update servo angles

    while(1) {

    }
}

 * @endcode
 */

class Leg
{

public:
    /** Create a Leg object connected to the specified pins. MUST be PWM-enabled pins.
    *
    * @param coxa_pin Signal line for the coxa servo
    * @param femur_pin Signal line for the femur servo
    * @param tibia_pin Signal line for the tibia servo
    *
    */
    Leg(PinName coxa_pin, PinName femur_pin, PinName tibia_pin);

    /**  Solve inverse kinematic equations to get the required joint angles
    * The x-axis is defined as the common normal of the joints.
    * The coxa joint rotates about the z-axis.
    * The y-axis is defined by the right-hand rule.
    * @param x Distance away from body
    * @param y Distance in front/behind the hip
    * @param z Height of foot
    * @returns a vector containing the joint angles [coxa,femur,tibia]
    */
    vector_t solve_inverse_kinematics(float x, float y, float z);

    /**  Set link lengths (in mm).
    * @param coxa_length Length of coxa
    * @param femur_length Length of femur
    * @param tibia_length Length of tibia
    */
    void set_link_lengths(float coxa_length, float femur_length, float tibia_length);

    /**  Move servos to calculated angles
    * @param a vector containing the joint angles [coxa,femur,tibia]
    */
    void move(vector_t angles);

private:

public:



private:  // private variables
    // pins for servos
    PwmOut* coxa_servo;
    PwmOut* femur_servo;
    PwmOut* tibia_servo;
    //Serial* serial;  // for comms

    // link lengths
    float coxa_length_;
    float femur_length_;
    float tibia_length_;

};

#endif