forked from birlrobotics/PivotApproach
-
Notifications
You must be signed in to change notification settings - Fork 1
/
forceSensorPlugin_impl.cpp
executable file
·2203 lines (1878 loc) · 65 KB
/
forceSensorPlugin_impl.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 code is called when the HIRO Simulation is called.
// Three main functions are called:
// 1) Init
// - Initialize translation and rotation parameters for both arms. Allocates Right and Left arm clases and force sensor classes.
// 2) Setup
// - Called when the Simulator Start Control Button is pressed
// - Sets up initial force values, joint angles, and cartesian positions.
// - Calls Initialization routine on hiroArm clases.
// - Reads calibration and trajectory files.
// 3) Control
// - Executes selected control methods through control mode parameters.
// - Input and Output pass the RobotState.
// - struct RobotState:
// {
// DblSequence angle; // As input it is the current position. When outputed it's the desired position.
// DblSequence velocity;
// DblSequence torque;
// sequence<DblSequence6> force;
// sequence<DblSequence3> rateGyro;
// sequence<DblSequence3> accel;
// sequence<DblSequence9> attitude;
// DblSequence3 zmp;
// DblSequence3 basePos;
// DblSequence9 baseAtt;
// sequence<ImageData> image;
// LongSequence dio;
// };
// - Output:
// - By writing reference angle updates, the HIRO simulation will move to the requested angles.
//
// - Modifications based on "serverv0.1" (09.05.12)
// - Deleted "setDirectTeachingAxis(::CORBA::ULong axisflag)". (09.05.13)
// - Deleted "setInertiaDamping(::CORBA::ULong mx,::CORBA::ULong dx)", (09.05.13)
// - Added "setRPWbySensor(::CORBA::ULong r,::CORBA::ULong p, ::CORBA::ULong w)", (09.05.13)
// - Added Control starts by DTES signal( not via corba)
/***************************************************************************************************************************************************/
#include "Body.h" // In DynamicsSimulator/server
#include <sstream>
#include <cstdlib>
#include <ctime> // compute cycle time
#include <sys/time.h>
#include "iob.h" // Controller/IOServer/include
#include "forceSensorPlugin_impl.h"
//----------------------------------------------------------------------------------------------------------------------------------------------------
extern "C" {
#include <unistd.h> // Provides access to the POSIX operating system API
#include <stdio.h>
}
//-----------------------------------------------------------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------------------------------------------------------------
// HARDWARE BIT-WISE SWITCH DEFINITIONS
// The HIRO robot is connected to a hardware box that can be modified in four ways to achieve different behvaiors.
#define MSSL 0x80000000 // Motion Select Switch-> left
#define MSSR 0x40000000 // Motion Select Switch-> right
#define ASSL 0x20000000 // Axis Select Switch-> left
#define ASSR 0x10000000 // Axis Select Switch-> right
#define DTES 0x08000000 // DT enable switch (for data acquisition)
//----------------------------------------------------------------------------------------------------------------------------------------------------
// Debugging
#define DB_TIME 0 // Used to print timing duration of functions
#define FORCE_TEST 0 // Used to test if force drivers are working in Old HIRO
#define SIMULATION_TEST 1 // Used to test certain pieces of code within the control method for testing purposes
#define DEBUG 1 // Used to test temporary cerr statements
//----------------------------------------------------------------------------------------------------------------------------------------------------
// GLOBALS
unsigned long long distate; // Digital state parameter. Holds bit values.
double size;
//Left Arm Enable
#define LEFT_ARM 0 //Used to enable the left Arm
//----------------------------------------------------------------------------------------------------------------------------------------------------
/***************************** Allocate Plugin*********************************/
//class forceSensorPlugin_impl: public plugin,
////Virtual public POA_SamplePlugin, virtual public PortableServer::RefCountServantBase
//{};
plugin *create_plugin(istringstream &strm)
{
forceSensorPlugin_impl *cpImpl = new forceSensorPlugin_impl(strm);
return cpImpl;
}
void forceSensorPlugin_impl::test()
{
cout << "test" << endl;
}
/***************************** Create Plugin*********************************/
// Constructor
//forceSensorPlugin_impl::forceSensorPlugin_impl(istringstream &strm)
forceSensorPlugin_impl::forceSensorPlugin_impl(istringstream &strm)
{
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin_impl entered constructor" << std::endl;
#endif
DT = 0.005; // [sec]
assigned_time = 0.002; // assigned_time = 2[ms]
// Test Flags used within the control method
initControl = 0;
testFlag = 0;
num_test = 0;
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin_impl(): reading files" << std::endl;
#endif
// Read Arm and Gain parameters
readInitialFile("ArmParam"); // Velocity and Accelretion Gains and Trajectories
readGainFile("GainParam"); // GainP and GainR for HNL modes
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin_impl(): finished reading files" << std::endl;
#endif
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin_impl(): initializing variables" << std::endl;
#endif
// Pivot Approach Variables Initialization
for(int i=0;i<3;i++)
{
CurXYZ(i) =0.0;
}
for(int i=0;i<6;i++)
{
CurrentForces(i) =0.0;
CurrentAngles(i) =0.0;
JointAngleUpdate(i) =0.0;
#if LEFT_ARM
L_JointAngleUpdate(i) = 0.0;
#endif
}
for(int i=0;i<3;i++)
for(int j=0;j<3;j++){
CurRot(i,j) = 0.0;
#if LEFT_ARM
L_CurRot(i,j) = 0.0;
#endif
}
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin_impl(): finished initializing variables" << std::endl;
#endif
// Flags
initFlag = false;
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin_impl: leaving constructor" << std::endl;
#endif
}
forceSensorPlugin_impl::~forceSensorPlugin_impl()
{
close_ifs();
#ifdef WRITELOG
if(ostr_astate.is_open())
ostr_astate.close();
ostr_astate.clear();
if(ostr_rstate.is_open())
ostr_rstate.close();
ostr_rstate.clear();
if(ostr_force.is_open())
ostr_force.close();
ostr_force.clear();
if(ostr_worldforce.is_open())
ostr_worldforce.close();
ostr_force.clear();
#endif
}
/***************************** Initialize Plugin*********************************/
// Runs when similuator script is activated.
// Initializes Left and Right Arm Position/Rotation Variables
// Calls force sensor Contstructor
// Calls Left and Right arm Constructors
// TODO: Add POA single_thread or main_thread policy to this server.(needed?)
/********************************************************************************/
void forceSensorPlugin_impl::init(void)
{
// Local Variables
// e = wrist
// h = hand
// fs = force sensor
// P = position, R = rotation
vector3 ePh; // Wrist to EndEffector Translation
matrix33 eRh; // Wrist to EndEffector Rotation
vector3 hPfs; // EndEffector to Force Sense translation
matrix33 hRfs; // EndEffector to Force Sensor Tool Center Point Rotation
std::cout << "In init()" << std::endl;
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin::init()" << std::endl;
#endif
/*------------------------------------------------------------------------------- Load model file -------------------------------------------------------------------------------*/
if (!CORBA::is_nil(manager->orb))
{
// body data
std::cout << "loading Model: " << manager->url << std::endl;
body = OpenHRP::loadBodyFromModelLoader((manager->url).c_str(),manager->orb); // 使用方法は // http://www.openrtp.jp/openhrp3/jp/calc_model.html
}
else
std::cout << "manager->orb is nil" << std::endl;
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin::init() - exiting" << std::endl;
#endif
/*------------------------------------------------------------------------------- Setup Force Sensor -------------------------------------------------------*/
// ------------------ FORCE SENSOR ------------------------//
// Open the oldHIro IFS sensor
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin::Opening the ifs force lib" << std::endl;
#endif
#ifndef SIMULATION
open_ifs();
#endif
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin::init() - Closeing the ifs force lib" << std::endl;
#endif
#ifndef SIMULATION
// if (!fs->init())
// std::cerr << "error: fs->init()" << std::endl;
#endif
/*------------------------------------------------------------------------------- Setup LEFT and RIGHT arms angle limits -------------------------------------*/
float ang_limit_sub[ARM_DOF][5];
#if LEFT_ARM
//---------------------- LEFT arm ----------------------------//
#ifdef DEBUG_PLUGIN
std::cout << "ang_limit_sub left arm: " << std::endl;
#endif
for (int i = 0; i < ARM_DOF; i++)
{
for (int j = 0; j < 5; j++)
{
ang_limit_sub[i][j] = ang_limit[9 + i][j];
#ifdef DEBUG_PLUGIN
std::cout << ang_limit_sub[i][j] << " ";
#endif
}
#ifdef DEBUG_PLUGIN
std::cout << std::endl;
#endif
}
/***************************** Initialize Variables *************************************/
/*********************** LEFT ARM ****************************/
// Position and Rotation Variables
//ePh = -0.052, 0.0, 0.0;
ePh = -0.0915, 0.00, -0.0255; // -0.051, 0.0020, -0.0225; //0.0715, 0.0, 0.0; // Wrist to EndEffector translation
eRh = 1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0; // Wrist to EndEffector rotation
hPfs = (0.0085 + (0.0315 / 2)), 0.0, 0.0; // Wrist to Force Sensor Tool Center Point
// Allocate the Master Arm for Hiro (Left Arm)
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin::Allocating LEFT hiroArm" << std::endl;
#endif
int left_NUM_q0 = 9;
lArm = new hiroArmMas("left", body, left_NUM_q0, DT, ang_limit_sub, ePh, eRh, hPfs);
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin::Finished allocating LEFT hiroArm" << std::endl;
#endif
// Set the force pointer
// lArm->set_FSptr(fs, 0); // Connect to Force Sensor
// arg2: int *full_scale
#endif
/*********************** RIGHT ARM ****************************/
#ifdef DEBUG_PLUGIN
std::cout << "Right Arm: ang_limit_sub right arm: " << std::endl;
#endif
#ifdef PIVOTAPPROACH
// Position and Rotation Variables in local wrist coordinates. rot mat={0 0 -1 0 1 0 1 0 0}
ePh = -0.0785, 0.0020, -0.0245; //-0.051, 0.0020, -0.0225;//0.025, 0.0, -0.063; // -0.063, 0.0, -0.025; // -0.127, 0.025, 0.0; //-0.127, -0.03, -0.005; // Wrist to EndEffector (TCP) translation.
// This accounts for the end-effector that holds the camera molds in the pivot approach.
// -0.127=height,0.025=frontal, 0.0=horizontal
eRh = 1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0;
// Wrist to EndEffector rotation
hPfs = 0.063 + (0.0315 / 2), 0.0, 0.0; // EndEffector to Force Sensor Tool Center Point Translation //hPfs = 53+(31.5/2), 0.0, 60.0;
hRfs = get_rot33(Y, M_PI / 2.0) * get_rot33(Z, -(3 * M_PI / 4.0)); // EndEffector to Force Sensor Tool Center Point Rotation
// Allocate the Master Arm for Hiro (Left Arm)
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin()::Allocating RIGHT hiroArm" << std::endl;
#endif
// Allocate the slave arm - right arm
int NUM_q0 = 3; // Joint angle at which the right arm starts
rArm = new hiroArmSla("right", body, NUM_q0, DT, ang_limit_sub, ePh, eRh, hPfs, hRfs);
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin()::Finished allocating RIGHT hiroArm" << std::endl;
#endif
//rArm->set_FSptr(fs, 1);
//initialize_ifs(0);
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin::Finished allocating LEFT hiroArm" << std::endl;
#endif
// Assign Joint Angle Limits
for(int i = 0; i < ARM_DOF; i++){ // 6 DOF per arm
for(int j = 0; j < 5; j++){
ang_limit_sub[i][j] = ang_limit[3 + i][j];
#ifdef DEBUG_PLUGIN
std::cout << ang_limit_sub[i][j] << " ";
#endif
}
#ifdef DEBUG_PLUGIN
std::cout << std::endl;
#endif
}
// If not PivotApproach
#else
// Position and Rotation Variables
ePh = -0.12, 0.0, 0.0; // Wrist to EndEffector translation //ePh = -(53.0+31.5+16.0), 0.0, -60.0;
eRh = 1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0; // Wrist to EndEffector rotation
hPfs = 0.074 + (0.0315 / 2), 0.0, 0.0; // EndEffector to Force Sensor Tool Center Point Translation //hPfs = 53+(31.5/2), 0.0, 60.0;
hRfs = get_rot33(Y, M_PI / 2.0) * get_rot33(Z, -(3 * M_PI / 4.0)); // EndEffector to Force Sensor Tool Center Point Rotation
// Allocate the slave arm - right arm
int NUM_q0 = 3; // Joint angle at which the right arm starts
rArm = new hiroArmSla("right", body, NUM_q0, DT, ang_limit_sub, ePh, eRh, hPfs, hRfs);
//rArm->set_FSptr(fs, 1);
//IFS_Init(CHANNEL,FULL_SCALE);
// Assign Joint Angle Limits
for(int i = 0; i < ARM_DOF; i++){ // 6 DOF per arm
for(int j = 0; j < 5; j++){
ang_limit_sub[i][j] = ang_limit[3 + i][j];
#ifdef DEBUG_PLUGIN
std::cout << ang_limit_sub[i][j] << " ";
#endif
}
#ifdef DEBUG_PLUGIN
std::cout << std::endl;
#endif
}
#endif // If pivot approach
/*************************************** Initialize Control Flags ***************************************/
f_gravity_comp[0] = f_gravity_comp[1] = false;
controlmode_nr = NotControlled;
controlmode_r = NotControlled;
#ifdef PIVOTAPPROACH // set the controlmode_nr and controlmode_r parameters to PivotApproach to implement this control mode in ::control
controlmode_nr = PivotApproach; // Set the enumeration to both controlmode_nr and r
controlmode_r = PivotApproach;
#elif IMPEDANCE // set the controlmode_nr and controlmode_r parameters to ImpedanceControl to implement this control mode
// controlmode_nr = ImpedanceControl;
// controlmode_r = ImpedanceControl;
#endif
#ifdef WRITELOG
ostr_astate.open("./astate.dat");
if(!ostr_astate.is_open())
std::cerr << "astate.dat was not opened." << std::endl;
ostr_rstate.open("./rstate.dat");
if(!ostr_rstate.is_open())
std::cerr << "rstate.dat was not opened." << std::endl;
ostr_force.open("./localforce.dat");
if(!ostr_force.is_open())
std::cerr << "localforce.dat was not opened." << std::endl;
ostr_worldforce.open("./worldforce.dat");
if(!ostr_worldforce.is_open())
std::cerr << "worldforce.dat was not opened." << std::endl;
#endif
#ifdef PLUGIN_DEBUG2
std::cout << "out init()" << std::endl;
#endif
}
/******************************************************************************************************************************************/
// Setup()
// Sets up initial force values, joint angles, and cartesian positions.
// Calls Initialization routine on hiroArm clases.
// Reads calibration and trajectory files.
// This routine is called when "Start Control" is clicked on the HIRO Simulation dialogue that pops out when the script is started.
// Followed by ::control
/******************************************************************************************************************************************/
bool forceSensorPlugin_impl::setup(RobotState *rs, RobotState *mc)
{
// 1) Local variable initialization
int ret = 0;
double CurAngles[15] = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0};
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin::setup() - entered" << std::endl;
#endif
/*------------------------------------------------------------- Simulation ---------------------------------------------------*/
#ifdef SIMULATION
for(int i=0; i<6; i++)
{
rArm->raw_forces[i] = rs->force[0][i];
#if LEFT_ARM
lArm->raw_forces[i] = rs->force[1][i];
#endif
}
#endif
#ifdef DEBUG_PLUGIN
cerr << "forceSensorPlugin::setup() - finished\n";
#endif
// ----------------------------------------------------------- FORCE SENSOR -----------------------------------------------------------------/
#ifndef SIMULATION
initialize_ifs(0);
initialize_ifs(1);
#endif
#ifndef SIMULATION
rs->angle[8] -= 0.531117;
#endif
/*------------------------------------------------------------ Current Joint Angles --------------------------------------------------------*/
// 2) Set the desired robot state angles equal to the motion command angles, to avoid jump in the data or a discontinuity
// Set output angles to input angles
for (unsigned int i=0; i<DOF; ++i) // 15 DoF
{
body->joint(i)->q = rs->angle[i];
mc->angle[i] = rs->angle[i];
CurAngles[i] = rs->angle[i]; // Set the local variables to this
}
int NUM_q0=3;
// And also set CurrentAngles -- private member variable -- to rs->angle
CurrentAngles[0]=rs->angle[NUM_q0];
CurrentAngles[1]=rs->angle[NUM_q0+1];
CurrentAngles[2]=rs->angle[NUM_q0+2];
CurrentAngles[3]=rs->angle[NUM_q0+3];
CurrentAngles[4]=rs->angle[NUM_q0+4];
CurrentAngles[5]=rs->angle[NUM_q0+5];
#if LEFT_ARM
int left_NUM_q0 = 9;
L_CurrentAngles[0]=rs->angle[left_NUM_q0];
L_CurrentAngles[1]=rs->angle[left_NUM_q0+1];
L_CurrentAngles[2]=rs->angle[left_NUM_q0+2];
L_CurrentAngles[3]=rs->angle[left_NUM_q0+3];
L_CurrentAngles[4]=rs->angle[left_NUM_q0+4];
L_CurrentAngles[5]=rs->angle[left_NUM_q0+5];
#endif
#ifndef SIMULATION
mc->angle[8] += 0.531117;
#endif
#ifdef DEBUG_PLUGIN
std::cerr << "\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
// 3) Calculate the Fwd Kinematics=>Cartesian Positions
body->calcForwardKinematics();
/****************************************** PIVOT APPROACH SETUP ************************************************************/
#ifdef PIVOTAPPROACH
// 4) Initialization routine:
// Compute the position vector and rotation matrix from base to the wrist the robot has moved to HOMING POSITION
// This routine behave's different according to user. Assign Desired Behavior.
// Kensuke: read position and force data for both arms.
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin::setup() - Arm Initialization" << std::endl;
#endif
#if LEFT_ARM
lArm->init(body->link(LARM_JOINT5)->p, body->link(LARM_JOINT5)->attitude(), CurAngles);
if(DEBUG)
{
// Number of joints
int n2=0;
n2 = lArm->m_path->numJoints();
cerr << "forceSensorPlugin::setup(). LEFT Num Joints: " << n2 << std::endl;
// Position
vector3 rpy2(0);
lArm->set_OrgPosRot(L_CurXYZ,rpy2);
cerr << "forceSensorPlugin::setup(). LEFT Current Position: " << L_CurXYZ << std::endl;
cerr << "forceSensorPlugin::setup(). LEFT Current Pose: " << rpy2 << std::endl;
// Angles
cerr << "forceSensorPlugin::setup(). LEFT Current Angles (radians):\t" << L_CurrentAngles << std::endl;
}
#endif
//set up right hand
ret = rArm->init(body->link(RARM_JOINT5)->p, body->link(RARM_JOINT5)->attitude(),CurAngles); // Body object 15 DOF. Need link8 or RARM_JOINT5.
// Update the latest data angles and position
if(DEBUG)
{
// Number of joints
int n=0;
n = rArm->m_path->numJoints();
cerr << "forceSensorPlugin::setup(). RIGHT Num Joints: " << n << std::endl;
// Position
vector3 rpy(0);
rArm->set_OrgPosRot(CurXYZ,rpy);
cerr << "forceSensorPlugin::setup(). RIGHT Current Position: " << CurXYZ << std::endl;
cerr << "forceSensorPlugin::setup(). RIGHT Current Pose: " << rpy << std::endl;
// Angles
cerr << "forceSensorPlugin::setup(). RIGHT Current Angles (radians):\t" << CurrentAngles << std::endl;
}
// Check result
if(ret==-1)
{
#ifdef DEBUG_PLUGIN
std::cerr << "\nProgram Failed!!";
#endif
}
else
{
#ifdef DEBUGC_PLUGIN2
std::cerr <<"forceSensorPlugin::setup() - Initialization was successful!" << std::endl;
#endif
}
#endif
/****************************************** PIVOT APPROACH ************************************************************/
#ifdef PIVOTAPPROACH
controlmode_nr = PivotApproach;
controlmode_r = PivotApproach;
#endif
//~ if((fp_nitta=fopen(f_name1.c_str(),"w"))==NULL){
//~ std::cerr<< "file open error!!" << std::endl; //~ }
// Exit
#ifdef DEBUG_PLUGIN
std::cerr << "forceSensorPlugin::setup() - Exiting" << std::endl;
#endif
return true;
}
/******************************************************************************************************************************************/
// Control()
// The control function is called by the GrxUI simulation every 2-5ms. This method implements the control routine that will control HIRO.
// This function is passed the RobotState rs which i a structure containing all the data of the robot:
//
// struct RobotState:
// {
// DblSequence angle;
// DblSequence velocity;
// DblSequence torque;
// sequence<DblSequence6> force;
// sequence<DblSequence3> rateGyro;
// sequence<DblSequence3> accel;
// sequence<DblSequence9> attitude;
// DblSequence3 zmp;
// DblSequence3 basePos;
// DblSequence9 baseAtt;
// sequence<ImageData> image;
// LongSequence dio;
// };
//
// Function performs the following tasks:
// - Read Joint Angles from Simulation
// - Compute corresponding Cartesian Coordinates
//
// The second part uses a case-switch statement to determine the control command.
// New control modes can be inserted here
/******************************************************************************************************************************************/
void forceSensorPlugin_impl::control(RobotState *rs, RobotState *mc)
{
// Local variable
int ret = 0;
#ifndef SIMULATION
rs->angle[8] -= 0.531117;
#endif
//---------------------------------------- FORCE TEST ------------------------------------------/
if(!FORCE_TEST)
{
#ifdef DEBUG_PLUGIN
std::cerr << "/----------------------------------\nforceSensorPlugin::control() - entered\n-------------------------------------/\n\n" << std::endl;
#endif
// Initial code
if(initControl==0)
{
// Initialize the iteration
rArm->m_time=0;
#if LEFT_ARM
lArm->m_time=0;
#endif
if(DEBUG)
{
#if LEFT_ARM
vector3 rpy2(0);
lArm->set_OrgPosRot(L_CurXYZ,rpy2);
lArm->m_path->calcInverseKinematics(L_CurXYZ,L_CurRot);
for(int i=0;i<6;i++)
L_CurrentAngles(i) = lArm->m_path->joint(i)->q;
#endif
// Update the latest data angles and position
vector3 rpy(0);
rArm->set_OrgPosRot(CurXYZ,rpy);
rArm->m_path->calcInverseKinematics(CurXYZ,CurRot);
for (int i=0;i<6;i++)
CurrentAngles(i) = rArm->m_path->joint(i)->q;
cerr << "\n\nforceSensorPlugin::control()-Current time is:\t" << DT*double(rArm->get_Iteration()) << std::endl;
cerr << "forceSensorPlugin::control()-Current position is:\t" << CurXYZ << std::endl;
cerr << "forceSensorPlugin::control()-Current pose is:\t" << rpy << std::endl;
cerr << "forceSensorPlugin::control()-Current Angles (radians) are:\t" << CurrentAngles << std::endl;
}
// Change the flag
initControl=1;
}
// Simulation test is used to skip code that is enclosed the if function.
if(SIMULATION_TEST)
{
// Timing
timeval startTime, endTime; // create variables
double duration = 0;
if(DB_TIME)
{
gettimeofday(&startTime,NULL); // Initialize startTime
}
/*-------------------------------------------------------------- Arm Selection ---------------------------------------------------*/
// What arm will you use. Left = 0 index. Right = 1 index.
bool f_control[2];
f_control[0] = false;
f_control[1] = true;
#if LEFT_ARM
f_control[0] = true;
#endif
// Set controlmode _r equal to _nr
#if 0
if (controlmode_r != controlmode_nr)
controlmode_r = controlmode_nr;
#endif
/*----------------------------------------------------------- Simulation Force Values ----------------------------------------*/
#ifdef SIMULATION
for(int i=0; i<6; i++) {
rArm->raw_forces[i] = rs->force[0][i];
#if LEFT_ARM
lArm->raw_forces[i] = rs->force[1][i];
#endif
}
#else
#if 0
// Read DIN state
read_di(distate);
DioState = distate >> 32;
#endif
#ifdef DEBUG_PLUGIN
std::cerr << "Getting Force Values" << std::endl;
#endif
#endif
#ifdef DEBUG_PLUGIN
std::cerr << "The control mode for the PivotApproach should say 6. Currently it is: " << controlmode_r << std::endl;
#endif
/*------------------------------------------------------------ INITIALIZATION STAGE ----------------------------------------------*/
if(initFlag==false)
{
/*---------------------- Angle Update --------------------------*/
// For the first iteration make sure that output angles are the same as input angles for all 15 DOF.
for (unsigned int i = 0; i < DOF; ++i)
{
body->joint(i)->q = rs->angle[i]; // the body object is for the entire body 15 DoF
mc->angle[i] = rs->angle[i];
}
//for(int i=0; i<ARM_DOF; i++) //body->joint(i)->q = rs->angle[i+3]; // Copy the latest actual angles into our private member variable.
// change flag
initFlag = true;
//controlmode_pre = controlmode_r;
#ifdef DEBUG_PLUGIN
std::cerr << "\n/---------------------------------------------------------------------------------------------------------------------------\n"
"forceSensorPlugin - The 15 current angles in radians are:\t" << rs->angle[0]/**rad2degC*/ << "\t" << rs->angle[1]/**rad2degC*/ << "\t" << rs->angle[2]/**rad2degC*/ << "\t"
<< rs->angle[3]/**rad2degC*/ << "\t" << rs->angle[4]/**rad2degC*/ << "\t" << rs->angle[5]/**rad2degC*/ << "\t"
<< rs->angle[6]/**rad2degC*/ << "\t" << rs->angle[7]/**rad2degC*/ << "\t" << rs->angle[8]/**rad2degC*/ << "\t"
<< rs->angle[9]/**rad2degC*/ << "\t" << rs->angle[10]/**rad2degC*/<< "\t" << rs->angle[11]/**rad2degC*/<< "\t"
<< rs->angle[12]/**rad2degC*/<< "\t" << rs->angle[13]/**rad2degC*/<< "\t" << rs->angle[14]/**rad2degC*/<<
"\n/------------------------------------------------------------------------------------------------------------\n" << std::endl;
#endif
// 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
std::cerr << "Duration of forceSensorPlugin::control() is: " << duration << "ms." << std::endl;
}
} // End initFlag
/*----------------------------------------------------------------------------------------------------------------------------------------------------------*/
#ifdef DEBUG_PLUGIN
std::cerr << "Calculate Fwd Kins" << std::endl;
#endif
// Calculate cartesian positions
body->calcForwardKinematics();
#ifdef DEBUG_PLUGIN
std::cerr << "Update the current position data." << std::endl;
#endif
// Update cartesian position of robot arms
//lArm->update_currposdata(); // Gets base2wrist translation/rotation, and base2endeffector translation/rotation
rArm->update_currposdata(); // And, current joint angles for the respective arm
#if LEFT_ARM
lArm->update_currposdata();
#endif
/*------------------------------------------------------------- Select Control Mode-----------------------------------------------------------------------*/
// There are eight control modes: NotControlled, GravityCompensation, ResetGravityCompensation, BirateralControl, DirectTeaching, Impedance Control, and Pivot Approach
#ifdef DEBUG_PLUGIN
std::cerr << "Current mode is: " << controlmode_r << std::endl;
#endif
switch (controlmode_r)
{
/*--------------------------------------------------------------------------- Not Controlled ----------------------------------------------------*/
case NotControlled:
#ifdef DEBUG_PLUGIN
std::cout << "NotControlled" << std::endl;
#endif
f_control[0] = f_control[1] = false;
break;
/*-------------------------------------------------------------------------------------------- Gravity Compensaation ---------------------------------------------------------------------------------------*/
case GravityCompensation:
#ifdef DEBUG_PLUGIN
std::cout << "GravityCompensation" << std::endl;
#endif
// Go to the Initial Position
// (A) LEFT ARM
if (!f_gravity_comp[0])
{
// Call gravity compsensation
int res_gc;
res_gc = lArm->gravity_comp();
#ifdef DEBUG_PLUGIN
std::cout << "Gravity Compensation: res_gc = " << res_gc << std::endl;
#endif
// Success
if (res_gc == 1)
{
f_gravity_comp[0] = true;
num_test = 0;
}
else if (res_gc == 0)
f_control[0] = true;
}
// (B) RIGHT ARM
else if (!f_gravity_comp[1])
{
// Call gravity compensation
int res_gc;
res_gc = rArm->gravity_comp();
#ifdef DEBUG_PLUGIN
std::cout << "Gravity Compensation: res_gc = " << res_gc << std::endl;
#endif
// Success
if (res_gc == 1)
{
f_gravity_comp[1] = true;
num_test = 0;
}
else if (res_gc == 0)
f_control[1] = true;
}
// Manual Algorithm
else
{
// force sensor data の チェック
lArm->update_currforcedata(); //~ lArm->savedata();
rArm->update_currforcedata(); //~ rArm->savedata();
vector3 rF_gc[2], rM_gc[2];
// Get forces and moments
lArm->get_forces(rF_gc[0], rM_gc[0]);
rArm->get_forces(rF_gc[1], rM_gc[1]);
if (num_test < 2000)
{
if (num_test == 0)
{
// Initialize
for (int i = 0; i < 2; i++)
{
F_ave[i] = 0.0, 0.0, 0.0;
M_ave[i] = 0.0, 0.0, 0.0;
F_sd[i] = 0.0, 0.0, 0.0;
M_sd[i] = 0.0, 0.0, 0.0;
F_err_max[i] = -100.0, -100.0, -100.0;
M_err_max[i] = -100.0, -100.0, -100.0;
}
}
// Compute Averages for Force and Moment
for (int i = 0; i < 2; i++)
{
F_ave[i] += rF_gc[i];
M_ave[i] += rM_gc[i];
// Limit Error Computations
for (int j = 0; j < 3; j++)
{
// Square Error
F_sd[i][j] += rF_gc[i][j] * rF_gc[i][j];
M_sd[i][j] += rM_gc[i][j] * rM_gc[i][j];
// Check Limits
if (F_err_max[i][j] < fabs(rF_gc[i][j]))
F_err_max[i][j] = fabs(rF_gc[i][j]);
if (M_err_max[i][j] < fabs(rM_gc[i][j]))
M_err_max[i][j] = fabs(rM_gc[i][j]);
}
}
// Increase number counter
num_test++;
/*lArm->get_raw_forces(fout);
fprintf(fp_nitta,"%f %f %f %f %f %f\n",fout[0],fout[1],fout[2],fout[0],fout[1],fout[2]);
*/
}
else if (num_test == 2000)
{
std::string f_name1 = "/home/hrpuser/yamanobe/data/fs.dat";
if ((fp = fopen(f_name1.c_str(), "a")) == NULL) std::cerr << "file open error!!" << std::endl;
for (int i = 0; i < 2; i++)
{
// Compute averages by dividing by number of elements
F_ave[i] = (1.0 / 2000) * F_ave[i];
M_ave[i] = (1.0 / 2000) * M_ave[i];
for (int j = 0; j < 3; j++)
{
F_sd[i][j] = sqrt(
((1.0 / 2000) * F_sd[i][j])
- (F_ave[i][j] * F_ave[i][j]));
M_sd[i][j] = sqrt(
((1.0 / 2000) * M_sd[i][j])
- (M_ave[i][j] * M_ave[i][j]));
}
F_zero_lim[i] = -100;
M_zero_lim[i] = -100;
double tmp;
for (int j = 0; j < 3; j++)
{
tmp = fabs(F_ave[i][j]) + F_sd[i][j];
if (tmp > F_zero_lim[i])
F_zero_lim[i] = tmp;
tmp = fabs(M_ave[i][j]) + M_sd[i][j];
if (tmp > M_zero_lim[i])
M_zero_lim[i] = tmp;
}
F_zero_lim[i] = 2.0 * F_zero_lim[i];
M_zero_lim[i] = 2.0 * M_zero_lim[i];
fprintf(fp, "sensor %d:\n", i);
fprintf(fp, "average: %f %f %f %f %f %f\n", F_ave[i][0],
F_ave[i][1], F_ave[i][2], M_ave[i][0], M_ave[i][1],
M_ave[i][2]);
fprintf(fp, "s_deviation: %f %f %f %f %f %f\n", F_sd[i][0],
F_sd[i][1], F_sd[i][2], M_sd[i][0], M_sd[i][1],
M_sd[i][2]);
fprintf(fp, "max_error: %f %f %f %f %f %f\n",
F_err_max[i][0], F_err_max[i][1], F_err_max[i][2],
M_err_max[i][0], M_err_max[i][1], M_err_max[i][2]);
fprintf(fp, "zero_limit: %f %f\n\n", F_zero_lim[i],
M_zero_lim[i]);
#ifdef DEBUG_PLUGIN
std::cout << "error of rF_gc = " << F_ave << std::endl;
std::cout << "error of rM_gc = " << M_ave << std::endl;
std::cout << "max error F" << F_err_max << std::endl;
std::cout << "max error M" << M_err_max << std::endl;
#endif
}
std::cout << "Gravity Compensation is finished." << std::endl;
//~ fprintf(fv_L,"Gravity compensation is finished.\n");
//~ fprintf(fv_R,"Gravity compensation is finished.\n");
fclose(fp);
num_test++;
}
}
break;
/*---------------------------------------------------------------------------------------------- Reset Gravity Compensation -----------------------------------------------------------------------------------------*/
case ResetGravityCompensation:
#ifdef DEBUG_PLUGIN
std::cout << "ResetGravityCompensation" << std::endl;
#endif
lArm->reset_gravity_comp();
rArm->reset_gravity_comp();
f_gravity_comp[0] = f_gravity_comp[1] = false;
break;
case BirateralControl:
#ifdef DEBUG_PLUGIN
std::cout << "BirateralControl" << std::endl;
#endif
/*~ if(controlmode_r != controlmode_pre){
//~ ofs.open("q_birateral.log");
//~ if(!ofs.is_open()) std::cerr << "ERROR: can't open q_birateral.log" << std::endl;
~ }*/
// Once gravity compensation has taken place
if (f_gravity_comp[0] && f_gravity_comp[1])
{
//~ if(1){
bool f_new = false;