State machine
Dependencies: mbed Adafruit_GFX BioroboticsMotorControl MODSERIAL BioroboticsEMGFilter
Diff: forward_kinematics.h
- Revision:
- 22:720a410c4980
- Parent:
- 20:af1a6cd7469b
- Child:
- 50:5d2176b93a65
--- a/forward_kinematics.h Wed Oct 31 18:54:07 2018 +0000 +++ b/forward_kinematics.h Thu Nov 01 06:55:10 2018 +0000 @@ -38,7 +38,7 @@ float J2y_0 = J2x_2*sin(sec_angle) + J2y_2 * cos(sec_angle) + J1y_1; // Calculation of End-effector - float f_x = J2x_0 - J3x_0; + float f_x = J2x_0 - L6; float f_y = J2y_0; float f = sqrt(pow(f_x,2) + pow(f_y,2)); // Radius between motor 1 and Joint 2 float xhi = acos( -(pow(f,2) - pow(L3,2) - pow(L4,2))/(2*L3*L4) ); // Angle between L3 and L4