-
Notifications
You must be signed in to change notification settings - Fork 1
/
codestraightline.cpp
4948 lines (4286 loc) · 448 KB
/
codestraightline.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
//****************************************INCLUDING***************************************************
#include <ctime>
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
#include <cmath>
#include <string.h>
#include <unistd.h>
#include <arpa/inet.h>
#include <sys/socket.h>
#include <pthread.h>
#include <signal.h>
#include <time.h>
#include <fstream>
#include <iostream>
#include "downscale4/one.h"
#include "downscale4/two.h"
#include "downscale4/three.h"
#include "downscale4/seven.h"
#include "downscale4/trans.h"
#include "downscale4/buttons.h"
#include "downscale4/charmsg.h"
#include "ros/ros.h"
#include "ros/time.h"
#include </home/robotory/eigen/Eigen/Dense>
#include </home/robotory/eigen/pseudoinverse.cpp>
#include <boost/bind.hpp>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include <gazebo/common/common.hh>
//#include "PowerPMACcontrol.h"
//#include "argParser.h"
//************************************GLOBAL DEFINITION**********************************************
#define pi 3.14159265359
#define g_acc 9.81
using namespace std;
//using namespace PowerPMACcontrol_ns;
using Eigen::MatrixXd;
//*************************************ARM CONFIGURATION**********************************************
//Joint offset [m]
#define d1 0.371
#define d3 0.547
#define d5 0.484
#define d7 0.323
//#define d7 0.52
//Arm offset [m] - Issac dynamics Eq
#define L1 0.371
#define L3 0.547
#define L5 0.484
#define L7 0.273
#define L2 0.547
#define L4 0.484
//#define L6 0.273
#define L6 0.323
//Center of mass for each joint, from local coordinate [m]
#define lg1 0.247
#define lg2 0.32328
#define lg3 0.24043
#define lg4 0.52448
#define lg5 0.21711
#define lg6 0.46621
#define lg7 0.15735
#define lge 0.02301
//Center of mass for each joint, from local coordinate (m)
double LL1=L1-lg1;
double LL3=L3-lg3;
double LL5=L5-lg5;
double LL7=L7-lg7;
double LL2=-L3+lg3;
double LL4=-L5+lg5;
double LL6=-L7+lg7;
//External force at EE
double fx, fy, fz, falp, fbet, fgam;
//Positive weigting matrix used to give priority to joints with higher torque capacity/better mechanical advantage
double K1, K2, K3, K4, K5, K6, K7;
//Gear ratio
#define kr1 1 //160
#define kr2 1 //160
#define kr3 1 //160
#define kr4 1 //160
#define kr5 1 //160
#define kr6 1 //160
#define kr7 1 //160
//Motor inertia
double im1=0.24*0.0001;
double im1zz=0.24*0.0001;
double im2=1.447*0.0001;
double im2zz=1.447*0.0001;
double im3=0.437*0.0001;
double im3zz=0.437*0.0001;
double im4=0.437*0.0001;
double im4zz=0.437*0.0001;
double im5=0.24*0.0001;
double im5zz=0.24*0.0001;
double im6=0.24*0.0001;
double im6zz=0.24*0.0001;
double im7=0.0303*0.0001;
double im7zz=0.0303*0.0001;
//inertia for dyn
double ia1xx=0.2558;
double ia1yy=0.1516;
double ia1zz=0.1804;
double ia1xy=0;
double ia1xz=0;
double ia1yz=0;
double ia2xx=0.2235;
double ia2yy=0.1796;
double ia2zz=0.0707;
double ia2xy=0;
double ia2xz=0;
double ia2yz=0.0041;
double ia3xx=0.1651;
double ia3yy=0.0868;
double ia3zz=0.1268;
double ia3xy=0;
double ia3xz=0;
double ia3yz=0;
double ia4xx=0.097;
double ia4yy=0.0768;
double ia4zz=0.03;
double ia4xy=0;
double ia4xz=0;
double ia4yz=-0.0025;
double ia5xx=0.0228;
double ia5yy=0.003;
double ia5zz=0.0151;
double ia5xy=0;
double ia5xz=0;
double ia5yz=0;
double ia6xx=0.0371;
double ia6yy=0.0288;
double ia6zz=0.0141;
double ia6xy=0;
double ia6xz=0;
double ia6yz=0;
double ia7xx=0.0001;
double ia7yy=0.0001;
double ia7zz=0.0001;
//double ia7xx=0.01;
//double ia7yy=0.01;
//double ia7zz=0.01;
double ia7xy=0;
double ia7xz=0;
double ia7yz=0;
//following modelling world file
double m1 = 23;
double m2 = 15;
double m3 = 24;
double m4 = 6.3;
double m5 = 6.74;
double m6 = 3.8;
//double m7 = 0.808; // 3.8 + eef
double m7 = 0.808; // 3.8 + eef
//------------------data save -------------------------------------------
FILE *pData;
//Joint mass (kg)
double m[7];
std::string sep = "\n----------------------------------------\n";
//***********************************MASTER DEVICE SUBCRIBER******************************************
double Output_data[16]; //4x4 homogeneous trans from master device - hd_callback_trans
double hd_rotation_matrix[9]; //3x3 rotation matrix coverted from Output_data - hd_callback_trans
double hd_current_xyz[3]; //current position
double hd_del_xyz[3]; //position errors
double hd_initial_xyz[3]; //init position
double robot_prev_xyz[3]; //previous position
double robot_del_xyz[3]; //Differential position
double robot_initial_xyz[3]; //Init EE position
double haptic_del_xyz[3];
int Buttons[2]; //Phantom omni button variables - hd_callback_buttons
int Inkwell=0; //Phantom omni Inkwell button - hd_callback_buttons
int button0_click_time = 0; //Buttons[0] clicked counting variable
int button1_click_time = 0;
double Euler_r, Euler_b, Euler_a;
double time_taken = 0.003;
MatrixXd robot_initial_rotation(3,3); //
MatrixXd robot_current_rotation(3,3); //
MatrixXd hd_del_rotation(3,3); //
MatrixXd hd_current_rotation(3,3); //
MatrixXd hd_initial_rotation(3,3); //
MatrixXd Euler_angle(3,3); //
MatrixXd Euler_x(3,3); //
MatrixXd Euler_y(3,3); //
MatrixXd Euler_z(3,3); //
char ReadKey;
//**************************************PMAC DEFINITION***********************************************
int motor[7]; //motor index
double Kt[7]; //motor torque constant (1/A)
double Nhd[7]; //Harmonic driver's gear ratio
double Icon[7]; //motor driver's continuous current (A)
double Kp[7], Kd[7]; //P gain for joint i
double T_limit[7]; //Torque limit (for safety)
double fric_amp_lim[7]; //Friction compensate current (A) limit +/-
//**************************************GLOBAL PARAMETERS*********************************************
//ROSE nodes description:
ros::Publisher pub_jointp; //joint position publisher node
ros::Publisher pub_jointt; //joint torque publisher node
ros::Subscriber hd_trans; //sub transformation matrix
ros::Subscriber hd_buttons; //sub phantom omni button
ros::Subscriber hd_char; //sub keyboard
ros::Subscriber sub_jointp; //joint position subcriber node
ros::Subscriber sub_jointv; //joint velocity subcriber node
ros::Subscriber sub_jointt; //joint torque subcriber node
double current_joint_states[7]; //current joint angles _ from msgCallbackP function
double current_joint_vel[7]; //current joint angles _ from msgCallbackP function
double cur_vel[7]; //current joint vel _ from msgCallbackv function
double cur_tau[7]; //current joint torque _ from msgCallbackT function
double robot_current_xyz[3];; //current pos - output of forward kinematics
double SI,SI_COM,SI_HIG,SI_LOW,SI_FIX; //Computed arm angles - redundancy
double q[7], q_pmac[7], th[7], q_pmac_update[7], dq_pmac_update[7]; //Imtermediate joint angles for a specific computational
const int N = 1000; //Number of Cartesian steps
double dt; //incremental step time
//********************************Eigen Matrices Definition***********************************
//Given
MatrixXd P_INIT(4,4); //Given init homogeneous transformation matrix
MatrixXd P_END(4,4); //Given end homogeneous transformation matrix
MatrixXd P_COM(4,4); //Given end homogeneous transformation matrix
//Temp matrices for Inverse Kinematics computation
MatrixXd W(3,1); //Wrist position relating to base
MatrixXd DZ(3,1); //[0; 0; 1] matrix
MatrixXd L_SW(3,1); //Wrist position relating to shoulder
MatrixXd D1(3,1); //D1 column matrix
MatrixXd KSW(3,3); //Skew symetric matrix of vector between wrist and shoulder
MatrixXd USW(3,1); //Unit vector of L_SW
MatrixXd R03dot(3,3); //Rotation matrix of the ref joint angles q1dot, q2dot
MatrixXd XS(3,3); //Shoulder constant matrix
MatrixXd YS(3,3); //
MatrixXd ZS(3,3); //
MatrixXd I(3,3); //Identity matrix
MatrixXd I7(7,7); //Identity matrix 7x7
MatrixXd R34(3,3); //Rotation matrix from joint 3 to joint 4
MatrixXd XW(3,3); //Wrist constant matrix
MatrixXd YW(3,3); //
MatrixXd ZW(3,3); //
//Temp matrices for stiffness control computation
MatrixXd desired_theta(7,1); //Desired joint positions
MatrixXd desired_dtheta(7,1); //Desired joint velocities
MatrixXd current_theta(7,1); //Current joint position
MatrixXd current_dtheta(7,1); //Current joint velocities
MatrixXd theta_err1(7,1); //Joint position error 1
MatrixXd theta_err2(7,1); //Joint position error 2
MatrixXd dtheta_err(7,1); //Joint velocity error
MatrixXd Jacob(6,7); //Jacobian matrix 6x7
MatrixXd DiffJacob(6,7); //Differentiate of Jacobian matrix 6x7
MatrixXd Trans_Jacob(7,6); //Jacobian transpose matrix 7x6
MatrixXd pinv_Jacob(7,6); //Jacobian pseudo inverse matrix 7x6 - unweighted pseudo inverse
MatrixXd Mpinv_Jacob(7,6); //Jacobian pseudo inverse matrix 7x6 - weighted pseudo inverse
MatrixXd Mpinv_Jacob_Prev(7,6); //Jacobian pseudo inverse matrix 7x6 - weighted pseudo inverse
MatrixXd pinv_Jacob_Prev(7,6); //Jacobian pseudo inverse matrix 7x6 - weighted pseudo inverse
MatrixXd Diff_Mpinv_Jacob(7,6); //Differentiate of Jacobian pseudo inverse matrix 7x6 - weighted pseudo inverse
MatrixXd Diff_pinv_Jacob(7,6); //Differentiate of Jacobian pseudo inverse matrix 7x6 - weighted pseudo inverse
MatrixXd Mass(7,7); //Mass matrix 7x7
MatrixXd Coriolis(7,1); //Coriolis and centrifugal matrix 7x1
MatrixXd Coriolis_k(7,1); //Coriolis and centrifugal matrix 7x1
MatrixXd Gravity(7,1); //Gravity compensate matrix 7x1
MatrixXd kd_matrix_7(7,7);
MatrixXd kp_matrix_7(7,7);
MatrixXd kd_matrix_6(6,6);
MatrixXd kp_matrix_6(6,6);
MatrixXd SCL_FACTOR(7,7);
MatrixXd K_prior(7,7); //Positive weigting matrix used to give priority to joints with higher torque capacity/better mechanical advantage
MatrixXd Kx(6,6); //cartesian stiffness diagonal matrix
MatrixXd KxVec(6,1); //stiffness diagonal vector
MatrixXd Ki(7,7); //joint stiffness matrix
MatrixXd Kmin(7,7); //minimum joint stiffness matrix under mapping Kc -> Ki
MatrixXd Knull(7,7); //Null space joint stiffness under mapping Kc -> Ki
MatrixXd K0(7,7); //weighting matrix (symmetric positive definite) under mapping Kc -> Ki
MatrixXd K0Vec(7,1); //weighting matrix diagonal vector
MatrixXd Dx(6,6); //cartesian damping diagonal matrix
MatrixXd DxVec(6,1); //damping diagonal vector
MatrixXd Di(7,7); //joint damping matrix
MatrixXd Tau_stif(7,1); //Torque computed from stiffness control
MatrixXd Friction_I(7,1); //Friction compensation torque
MatrixXd Gravity_T(7,1); //Gravity compensation torque
MatrixXd Tau_I(7,1); //Overall torque -> send to PMAC
MatrixXd Tau_I_prev(7,1); //Overall torque -> send to PMAC
MatrixXd Tau_e(7,1); //End point torque
MatrixXd Tau_null(7,1);
MatrixXd v7(6,1); //End point force
MatrixXd grad_cost(7,1); //Gradient of torque minimization cost function
MatrixXd dy1(7,1); //secondary velocities (null space) for static torque minimization at current state
MatrixXd dy2(7,1); //secondary velocities (null space) for dynamic torque minimization at current state
MatrixXd dy(7,1); //SUM of secondary velocities (null space) for both static & dynamic torque minimization at current state
MatrixXd dy1_prev(7,1); //secondary velocities (null space) for static torque minimization at previous state
MatrixXd dy2_prev(7,1); //secondary velocities (null space) for dynamic torque minimization at previous state
MatrixXd ddy1(7,1); //secondary acceleration (null space) for static torque minimization at current state
MatrixXd ddy2(7,1); //secondary acceleration (null space) for dynamic torque minimization at current state
MatrixXd ddy2_prev(7,1); //secondary acceleration (null space) for dynamic torque minimization at previous state
MatrixXd ddy(7,1); //SUM of secondary acceleration (null space) for both static & dynamic torque minimization at current state
double alpha1, alpha2; //weighting factors for minimizing the static torque term & dynamic torque term, respectively
MatrixXd e_Ndot(7,1);
MatrixXd phi_N(7,1);
MatrixXd dpd_prev(6,1);
MatrixXd ddy1_prev(7,1);
MatrixXd jointpos(6,1);
MatrixXd currentp(6,1);
MatrixXd currentdp(6,1);
MatrixXd pderror(6,1);
MatrixXd dpderror(6,1);
MatrixXd maxperror(3,1);
MatrixXd prevp(6,1);
MatrixXd a0(6,1); //cubic polynomial coefficient
MatrixXd a1(6,1); //cubic polynomial coefficient
MatrixXd a2(6,1); //cubic polynomial coefficient
MatrixXd a3(6,1); //cubic polynomial coefficient
MatrixXd p0(6,1); //Init pose
MatrixXd pe(6,1); //End pose
MatrixXd pd(6,1); //calculated desired cartesian pose for each step
MatrixXd pd_temp1(6,1);
MatrixXd pd_temp2(6,1);
MatrixXd pd_temp3(6,1);
MatrixXd pd_temp4(6,1);
MatrixXd pd_temp5(6,1);
MatrixXd pd_temp6(6,1);
MatrixXd pd_temp7(6,1);
MatrixXd pd_prev(6,1);
MatrixXd pd_offset(6,1);
MatrixXd stepsize(6,1);
MatrixXd dpd(6,1); //calculated desired cartesian velocity for each step
MatrixXd ddpd(6,1); //calculated desired cartesian acceleration for each step
MatrixXd qd(7,1); //calculated desired joint angle for each step
MatrixXd dqd(7,1); //calculated desired joint angular velocity for each step
MatrixXd ddqd(7,1); //calculated desired joint acceleration for each step
MatrixXd ddqd_prev(7,1); //calculated desired joint acceleration for each step
MatrixXd dqd_prev(7,1);
MatrixXd current_q(7,1);
MatrixXd prev_q(7,1);
MatrixXd current_dq(7,1);
MatrixXd prev_dq(7,1);
MatrixXd current_ddq(7,1);
MatrixXd I6(6,6);
double lamda, lamda0, singular_wt, singular_w;
MatrixXd Manipulability(6,6);
MatrixXd jactest(6,7);
MatrixXd dqdprev(7,1);
MatrixXd dqdupt(7,1);
MatrixXd qdprev(7,1);
MatrixXd qdupt(7,1);
MatrixXd drtorque(1,1);
double totaldrivingtorque=0;
double taunorm=0;
double sumtaunorm=0;
double velocitynorm=0;
double accelerationnorm=0;
double errornorm=0;
double maxerrornorm=0;
int trajec_option=0;
int firstrun=0;
double freq=0.001;
double timecounting=0;
double t0=0;
//Moving time
double T = 5; //[sec]
double p1[6], p2[6], p3[6], p4[6], pinit[6], pend[6], pdesired[6], dqdesired[7], dqdesired_prev[7], command_tau[7];
unsigned int runcount=0;
unsigned int savedata=0;
double eta1, eta2;
double Kb, damp_factor;
//**********************************************
//Trajectory parameters
double t_total; //total trajectory time
double t_acc; //time of acceleration and deceleration process
double N_portion; //proportion of non-acceleration time N>=2
double linear_disp; //Linear displacement
double angular_disp; //angular displacement
int plan_step; //Number of planning step
int count_step; //counting step
//Trapezoid velocity curve params - divided into 7 segments
//V1(t)=linear_a1*t^2+linear_b1*t+linear_c1
//V2(t)=linear_a2*t+linear_b2
//V3(t)=linear_a3*t^2+linear_b3*t+linear_c3
//V4(t)=vmax
//V5(t)=linear_a5*t^2+linear_b5*t+linear_c5
//V6(t)=linear_a6*t+linear_b6
//V7(t)=linear_a7*t^2+linear_b7*t+linear_c7
double linear_V1, linear_V2, linear_V3, linear_V4, linear_V5, linear_V6, linear_V7;
double linear_a1, linear_a2, linear_a3, linear_a4, linear_a5, linear_a6, linear_a7;
double linear_b1, linear_b2, linear_b3, linear_b4, linear_b5, linear_b6, linear_b7;
double linear_c1, linear_c2, linear_c3, linear_c4, linear_c5, linear_c6, linear_c7;
double linear_vmax;
double angular_V1, angular_V2, angular_V3, angular_V4, angular_V5, angular_V6, angular_V7;
double angular_a1, angular_a2, angular_a3, angular_a4, angular_a5, angular_a6, angular_a7;
double angular_b1, angular_b2, angular_b3, angular_b4, angular_b5, angular_b6, angular_b7;
double angular_c1, angular_c2, angular_c3, angular_c4, angular_c5, angular_c6, angular_c7;
double angular_vmax;
double linear_dir_vec[3];
double angular_dir_vec[3];
//*************************************SUB PROGRAMS DEFINITION*****************************************
MatrixXd rotx(double angle); //3x3 rotx about angle
MatrixXd roty(double angle); //3x3 roty about angle
MatrixXd rotz(double angle); //3x3 rotz about angle
void delay_ms(int count);
int sgn(double x);
void hd_callback_trans(const downscale4::trans::ConstPtr& msg); //callback transformation matrix from master device
void hd_callback_buttons(const downscale4::buttons::ConstPtr& msga); //callback buttons from master device
void hd_callback_keyboards(const downscale4::charmsg::ConstPtr& msga); //callback from keyboard node
void msgCallbackP(const downscale4::seven::ConstPtr& msg); //callback joint angle from Gazebo
void msgCallbackT(const downscale4::seven::ConstPtr& msg); //callback joint torque from Gazebo
void msgCallbackv(const downscale4::seven::ConstPtr& msg); //callback joint angular velocity from Gazebo
void joint_publish(double theta[7]); //joint angle publishing to Gazebo
void jointt_publish(double tau[7]); //joint torque publishing to Gazebo
void InvK7_1(double pdata[6], double si); //inverse kinematics function
void InvK7_0(const Eigen::MatrixXd &data, double si);
MatrixXd forwd7(double qdata[7]); //forward kinematics function
MatrixXd Mass_Matrix(double q[7]); //inertia matrix computation
MatrixXd Gravity_Matrix(double q[7]); //gravity compensate matrix computation
MatrixXd Coriolis_Matrix(double q[7], double dq[7]); //coriolis & centrifugal matrix computation
MatrixXd Jacobian_Matrix(double q[7]); //jacobian matrix computation
MatrixXd DiffJacobian_Matrix(double q[7], double dq[7]); //jacobian derivative computation
MatrixXd TorqueOptCase1(double q[7]); //Torque minimization gradient of cost function computation CASE1 - Both Gravity & EE load
MatrixXd TorqueOptCase2(double q[7]); //Torque minimization gradient of cost function computation CASE2 - Gravity only
MatrixXd TorqueOptCase3(double q[7]); //Torque minimization gradient of cost function computation CASE3 - EE load only
MatrixXd TorqueOptCase4(double q[7]); //Torque minimization gradient of cost function computation proposed
void DataSave(unsigned int count);
void inversedynamics_torqueopt();
void inversedynamics_torqueopt1();
void inversedynamics_torqueopt2();
void cartesianstepcomputing();
//************************************SUB PROGRAMS DESCRIPTION****************************************
void DataSave(unsigned int count)
{
pData = fopen("MKE.txt","a+");
fprintf(pData,"%i", count);
//fprintf(pData,"%f", timer);ㄴ
//fprintf(pData," %f ", SI_FIX);
//EE Desired Position
fprintf(pData," %f ", pd(0,0)); //x
fprintf(pData," %f ", pd(1,0)); //y
fprintf(pData," %f ", pd(2,0)); //z
//EE Real Position
fprintf(pData," %f ", jointpos(0,0)); //x
fprintf(pData," %f ", jointpos(1,0)); //y
fprintf(pData," %f ", jointpos(2,0)); //z
//EE xyz tracking error
fprintf(pData," %f ", pderror(0,0)); //x
fprintf(pData," %f ", pderror(1,0)); //y
fprintf(pData," %f ", pderror(2,0)); //z
//Joint angle
fprintf(pData," %f ", current_joint_states[0]);
fprintf(pData," %f ", current_joint_states[1]);
fprintf(pData," %f ", current_joint_states[2]);
fprintf(pData," %f ", current_joint_states[3]);
fprintf(pData," %f ", current_joint_states[4]);
fprintf(pData," %f ", current_joint_states[5]);
fprintf(pData," %f ", current_joint_states[6]);
//Joint torque
fprintf(pData," %f ", Tau_I(0,0));
fprintf(pData," %f ", Tau_I(1,0));
fprintf(pData," %f ", Tau_I(2,0));
fprintf(pData," %f ", Tau_I(3,0));
fprintf(pData," %f ", Tau_I(4,0));
fprintf(pData," %f ", Tau_I(5,0));
fprintf(pData," %f ", Tau_I(6,0));
//Norm of dynamic torque
fprintf(pData," %f ", taunorm);
//SUM of Norm of dynamic torque
fprintf(pData," %f ", sumtaunorm);
//SUM TORQUE DURING TRAJECTORY (integral)
fprintf(pData," %f ", drtorque(0,0));
//EE xyz maximum tracking error
fprintf(pData," %f ", maxperror(0,0)); //x
fprintf(pData," %f ", maxperror(1,0)); //y
fprintf(pData," %f ", maxperror(2,0)); //z
//xyz tracking error norm
fprintf(pData," %f ", errornorm); //x
fprintf(pData," %f ", maxerrornorm); //y
//Velocity norm acc norm
fprintf(pData," %f ", velocitynorm); //x
fprintf(pData," %f ", accelerationnorm); //y
/*
fprintf(pData," %f ", Tau_I(0,0));
fprintf(pData," %f ", Tau_I(1,0));
fprintf(pData," %f ", Tau_I(2,0));
fprintf(pData," %f ", Tau_I(3,0));
fprintf(pData," %f ", Tau_I(4,0));
fprintf(pData," %f ", Tau_I(5,0));
fprintf(pData," %f ", Tau_I(6,0));
fprintf(pData," %f ", ddqd(0,0));
fprintf(pData," %f ", ddqd(1,0));
fprintf(pData," %f ", ddqd(2,0));
fprintf(pData," %f ", ddqd(3,0));
fprintf(pData," %f ", ddqd(4,0));
fprintf(pData," %f ", ddqd(5,0));
fprintf(pData," %f ", ddqd(6,0));
fprintf(pData," %f ", current_joint_states[0]);
fprintf(pData," %f ", current_joint_states[1]);
fprintf(pData," %f ", current_joint_states[2]);
fprintf(pData," %f ", current_joint_states[3]);
fprintf(pData," %f ", current_joint_states[4]);
fprintf(pData," %f ", current_joint_states[5]);
fprintf(pData," %f ", current_joint_states[6]);
fprintf(pData," %f ", drtorque(0,0));
*/
//fprintf(pData," %f ", z_c);
/*
fprintf(pData," %f ", x_c);
fprintf(pData," %f ", y_c);
fprintf(pData," %f ", z_c);
fprintf(pData," %f ", posX); //desired x
fprintf(pData," %f ", posY);//desired y
fprintf(pData," %f ", posZ);//desired z
fprintf(pData, "%f ", force_X);
fprintf(pData," %f ", force_Y);
fprintf(pData," %f ", force_Z);
*/
fprintf(pData,"\n");
fclose(pData);
}
//***************************************Delay ms function********************************************
void delay_ms(int count)
{
int i,j;
for (i=0; i<count; i++)
{
for (j=0; j<1000; j++)
{
}
}
}
//****************************************sign function***********************************************
int sgn(double x)
{
if (x > 0) return 1;
if (x < 0) return -1;
if (x == 0) return 0;
}
//*****************************Call Back Trans matrix from Master device*******************************
void hd_callback_trans(const downscale4::trans::ConstPtr& msg) {
Output_data[0] = msg->a;
Output_data[1] = msg->b;
Output_data[2] = msg->c;
Output_data[3] = msg->d;
Output_data[4] = msg->e;
Output_data[5] = msg->f;
Output_data[6] = msg->g;
Output_data[7] = msg->h;
Output_data[8] = msg->i;
Output_data[9] = msg->j;
Output_data[10] = msg->k;
Output_data[11] = msg->l;
Output_data[12] = msg->m;
Output_data[13] = msg->n;
Output_data[14] = msg->o;
Output_data[15] = msg->p;
hd_rotation_matrix[0] = -Output_data[2];
hd_rotation_matrix[1] = -Output_data[0];
hd_rotation_matrix[2] = Output_data[1];
hd_rotation_matrix[3] = -Output_data[6];
hd_rotation_matrix[4] = -Output_data[4];
hd_rotation_matrix[5] = Output_data[5];
hd_rotation_matrix[6] = -Output_data[10];
hd_rotation_matrix[7] = -Output_data[8];
hd_rotation_matrix[8] = Output_data[9];
hd_current_xyz[0] = Output_data[12];
hd_current_xyz[1] = Output_data[13];
hd_current_xyz[2] = Output_data[14];
}
//********************************Call Back Buttons from Master device*******************************
void hd_callback_buttons(const downscale4::buttons::ConstPtr& msga) {
Buttons[0] = msga->a;
Buttons[1] = msga->b;
Inkwell = msga->c;
//std::cout << std::string(80, '-') << std::endl;
}
//**************************************Call Back keyboard********************************************
void hd_callback_keyboards(const downscale4::charmsg::ConstPtr& msga) {
ReadKey = msga->a;
//printf(" %c \n",ReadKey);
}
//**********************************Call Back Joint Position******************************************
void msgCallbackP(const downscale4::seven::ConstPtr& msg)
{
current_joint_states[0] = msg->a;
current_joint_states[1] = msg->b;
current_joint_states[2] = msg->c;
current_joint_states[3] = msg->d;
current_joint_states[4] = msg->e;
current_joint_states[5] = msg->f;
current_joint_states[6] = msg->g;
}
//***********************************Call Back Joint Torque*******************************************
void msgCallbackT(const downscale4::seven::ConstPtr& msg)
{
cur_tau[0] = msg->a;
cur_tau[1] = msg->b;
cur_tau[2] = msg->c;
cur_tau[3] = msg->d;
cur_tau[4] = msg->e;
cur_tau[5] = msg->f;
cur_tau[6] = msg->g;
}
//*********************************Call Back Joint Velocities*****************************************
void msgCallbackv(const downscale4::seven::ConstPtr& msg)
{
cur_vel[0] = msg->a;
cur_vel[1] = msg->b;
cur_vel[2] = msg->c;
cur_vel[3] = msg->d;
cur_vel[4] = msg->e;
cur_vel[5] = msg->f;
cur_vel[6] = msg->g;
}
//**********************************Joint position publisher******************************************
void joint_publish(double theta[7])
{
downscale4::seven msgp;
msgp.a = theta[0];
msgp.b = theta[1];
msgp.c = theta[2];
msgp.d = theta[3];
msgp.e = theta[4];
msgp.f = theta[5];
msgp.g = theta[6];
pub_jointp.publish(msgp);
}
//************************************Joint torque publisher*******************************************
void jointt_publish(double tau[7])
{
downscale4::seven msgp;
msgp.a = tau[0];
msgp.b = tau[1];
msgp.c = tau[2];
msgp.d = tau[3];
msgp.e = tau[4];
msgp.f = tau[5];
msgp.g = tau[6];
pub_jointt.publish(msgp);
}
//*******************************Inverse Kinematics***************************************************
void InvK7_1(double pdata[6], double si)
{
/*
description
inverse kinemaitcs
input -> cartesian pose 6x1 vector (x,y,z,alpha,beta,gamma); primary arm angle si
output: joint angles 7x1 vector (q[0]->q[6])
*/
double q1dot, q2dot;
double norm_L_SW;
int GC2, GC4, GC6;
//Given homogeneous transformation matrix
MatrixXd Tinput(4,4);
MatrixXd Rinput(3,3);
MatrixXd T_rot_matrix(3,3);
MatrixXd T_angvel_matrix(3,3);
MatrixXd ROT_pos_d(3,1);
MatrixXd ROT_pos_d_2(3,1);
double alpha, beta, gamma;
//Assign cartesian pose into homogeneous transformation matrix Tinput
alpha = pdata[3];
beta = pdata[4];
gamma = pdata[5];
Rinput = rotz(gamma)*roty(beta)*rotx(alpha);
Tinput(0,0)=Rinput(0,0);
Tinput(1,0)=Rinput(1,0);
Tinput(2,0)=Rinput(2,0);
Tinput(3,0)=0;
Tinput(0,1)=Rinput(0,1);
Tinput(1,1)=Rinput(1,1);
Tinput(2,1)=Rinput(2,1);
Tinput(3,1)=0;
Tinput(0,2)=Rinput(0,2);
Tinput(1,2)=Rinput(1,2);
Tinput(2,2)=Rinput(2,2);
Tinput(3,2)=0;
Tinput(0,3)=pdata[0];
Tinput(1,3)=pdata[1];
Tinput(2,3)=pdata[2];
Tinput(3,3)=1;
//Computation
DZ << 0, 0, 1;
D1 << 0, 0, d1;
I = I.setIdentity(3,3);
//Compute wrist position relating to base from the given EE position end orientation
W = Tinput.topRightCorner(3,1)-d7*(Tinput.topLeftCorner(3,3)*DZ); //P(1:3,4)
//Compute wrist position relating to shoulder
L_SW = W - D1;
norm_L_SW = L_SW.norm();
//Elbow angle q4 in radian
q[3] = acos((pow(norm_L_SW,2) - pow(d3,2) - pow(d5,2))/(2*d3*d5));
if (q[3]>=0) GC4 = 1;
else GC4 = -1;
//Compute skew symetric matrix of the vector between wrist and shoulder:
USW = L_SW/norm_L_SW;
KSW << 0, -USW(2), USW(1),
USW(2), 0, -USW(0),
-USW(1), USW(0), 0;
//Set q3=0, compute reference joint angle q1dot, q2dot of the ref plane
q1dot = atan2(W(1),W(0));
q2dot = pi/2 - asin((W(2)-d1)/norm_L_SW) - acos((pow(d3,2)+pow(norm_L_SW,2)-pow(d5,2))/(2*d3*norm_L_SW));
//Rotation matrix of the ref joint angles q1dot, q2dot:
R03dot << cos(q1dot)*cos(q2dot), -cos(q1dot)*sin(q2dot), -sin(q1dot),
cos(q2dot)*sin(q1dot), -sin(q1dot)*sin(q2dot), cos(q1dot),
-sin(q2dot), -cos(q2dot), 0;
//Shoulder constant matrices Xs Ys Zs
XS = KSW*R03dot;
YS = -(KSW*KSW)*R03dot;
ZS = (I+KSW*KSW)*R03dot;
//constant matrices Xw Yw Zw
R34 << cos(q[3]), 0, sin(q[3]),
sin(q[3]), 0, -cos(q[3]),
0, 1, 0;
XW = R34.transpose()*XS.transpose()*Tinput.topLeftCorner(3,3);
YW = R34.transpose()*YS.transpose()*Tinput.topLeftCorner(3,3);
ZW = R34.transpose()*ZS.transpose()*Tinput.topLeftCorner(3,3);
//Theta2
q[1] = acos(-sin(si)*XS(2,1)-cos(si)*YS(2,1)-ZS(2,1));
if (q[1]>=0)GC2 = 1;
else GC2 = -1;
//Theta1, theta3
q[0] = atan2(GC2*(-sin(si)*XS(1,1)-cos(si)*YS(1,1)-ZS(1,1)),GC2*(-sin(si)*XS(0,1)-cos(si)*YS(0,1)-ZS(0,1)));
q[2] = atan2(GC2*(sin(si)*XS(2,2)+cos(si)*YS(2,2)+ZS(2,2)),GC2*(-sin(si)*XS(2,0)-cos(si)*YS(2,0)-ZS(2,0)));
//Theta6
q[5] = acos(sin(si)*XW(2,2)+cos(si)*YW(2,2)+ZW(2,2));
if (q[5]>=0)GC6 = 1;
else GC6 = -1;
//Theta5, theta7
q[4] = atan2(GC6*(sin(si)*XW(1,2)+cos(si)*YW(1,2)+ZW(1,2)),GC6*(sin(si)*XW(0,2)+cos(si)*YW(0,2)+ZW(0,2)));
q[6] = atan2(GC6*(sin(si)*XW(2,1)+cos(si)*YW(2,1)+ZW(2,1)),GC6*(-sin(si)*XW(2,0)-cos(si)*YW(2,0)-ZW(2,0)));
}
void InvK7_0(const Eigen::MatrixXd &data, double si)
{
double q1dot, q2dot;
double norm_L_SW;
int GC2, GC4, GC6;
//Given homogeneous transformation matrix
DZ << 0, 0, 1;
D1 << 0, 0, d1;
I = I.setIdentity(3,3);
//Compute wrist position relating to base from the given EE position end orientation
W = data.topRightCorner(3,1)-d7*(data.topLeftCorner(3,3)*DZ); //P(1:3,4)
//Compute wrist position relating to shoulder
L_SW = W - D1;
norm_L_SW = L_SW.norm();
//Elbow angle q4 in radian
q[3] = acos((pow(norm_L_SW,2) - pow(d3,2) - pow(d5,2))/(2*d3*d5));
if (q[3]>=0) GC4 = 1;
else GC4 = -1;
//Compute skew symetric matrix of the vector between wrist and shoulder:
USW = L_SW/norm_L_SW;
KSW << 0, -USW(2), USW(1),
USW(2), 0, -USW(0),
-USW(1), USW(0), 0;
//Set q3=0, compute reference joint angle q1dot, q2dot of the ref plane
q1dot = atan2(W(1),W(0));
q2dot = pi/2 - asin((W(2)-d1)/norm_L_SW) - acos((pow(d3,2)+pow(norm_L_SW,2)-pow(d5,2))/(2*d3*norm_L_SW));
//Rotation matrix of the ref joint angles q1dot, q2dot:
R03dot << cos(q1dot)*cos(q2dot), -cos(q1dot)*sin(q2dot), -sin(q1dot),
cos(q2dot)*sin(q1dot), -sin(q1dot)*sin(q2dot), cos(q1dot),
-sin(q2dot), -cos(q2dot), 0;
//Shoulder constant matrices Xs Ys Zs
XS = KSW*R03dot;
YS = -(KSW*KSW)*R03dot;
ZS = (I+KSW*KSW)*R03dot;
//constant matrices Xw Yw Zw
R34 << cos(q[3]), 0, sin(q[3]),
sin(q[3]), 0, -cos(q[3]),
0, 1, 0;
XW = R34.transpose()*XS.transpose()*data.topLeftCorner(3,3);
YW = R34.transpose()*YS.transpose()*data.topLeftCorner(3,3);
ZW = R34.transpose()*ZS.transpose()*data.topLeftCorner(3,3);
//Theta2
q[1] = acos(-sin(si)*XS(2,1)-cos(si)*YS(2,1)-ZS(2,1));
if (q[1]>=0)GC2 = 1;
else GC2 = -1;
//Theta1, theta3
q[0] = atan2(GC2*(-sin(si)*XS(1,1)-cos(si)*YS(1,1)-ZS(1,1)),GC2*(-sin(si)*XS(0,1)-cos(si)*YS(0,1)-ZS(0,1)));
q[2] = atan2(GC2*(sin(si)*XS(2,2)+cos(si)*YS(2,2)+ZS(2,2)),GC2*(-sin(si)*XS(2,0)-cos(si)*YS(2,0)-ZS(2,0)));
//Theta6
q[5] = acos(sin(si)*XW(2,2)+cos(si)*YW(2,2)+ZW(2,2));
if (q[5]>=0)GC6 = 1;
else GC6 = -1;
//Theta5, theta7
q[4] = atan2(GC6*(sin(si)*XW(1,2)+cos(si)*YW(1,2)+ZW(1,2)),GC6*(sin(si)*XW(0,2)+cos(si)*YW(0,2)+ZW(0,2)));
q[6] = atan2(GC6*(sin(si)*XW(2,1)+cos(si)*YW(2,1)+ZW(2,1)),GC6*(-sin(si)*XW(2,0)-cos(si)*YW(2,0)-ZW(2,0)));
}
//***********************************Forward Kinematics***********************************************
/*
MatrixXd forwd7(double qdata[7])
{
MatrixXd pforwk7(3,1); //computed EE destination postion
double th1, th2, th3, th4, th5, th6, th7;
//Update theta from msgCallbackP function
th1 = qdata[0];
th2 = qdata[1];
th3 = qdata[2];
th4 = qdata[3];
th5 = qdata[4];
th6 = qdata[5];
th7 = qdata[6];
pforwk7(0,0) = d3 * cos(th1)*sin(th2) - d7 * (cos(th6)*(sin(th4)*(sin(th1)*sin(th3) - cos(th1)*cos(th2)*cos(th3)) - cos(th1)*cos(th4)*sin(th2)) + sin(th6)*(cos(th5)*(cos(th4)*(sin(th1)*sin(th3) - cos(th1)*cos(th2)*cos(th3)) + cos(th1)*sin(th2)*sin(th4)) + sin(th5)*(cos(th3)*sin(th1) + cos(th1)*cos(th2)*sin(th3)))) - d5 * (sin(th4)*(sin(th1)*sin(th3) - cos(th1)*cos(th2)*cos(th3)) - cos(th1)*cos(th4)*sin(th2));
pforwk7(1,0) = d5 * (sin(th4)*(cos(th1)*sin(th3) + cos(th2)*cos(th3)*sin(th1)) + cos(th4)*sin(th1)*sin(th2)) + d7 * (cos(th6)*(sin(th4)*(cos(th1)*sin(th3) + cos(th2)*cos(th3)*sin(th1)) + cos(th4)*sin(th1)*sin(th2)) + sin(th6)*(cos(th5)*(cos(th4)*(cos(th1)*sin(th3) + cos(th2)*cos(th3)*sin(th1)) - sin(th1)*sin(th2)*sin(th4)) + sin(th5)*(cos(th1)*cos(th3) - cos(th2)*sin(th1)*sin(th3)))) + d3 * sin(th1)*sin(th2);
pforwk7(2,0) = d1 - d7 * (sin(th6)*(cos(th5)*(cos(th2)*sin(th4) + cos(th3)*cos(th4)*sin(th2)) - sin(th2)*sin(th3)*sin(th5)) - cos(th6)*(cos(th2)*cos(th4) - cos(th3)*sin(th2)*sin(th4))) + d5 * (cos(th2)*cos(th4) - cos(th3)*sin(th2)*sin(th4)) + d3 * cos(th2);
return pforwk7;
}
*/
MatrixXd forwd7(double qdata[7]) //// input: joint angles output: position + rotation need
{
/*
description
forward kinemaitcs
input -> joint angles
output: position(x,y,z) , eulerangles(alpha,beta,gamma) -> 6x1 vector (x,y,z,alpha,beta,gamma)
*/
MatrixXd pforwk7(6,1); //computed EE destination postion
MatrixXd T01(4,4);
MatrixXd T12(4,4);
MatrixXd T23(4,4);
MatrixXd T34(4,4);
MatrixXd T45(4,4);
MatrixXd T56(4,4);
MatrixXd T67(4,4);
MatrixXd T7E(4,4);
MatrixXd T0E(4,4);
T01 << cos(qdata[0]), 0, -sin(qdata[0]), 0,
sin(qdata[0]), 0, cos(qdata[0]), 0,
0, -1, 0 , d1,
0, 0, 0 , 1;
T12 << cos(qdata[1]), 0, sin(qdata[1]), 0,
sin(qdata[1]), 0, -cos(qdata[1]),0,
0, 1, 0, 0,
0, 0, 0 , 1;
T23 << cos(qdata[2]), 0, -sin(qdata[2]), 0,
sin(qdata[2]), 0, cos(qdata[2]),0,
0, -1, 0, d3,
0, 0, 0 , 1;
T34 << cos(qdata[3]), 0, sin(qdata[3]), 0,
sin(qdata[3]), 0, -cos(qdata[3]), 0,
0, 1, 0,0 ,
0, 0, 0 , 1;
T45 << cos(qdata[4]), 0, -sin(qdata[4]), 0,
sin(qdata[4]), 0, cos(qdata[4]), 0,
0, -1, 0, d5,
0, 0, 0 , 1;
T56 << cos(qdata[5]), 0, sin(qdata[5]), 0,
sin(qdata[5]), 0, -cos(qdata[5]),0,
0, 1, 0, 0,
0, 0, 0 , 1;
T67 << cos(qdata[6]), -sin(qdata[6]), 0, 0,
sin(qdata[6]), cos(qdata[6]), 0, 0,
0, 0, 1, d7,
0, 0, 0 , 1;
T7E << 1, 0, 0, 0,