-
Notifications
You must be signed in to change notification settings - Fork 3
/
hiroArm.cpp
executable file
·2288 lines (1972 loc) · 73.8 KB
/
hiroArm.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
/** This class is called by forceSensorPlugin_impl
* @file hiroArm.cpp
* @brief arm class for HIRO
* @author Natsuki Yamanobe
* @date 2011/02/16
* @note
*/
//----------------------------------------------------------------------------------------------------------------------------------------------------
// Includes
//----------------------------------------------------------------------------------------------------------------------------------------------------
#include "hiroArm.h"
//----------------------------------------------------------------------------------------------------------------------------------------------------
// Namespaces
//----------------------------------------------------------------------------------------------------------------------------------------------------
using OpenHRP::dmatrix;
using std::pow;
using std::sqrt;
using std::exp;
using std::ceil;
//----------------------------------------------------------------------------------------------------------------------------------------------------
// DEFINITIONS
//----------------------------------------------------------------------------------------------------------------------------------------------------
// Directories
//----------------------------------------------------------------------------------------------------------------------------------------------------
// Main Directories
#define READ_DIR "./data/PivotApproach"
#define WRITE_DIR "./data/Results"
// To Read Data
#define SL_APPROACH_FILE "/PA10/pivotApproachState1.dat" // Waypoints for State1 in StraightLineApproach for the PA10 Robot
#define PIVOT_APPROACH_FILE "/PA10/PA10_pivotApproachState1.dat" // Waypoints for State1 in PivotApproach for the PA10 Robot
#define SIDE_APPROACH_FILE "/HIRO/sideApproachState1.dat" // Waypoints for State1 in SideApproach for the HIRO Robot
#define FAILURE_CHARAC_FILE "/FC/failureCaseXDir.dat" // Waypoints for State1 in FailureCase. Three files: failureCaseXDir.dat, failureCaseYDir.dat, and failureCaseRollDir.dat
//----------------------------------------------------------------------------------------------------------------------------------------------------
// To Write Data (used in AssemblyStrategy::OpenFiles)
#define ANGLES_FILE "/R_Angles.dat" // Save joint angles of robot
#define CARTPOS_FILE "/R_CartPos.dat" // Save CartPos of End-Effector in world coordinates
#define STATE_FILE "/R_State.dat" // Save State Transition times for SideApproach
#define FORCES_FILE "/R_Torques.dat" // Save Joint Torques for robot
#define MANIP_TEST_FILE "/manipulationTestAxis.dat" // Used to test force and moment controllers behavior
//----------------------------------------------------------------------------------------------------------------------------------------------------
// DEBUGGING
//----------------------------------------------------------------------------------------------------------------------------------------------------
#define DB_TIME 0 // Used to print timing duration of functions
//----------------------------------------------------------------------------------------------------------------------------------------------------
// TEST MODE
//----------------------------------------------------------------------------------------------------------------------------------------------------
#define TEST 0 // If true, a test is activated to see the response of the force/moment controllers. Reads an int from file to known which axis to activate.
//----------------------------------------------------------------------------------------------------------------------------------------------------
// CONTROL METHODS
//----------------------------------------------------------------------------------------------------------------------------------------------------
#define USE_MOTION_DAT 0 // Should be zero if used with control basis approach or reading a trajectory from file
#define CONTROL_BASIS 1 // If using the control basis approach
//----------------------------------------------------------------------------------------------------------------------------------------------------
// ASSEMBLY STRATEGY TYPES
//----------------------------------------------------------------------------------------------------------------------------------------------------
#define STRAIGHT_LINE_FLAG 0 // Masking Flags to determine which trajectory to choose
#define PIVOT_APPROACH_FLAG 0 // Pivot approach. If true, STRAIGHT_LINE_FLAG=0,SIDE_APPROACH_FLAG=0, FAILURE_CHARAC_FLAG=0.
#define SIDE_APPROACH_FLAG 1 // Similar to PivotApproach but no alignment. If true, STRAIGHT_LINE_FLAG=0,PIVOT_APPROACH_FLAG=0,FAILURE_CHARAC_FLAG=0.
#define FAILURE_CHARAC_FLAG 0 // Uses params from SideApproach. If true, STRAIGHT_LINE_FLAG=0,PIVOT_APPROACH_FLAG=0,SIDE_APPROACH_FLAG=0.
//----------------------------------------------------------------------------------------------------------------------------------------------------
#define STRAIGHT_LINE_APPROACH 1 // Numbers assigned in correlation to the enumeration CtrlStrategy in AssemblyStrategy.h
#define PIVOT_APPROACH 2
#define SIDE_APPROACH 3
#define FAILURE_CHARAC 4
//----------------------------------------------------------------------------------------------------------------------------------------------------
// ASSIGN VARIABLES TO BE USED WITH PA->INITIALIZE(...)
//----------------------------------------------------------------------------------------------------------------------------------------------------
#if(USE_MOTION_DAT==0) //I.e. We are using the control basis approach, then choose between strategies. File name assigned during constructor to private member.
// (A) Define the Control Strategy
#define CONTROL_TYPE CONTROL_BASIS
// (B) Define the Assembly Strategy
#if(STRAIGHT_LINE_FLAG)
#define MOTION_FILE SL_APPROACH_FILE
#define APPROACH_TYPE STRAIGHT_LINE_APPROACH
#elif(PIVOT_APPROACH_FLAG)
#define MOTION_FILE PIVOT_APPROACH_FILE
#define APPROACH_TYPE PIVOT_APPROACH
#elif(SIDE_APPROACH_FLAG)
#define MOTION_FILE SIDE_APPROACH_FILE
#define APPROACH_TYPE SIDE_APPROACH
#elif(FAILURE_CHARAC_FLAG)
#define MOTION_FILE FAILURE_CHARAC_FILE
#define APPROACH_TYPE FAILURE_CHARAC
#endif
#else
#define CONTROL_TYPE USE_MOTION_DAT
#endif
//----------------------------------------------------------------------------------------------------------------------------------------------------
// Constructor Definition : Variable Initialisation List
//----------------------------------------------------------------------------------------------------------------------------------------------------
hiroArm::hiroArm(std::string name_in, BodyPtr body_in, unsigned int num_q0_in, double period_in, float ang_limits_in[6][5], vector3 ePh_in, matrix33 eRh_in, vector3 hPfs_in)
:f_moving(false), f_reached(false), initFlag(false), m_time(0),
f_gc(false), f_gc_init(false), step_gc(0), fp1(NULL),
mass(0.0), GACC(9.8), wait_step(200), fp2(NULL),
/*fs(0),*/ step_fs(0), max_step_fs(500), fp3(NULL),
MAX_JVEL(0.5), TIME_LIMIT(100.0), MIN_PERIOD(1.0e-9), TOLERANCE(1.0e-6)
{
#ifdef DEBUG_PLUGIN2
std::cerr << "hiroArm(): Entering hiroArm constructor" << std::endl;
#endif
// Save to local members
name = name_in; // Right or left arm
body = body_in; // Body object extracted from ModelLoader
NUM_q0 = num_q0_in; // Which joint is the starting joint. Right arm=3, Left arm=9
DEL_T = period_in; // Time step set at 0.0005 secs in calling function
for(int i = 0; i < ARM_DOF; i++){
for(int j = 0; j < 5; j++){
ang_limits[i][j] = ang_limits_in[i][j]; // Set angle limits
}
}
// Arms' Current state
ePh = ePh_in; // Wrist 2 End Effector Left: <0.0715, 0.0, 0.0>, Right: <-0.12,0.0,0.0>
eRh = eRh_in; // Equivalent Rotation matrix. Set to the identity matrix.
hPfs = hPfs_in; //
#ifdef DEBUG_PLUGIN2
std::cerr << "hiroArm(): Setting body links." << std::endl;
#endif
// Set Body linksOB
//Link* S0 = body->link(CHEST_JOINT); // SO link starts at the chest joint. It's the first link, then two for the head, then six for the right arm, then six for the left arm
Link* S0 = body->joint(CHEST_JOINT0);
//Link* W6 = body->joint(NUM_q0 + ARM_DOF - 1); // The wrist occurs six links later (i.e.start+6-1).
Link* W6;
if(NUM_q0 == RARM_JOINT0)
W6 = body->joint(RARM_JOINT5); // Is it joint or link?
else
W6 = body->joint(LARM_JOINT5); // Is it joint or link?
if(!S0)
std::cerr << "S0 is null\n";
if(!W6)
std::cerr << "W6 is null\n";
#ifdef DEBUG_PLUGIN2
std::cerr << "hiroArm(): Getting the joint path." << std::endl;
#endif
m_path = body->getJointPath(S0,W6); // Base to Wrist Path
#ifdef DEBUG_PLUGIN2
cout << "Joint path:" << m_path->numJoints() << std::endl;
cerr << m_path->joint(0)->name << std::endl;
cerr << m_path->joint(1)->name << std::endl;
cerr << m_path->joint(2)->name << std::endl;
cerr << m_path->joint(3)->name << std::endl;
cerr << m_path->joint(4)->name << std::endl;
cerr << m_path->joint(5)->name << std::endl;
#endif
#if 0
m_path->setMaxIKIter(200); // Maximum limit of iterations to numerically compute the inverse kinematics
#endif
// Inverse Kinematics gains for
ikGains[0] = 0.3;
ikGains[1] = 0.6;
ikGains[2] = 0.7;
ikGains[3] = 0.8;
ikRot[0] = 1e-2;
ikRot[1] = 1e-7;
ikRot[2] = 1e-8;
ikRot[3] = 1e-10;
ikTrans[0] = 1e-2;
ikTrans[1] = 1e-7;
ikTrans[2] = 1e-8;
ikTrans[3] = 1e-10;
// Program Design Parameters
p_param.method = CONSTANT_VELOCITY; // Interpolation Method: Velocity
p_param.max_jvel = MAX_JVEL; // With MAX_JVEL as maximum joint velocity limit = 0.5
controlmode = NOCONTROL; // One of six control modes. No control.
//******************************************** Pivot Approach ***********************************************************************/
// Takes the following parameters int NUM_q0, vector3 base2endEffectorPos, matrix33 base2endEffectorRot, dmatrix jacobian, double curr_time, vector6 curr_force
vector3 pos(0);
matrix33 rot;//x(0);
double momentGainFactor = 10.0; // Used to scale the gain for the control basis for the moment.
#ifdef DEBUG_PLUGIN2
std::cerr << "hiroArm(): Getting current position and attitude values" << std::endl;
#endif
#ifdef DEBUG_PLUGIN2
std::cerr << "hiroArm(): Retrieving the position" << std::endl;
#endif
// HOMING Position and rotation matrix for right arm's WRSIT
// Right arm's last joint is joint 8 (index starts at 0, chest pan tilt...)
pos=m_path->joint(5)->p; // instead of RARM_JOINT5 i had 5 before.
#ifdef DEBUG_PLUGIN2
std::cerr << "hiroArm(): Position retrieved" << std::endl;
#endif
#ifdef DEBUG_PLUGIN2
std::cerr << "hiroArm(): Retrieving the attitude." << std::endl;
#endif
//rot=m_path->joint(5)->attitude(); // used in linux simulation
rot=m_path->joint(5)->segmentAttitude(); // Instead of RARM_JOINT5 I had a 5 before.
#ifdef DEBUG_PLUGIN2
std::cerr << "hiroArm(): Attitude retrieved." << std::endl;
#endif
#ifdef DEBUG_PLUGIN2
std::cerr << "hiroArm(): Allocating AssemblyStrategy" << std::endl;
#endif
// Pivot Approach variables
PA = new AssemblyStrategy(NUM_q0,pos,rot,ePh,momentGainFactor); // Wrist position, Wrist Rotation Matrix, Wrist2EndEffXform
#ifdef DEBUG_PLUGIN2
std::cerr << "hiroArm(): Finished allocating AssemblyStrategy" << std::endl;
#endif
#ifdef DEBUG_PLUGIN2
std::cout << "hiroArm: exit constructor" << std::endl;
#endif
}
// Destructor
hiroArm::~hiroArm()
{
fclose(fp1);
fclose(fp2);
fclose(fp3);
}
/*************************************************************************************************************/
// Init()
/*************************************************************************************************************/
void hiroArm::init()
{
update_currposdata();
rPh_ref = rPh;
rRh_ref = rRh;
q_ref = q;
}
/*************************************************************************************************************/
// init(vector3 pos, matrix33 rot, double CurAngles[15])
// Initialization Routine for a selected arm. Compute the position vector and rotation matrix from base to end effector
// Different behavior according to user.
// Kensuke: Open position and force data for left and right arms.
// Yamanobe: reads force, position, and velocity information.
/*************************************************************************************************************/
int hiroArm::init(vector3 pos, matrix33 rot, double CurAngles[15])
{
// Local variables
#ifdef DEBUG_PLUGIN2
std::cerr << "\nhiroArm::init - entered" << std::endl;
#endif
int ret = 0;
#ifdef PIVOTAPPROACH
//******************************************** Pivot Approach ***********************************************************************/
/*************************************** Initialize Strategy ***************************************/
// PA can use three optional user specified files to read or write information (designed for one arm):
// Read: Trajectory File - Reads Trajectory.
// Write: State File - writes times at which new states start.
// Forces File - writes forces and moments experienced by the simulation
// If no arguments are passed, the files can be found at:
// /home/hrpuser/forceSensorPlugin_Pivot/data/PivotApproach/
// Path trunk
// Folder where robot joint angles, cart. position, and forces will be saved and desired trajectory read from.
// Assign path trunk to each of the FIVE char variables
strcpy(TrajState1, READ_DIR);
strcpy(TrajState2, READ_DIR);
strcpy(manipTest, READ_DIR);
strcpy(Angles, WRITE_DIR);
strcpy(CartPos, WRITE_DIR);
strcpy(State, WRITE_DIR);
strcpy(Forces, WRITE_DIR);
// Concatenate with appropriate endings
strcat(TrajState1, MOTION_FILE); // Desired Trajectory
strcat(TrajState2, "/PA10/PA10_pivotApproachState2.dat"); // Desired Trajectory
strcat(manipTest, MANIP_TEST_FILE); // What test axis do you want to try
strcat(Angles, ANGLES_FILE); // Robot Joint Angles
strcat(CartPos, CARTPOS_FILE); // Cartesian Positions
strcat(State, STATE_FILE); // New States Time Occurrence
strcat(Forces, FORCES_FILE); // Robot Forces/Moments
// Initialize AssemblyStrategy Class:
// 1) Open files associated with the directories to read/write data
// 2) Assign homing Cartesian Position, Joint Angles, and Rotation matrix position.
// 3) Assign Motion and Control Strategies
// 4) Declare and Allocate Filtering Object (consider using a static object instead for faster real-time performance).
ret=PA->Initialize(TrajState1,TrajState2,Angles,CartPos,State,Forces, // Data Directories
pos, rot, CurAngles, // Homing Data
APPROACH_TYPE, CONTROL_TYPE); // Assembly Strategy and Control Method Used
#endif
// Compute the current position vector and rotation matrix from base to end effector and current joint angles.
update_currposdata();
rPh_ref = rPh; // Base2EndEff position translation
rRh_ref = rRh; // Base2EndEff rotation matrix
q_ref = q; // At home joint angles
#ifdef DEBUG_PLUGIN2
std::cerr << "\nhiroArm::init - exited" << std::endl;
#endif
return ret;
}
void hiroArm::savedata()
{
// Initialization
vector3 tmp = OpenHRP::rpyFromRot(rRh); // Get RPY terms for the wrist
// Hand (not arm) Gravity Compensation terms for force and moment
fprintf(fp1,"%f %f %f %f %f %f\n", rFh_gc[0], rFh_gc[1], rFh_gc[2], rMh_gc[0], rMh_gc[1],rMh_gc[2]);
fprintf(fp2,"%f %f %f %f %f %f %f %f %f %f %f %f %f %f %f\n",rPh[0], rPh[1], rPh[2], // Position translation from base 2 end effector
tmp[0], tmp[1], tmp[2], // RPY terms
rRh(0,0),rRh(0,1),rRh(0,2), // Rotation matrix terms for base 2 end effector
rRh(1,0),rRh(1,1),rRh(1,2),
rRh(2,0),rRh(2,1),rRh(2,2));
/*printf(fp1,"%f %f %f %f %f %f\n",rFfs_gc[0],rFfs_gc[1],rFfs_gc[2],rMfs_gc[0],rMfs_gc[1],rMfs_gc[2]); arm terms
vector3 tmp = OpenHRP::rpyFromRot(rRh);
fprintf(fp2,"%f %f %f %f %f %f %f %f %f %f %f %f %f %f %f\n",rPh[0],rPh[1],rPh[2],tmp[0],tmp[1],tmp[2], rRh(0,0),rRh(0,1),rRh(0,2), rRh(1,0),rRh(1,1),rRh(1,2), rRh(2,0),rRh(2,1),rRh(2,2));
*/
}
/*******************************************************************************************************
// get_name()
// Return whether right or left arm
*******************************************************************************************************/
std::string hiroArm::get_name() { return name; }
/********************************************************************************
* update_currposdata()
* Update current arm configuration by:
* First, retreving:
* The wrist position,
* The base2wrist rotation, and
* The current joint angles of the body
* Second, by computing the:
* base2EndEffectorPosition
*********************************************************************************/
void hiroArm::update_currposdata()
{
// base2wrist position. Homing pos: <0.3019, -0.1724, 0.064>
rPe = body->joint(NUM_q0 + ARM_DOF -1)->p;
#ifdef DEBUG_PLUGIN2
cerr << "hiroArm::updated_currposdata - rPe is: " << rPe(0) << " " << rPe(1) << " " << rPe(2) << std::endl;
#endif
// base2wrist rotation matrix
rRe = body->joint(NUM_q0 + ARM_DOF -1)->segmentAttitude();
// Current joint angles
for(int i=0; i<ARM_DOF; i++)
q[i] = body->joint(NUM_q0 + i)->q;
wrist2EndEffXform(/*in*/rPe, /*in*/rRe, /*out*/rPh, /*out*/rRh);
#ifdef DEBUG_PLUGIN2
cerr << "hiroArm::updated_currposdata - rPh is: " << rPh(0) << " " << rPh(1) << " " << rPh(2) << std::endl;
#endif
}
/********************************************************************************
* wrist2EndEffXform()
* Takes the base2wrist position and rotation and transforms them to base2endeff
* position and orientation
*********************************************************************************/
void hiroArm::wrist2EndEffXform(/*in*/vector3 rPe, /*in*/matrix33 rRe, /*out*/vector3& rPh, /*out*/matrix33& rRh)
{
// base2EndEffector
// Caculation rPh & rRh from rPe & rRe
rRh = rRe * eRh; // base2EndEffRot=base2wristRot*wrist2EndEffRot
rPh = rPe + rRe * ePh; // base2EndEffPos=base2wristPos + transformed wrist2EndEffPos
}
/********************************************************************************
* wrist2EndEffXform()
* Takes the base2wrist position and rotation and transforms them to base2endeff
* position and orientation
*********************************************************************************/
void hiroArm::EndEff2wristXform(/*in*/vector3 rPh, /*in*/matrix33 rRh, /*out*/vector3& rPe)
{
// base2EndEffector
// Caculation rPh & rRh from rPe & rRe
rPe = rPh - rRe * ePh; // base2EndEffPos=base2wristPos + transformed wrist2EndEffPos
}
/*******************************************************************************************************
// get_qref()
// Retrieve reference joint angle in degrees
*******************************************************************************************************/
dvector6 hiroArm::get_qref()
{
#ifdef DEBUG_PLUGIN2
std::cout << "q_ref in hiroArm::get_qref: " << q_ref*180/M_PI << std::endl;
#endif
return q_ref;
}
/*******************************************************************************************************
// get_qcur()
// Retrieve currentjoint angle in degrees
*******************************************************************************************************/
dvector6 hiroArm::get_qcur()
{
#ifdef DEBUG_PLUGIN2
std::cout << "q_ref in get_qref: " << q_ref*180/M_PI << std::endl;
#endif
return q;
}
/*******************************************************************************************************
// update_currforcedata()
// Return latest force and moment data.
// If gravitational compensation is consider, it uses that information to compute the latest values
*******************************************************************************************************/
void hiroArm::update_currforcedata()
{
// update current force-moment data
// if(fs != 0)
// {
double f_out[6];
// A) Read raw forces
//get_raw_forces(f_out); // Updated Aug 2012 for OldHiro
ifs_read_data(0,f_out);
// B) Separate them into force and moment
for(int i=0; i<3; i++)
{
fsF_raw[i] = f_out[i];
fsM_raw[i] = f_out[i+3];
}
// If gravitational component flag is true
if(f_gc)
{
// Calculate the hand's gravitational force and moment
calc_gc_forces(rFfs_gc, rMfs_gc); // Arm's force and moment
calc_gc_forces_at_hand(rFh_gc, rMh_gc); // Hand's force and moment
}
// }
}
#if 0
/******************************************************************************************************/
// set_FSptr()
// Set the Force Sensor pointer from the niitaFs class. Give an identifier for left and right arms.
// Left arm has id 0.
/******************************************************************************************************/
void hiroArm::set_FSptr(nittaFS *fs_in, int NO_fs_in)
{
fs = fs_in;
NO_fs = NO_fs_in;
}
#endif
/*******************************************************************************************************
// get_forces()
// Retrieve the HAND's gravity compensation terms for force and moment
*******************************************************************************************************/
bool hiroArm::get_forces(vector3 &rFh_gc_out, vector3 &rMh_gc_out)
{
if(f_gc)
{
rFh_gc_out = rFh_gc; // force
rMh_gc_out = rMh_gc; // moment
return true;
}
else return false;
}
/*******************************************************************************************************
// get_curr_handpos()
// Retrieve the HAND's position translation vector and rotation matrix from base to end-effecter
*******************************************************************************************************/
void hiroArm::get_curr_handpos(vector3 &rPh_out, matrix33 &rRh_out){
rPh_out = rPh; // base2endeffecter translation vector
rRh_out = rRh; // base2endeffecter rotation matrix
}
/*******************************************************************************************************
// set_ref_handpos()
// Write the HAND's reference position translation vector and rotation matrix from base to end-effecter
*******************************************************************************************************/
void hiroArm::set_ref_handpos(vector3 rPh_ref_in, matrix33 rRh_ref_in)
{
rPh_ref = rPh_ref_in; // position
rRh_ref = rRh_ref_in; // rotation
}
/*******************************************************************************************************
// get_ref_handpos()
// Retrieve the HAND's reference position translation vector and rotation matrix from base to end-effecter
*******************************************************************************************************/
void hiroArm::get_ref_handpos(vector3 &rPh_ref_out, matrix33 &rRh_ref_out)
{
rPh_ref_out = rPh_ref;
rRh_ref_out = rRh_ref;
}
/*******************************************************************************************************
// get_Iteration()
// Retrieve the current iteration of the simulation
*******************************************************************************************************/
unsigned long hiroArm::get_Iteration()
{
return m_time;
}
/*******************************************************************************************************
// set_Iteration()
// Increase iteration by one
*******************************************************************************************************/
void hiroArm::set_Iteration()
{
m_time++;
}
/*******************************************************************************************************
// velocity_control()
// Used in Bilateral control.
// Takes in rdP, rate of change in position; rW, rate of change in orientation.
*******************************************************************************************************/
bool hiroArm::velocity_control(vector3 rdP, vector3 rW, bool f_new)
{
// If NOT vel control or NOT new, assign base2endeffector pos/rot, reference angles, and set to vel control
if((controlmode != VEL_CONTROL) || f_new)
{
rPh_ref = rPh;
rRh_ref = rRh;
q_ref = q;
controlmode = VEL_CONTROL;
}
// 1) Calculate the next step joint-angle using the Jacobian.
dvector6 q_next, dq;
dvector6 dx; // velocity at the arm end frame
// Change the input velocity from endeffector to wrist
vector3 rdPe, rWe; // base-to-wrist
rWe = rW;
rdPe = rdP + cross(rW, (rRe*(-ePh)));
for(int i=0; i<3; ++i)
{
dx(i) =rdPe(i); // Lin Velocity at wrist
dx(i+3) =rWe(i); // Angular Velocity at Wrist
//~ dx(i)=rdP(i);
//~ dx(i+3)=rW(i);
}
//~ fprintf(fp3,"%f %f %f %f %f %f %f %f %f %f %f %f %f %d %d %d:: %f %f %f %f %f %f:: %f %f %f %f %f %f\n",rdP(0),rdP(1),rdP(2),rW(0),rW(1),rW(2), dx(0),dx(1),dx(2),dx(3),dx(4),dx(5), suprate,jlimit,lim_tmp,mability,q(0),q(1),q(2),q(3),q(4),q(5),q_ref(0),q_ref(1),q_ref(2),q_ref(3),q_ref(4),q_ref(5));
// 2) Check angular velocity limit
double suprate = 1; // Suppression rate. Change the value of dx for each iteration of computation
int supflag = 0; // Flag: Joint angles surppased
int supexit = 1; // While loop flag
dmatrix jacob(6,6), inv_jacob(6,6);
// Compute the Jacobian and the Pseudoinverse
jacob = m_path->Jacobian(); //inv_jacob = OpenHRP::inverse(jacob);
bool ret = OpenHRP::calcPseudoInverse(jacob, inv_jacob,1.0e-18);
// Check if correct
if(ret !=0)
{
std::cout << "ERROR(velocity_control): calcPseudoInverse ret = " << ret << std::endl;
return false;
}
// 3) Calculate the next step joint-angle
while(supexit)
{
// Joint-Angle Step = inv_Jacobian*Velocity Step
//~ dq = prod(OpenHRP::inverse(m_path->Jacobian()),dx);
dq = prod(inv_jacob, dx);
// Check angle limits for each axis
for(int i=0; i<ARM_DOF; i++)
{
// If limits surpased
if(fabs(dq(i)) > ang_limits[i][2])
{
//~ if(fabs(dq(i)) > MAX_JVEL){
supflag=1;
#ifdef DEBUG_PLUGIN2
std::cout << "dq = " << dq << std::endl;
std::cout << "suprate = " << suprate << std::endl;
#endif
}
// if(fabs(nextdth(i)) > 5*deg2radC) supflag=1;
}
// Update the suppresion value used to update the step velocity parameter
if(supflag)
{
suprate -= 0.1;
supflag = 0;
}
// An admissible computation for the next step joint-angle has been achieved
else
supexit=0;
dx = suprate * dx;
}
//~ std::cout<< "jacob: " << jacob << std::endl;
//~ std::cout<< "inv_jacob: " << inv_jacob << std::endl;
//~ std::cout<< "inv_jacob * jacob: " << prod(inv_jacob,jacob) << std::endl;
//~ std::cout<< "dq" << dq << std::endl;
//~ std::cout<< "jacob*dq" << prod(jacob,dq) << std::endl;
//~ std::cout << std::endl;
// 4) Update the joint angle reference position by adding the step update to the current position
q_next = q_ref + DEL_T * dq;
// 5) Check lower and upper joint limits
bool flag = false;
bool jlimit = true;
// For each axis
for(int i=0; i<ARM_DOF; i++)
{
if(q_next(i) < ang_limits[i][0] || q_next(i) > ang_limits[i][1])
jlimit = false;
}
// If limits have been surpassed, then
if(jlimit)
{
// Check the difference limit between q_next and q_cur
bool jdifflimit = true;
// If the difference is greater than the limit
for(int i=0; i<ARM_DOF; i++)
{
if(fabs(q_next(i)-q(i)) > ang_limits[i][2] * DEL_T)
jdifflimit = false;
}
// If the difference is not greater than the limit:
// We have a singularity. Perform manipulability to avoid the singularity.
if(jdifflimit)
{
// Skip the point and set the joint angle to q_next
// ublas det(,), trans, prod. jacobian is dmatrix type(ublas)
for(int i = 0; i < ARM_DOF; i++)
body->joint(NUM_q0 + i)->q = q_next(i);
// Then compute the forward kinmeatics
body->calcForwardKinematics();
// Compute the determinant of the Jacobian at this new position
//bool mability = true;
double det_value = OpenHRP::det(m_path->Jacobian());
// Recompute Fwd Kinematics for current position
for(int i = 0; i < ARM_DOF; i++)
body->joint(NUM_q0 + i)->q = q(i);
body->calcForwardKinematics();
// If the determinant is not zero,
if(fabs(det_value) > 0.00001)
flag = true;
}
}
// joint limit avoidance // double LAUpLimit[6]={84,114,-1,249,94,124}; // double LALoLimit[6]={-84,-174,-154,-60,-94,-124};
//~ fprintf(fp3,"%f %f %f %f %f %f:: %f %d %d %d:: %f %f %f %f %f %f:: %f %f %f %f %f %f\n",rdP(0),rdP(1),rdP(2),rW(0),rW(1),rW(2), suprate,jlimit,lim_tmp,mability,q(0),q(1),q(2),q(3),q(4),q(5),q_ref(0),q_ref(1),q_ref(2),q_ref(3),q_ref(4),q_ref(5));
fprintf(fp3,"%f %f %f %f %f %f %f %f %f %f %f %f %f %d %f %f %f %f %f %f %f %f %f %f %f %f %f %f\n",
rdP(0),rdP(1),rdP(2), // Position
rW(0),rW(1),rW(2), // Orientation
dx(0),dx(1),dx(2), // Lin Vel
dx(3),dx(4),dx(5), // Rotational Vel
suprate, jlimit, // Params
dq(0), dq(1), dq(2), dq(3), dq(4), dq(5), // Joint Vel
q_next(0), q_next(1), q_next(2), q_next(3), q_next(4), q_next(5)); // Next Joint position
#ifdef DEBUG_PLUGIN2
std::cout << "q_ref = " << q_ref << std::endl;
std::cout << "q = " << q << std::endl;
#endif
// Set the reference joint position to q_next
if(flag)
{
q_ref = q_next;
return true;
}
else
return false;
}
/****************************************************************************************************
// Impedance Control
// Mapping from generalized velocities to generalized forces
** Sets the damping and inertia coefficient values
****************************************************************************************************/
bool hiroArm::impedance_control()
// DSRG's direct teaching function
{
// If control mode is not set to impedance_control mode, correct.
if(controlmode != IMP_CONTROL)
{
rPh_ref = rPh;
rRh_ref = rRh;
controlmode = IMP_CONTROL;
}
// 1a) Set desired inertia and damping factor(for POSITION)
const double Dlh[2]= {100,250}; // Threshold of damping coef.[low, high]
const double vlh[2]= {0.005,0.1}; // Threshold of velocity. [low, high]
double Dxth[3]; // Damping coefficients
double Mxth[3]; // Inertia coefficients With values 5,15,20
#if 1
// double size = sqrt(pow(rdXd(X),2)+pow(rdXd(Y),2)+pow(rdXd(Z),2));
// Norm of velocity. Measure of velocity.
double size = sqrt(pow(rdXd(X),2)+pow(rdXd(Y),2)+pow(rdXd(Z),2));
for(int i=0; i<3; i++)
{
// If the velocity is under our velocity threshold: low velocity zone
if(fabs(size) <= vlh[0])
{
// Set the damping and inertia coefficients
Dxth[i]= Dlh[1];
Mxth[i]=3;
}
// Middle velocity zone
else if(fabs(size) > vlh[0] && fabs(size)< vlh[1] )
{
Dxth[i]= ((Dlh[0]-Dlh[1])/(vlh[1]-vlh[0]))*(fabs(rdXd(i))-vlh[0])+Dlh[1];
Mxth[i]=5;
}
// High velocity zone
else if(fabs(size) >= vlh[1])
{
Dxth[i]= Dlh[0];
Mxth[i]=10;
}
// Other case
else
{
Dxth[i]= Dlh[1];
Mxth[i]=15;
}
}
#endif
// Place coefficients in matrix form
Mt = Mxth[X],0,0, 0,Mxth[Y],0, 0,0,Mxth[Z];
Dt = Dxth[X],0,0, 0,Dxth[Y],0, 0,0,Dxth[Z];
//1b) Set desired inertia and damping factor(for ROTATION)
const double Drlh[2]= {15,40}; // threshold of damping coef.[low, high]
const double vrlh[2]= {0.2,0.7}; // thrheshold of velocity. [low, high]
double Drth[3]; // Damping coefficients for wrist={10,10,10};
double Mrth[3]; // Inertia coefficients for wrist={1,1,1};
#if 1
size = sqrt(pow(rdRd(X),2)+pow(rdRd(Y),2)+pow(rdRd(Z),2));
for(int i=0; i<3; i++)
{
// Low velocity zone
if(fabs(size) <= vrlh[0])
{
Drth[i]= Drlh[1];
Mrth[i]=1;
}
// Middle velocity zone
else if(fabs(size) > vrlh[0] && fabs(size)< vrlh[1] )
{
Drth[i]= ((Drlh[0]-Drlh[1])/(vrlh[1]-vrlh[0]))*(fabs(rdRd(i))-vrlh[0])+Drlh[1];
Mrth[i]=3;
}
// High velocity zone
else if(fabs(size) >= vrlh[1])
{
Drth[i]= Dlh[0];
Mrth[i]=5;
}
// Other
else
{
Drth[i]= Drlh[1];
Mrth[i]=7;
}
}
#endif
// Compile damping and inertia coefficients for rotation into a matrix
Mr = Mrth[X],0,0, 0,Mrth[Y],0, 0,0,Mrth[Z];
Dr = Drth[X],0,0, 0,Drth[Y],0, 0,0,Drth[Z];
/* Mt = 10, 0, 0, 0, 10, 0, 0, 0, 10;
Dt = 100, 0, 0, 0, 100, 0, 0, 0, 100;
Mr = 5, 0, 0, 0, 5, 0, 0, 0, 5;
Dr = 15, 0, 0, 0, 15, 0, 0, 0, 15;*/
// Compute the velocity updates in the position and orientation
for(int i=0;i<3; i++)
{
rdXd(i) = exp((-Dt(i,i)/Mt(i,i))*DEL_T)*rdXd(i)+((1-exp((-Dt(i,i)/Mt(i,i))*DEL_T))/Dt(i,i))*rFfs_gc(i);
rdRd(i) = exp((-Dr(i,i)/Mr(i,i))*DEL_T)*rdRd(i)+((1-exp((-Dr(i,i)/Mr(i,i))*DEL_T))/Dr(i,i))*rMfs_gc(i);
rRd(i) = rdRd(i)*DEL_T;
}
//rRd=ASMRo*rRd;
rPh_ref += rdXd*DEL_T;
rRh_ref = rRh_ref * get_rot33(Z,rRd(Z))*get_rot33(Y,rRd(Y))*get_rot33(X,rRd(X)); //RzRyRx
#ifdef DEBUG_PLUGIN2
std::cout << "direct teaching: " << std::endl;
std::cout << "rdXd = " << rdXd << std::endl;
std::cout << "rFfs_gc = " << rFfs_gc << std::endl;
std::cout << "rMfs_gc = " << rMfs_gc << std::endl;
#endif
// Target hand first position, fortation, and then calculation
// 目標手先位置・姿勢の計算 (rPh_ref, rRh_ref --> rPe_ref, rRe_ref --> q_ref)
// robot2endeffector to robot2wrist
calc_rPe_rRe(rPh_ref, rRh_ref, rPe_ref, rRe_ref);
bool ret;
dvector6 q_ref_tmp;
// Compute reference joint angles
ret = calc_qref(rPe_ref, rRe_ref, q_ref_tmp);
if(ret) q_ref = q_ref_tmp;
#ifdef DEBUG_PLUGIN2
std::cout << "q_ref = " << q_ref << std::endl;
std::cout << "q = " << q << std::endl;
#endif
return ret;
}
#ifdef IMPEDANCE
bool hiroArm::impedance_control2()
{
if(controlmode != IMP_CONTROL)
{
rPh_ref = rPh; // Set the base2wrist parameters as ref params: position
rRh_ref = rRh;
controlmode = IMP_CONTROL; // Change the control mode to impedance control
}
// Inertia and damping matrix coefficients for position/orientation
Mt = 10, 0, 0, 0, 10, 0, 0, 0, 10;
Dt = 100, 0, 0, 0, 100, 0, 0, 0, 100;
Mr = 5, 0, 0, 0, 5, 0, 0, 0, 5;
Dr = 15, 0, 0, 0, 15, 0, 0, 0, 15;
matrix33 Kt, Kr;
Kt = 200, 0, 0, 0, 200, 0, 0, 0, 200;
Kr = 100, 0, 0, 0, 100, 0, 0, 0, 100;
matrix33 Ft, Fr;
Kt = 2, 0, 0, 0, 2, 0, 0, 0, 2;
Kr = 1, 0, 0, 0, 1, 0, 0, 0, 1;
// Desired position and rotation data
vector3 rXd_des, rRd_des, rFd_des, rMd_des;
if(!fin_rpos.eof()) fin_rpos >> rXd_des(0); // Right Pos Data is read in
if(!fin_rpos.eof()) fin_rpos >> rXd_des(1);
if(!fin_rpos.eof()) fin_rpos >> rXd_des(2);
if(!fin_rpos.eof()) fin_rpos >> rRd_des(0); // Right Rot Data is read in
if(!fin_rpos.eof()) fin_rpos >> rRd_des(1);
if(!fin_rpos.eof()) fin_rpos >> rRd_des(2);
for(int i=0; i<9; i++)
{
double t;
fin_rpos >> t;
}
// Desired Force and Moment Data
if(!fin_rfc.eof()) fin_rfc >> rFd_des(0); // Right Force Data is read in
if(!fin_rfc.eof()) fin_rfc >> rFd_des(1);
if(!fin_rfc.eof()) fin_rfc >> rFd_des(2);
if(!fin_rfc.eof()) fin_rfc >> rMd_des(0);
if(!fin_rfc.eof()) fin_rfc >> rMd_des(1);
if(!fin_rfc.eof()) fin_rfc >> rMd_des(2);
// k*pos_error - t*force_error...
for(int i=0;i<3; i++)
{
rdXd(i) = rdXd(i) - (Dt(i,i)*rdXd(i) + Kt(i,i)*(rPh_ref(i) - rXd_des(i)) - Ft(i,i)*(rFfs_gc(i) - rFd_des(i)))/Mt(i,i)*DEL_T; //rdXd(i) = exp((-Dt(i,i)/Mt(i,i))*DEL_T)*rdXd(i)+((1-exp((-Dt(i,i)/Mt(i,i))*DEL_T))/Dt(i,i))*rFfs_gc(i);
rdRd(i) = rdRd(i) - (Dr(i,i)*rdRd(i) + Kr(i,i)*(OpenHRP::rpyFromRot(rRh_ref)(i) - rRd_des(i)) - Fr(i,i)*(rMfs_gc(i) - rMd_des(i)))/Mr(i,i)*DEL_T; //rdRd(i) = exp((-Dr(i,i)/Mr(i,i))*DEL_T)*rdRd(i)+((1-exp((-Dr(i,i)/Mr(i,i))*DEL_T))/Dr(i,i))*rMfs_gc(i);
rRd(i) = rdRd(i)*DEL_T; //rRd=ASMRo*rRd;
}
rPh_ref += rdXd*DEL_T;
rRh_ref = rRh_ref * get_rot33(Z,rRd(Z))*get_rot33(Y,rRd(Y))*get_rot33(X,rRd(X)); // RzRyRx
#ifdef DEBUG_PLUGIN2
std::cout << "rXd_des = " << rXd_des << std::endl;
std::cout << "direct teaching: " << std::endl;
std::cout << "rdXd = " << rdXd << std::endl;
std::cout << "rXd = " << rPh_ref << std::endl;
std::cout << "rFfs_gc = " << rFfs_gc << std::endl;
std::cout << "rMfs_gc = " << rMfs_gc << std::endl;
#endif
// 目標手先位置・姿勢の計算 (rPh_ref, rRh_ref --> rPe_ref, rRe_ref --> q_ref)
calc_rPe_rRe(rPh_ref, rRh_ref, rPe_ref, rRe_ref);
bool ret;
dvector6 q_ref_tmp;
ret = calc_qref(rPe_ref, rRe_ref, q_ref_tmp);
if(ret) q_ref = q_ref_tmp;
#ifdef DEBUG_PLUGIN2
std::cout << "q_ref = " << q_ref << std::endl;
std::cout << "q = " << q << std::endl;
#endif
return ret;
}
#endif
//------------------------------------------------------------------------------------------
// PivotApproach(...)
// Two modes.
// (1) A test mode that allows you test the force controller as part of the control
// basis for a desired axis. That axis is indicated by a file found in data/PivotApproach/manipulationTestAxis.dat
//
// (2) Actual Pivot Approach.
// There are three modes (other than testing) thus far:
// 1. StraightLineApproach, originally implemented with the PA10.
// 2. PivotApproach: implemented by HIRO on a two snap cantilever snap.
// 3. SideApproach: implemented by HIRO on a four snap cantilever snap.
// Save the updated value of CurrAngles into the private member q_ref for the appropriate HIRO arm.
//------------------------------------------------------------------------------------------
int hiroArm::PivotApproach(double cur_time, /*in*/
vector3 pos, /*in*/ // end effector position
matrix33 rot, /*in*/ // end effector rotation
dvector6 currForces, /*in*/
dvector6& JointAngleUpdate, /*out*/
dvector6& CurrAngles) /*out*/
{
#ifdef DEBUG_PLUGIN2
std::cerr << "Entering hiroArm::PivotApproach" << std::endl;
#endif
// Local variables
int ret = 0;
dmatrix Jac;
dmatrix PseudoJac;
::AssemblyStrategy::TestAxis testAxis;
// Timing
//timeval startTime, endTime, sJ, eJ; // create variables
#if 0
unsigned long long sJ,eJ,endTick;
double duration = 0.0;
double dJ = 0.0;
double freq = 0;
freq = SYSPAGE_ENTRY(qtime)->cycles_per_sec; // define operational frequency
std::cerr << "The frequency is: " << freq << std::endl;
if(DB_TIME)
{
//gettimeofday(&startTime,NULL); // Initialize startTime for this function
//gettimeofday(&sJ,NULL); // start time for jacobian computations
sJ = get_tick();
}
#endif
// Compute Jacobian and PseudoJac
m_path->calcJacobian(Jac); // Calculate the Jacobian based on the base-2-wrist path segment we have assigned. This is a JointPathPtr type
//OpenHRP::calcPseudoInverse(Jac,PseudoJac); // Not used with HIRO
// Finalize jacobian time computations