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.
Leg.h
00001 /** 00002 @file Leg.h 00003 00004 @brief Header file containing member functions and variables 00005 00006 */ 00007 00008 #ifndef LEG_H 00009 #define LEG_H 00010 00011 #include "mbed.h" 00012 #include "Utils.h" 00013 00014 /** 00015 @brief mbed library for controlling a 3DOF robotic leg such as though found on the Lynxmotion MAH3-R Hexapod. 00016 @brief The library solves the inverse kinematic equations of the leg to position the foot at a 00017 @brief specified [X,Y,Z] cordinate. 00018 00019 @see http://www.lynxmotion.com/c-157-mah3-r.aspx 00020 00021 @brief Revision 0.1 00022 00023 @author Craig A. Evans 00024 @date May 2015 00025 * 00026 * Example: 00027 * @code 00028 00029 #include "mbed.h" 00030 #include "Leg.h" 00031 00032 Serial serial(USBTX,USBRX); 00033 Leg leg(p21,p22,p23); 00034 00035 int main() 00036 { 00037 serial.baud(115200); 00038 00039 leg.set_link_lengths(28.0,58.0,125.0); // set leg dimensions 00040 00041 Timer t; // timer for calculation (~80 us on LPC1768) 00042 t.start(); 00043 vector_t angles = leg.solve_inverse_kinematics(80.0,0.0,-100.0); // solve IK equations 00044 t.stop(); 00045 00046 serial.printf("\nSolution time = %f us\n",1e6*t.read()); 00047 00048 leg.move(angles); // update servo angles 00049 00050 while(1) { 00051 00052 } 00053 } 00054 00055 * @endcode 00056 */ 00057 00058 class Leg 00059 { 00060 00061 public: 00062 /** Create a Leg object connected to the specified pins. MUST be PWM-enabled pins. 00063 * 00064 * @param coxa_pin Signal line for the coxa servo 00065 * @param femur_pin Signal line for the femur servo 00066 * @param tibia_pin Signal line for the tibia servo 00067 * 00068 */ 00069 Leg(PinName coxa_pin, PinName femur_pin, PinName tibia_pin); 00070 00071 /** Solve inverse kinematic equations to get the required joint angles 00072 * The x-axis is defined as the common normal of the joints. 00073 * The coxa joint rotates about the z-axis. 00074 * The y-axis is defined by the right-hand rule. 00075 * @param x Distance away from body 00076 * @param y Distance in front/behind the hip 00077 * @param z Height of foot 00078 * @returns a vector containing the joint angles [coxa,femur,tibia] 00079 */ 00080 vector_t solve_inverse_kinematics(float x, float y, float z); 00081 00082 /** Set link lengths (in mm). 00083 * @param coxa_length Length of coxa 00084 * @param femur_length Length of femur 00085 * @param tibia_length Length of tibia 00086 */ 00087 void set_link_lengths(float coxa_length, float femur_length, float tibia_length); 00088 00089 /** Move servos to calculated angles 00090 * @param a vector containing the joint angles [coxa,femur,tibia] 00091 */ 00092 void move(vector_t angles); 00093 00094 private: 00095 00096 public: 00097 00098 00099 00100 private: // private variables 00101 // pins for servos 00102 PwmOut* coxa_servo; 00103 PwmOut* femur_servo; 00104 PwmOut* tibia_servo; 00105 //Serial* serial; // for comms 00106 00107 // link lengths 00108 float coxa_length_; 00109 float femur_length_; 00110 float tibia_length_; 00111 00112 }; 00113 00114 #endif
Generated on Wed Jul 13 2022 20:28:41 by 1.7.2