Biorobotics 7
/
Inverse_kinematic
Inverse kinematics
main.cpp@1:df3d7f71db4b, 2018-10-29 (annotated)
- Committer:
- MAHCSnijders
- Date:
- Mon Oct 29 14:59:34 2018 +0000
- Revision:
- 1:df3d7f71db4b
- Parent:
- 0:4a9c733c3b53
- Child:
- 2:8632e61cafc8
Killed bugs; Added delta angle
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
MAHCSnijders | 0:4a9c733c3b53 | 1 | #include "mbed.h" |
MAHCSnijders | 0:4a9c733c3b53 | 2 | #include "math.h" |
MAHCSnijders | 0:4a9c733c3b53 | 3 | #include "Matrix.h" |
MAHCSnijders | 0:4a9c733c3b53 | 4 | |
MAHCSnijders | 1:df3d7f71db4b | 5 | const float L0 = 0.15; // Length between two motors [meter] |
MAHCSnijders | 1:df3d7f71db4b | 6 | const float L1 = 0.10; // Length first beam from right motor2 [meter] |
MAHCSnijders | 1:df3d7f71db4b | 7 | const float L2 = 0.30; // Length second beam from right motor2 [meter] |
MAHCSnijders | 1:df3d7f71db4b | 8 | const float L3 = 0.15; // Length beam between L2 and L4 [meter] |
MAHCSnijders | 1:df3d7f71db4b | 9 | const float L4 = 0.30; // Length first beam from left motor1 [meter] |
MAHCSnijders | 1:df3d7f71db4b | 10 | const float L5 = 0.35; // Length from L3 to end-effector [meter] |
MAHCSnijders | 0:4a9c733c3b53 | 11 | const double PI = 3.14159265359; |
MAHCSnijders | 1:df3d7f71db4b | 12 | volatile float Pe_x; // x-coordinate of end-effector from frame 0 [meter] |
MAHCSnijders | 1:df3d7f71db4b | 13 | volatile float Pe_y; // y-coordinate of end-effector from frame 0 [meter] |
MAHCSnijders | 1:df3d7f71db4b | 14 | volatile static float des_motor_angle1; // Desired angle of motor 1 (left) based on kinematics [rad] |
MAHCSnijders | 1:df3d7f71db4b | 15 | volatile static float des_motor_angle2; // Desired angle of motor 2 (right) based on kinematics [rad] |
MAHCSnijders | 0:4a9c733c3b53 | 16 | |
MAHCSnijders | 1:df3d7f71db4b | 17 | Ticker kinematics_ticker; // Ticker function for inverse kinematics |
MAHCSnijders | 0:4a9c733c3b53 | 18 | |
MAHCSnijders | 0:4a9c733c3b53 | 19 | void InverseKinematics() |
MAHCSnijders | 0:4a9c733c3b53 | 20 | { |
MAHCSnijders | 0:4a9c733c3b53 | 21 | // Calculation of the position of joint 3 in frame 0 |
MAHCSnijders | 1:df3d7f71db4b | 22 | float n = sqrt(pow(Pe_x,2) + pow(Pe_y,2)); // Radius between origin frame 0 and endeffector [meter] |
MAHCSnijders | 0:4a9c733c3b53 | 23 | float omega = acos(-(pow(n,2) - pow(L4,2) - pow(L5,2))/(2*L4*L5)); // Angle between L4 and L5 [rad] |
MAHCSnijders | 0:4a9c733c3b53 | 24 | float q4 = PI - omega; // Angle of joint 3 between L3 and L4 |
MAHCSnijders | 1:df3d7f71db4b | 25 | float theta = atan(L5*sin(q4)/(L4 + L5*cos(q4))); // Angle between n and L4 |
MAHCSnijders | 0:4a9c733c3b53 | 26 | float lambda = PI - atan(abs(Pe_y/Pe_x)); // Entire angle between x-axis frame 0 and n |
MAHCSnijders | 1:df3d7f71db4b | 27 | float des_motor_angle1 = lambda - theta; |
MAHCSnijders | 1:df3d7f71db4b | 28 | float J3x_0 = L4*cos(des_motor_angle1); // x-coordinate of joint 3 in frame 0 |
MAHCSnijders | 1:df3d7f71db4b | 29 | float J3y_0 = L4*sin(des_motor_angle1); // y-coordinate of joint 3 in frame 0 |
MAHCSnijders | 0:4a9c733c3b53 | 30 | |
MAHCSnijders | 0:4a9c733c3b53 | 31 | // Calculation of the position of joint 2 in frame 0 |
MAHCSnijders | 0:4a9c733c3b53 | 32 | float S = abs(J3y_0 - Pe_y); // Distance between height endeffector and joint 3 |
MAHCSnijders | 0:4a9c733c3b53 | 33 | float kappa = asin(S/L5); // Angle of L5 |
MAHCSnijders | 0:4a9c733c3b53 | 34 | float J2x_0 = (L3+L5)*cos(kappa) + Pe_x; // x-coordinate of joint 2 in frame 0 |
MAHCSnijders | 0:4a9c733c3b53 | 35 | float J2y_0 = (L3+L5)*sin(kappa) + Pe_y; // y-coordinate of joint 2 in frame 0 |
MAHCSnijders | 0:4a9c733c3b53 | 36 | |
MAHCSnijders | 0:4a9c733c3b53 | 37 | // Calculation of the position of joint 1 in frame 0 |
MAHCSnijders | 0:4a9c733c3b53 | 38 | float J2x_1 = J2x_0 - L0; // x-coordinate of joint 2 in frame 1 |
MAHCSnijders | 0:4a9c733c3b53 | 39 | float J2y_1 = J2y_0; // y-coordinate of joint 2 in frame 1 |
MAHCSnijders | 1:df3d7f71db4b | 40 | float r = sqrt(pow(J2x_1,2) + pow(J2y_1,2)); // Radius between origin frame 1 and J2 |
MAHCSnijders | 1:df3d7f71db4b | 41 | float alfa = acos( -(pow(r,2) - pow(L1,2) - pow(L2,2))/(2*L1*L2) ); // Angle opposite of radius r |
MAHCSnijders | 0:4a9c733c3b53 | 42 | float q2 = PI - alfa; // Angle between L1 and L2 |
MAHCSnijders | 0:4a9c733c3b53 | 43 | |
MAHCSnijders | 0:4a9c733c3b53 | 44 | // Calculation of motor_angle2 |
MAHCSnijders | 0:4a9c733c3b53 | 45 | float beta = atan(L2*sin(q2)/(L1+L2*cos(q2))); // Angle between r and L1 |
MAHCSnijders | 1:df3d7f71db4b | 46 | float gamma = PI - atan(abs(J2y_1/J2x_1)); // Angle between r and x-axis |
MAHCSnijders | 0:4a9c733c3b53 | 47 | // check if gamma works! |
MAHCSnijders | 1:df3d7f71db4b | 48 | des_motor_angle2 = gamma - beta; |
MAHCSnijders | 1:df3d7f71db4b | 49 | float J1x_0 = L0 + L1*cos(des_motor_angle2); // x-coordinate of joint 1 in frame 0 |
MAHCSnijders | 1:df3d7f71db4b | 50 | float J1y_0 = L1*sin(des_motor_angle2); // y-coordinate of joint 1 in frame 0 |
MAHCSnijders | 0:4a9c733c3b53 | 51 | |
MAHCSnijders | 1:df3d7f71db4b | 52 | |
MAHCSnijders | 1:df3d7f71db4b | 53 | // Determining angle delta for safety |
MAHCSnijders | 1:df3d7f71db4b | 54 | float m = sqrt(pow((abs(J3x_0)+J1x_0),2) + pow((J3y_0 - J1y_0),2)); // Radius between Joint 1 and Joint 3 |
MAHCSnijders | 1:df3d7f71db4b | 55 | float delta = acos(- (pow(m,2) - pow(L2,2) - pow(L3,2))/(2*L2*L3)); // Angle between L2 and L3 |
MAHCSnijders | 1:df3d7f71db4b | 56 | |
MAHCSnijders | 0:4a9c733c3b53 | 57 | } |
MAHCSnijders | 0:4a9c733c3b53 | 58 | |
MAHCSnijders | 0:4a9c733c3b53 | 59 | |
MAHCSnijders | 0:4a9c733c3b53 | 60 | int main() |
MAHCSnijders | 0:4a9c733c3b53 | 61 | { |
MAHCSnijders | 1:df3d7f71db4b | 62 | kinematics_ticker.attach(InverseKinematics,0.5); |
MAHCSnijders | 0:4a9c733c3b53 | 63 | } |