Biorobotics / Robot-Software

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed Servo

Revision:
6:8ff9566c91e2
Parent:
5:0dd66c757f24
Child:
7:b77f2201b156
Child:
19:e1e18746d98d
--- a/help_functions/kinematics.h	Mon Oct 22 19:12:42 2018 +0000
+++ b/help_functions/kinematics.h	Mon Oct 22 19:13:37 2018 +0000
@@ -5,15 +5,11 @@
 double x01 = 0.0;
 double y01 = 0.2;
 
-double forwardkinematics_function(double q1, double q2) {
+void forwardkinematics_function(double q1, double q2) {
     // input are joint angles, output are x and y position of end effector
     
-    double x; // WE SHOULD MAKE x and y global. Discuss this!!
-    double y;
-    
     x = x01 - L1 * sin(q1) + L2 * cos(q1 + q2);
-    y = y01 + L1 * cos(q1) + L2 * sin(q1 + q2);
-    return x;    
+    y = y01 + L1 * cos(q1) + L2 * sin(q1 + q2);    
 }
 
 double inversekinematics_function(double q1, double q2, double reference) {