Delta Robot example

Dependencies:   BufferedSerial Eigen

Fork of TCPSocket_Example by mbed_example

Committer:
je310
Date:
Mon Oct 15 18:30:20 2018 +0000
Revision:
5:01e1e68309ae
Parent:
4:778bc352c47f
testing eigen;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
je310 4:778bc352c47f 1 #ifndef KINEMATICS_H
je310 4:778bc352c47f 2 #define KINEMATICS_H
je310 4:778bc352c47f 3 #include "odrive.h"
je310 4:778bc352c47f 4 #include "Axis.h"
je310 4:778bc352c47f 5 #include <math.h>
je310 4:778bc352c47f 6 #include "calibration.h"
je310 4:778bc352c47f 7 #include "comms.h"
je310 4:778bc352c47f 8 #include "DeltaKinematics.h"
je310 4:778bc352c47f 9
je310 4:778bc352c47f 10
je310 4:778bc352c47f 11
je310 4:778bc352c47f 12
je310 4:778bc352c47f 13
je310 4:778bc352c47f 14 // trigonometric constants
je310 4:778bc352c47f 15 const float sqrt3 = sqrt(3.0);
je310 4:778bc352c47f 16 const float pi = 3.141592653; // PI
je310 4:778bc352c47f 17 const float sin120 = sqrt3/2.0;
je310 4:778bc352c47f 18 const float cos120 = -0.5;
je310 4:778bc352c47f 19 const float tan60 = sqrt3;
je310 4:778bc352c47f 20 const float sin30 = 0.5;
je310 4:778bc352c47f 21 const float tan30 = 1/sqrt3;
je310 4:778bc352c47f 22
je310 4:778bc352c47f 23 class Kinematics
je310 4:778bc352c47f 24 {
je310 4:778bc352c47f 25 public:
je310 4:778bc352c47f 26 Kinematics(Axis* A_, Axis* B_, Axis* C_,calVals calibration_);
je310 4:778bc352c47f 27 int goToPos(float x, float y, float z);
je310 4:778bc352c47f 28 void goToAngles(float a, float b, float c);
je310 4:778bc352c47f 29 void goToPosVel(float x, float y, float z, float xv, float yv, float zv);
je310 4:778bc352c47f 30 void activateMotors();
je310 4:778bc352c47f 31 void homeMotors();
je310 5:01e1e68309ae 32 void findIndex();
je310 5:01e1e68309ae 33 void goIdle();
je310 4:778bc352c47f 34 void updateCalibration(calVals calibration_);
je310 5:01e1e68309ae 35 int setSafeParams();
je310 5:01e1e68309ae 36 int setFastParams();
je310 4:778bc352c47f 37 DeltaKinematics<float>* DK;
je310 4:778bc352c47f 38
je310 4:778bc352c47f 39
je310 4:778bc352c47f 40 private:
je310 4:778bc352c47f 41 float e ; // end effector
je310 4:778bc352c47f 42 float f; // base
je310 4:778bc352c47f 43 float re;
je310 4:778bc352c47f 44 float rf;
je310 4:778bc352c47f 45 int delta_calcInverse(float x0, float y0, float z0, float &theta1, float &theta2, float &theta3);
je310 4:778bc352c47f 46 void delta_calcInverseDy(float x0, float y0, float z0, float vx0, float vy0, float vz0, float &theta1, float &theta2, float &theta3,float &vtheta1, float &vtheta2, float &vtheta3);
je310 4:778bc352c47f 47 int delta_calcForward(float theta1, float theta2, float theta3, float &x0, float &y0, float &z0);
je310 4:778bc352c47f 48 int delta_calcAngleYZ(float x0, float y0, float z0, float &theta);
je310 4:778bc352c47f 49 Axis* A;
je310 4:778bc352c47f 50 Axis* B;
je310 4:778bc352c47f 51 Axis* C;
je310 4:778bc352c47f 52
je310 4:778bc352c47f 53
je310 4:778bc352c47f 54 };
je310 4:778bc352c47f 55
je310 4:778bc352c47f 56
je310 4:778bc352c47f 57
je310 4:778bc352c47f 58
je310 4:778bc352c47f 59
je310 4:778bc352c47f 60
je310 4:778bc352c47f 61
je310 4:778bc352c47f 62
je310 4:778bc352c47f 63
je310 4:778bc352c47f 64 #endif // KINEMATICS_H