-
Notifications
You must be signed in to change notification settings - Fork 3
/
AssemblyStrategy.cpp
executable file
·2553 lines (2166 loc) · 98.8 KB
/
AssemblyStrategy.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
/*--------------------------------
ANGLES * AssemblyStrategy.cpp
* Created on: Mar 19, 2012
* Author: juan
--------------------------------*/
#include <sys/types.h>
#include <sys/stat.h>
#include "AssemblyStrategy.h"
///---------------------------------------------------------------------------------------------------------------------------------------------------//
/************************************************************* DESIGN PARAMETERS AND FLAGS ************************************************************/
// ----------------------------------------------------- PLEASE SEE MORE DESIGN PARAMETERS IN hiroArm ------------------------------------------------//
//----------------------------------------------------------------------------------------------------------------------------------------------------
#define PA10 0
#define HIRO 1
//----------------------------------------------------------------------------------------------------------------------------------------------------
// ASSEMBLY_STRATEGY_AUTOMATA STATES
//----------------------------------------------------------------------------------------------------------------------------------------------------
#define PA_FINISH 10 // value returned when the assembly is finished
//----------------------------------------------------------------------------------------------------------------------------------------------------
// FAILURE CHARACTERIZATION VARIABLES
//----------------------------------------------------------------------------------------------------------------------------------------------------
#define PATH_DEVIATION_MAGNITUDE_X 0 // 0.0085 // xDir (4) 0.0105 // (3) 0.0095 // (2) 0.0085 // (1) 0.0075 // Parameter used to study Failure Characterization.
#define PATH_DEVIATION_MAGNITUDE_Y 0 // -0.0105 // yDir (4) 0.0105 // (3) 0.0095 // (2) 0.0085 // (1) 0.0075
#define ANGLE_DEVIATION_MAGNITUDE 0 // 0.4363 // YawDir (6) 0.5235 // (5) 0.4363 // (4) 0.3490 // (3) 0.2618 // (2) 0.1745 // (1) 0.08725
//----------------------------------------------------------------------------------------------------------------------------------------------------
// FILTERING
//----------------------------------------------------------------------------------------------------------------------------------------------------
#define FILT_FLAG 1 // Used to enable or disable the filtering of the torques signal. Filtering uses FilterTools class and is called in ::StateMachine
//-----------------------------------------------------------------------------------------------------------------------------------------
// DEBUGGING
//----------------------------------------------------------------------------------------------------------------------------------------------------
#define DEBUG_AS 0 // Flag used to test functions with hard-coded data
#define DB_PRINT 0 // Used to write angles, cart positions, forces, and states to std::cerr
#define DB_WRITE 1 // Used to write angles, cart position, forces, and states to FILE.
#define DB_TIME 0 // Used to print timing duration of functions
//----------------------------------------------------------------------------------------------------------------------------------------------------
// WORLD COORDINATES
//----------------------------------------------------------------------------------------------------------------------------------------------------
// Vertical Axes in WORLD coordinates using a right handed coordinate system: +Z:Up, +Y:Right, +X:Out
#if(PA10==1)
#define UP_AXIS 2 // Defines the local wrist axis for a robot. Used to set desired forces.
#else // HIRO
#define UP_AXIS 0 // x becomes up/down after transform
#define FWD_AXIS 2 // z becomes backward/forward after transform
#define SIDE_AXIS 1
#endif
//----------------------------------------------------------------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------------------------------------------------------------
// Default Constructor
//----------------------------------------------------------------------------------------------------------------------------------------------------
AssemblyStrategy::AssemblyStrategy()
{
#ifdef DEBUG_PLUGIN3
std::cerr << "AssemblyStrategy(): Entering Constructor" << std::endl;
#endif
// Control Method
controlType = controlBasis;
// Strategy Default
approachType = SideApproach;
approachFlag = false;
// Pivot Approach Contact
noContact = true;
completionFlag = false;
// Manipulation Test
testCounter = 0;
compositionTypeTest = 0; // Force or Moment
DesForceSwitch = 0; // Switch which element to activate
initialFlag = true;
completionFlag = false;
// State Transition
signChanger = 0.0;
switchFlag = true;
nextState = false;
hsaHIROTransitionExepction = normal;
State = 1;
transitionTime = 0.0;
transitionTimebool = false;
state3_zPos = 0.0;
state3_zPrevPos = 0.0;
SA_S4_Height = 0.0;
mating2EndTime = 1.0;
// Control Basis Members
NumCtlrs = 1;
ErrorFlag = true;
ctrlInitFlag = true;
// Data vectors
// DesIKin holds the final desired position for contact with the pivoting dock
if(PA10)
{
DesIKin(0) = 0.0000;
DesIKin(1) = -0.7330;
DesIKin(2) = 0.0075;
DesIKin(3) = 3.1415;
DesIKin(4) = 0.0000;
DesIKin(5) = -3.1415;
}
else if(HIRO)
{
DesIKin(0) = 0.0000;
DesIKin(1) = -0.7330;
DesIKin(2) = 0.0075;
DesIKin(3) = 3.1415;
DesIKin(4) = 0.0000;
DesIKin(5) = -3.1415;
}
else
for(int i=0; i<6; i++) DesIKin(i)=0.0;
for(int i=0; i<6; i++)
{
CurCartPos(i) = 0.0;
DesCartPos(i) = 0.0;
contactPos(i) = 0.0;
CurJointAngles(i) = 0.0;
JointAngleUpdate(i) = 0.0;
}
// Control Basis and FilterTools
c1 = 0;
c2 = 0;
c3 = 0;
ft = 0;
// Kinematics
IKinTestFlag = 0;
zerothJoint = 0;
transWrist2CamXEff = 0.0;
ContactWristAngle = 0.0, -1.5708, 0.0;
for(int i=0; i<6; i++) avgSig = 0.0;
// Motion
wrist_r = (0);
EndEff_r_org = (0);
wrist_p = (0);
EndEff_p_org = (0);
divPoint = (0);
// File Paths: save global path's to internal variables
strcpy(strState, ""); // File designed to save the time at which new states occur
strcpy(strForces, ""); // File designed to save the value of forces and moments registered in the task
strcpy(strTrajState1, ""); // File that contains the desired position trajectory to be followed
strcpy(strAngles, ""); // File designed to save the joint angles during the task
strcpy(strCartPos, ""); // File designed to save the cartesian positions during the task
// Imported Values
cur_time = 0.0; // used in transitions
flagFiltering = FILT_FLAG; // Set filtering flag to parameter define in preprocessor
// Control Basis
momentGainFactor = 1.0;
#ifdef DEBUG_PLUGIN3
std::cerr << "AssemblyStrategy(): Exiting Constructor" << std::endl;
#endif
}
//----------------------------------------------------------------------------------------------------------------------------------------------------
// Overloaded Constructor
// Called from the hiroArm class.
// Constructor called from HIRO Simulation and passes variables like position, rotation, jacobian, curr_time, curr_force for a given arm. just working with one arm so far.
//----------------------------------------------------------------------------------------------------------------------------------------------------
AssemblyStrategy::AssemblyStrategy(int NUM_q0, vector3 base2endEffectorPos, matrix33 base2endEffectorRot, vector3 ePh, double momentGainFac)
{
// Default Control Methodology
controlType = controlBasis;
// Strategy Default
approachType = SideApproach;
approachFlag = false;
// Pivot Approach Contact
noContact = true;
completionFlag = false;
// Manipulation Test
testCounter = 0;
compositionTypeTest = 0; // Force or Moment
DesForceSwitch = 0; // Switch which element to activate
initialFlag = true;
// State Transition
signChanger = 0.0;
switchFlag = true;
nextState = false;
hsaHIROTransitionExepction = normal;
State = 1;
transitionTime = 0.0;
transitionTimebool = false;
state3_zPos = 0.0;
state3_zPrevPos = 0.0;
SA_S4_Height = 0.0;
mating2EndTime = 1.00;
// Control Basis Members
NumCtlrs = 1;
ErrorFlag = true;
ctrlInitFlag = true;
// Data vectors
// DesIKin holds the final desired position for contact with the pivoting dock
if(PA10)
{
DesIKin(0) = 0.0000;
DesIKin(1) = -0.7330;
DesIKin(2) = 0.0075;
DesIKin(3) = 3.1415;
DesIKin(4) = 0.0000;
DesIKin(5) = -3.1415;
}
else if(HIRO)
{
DesIKin(0) = 0.0000;
DesIKin(1) = -0.7330;
DesIKin(2) = 0.0075;
DesIKin(3) = 3.1415;
DesIKin(4) = 0.0000;
DesIKin(5) = -3.1415;
}
else
for(int i=0; i<6; i++) DesIKin(i)=0.0;
for(int i=0; i<6; i++)
{
CurCartPos(i) = 0.0;
DesCartPos(i) = 0.0;
contactPos(i) = 0.0;
CurJointAngles(i) = 0.0;
JointAngleUpdate(i) = 0.0;
}
// Control Basis
c1 = 0;
c2 = 0;
c3 = 0;
ft = 0;
// Kinematics
IKinTestFlag = 0;
zerothJoint = NUM_q0;
transWrist2CamXEff = ePh; // wrist2endeffecter
ContactWristAngle = 0.0, -1.5708, 0.0;
for(int i=0; i<6; i++) avgSig = 0.0;
#ifdef DEBUG_PLUGIN3
std::cerr << "AssemblyStrategy(): Converting rot2rpy and position transformation." << std::endl;
#endif
// Motion: true end-effector position and rotation
EndEff_r_org = rpyFromRot(base2endEffectorRot);
wrist_r = EndEff_r_org;
EndEff_p_org = base2endEffectorPos;
wrist_p = EndEff_p_org;
divPoint(0) = 0;
#ifdef DEBUG_PLUGIN3
std::cerr << "The EndEffector position during the constructor is: " << wrist_p(0) << "\t" << wrist_p(1) << "\t" << wrist_p(2) << "\t" << wrist_r(0) << "\t" << wrist_r(1) << "\t" << wrist_r(2) << std::endl;
#endif
// File Paths: save global path's to internal variables
strcpy(strState, ""); // File designed to save the time at which new states occur
strcpy(strForces, ""); // File designed to save the value of forces and moments registered in the task
strcpy(strTrajState1, ""); // File that contains the desired position trajectory to be followed
strcpy(strAngles, ""); // File design to save the value of joint angles registered in the task
strcpy(strCartPos, ""); // File designed to save the Cartesian positions registered in the task
// Imported Values
cur_time = 0.0; // used in transitions
flagFiltering = FILT_FLAG; // Set filtering flag to parameter define in preprocessor
// ControlBasis
momentGainFactor = momentGainFac;
#ifdef DEBUG_PLUGIN3
std::cerr << "AssemblyStrategy::AssemblyStrategy(num_q0,base2endeffPoss,base2endeffRot,ePh,momentGainFac) - exiting\n-----------------------------------------------------------------------------------------" << std::endl;
#endif
}
//----------------------------------------------------------------------------------------------------------------------------------------------------
// Destructor
//----------------------------------------------------------------------------------------------------------------------------------------------------
AssemblyStrategy::~AssemblyStrategy()
{
// Set controller pointers to null.
if(c1!=NULL) c1 = NULL;
if(c2!=NULL) c2 = NULL;
if(c3!=NULL) c3 = NULL;
// Delete the filter object
delete ft;
ft = NULL;
// Close all read and write files
CloseFiles();
}
//----------------------------------------------------------------------------------------------------------------------------------------------------
// Initialize
//----------------------------------------------------------------------------------------------------------------------------------------------------
// 1) Allows user to set specific path files for the MOTION_FILE, ANGLES_FILE, CART_POS_FILE, STATE_FILE, and FORCE_FILE.
// 2) Extracts information from waypoints found in the trajectory file to be used in moveRobot().
// 3) Saves the homing position and rotation matrix of the wrist
// 4) Assigns the kind of control method and strategy motion that we will use. Currently (4) options: Straight Line Approach (PA10), Pivot Approach (PA10), Side Approach (HIRO), Failure Characterization (HIRO).
// 5) Allocates the filter class
//----------------------------------------------------------------------------------------------------------------------------------------------------
int AssemblyStrategy::Initialize(char TrajState1[STR_LEN], char TrajState2[STR_LEN], char AnglesDir[STR_LEN], char CartPosDir[STR_LEN], char StateDir[STR_LEN], char ForcesDir[STR_LEN],
vector3 pos, matrix33 rot, double CurAngles[15],
int strategyType, int controlMethodType)
{
#ifdef DEBUG_PLUGIN3
std::cerr << "\nAssemblyStrategy::Initialize - entered" << std::endl;
std::cerr << "\n These are the file names: \n" << TrajState1 << "\n" << TrajState2 << "\n" << AnglesDir << "\n" << CartPosDir << "\n" << StateDir << "\n" << ForcesDir << "\n" << std::endl;
#endif
//--------------------------------------------------------------------------------------------------------------------------------
// 1) Read user specified files. If null strings, go with default values. Trajectory File for State1. If not null, then read. Otherwise we used pre-saved values that were written during the constructor.
//--------------------------------------------------------------------------------------------------------------------------------
if(abs(strcmp(TrajState1,"")))
strcpy(strTrajState1,TrajState1);
// Trajectory File for State2. If not null, then read
if(abs(strcmp(TrajState2,"")))
strcpy(strTrajState2,TrajState2);
// Joint Angles File. If not null, then read
if(abs(strcmp(AnglesDir,"")))
strcpy(strAngles,AnglesDir);
// Cartesian Positions File. If not null, then read
if(abs(strcmp(CartPosDir,"")))
strcpy(strCartPos,CartPosDir);
// State File. If not null, then read
if(abs(strcmp(StateDir,"")))
strcpy(strState,StateDir);
// Trajectory File. If not null, then read
if(abs(strcmp(ForcesDir,"")))
strcpy(strForces,ForcesDir);
//--------------------------------------------------------------------------------------------------------------------------------
// 2) Open files for reading and writing data.
//--------------------------------------------------------------------------------------------------------------------------------
OpenFiles();
// Here we read the desired trajectory file for state 1 and save the data in local variables for position and orientation
#ifdef DEBUG_PLUGIN3
std::cerr << "\nAssemblyStrategy::Initialize - extract information from waypoint file: " << strTrajState1 << std::endl;
#endif
//--------------------------------------------------------------------------------------------------------------------------------
// 3) Reassign original end effector position and rotation
//--------------------------------------------------------------------------------------------------------------------------------
EndEff_r_org = rpyFromRot(rot);
wrist_r = EndEff_r_org;
EndEff_p_org = pos;
wrist_p = EndEff_p_org;
#ifdef DEBUG_PLUGIN3
// Cartesian Position
std::cerr << "/--------------------------------------------------------------------------------------------------------------------------------------------------------------------/\n"
"AssemblyStrategy::Initialize(): \nThe EndEffector position during initialization is: "
<< wrist_p(0) << "\t" << wrist_p(1) << "\t" << wrist_p(2) << "\t" << wrist_r(0) << "\t" << wrist_r(1) << "\t" << wrist_r(2)
// Joint Angles
<< "\n\nThe 15 body joint angles in radians are: "
<< CurAngles[0] << "\t" << CurAngles[1] << "\t" << CurAngles[2] << "\t" << CurAngles[3] << "\t" << CurAngles[4] << "\t" << CurAngles[5] << "\t"
<< CurAngles[6] << "\t" << CurAngles[7] << "\t" << CurAngles[8] << "\t" << CurAngles[9] << "\t" << CurAngles[10] << "\t" << CurAngles[11]
<< CurAngles[12] << "\t" << CurAngles[13] << "\t" << CurAngles[14] << "\t"
<< "\n/--------------------------------------------------------------------------------------------------------------------------------------------------------------------/" << std::endl;
#endif
vector3 rpy=rpyFromRot(rot);
// Extract information from the way point file for state 1
ProcessTrajFile(strTrajState1,1,pos,rpy,0.0); // string path,state,curr_pos,cur_time
// Copy wrist (endeffector) position and rotation matrix to internal variables
EndEff_p_org = pos;
EndEff_r_org = rpy;
// AssemblyStrategy needs end-effector position/rotation.
// hiroArm needs wrist position/orientation.
// When a position comes into AssemblyStrategy it is immediately converted to end-effector position/rotation/
// AssemblyStrategy::moveRobot() will convert it back to wrist coordinates which is then used by fwd/inv kinematics.
wrist2EndEffTrans(EndEff_p_org,EndEff_r_org);
//--------------------------------------------------------------------------------------------------------------------------------
// 4) Assign control method and motion strategy
//--------------------------------------------------------------------------------------------------------------------------------
// (A) Control Method Selection
if(controlMethodType==motionData)
{
controlType = motionData;
}
else if(controlMethodType==controlBasis)// Control Basis Approach
controlType = controlBasis;
// (B) Strategy Selection
if(strategyType==StraightLineApproach)
{
approachFlag = true;
approachType = StraightLineApproach;
}
else if(strategyType==PivotApproach)
{
approachFlag = false;
approachType = PivotApproach;
}
else if(strategyType==SideApproach)
{
approachFlag = false;
approachType = SideApproach;
}
else if(strategyType==FailureCharacerization)
{
approachFlag = false;
approachType = FailureCharacerization;
// Assign appropriate values to the divPoint array which will modify waypoint values.
/** Failure Case Characterization Vector **/
// Will only write values into x,y,roll,and yaw since these will not greatly affect the motion of the robot.
// Keep the z-axis, the pitch, and yaw at zero
divPoint(2)=0; divPoint(4)=0;divPoint(5)=0;
divPoint(0) = PATH_DEVIATION_MAGNITUDE_X; // x-axis
divPoint(1) = PATH_DEVIATION_MAGNITUDE_Y; // y-axis
if(divPoint(0)>0.00) divPoint(2) =-0.005; // Change z-axis
else divPoint(2) = 0.000; // If there is deviation in the x-axis, then we need to add a deviation in the z-axis with value of -0.005 such that there is contact after moving forward.
divPoint(3) = ANGLE_DEVIATION_MAGNITUDE; // Yaw ANGLE_DEVIATION_MAGNITUDE
}
// For the first iteration they are both the same.
wrist_p = EndEff_p_org;
wrist_r = EndEff_r_org;
//--------------------------------------------------------------------------------------------------------------------------------
// 5) Filter Class Allocation
//--------------------------------------------------------------------------------------------------------------------------------
ft = new FilterTools();
#ifdef DEBUG_PLUGIN3
std::cerr << "\nAssemblyStrategy::Initialize - exited" << std::endl;
#endif
return 1;
}
/****************************************************************************************************************************************************************************************************/
// StateMachine()
// The state machine will contain the appropriate states and desired actions that correspond to a desired control strategy.
// Three common control strategies are: StraightLineApproach, PivotApproach, and a variant of the PivotApproach, the SideApproach.
// Each state will call the ControlBasis class to execute a simple or compound controller with a defined desired position or force values.
// Transitions are defined in StateSwitcher() and are unique to each approach.
// The output of the function is the updated CurrentJointAngles which are passed to hiroArm class and then to the forceSensorPlugin class.
//
// Notes about position:
// The position received by this function corresponds to the endeffector position. For the IKinComposition, which uses inverse kinematics for position controll, the updated desired position is
// translated back to the wrist position and then the inverse kinematics are computed from there.
//
// Coordinate Frame of Reference:
// For force/moment control compositions the incoming desired forces and moments are set according to the world coordinate frame. Within each state those forces/moments are rotated according to the local
// wrist coordinate frame.
// Position is always computed with respect to the base/world coordinate frame.
/****************************************************************************************************************************************************************************************************/
int AssemblyStrategy::StateMachine(TestAxis axis, /*in*/
CtrlStrategy approach, /*in*/
JointPathPtr m_path, /*in*/
BodyPtr bodyPtr, /*in*/
double cur_time, /*in*/
vector3& pos, /*in*/ // end-effector pos
matrix33& rot, /*in*/ // end-effector rot
dvector6 currForces, /*in*/
dvector6& JointAngleUpdate, /*out*/
dvector6& CurrAngles, /*out*/
dmatrix Jacobian, /*in*/
dmatrix PseudoJacobian) /*in*/
{
/*----------------------------- Local variables ----------------------------------------*/
//float MaxErrNorm = 0.0;
int ret = 0;
double filteredSig[6];
double temp[6];
double noiseTemp = 0.0;
double ErrorNorm1 = 0, ErrorNorm2 = 0;
dvector6 n6;
matrix33 attitude(0);
Vector3 n(0), DesXYZ(0), DesRPY(0), DesForce(0), DesMoment(0), CurXYZ(0), CurRPY(0);
// Time variables
double duration = -1.0;
timeval startTime, endTime; // start and end time variables
#ifdef DEBUG_PLUGIN3
std::cerr << "Entering AssemblyStrategy::StateMachine" << std::endl;
#endif
if(DB_TIME)
gettimeofday(&startTime,NULL); // Start computing cycle time for the control function
/************************************************* LOW PASS FILTERING *************************************************************/
if(flagFiltering) // Copy force/torque data into a double array to be used by the Low-Pass Filter
{
for(int i=0; i<ARM_DOF; i++)
temp[i]=currForces(i);
ft->LowPassFilter(temp,filteredSig);
// ft->LowPassFilter(currForces,avgSig);
// ft->secOrderFilter(temp,filteredSig);
// ft->secOrderFilter(currForces,avgSig);
for(int i=0;i<3;i++)
{
noiseTemp=noise(3);
avgSig(i) = filteredSig[i]+noiseTemp;
}
for(int i=3;i<6;i++)
{
noiseTemp=noise(4);
avgSig(i) = filteredSig[i]+noiseTemp;
}
//ft->LowPassFilter(currForces,avgSig);
}
else
avgSig = currForces;
/****************************************** Wrist/EndEffecter Transformation *****************************************************/
// Convert from wrist position/rotation to endEffector position/rotation. I.e:
// AssemblyStrategy needs endEffector position/rotation.
// hiroArm needs wrist position/orientation.
// When a position comes into AssemblyStrategy it is immediately converted to endEffector position/rotation/
// AssemblyStrategy::mveRobot() will convert it back wrist coordinates which is then used by fwd/inv kinematics.
CurRPY = rpyFromRot(rot);
//wrist2EndEffTrans(pos,CurRPY);
/*************************************************************** TEST APPROACH ********************************************************************************/
if(approach==ManipulationTest) // something strange where forceSensorPlugin cannot see ManipulationTest... rigged here.
{
manipulationTest(axis, completionFlag,
m_path,bodyPtr,
JointAngleUpdate,CurrAngles,
DesForce,DesMoment,n6,
pos,rot,cur_time,
Jacobian,PseudoJacobian);
}
/*------------------------------------------------------------------ PIVOT APPROACH -------------------------------------------------------------------*/
else if(approach==PivotApproach)
{
switch (State)
{
/*-------------------------------------------------- Approach --------------------------------------------------*/
case paApproach:// Move, such that the TCP makes contact with the docking pivot in the male camera part at an angle.
{
// Initialize
if(ctrlInitFlag)
{
#ifdef DEBUG_PLUGIN3
std::cerr << "State 1 in AssemblyStrategy::StateMachine" << std::endl;
#endif
nextState = false;
ctrlInitFlag = false;
}
// Primitive Ikin controller: Use a preplanned trajectory to move the wrist at an angle until contact.
// DesIKin are hardcoded into the code.
ret=ControlCompositions(m_path,bodyPtr,JointAngleUpdate,CurrAngles,approach,IKinComposition,n,DesForce,n6,ErrorNorm1,ErrorNorm2,pos,rot,cur_time,Jacobian,PseudoJacobian);
// 0) Check for state termination.
StateSwitcher(approach,State,ErrorNorm1,ErrorNorm2,pos,rot,CurrAngles,avgSig,cur_time); // Fix to add ErrorNorm2
}
break;
/*-------------------------------------------------- Rotation --------------------------------------------------*/
case paRotation: // Rotate until contact
{
// Initialize
if(ctrlInitFlag)
{
#ifdef DEBUG_PLUGIN3
std::cerr << "State 2 in AssemblyStrategy::StateMachine" << std::endl;
#endif
nextState = false;
ctrlInitFlag = false;
// Set up a new trajectory file with current information
ProcessTrajFile(strTrajState2,State,pos,CurRPY,cur_time);
EndEff_p_org = pos;
EndEff_r_org = CurRPY;
}
// Primitive Ikin controller: Use a preplanned trajectory to rotate wrist until further contact
ret=ControlCompositions(m_path,bodyPtr,JointAngleUpdate,CurrAngles,approach, IKinComposition,n,DesForce,n6,ErrorNorm1,ErrorNorm2,pos,rot,cur_time,Jacobian,PseudoJacobian);
// Check for state termination. Also free allocated resources.
StateSwitcher(approach,State,ErrorNorm1,ErrorNorm2,pos,rot,CurrAngles,avgSig,cur_time);
}
break;
/*-------------------------------------------------- Alignment --------------------------------------------------*/
case paAlignment:
{
// Initialize
if(ctrlInitFlag)
{
#ifdef DEBUG_PLUGIN3
std::cerr << "State 3 in AssemblyStrategy::StateMachine" << std::endl;
#endif
nextState = false;
ctrlInitFlag = false;
}
// Set the desired force according to world coordinates. It will be modified within the control compositions to local coordinates.
DesForce(UP_AXIS) = currForces(UP_AXIS);
if( DesForce(UP_AXIS)<0 )
DesForce(UP_AXIS) = CONST_FORCE_STATE3;
// Moment Alignment
ret=ControlCompositions(m_path,bodyPtr,JointAngleUpdate,CurrAngles,approach,MomentForceComposition,DesMoment,DesForce,DesIKin,ErrorNorm1,ErrorNorm2,pos,rot,cur_time,Jacobian,PseudoJacobian); // takes the DesIKin wrist position
// Check for state termination. Also free allocated resources.
StateSwitcher(approach,State,ErrorNorm1,ErrorNorm2,pos,rot,CurrAngles,avgSig,cur_time);
}
break;
/*-------------------------------------------------- Compliant Insertion Controller --------------------------------------------------*/
case paInsertion:
{
// Initialize
if(ctrlInitFlag)
{
#ifdef DEBUG_PLUGIN3
std::cerr << "State 4 in AssemblyStrategy::StateMachine" << std::endl;
#endif
nextState = false;
ctrlInitFlag = false;
}
// Set the desired force according to world coordinates. It will be modified within the control compositions to local coordinates.
DesForce(UP_AXIS)=VERTICAL_FORCE; // PUSH DOWN
//DesForce(FWD_AXIS)=5.0; // PUSH AGAINST PIVOTDING DOCK
DesMoment(1) = ROTATIONAL_FORCE; // ROTATE TO CLOSE
/******************************************** Call controller ********************************************/
ControlCompositions(m_path,bodyPtr,JointAngleUpdate,CurrAngles,approach, MomentForceComposition,DesMoment,DesForce,DesIKin,ErrorNorm1,ErrorNorm2,pos,rot,cur_time,Jacobian,PseudoJacobian);
// Check for state termination. Also free allocated resources.
StateSwitcher(approach,State,ErrorNorm1,ErrorNorm2,pos,rot,CurrAngles,avgSig,cur_time);
}
break;
/*--------------------------------------------------Mating --------------------------------------------------*/
case paMating: // Maintain Position
{
// Change the paradigm to call directcompliancecontrol directly
//controlType=motionData;
// Save current wrist position to wrist_r, wrist_p, that's where we will direct the wrist.
//wrist_p=pos;
//wrist_p=rpyFromRot(arm_path->joint(6)->attitude()); // Used in linux simulation
//wrist_p=rpyFromRot(arm_path->joint(6)->segmentAttitude());
// Compound Ikin controller: Compute the joint angles
// //ComputeKinematics();
// Compute the torques to keep the position
// //DirectComplianceControl(0);
}
break;
}
}
/*---------------------------------------------------------------------- SIDE APPROACH ------------------------------------------------------------------------*/
else if(approach==SideApproach || approach==FailureCharacerization)
{
switch (State)
{
/*-------------------------------------------------- Approach --------------------------------------------------*/
case hsaApproach:// Move, such that the TCP makes contact with the docking pivot in the male camera part at an angle.
{
// Initialize
if(ctrlInitFlag)
{
#ifdef DEBUG_PLUGIN3
std::cerr << "State 1 in AssemblyStrategy::StateMachine" << std::endl;
#endif
// In this first step ensure that the original end-effector position and orientation are set correctly
EndEff_r_org = rpyFromRot(rot);
wrist_r = EndEff_r_org;
EndEff_p_org = pos;
wrist_p = EndEff_p_org;
#ifdef DEBUG_PLUGIN3
std::cerr << "/*******************************************************************************************\n"
"The original position of the EndEffector is: " << wrist_p(0) << "\t" << wrist_p(1) << "\t" << wrist_p(2)
<< "\t" << wrist_r(0) << "\t" << wrist_r(1) << "\t" << wrist_r(2) <<
"\n*******************************************************************************************/" << std::endl;
#endif
nextState = false;
ctrlInitFlag = false;
}
// Primitive Ikin controller: Use a preplanned trajectory to move the wrist at an angle until contact.
// DesIKin are hardcoded into the code.
// Output is JointAngleUpdate
ret=ControlCompositions(m_path,bodyPtr,JointAngleUpdate,CurrAngles,approach,IKinComposition,n,DesForce,n6,ErrorNorm1,ErrorNorm2,pos,rot,cur_time,Jacobian,PseudoJacobian);
// 0) Check for state termination.
StateSwitcher(approach,State,ErrorNorm1,ErrorNorm2,pos,rot,CurrAngles,avgSig,cur_time); // Fix to add ErrorNorm2
}
break;
/*-------------------------------------------------- Rotation --------------------------------------------------*/
case hsaRotation: // Rotate until contact
{
// Initialize
if(ctrlInitFlag)
{
#ifdef DEBUG_PLUGIN3
std::cerr << "State 2 in AssemblyStrategy::StateMachine" << std::endl;
#endif
nextState = false;
ctrlInitFlag = false;
// Set up a new trajectory file with current information
ProcessTrajFile(strTrajState2,State,pos,CurRPY,cur_time);
EndEff_p_org = pos;
EndEff_r_org = CurRPY;
}
// Primitive Ikin controller: Use a preplanned trajectory to rotate wrist until further contact
//ret=ControlCompositions(m_path,bodyPtr,JointAngleUpdate,CurrAngles,approach, IKinComposition,n,DesForce,n6,ErrorNorm1,ErrorNorm2,pos,rot,cur_time,Jacobian,PseudoJacobian);
// Or, use a ForceIKinController
// Set a DesForce that pushes down and against the wall of the camera model
#ifdef SIMULATION
/*------------------------ WORLD COORDINATES -------------------------------*/
// +X: Downwards
// +Y: Moves right
// +Z: Moves forward (and a bit left)
DesForce(UP_AXIS) = 1.000*VERTICAL_FORCE;
//DesForce(SIDE_AXIS) = -1.000*HORIZONTAL_FORCE;
DesForce(FWD_AXIS) = -16.000*TRANSVERSE_FORCE;
DesMoment(1) = 3.0*ROTATIONAL_FORCE;
#else
DesForce(UP_AXIS) = 1.375*VERTICAL_FORCE;
//DesForce(SIDE_AXIS) = HORIZONTAL_FORCE;
DesForce(FWD_AXIS) = -20*TRANSVERSE_FORCE;
DesMoment(1) = 2.100*ROTATIONAL_FORCE;
#endif
ret=ControlCompositions(m_path,bodyPtr,JointAngleUpdate,CurrAngles,approach,ForceMomentComposition,DesForce,DesMoment,n6,ErrorNorm1,ErrorNorm2,pos,rot,cur_time,Jacobian,PseudoJacobian);
// Check for state termination. Also free allocated resources.
StateSwitcher(approach,State,ErrorNorm1,ErrorNorm2,pos,rot,CurrAngles,avgSig,cur_time);
}
break;
/*-------------------------------------------------- Compliant Insertion Controller --------------------------------------------------*/
case hsaInsertion:
{
// Initialize
if(ctrlInitFlag)
{
#ifdef DEBUG_PLUGIN3
std::cerr << "State 3 in AssemblyStrategy::StateMachine" << std::endl;
#endif
nextState = false;
ctrlInitFlag = false;
}
/*------------------------ WORLD COORDINATES -------------------------------*/
// Set a DesForce that pushes down stronger and still rotates.
// +X: Downwards
// +Y: Moves right
// +Z: Moves forward (and a bit left)
#ifdef SIMULATION
DesForce(UP_AXIS) = 1.300*VERTICAL_FORCE;
DesForce(SIDE_AXIS) = 2.000*HORIZONTAL_FORCE;
DesForce(FWD_AXIS) = -13.000*TRANSVERSE_FORCE; // DesForce(FWD_AXIS) =-13.0*TRANSVERSE_FORCE*( pow(CurrAngles(4),2)/pow(1.5708,2) ); // backwards pushing force that counters the forward motion cause by the forward rotation (jacobian effect)
DesMoment(1) = 3.750*ROTATIONAL_FORCE;
#else
DesForce(UP_AXIS) = VERTICAL_FORCE;
// DesForce(SIDE_AXIS) = HORIZONTAL_FORCE;
DesForce(FWD_AXIS) = -20*TRANSVERSE_FORCE;
DesMoment(1) = 4*ROTATIONAL_FORCE;
#endif
ret=ControlCompositions(m_path,bodyPtr,JointAngleUpdate,CurrAngles,approach,ForceMomentComposition,DesForce,DesMoment,n6,ErrorNorm1,ErrorNorm2,pos,rot,cur_time,Jacobian,PseudoJacobian);
// Check for state termination. Also free allocated resources.
StateSwitcher(approach,State,ErrorNorm1,ErrorNorm2,pos,rot,CurrAngles,avgSig,cur_time);
}
break;
/*-------------------------------------------------- SubInsertionStage --------------------------------------------------*/
// Introduced in 2013Aug to deal with lack of empalement at end. Contains the same information that was formally used in the hsaMating state.
case hsaSubInsertion: // Only push down
{
// Initialize
if(ctrlInitFlag)
{
#ifdef DEBUG_PLUGIN3
std::cerr << "State 3b: in AssemblyStrategy::StateMachine" << std::endl;
#endif
nextState = false;
ctrlInitFlag = false;
//SA_S4_Height = pos(2);
}
// Set a DesForce that pushes down and against the wall of the camera model
//--------------------------------------------------------------------------
// Linux
//DesForce(UP_AXIS) = 1.25*VERTICAL_FORCE; // In world coordinates
//DesForce(FWD_AXIS) = -6.0*TRANSVERSE_FORCE*((pos(2)-0.0728)/(SA_S4_Height-0.0728)); // same as above but weaker backwards pushing. the push decreases as the rotation decreases and the snaps push in.
//DesForce(SIDE_AXIS) = HORIZONTAL_FORCE/10.0;
// QNX
//DesForce(UP_AXIS) = VERTICAL_FORCE; // In world coordinates
//DesForce(FWD_AXIS) = TRANSVERSE_FORCE; //
#ifdef SIMULATION
DesForce(UP_AXIS) = 1.5000*VERTICAL_FORCE;
//DesForce(SIDE_AXIS) = 0.000*HORIZONTAL_FORCE;
//DesForce(FWD_AXIS) = -13.000*TRANSVERSE_FORCE; // DesForce(FWD_AXIS) =-13.0*TRANSVERSE_FORCE*( pow(CurrAngles(4),2)/pow(1.5708,2) ); // backwards pushing force that counters the forward motion cause by the forward rotation (jacobian effect)
#else
DesForce(UP_AXIS) = 3*VERTICAL_FORCE;
DesForce(FWD_AXIS) = -20*TRANSVERSE_FORCE;
#endif
// DesForce(SIDE_AXIS) = HORIZONTAL_FORCE;
//--------------------------------------------------------------------------
ret=ControlCompositions(m_path,bodyPtr,JointAngleUpdate,CurrAngles,approach,MomentForceComposition,DesMoment,DesForce,n6,ErrorNorm1,ErrorNorm2,pos,rot,cur_time,Jacobian,PseudoJacobian);
// Check for Approach termination condition
ret=StateSwitcher(approach,State,ErrorNorm1,ErrorNorm2,pos,rot,CurrAngles,avgSig,cur_time);
break;
}
case hsaMating:
{
// 2013Aug. When mating takes place under current simulation circumstances, there is penetration from the male snap into the walls of the female snap.
// So even when no force is applied, the simulation produces a jittery effect that is seen as very high noise and large force jumps in the plots.
// This exponential decay for the force values registered by the FT sensor are an attempt to reproduce the decay that would take place upon proper mating.
avgSig = avgSig * exp(-cur_time/2.5);
ret=StateSwitcher(approach,State,ErrorNorm1,ErrorNorm2,pos,rot,CurrAngles,avgSig,cur_time);
if(ret==PA_FINISH)
exit;
}
break;
// case hsaFinsih
}
}
else
return -1;
/***************************************************************** Write data to file ***********************************************************************************/
// if state 1 or 2, return the endeffector (handPos) position, if state 3 or 4 return handpos<-wrist2endeffector
if(DB_WRITE)
{
if(approach==SideApproach || approach==FailureCharacerization)
{
vector3 handRPY;
vector3 handPos;
vector3 tempForce;
vector3 tempMoment;
vector3 temp1,temp2;
dvector6 transformedForce;
/***************************** Force/Moment ********************************/
// Copy forces in world coordinates to local variable
for(int i=0;i<3;i++)
{
tempForce(i) = avgSig(i);
tempMoment(i) = avgSig(i+3);
}
// Transform to local coordinates
temp1 = rot*tempForce;
temp2 = rot*tempMoment;
// Copy to 6 dimensional vector
for(int i=0;i<3;i++)
{
transformedForce(i) = temp1(i);
transformedForce(i+3) = temp2(i);
}
/***************************** Position transformations *************************/
// if(State==1)
// {
for(int i=0;i<3; i++)
handPos(i) = pos(i);
handRPY = rpyFromRot(rot);
// }
/* else
{
handPos = m_path->joint(5)->p;
//handRPY = rpyFromRot(m_path->joint(5)->attitude()); // Used in linux simulations
handRPY = rpyFromRot(m_path->joint(5)->segmentAttitude());
}*/
WriteFiles(cur_time, // Current time
CurrAngles, // Current robot joint angles
JointAngleUpdate, // Changes in Joint Angles in the last iteration
handPos, // Current end-effector Cartesian position
handRPY, // Current end-effector RPY
transformedForce); // Current end-effector force and moments.
}
// Timing
if(DB_TIME)
{
// Get end time
gettimeofday(&endTime,NULL);
// Compute duration
duration = (double)(endTime.tv_sec - startTime.tv_sec) * 1000.0; // Get from sec to msec
duration += (double)(endTime.tv_usec - startTime.tv_usec) / 1000.0; // From usec to msec
// Print out the duration of the function
#ifdef DEBUG_PLUGIN3
std::cerr << "Duration of AssemblyStrategy::StateMachine() is: " << duration << "ms." << std::endl;
#endif
}
#ifdef DEBUG_PLUGIN3
std::cerr << "Exiting AssemblyStrategy::StateMachine" << std::endl;
#endif
}
return ret;
}
/************************************************* Control Basis Methods *********************************************************************/
// Drive the kind of Ctrl Strategy that you want to accomplish.
// A control policy is selected according to the ctrlComp type. One can choose from:
// - IKinComposition - inverse kinematics controlled composition
// - ForceComposition - Use jacobian transpose control to drive force control
// - MomentForceComposition - Compound controller that optimizes moment controller over force control
// All desired forces and moments are first given in world coordinates and later changed to local wrist coordinates
//
// Inputs:
// JointPathPtr - object that contains information from shoulder to wrist. Can call kinematic routines.
// BodyPtr - object that contains information about the whole body of HIRO
// CtrlStrategy - Select between StraightLineApproach/PivotApproach and other future methods
// ctrlComp - the type of control composition to executed
// DesData1/2 - ControlBasis operates on the basis of two maximum desired quantities at a time
// DesIkin - Used in the IkinComposition
// ErrorNorm1/2 - returned by ControlBasis class for primtive/compound compositions respectively
// pos - incoming is the base-to-end effector position. when updated by the inverse kinematics it shifts to represent base-to-wrist position
// rot - rotation matrix with similar properties as pos
// cur_time - approximate value of control sampling time
//
// Outputs:
// The JointAngleUpdate's are passed by reference as well as the updated CurrAngles.
//
// Notes:
// More compositions were originally developed in my original project working with the PA10 and using OpenHRP-3.1.0 and OpenHRP-3.1.2-Release.
// You can find more compositions there under the sample/controller/PA10Controller2a folder, they need to be slightly adapted to work in this code per the code below.
// Juan Rojas. April 2012.
/********************************************************************************************************************************************/
int AssemblyStrategy::ControlCompositions(JointPathPtr m_path, // Contains kinematics calls for arm 6 DoF
BodyPtr bodyPtr, // Contains angles/path for 15 DoF
dvector6& JointAngleUpdate, // Joint angle update as a result of des angles - actual angles
dvector6& CurrAngles, // Current joint angles
CtrlStrategy strat, // Strategy type: pivot approach or straight line
ctrlComp type, // Type of controller