-
Notifications
You must be signed in to change notification settings - Fork 88
/
Stabilizer.cpp
2832 lines (2706 loc) · 136 KB
/
Stabilizer.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
// -*- C++ -*-
/*!
* @file Stabilizer.cpp
* @brief stabilizer filter
* $Date$
*
* $Id$
*/
#include <rtm/CorbaNaming.h>
#include <hrpModel/Link.h>
#include <hrpModel/Sensor.h>
#include <hrpModel/ModelLoaderUtil.h>
#include "Stabilizer.h"
#include "hrpsys/util/VectorConvert.h"
#include <math.h>
#include <boost/lambda/lambda.hpp>
typedef coil::Guard<coil::Mutex> Guard;
#ifndef deg2rad
#define deg2rad(x) ((x) * M_PI / 180.0)
#endif
#ifndef rad2deg
#define rad2deg(rad) (rad * 180 / M_PI)
#endif
// Module specification
// <rtc-template block="module_spec">
static const char* stabilizer_spec[] =
{
"implementation_id", "Stabilizer",
"type_name", "Stabilizer",
"description", "stabilizer",
"version", HRPSYS_PACKAGE_VERSION,
"vendor", "AIST",
"category", "example",
"activity_type", "DataFlowComponent",
"max_instance", "10",
"language", "C++",
"lang_type", "compile",
// Configuration variables
"conf.default.debugLevel", "0",
""
};
// </rtc-template>
static std::ostream& operator<<(std::ostream& os, const struct RTC::Time &tm)
{
int pre = os.precision();
os.setf(std::ios::fixed);
os << std::setprecision(6)
<< (tm.sec + tm.nsec/1e9)
<< std::setprecision(pre);
os.unsetf(std::ios::fixed);
return os;
}
static double switching_inpact_absorber(double force, double lower_th, double upper_th);
Stabilizer::Stabilizer(RTC::Manager* manager)
: RTC::DataFlowComponentBase(manager),
// <rtc-template block="initializer">
m_qCurrentIn("qCurrent", m_qCurrent),
m_qRefIn("qRef", m_qRef),
m_rpyIn("rpy", m_rpy),
m_zmpRefIn("zmpRef", m_zmpRef),
m_StabilizerServicePort("StabilizerService"),
m_basePosIn("basePosIn", m_basePos),
m_baseRpyIn("baseRpyIn", m_baseRpy),
m_contactStatesIn("contactStates", m_contactStates),
m_toeheelRatioIn("toeheelRatio", m_toeheelRatio),
m_controlSwingSupportTimeIn("controlSwingSupportTime", m_controlSwingSupportTime),
m_qRefSeqIn("qRefSeq", m_qRefSeq),
m_walkingStatesIn("walkingStates", m_walkingStates),
m_sbpCogOffsetIn("sbpCogOffset", m_sbpCogOffset),
m_qRefOut("q", m_qRef),
m_tauOut("tau", m_tau),
m_zmpOut("zmp", m_zmp),
m_refCPOut("refCapturePoint", m_refCP),
m_actCPOut("actCapturePoint", m_actCP),
m_diffCPOut("diffCapturePoint", m_diffCP),
m_diffFootOriginExtMomentOut("diffFootOriginExtMoment", m_diffFootOriginExtMoment),
m_actContactStatesOut("actContactStates", m_actContactStates),
m_COPInfoOut("COPInfo", m_COPInfo),
m_emergencySignalOut("emergencySignal", m_emergencySignal),
// for debug output
m_originRefZmpOut("originRefZmp", m_originRefZmp),
m_originRefCogOut("originRefCog", m_originRefCog),
m_originRefCogVelOut("originRefCogVel", m_originRefCogVel),
m_originNewZmpOut("originNewZmp", m_originNewZmp),
m_originActZmpOut("originActZmp", m_originActZmp),
m_originActCogOut("originActCog", m_originActCog),
m_originActCogVelOut("originActCogVel", m_originActCogVel),
m_actBaseRpyOut("actBaseRpy", m_actBaseRpy),
m_currentBasePosOut("currentBasePos", m_currentBasePos),
m_currentBaseRpyOut("currentBaseRpy", m_currentBaseRpy),
m_allRefWrenchOut("allRefWrench", m_allRefWrench),
m_allEECompOut("allEEComp", m_allEEComp),
m_debugDataOut("debugData", m_debugData),
control_mode(MODE_IDLE),
st_algorithm(OpenHRP::StabilizerService::TPCC),
emergency_check_mode(OpenHRP::StabilizerService::NO_CHECK),
szd(NULL),
// </rtc-template>
m_debugLevel(0)
{
m_service0.stabilizer(this);
}
Stabilizer::~Stabilizer()
{
}
RTC::ReturnCode_t Stabilizer::onInitialize()
{
std::cerr << "[" << m_profile.instance_name << "] onInitialize()" << std::endl;
// <rtc-template block="bind_config">
// Bind variables and configuration variable
bindParameter("debugLevel", m_debugLevel, "0");
// </rtc-template>
// Registration: InPort/OutPort/Service
// <rtc-template block="registration">
// Set InPort buffers
addInPort("qCurrent", m_qCurrentIn);
addInPort("qRef", m_qRefIn);
addInPort("rpy", m_rpyIn);
addInPort("zmpRef", m_zmpRefIn);
addInPort("basePosIn", m_basePosIn);
addInPort("baseRpyIn", m_baseRpyIn);
addInPort("contactStates", m_contactStatesIn);
addInPort("toeheelRatio", m_toeheelRatioIn);
addInPort("controlSwingSupportTime", m_controlSwingSupportTimeIn);
addInPort("qRefSeq", m_qRefSeqIn);
addInPort("walkingStates", m_walkingStatesIn);
addInPort("sbpCogOffset", m_sbpCogOffsetIn);
// Set OutPort buffer
addOutPort("q", m_qRefOut);
addOutPort("tau", m_tauOut);
addOutPort("zmp", m_zmpOut);
addOutPort("refCapturePoint", m_refCPOut);
addOutPort("actCapturePoint", m_actCPOut);
addOutPort("diffCapturePoint", m_diffCPOut);
addOutPort("diffStaticBalancePointOffset", m_diffFootOriginExtMomentOut);
addOutPort("actContactStates", m_actContactStatesOut);
addOutPort("COPInfo", m_COPInfoOut);
addOutPort("emergencySignal", m_emergencySignalOut);
// for debug output
addOutPort("originRefZmp", m_originRefZmpOut);
addOutPort("originRefCog", m_originRefCogOut);
addOutPort("originRefCogVel", m_originRefCogVelOut);
addOutPort("originNewZmp", m_originNewZmpOut);
addOutPort("originActZmp", m_originActZmpOut);
addOutPort("originActCog", m_originActCogOut);
addOutPort("originActCogVel", m_originActCogVelOut);
addOutPort("actBaseRpy", m_actBaseRpyOut);
addOutPort("currentBasePos", m_currentBasePosOut);
addOutPort("currentBaseRpy", m_currentBaseRpyOut);
addOutPort("allRefWrench", m_allRefWrenchOut);
addOutPort("allEEComp", m_allEECompOut);
addOutPort("debugData", m_debugDataOut);
// Set service provider to Ports
m_StabilizerServicePort.registerProvider("service0", "StabilizerService", m_service0);
// Set service consumers to Ports
// Set CORBA Service Ports
addPort(m_StabilizerServicePort);
// </rtc-template>
RTC::Properties& prop = getProperties();
coil::stringTo(dt, prop["dt"].c_str());
// parameters for corba
RTC::Manager& rtcManager = RTC::Manager::instance();
std::string nameServer = rtcManager.getConfig()["corba.nameservers"];
int comPos = nameServer.find(",");
if (comPos < 0){
comPos = nameServer.length();
}
nameServer = nameServer.substr(0, comPos);
RTC::CorbaNaming naming(rtcManager.getORB(), nameServer.c_str());
// parameters for internal robot model
m_robot = hrp::BodyPtr(new hrp::Body());
if (!loadBodyFromModelLoader(m_robot, prop["model"].c_str(),
CosNaming::NamingContext::_duplicate(naming.getRootContext())
)){
std::cerr << "[" << m_profile.instance_name << "]failed to load model[" << prop["model"] << "]" << std::endl;
return RTC::RTC_ERROR;
}
// Setting for wrench data ports (real + virtual)
std::vector<std::string> force_sensor_names;
// Find names for real force sensors
int npforce = m_robot->numSensors(hrp::Sensor::FORCE);
for (unsigned int i=0; i<npforce; ++i) {
force_sensor_names.push_back(m_robot->sensor(hrp::Sensor::FORCE, i)->name);
}
// load virtual force sensors
readVirtualForceSensorParamFromProperties(m_vfs, m_robot, prop["virtual_force_sensor"], std::string(m_profile.instance_name));
int nvforce = m_vfs.size();
for (unsigned int i=0; i<nvforce; ++i) {
for ( std::map<std::string, hrp::VirtualForceSensorParam>::iterator it = m_vfs.begin(); it != m_vfs.end(); it++ ) {
if (it->second.id == i) {
force_sensor_names.push_back(it->first);
}
}
}
int nforce = npforce + nvforce;
m_wrenches.resize(nforce);
m_wrenchesIn.resize(nforce);
m_ref_wrenches.resize(nforce);
m_ref_wrenchesIn.resize(nforce);
m_limbCOPOffset.resize(nforce);
m_limbCOPOffsetIn.resize(nforce);
std::cerr << "[" << m_profile.instance_name << "] force sensor ports (" << npforce << ")" << std::endl;
for (unsigned int i=0; i<nforce; ++i) {
std::string force_sensor_name = force_sensor_names[i];
// actual inport
m_wrenchesIn[i] = new RTC::InPort<RTC::TimedDoubleSeq>(force_sensor_name.c_str(), m_wrenches[i]);
m_wrenches[i].data.length(6);
registerInPort(force_sensor_name.c_str(), *m_wrenchesIn[i]);
// referecen inport
m_ref_wrenchesIn[i] = new RTC::InPort<RTC::TimedDoubleSeq>(std::string(force_sensor_name+"Ref").c_str(), m_ref_wrenches[i]);
m_ref_wrenches[i].data.length(6);
registerInPort(std::string(force_sensor_name+"Ref").c_str(), *m_ref_wrenchesIn[i]);
std::cerr << "[" << m_profile.instance_name << "] name = " << force_sensor_name << std::endl;
}
std::cerr << "[" << m_profile.instance_name << "] limbCOPOffset ports (" << npforce << ")" << std::endl;
for (unsigned int i=0; i<nforce; ++i) {
std::string force_sensor_name = force_sensor_names[i];
std::string nm("limbCOPOffset_"+force_sensor_name);
m_limbCOPOffsetIn[i] = new RTC::InPort<RTC::TimedPoint3D>(nm.c_str(), m_limbCOPOffset[i]);
registerInPort(nm.c_str(), *m_limbCOPOffsetIn[i]);
std::cerr << "[" << m_profile.instance_name << "] name = " << nm << std::endl;
}
// setting from conf file
// rleg,TARGET_LINK,BASE_LINK,x,y,z,rx,ry,rz,rth #<=pos + rot (axis+angle)
coil::vstring end_effectors_str = coil::split(prop["end_effectors"], ",");
if (end_effectors_str.size() > 0) {
size_t prop_num = 10;
size_t num = end_effectors_str.size()/prop_num;
for (size_t i = 0; i < num; i++) {
std::string ee_name, ee_target, ee_base;
coil::stringTo(ee_name, end_effectors_str[i*prop_num].c_str());
coil::stringTo(ee_target, end_effectors_str[i*prop_num+1].c_str());
coil::stringTo(ee_base, end_effectors_str[i*prop_num+2].c_str());
STIKParam ikp;
for (size_t j = 0; j < 3; j++) {
coil::stringTo(ikp.localp(j), end_effectors_str[i*prop_num+3+j].c_str());
}
double tmpv[4];
for (int j = 0; j < 4; j++ ) {
coil::stringTo(tmpv[j], end_effectors_str[i*prop_num+6+j].c_str());
}
ikp.localR = Eigen::AngleAxis<double>(tmpv[3], hrp::Vector3(tmpv[0], tmpv[1], tmpv[2])).toRotationMatrix(); // rotation in VRML is represented by axis + angle
ikp.target_name = ee_target;
ikp.ee_name = ee_name;
{
bool is_ee_exists = false;
for (size_t j = 0; j < npforce; j++) {
hrp::Sensor* sensor = m_robot->sensor(hrp::Sensor::FORCE, j);
hrp::Link* alink = m_robot->link(ikp.target_name);
while (alink != NULL && alink->name != ee_base && !is_ee_exists) {
if ( alink->name == sensor->link->name ) {
is_ee_exists = true;
ikp.sensor_name = sensor->name;
}
alink = alink->parent;
}
}
}
ikp.avoid_gain = 0.001;
ikp.reference_gain = 0.01;
ikp.ik_loop_count = 3;
// For swing ee modification
ikp.target_ee_diff_p = hrp::Vector3::Zero();
ikp.target_ee_diff_r = hrp::Matrix33::Identity();
ikp.d_rpy_swing = hrp::Vector3::Zero();
ikp.d_pos_swing = hrp::Vector3::Zero();
ikp.target_ee_diff_p_filter = boost::shared_ptr<FirstOrderLowPassFilter<hrp::Vector3> >(new FirstOrderLowPassFilter<hrp::Vector3>(50.0, dt, hrp::Vector3::Zero())); // [Hz]
ikp.target_ee_diff_r_filter = boost::shared_ptr<FirstOrderLowPassFilter<hrp::Vector3> >(new FirstOrderLowPassFilter<hrp::Vector3>(50.0, dt, hrp::Vector3::Zero())); // [Hz]
ikp.prev_d_pos_swing = hrp::Vector3::Zero();
ikp.prev_d_rpy_swing = hrp::Vector3::Zero();
//
stikp.push_back(ikp);
jpe_v.push_back(hrp::JointPathExPtr(new hrp::JointPathEx(m_robot, m_robot->link(ee_base), m_robot->link(ee_target), dt, false, std::string(m_profile.instance_name))));
// Fix for toe joint
if (ee_name.find("leg") != std::string::npos && jpe_v.back()->numJoints() == 7) { // leg and has 7dof joint (6dof leg +1dof toe)
std::vector<double> optw;
for (int j = 0; j < jpe_v.back()->numJoints(); j++ ) {
if ( j == jpe_v.back()->numJoints()-1 ) optw.push_back(0.0);
else optw.push_back(1.0);
}
jpe_v.back()->setOptionalWeightVector(optw);
}
target_ee_p.push_back(hrp::Vector3::Zero());
target_ee_R.push_back(hrp::Matrix33::Identity());
act_ee_p.push_back(hrp::Vector3::Zero());
act_ee_R.push_back(hrp::Matrix33::Identity());
projected_normal.push_back(hrp::Vector3::Zero());
act_force.push_back(hrp::Vector3::Zero());
ref_force.push_back(hrp::Vector3::Zero());
ref_moment.push_back(hrp::Vector3::Zero());
contact_states_index_map.insert(std::pair<std::string, size_t>(ee_name, i));
is_ik_enable.push_back( (ee_name.find("leg") != std::string::npos ? true : false) ); // Hands ik => disabled, feet ik => enabled, by default
is_feedback_control_enable.push_back( (ee_name.find("leg") != std::string::npos ? true : false) ); // Hands feedback control => disabled, feet feedback control => enabled, by default
is_zmp_calc_enable.push_back( (ee_name.find("leg") != std::string::npos ? true : false) ); // To zmp calculation, hands are disabled and feet are enabled, by default
std::cerr << "[" << m_profile.instance_name << "] End Effector [" << ee_name << "]" << std::endl;
std::cerr << "[" << m_profile.instance_name << "] target = " << m_robot->link(ikp.target_name)->name << ", base = " << ee_base << ", sensor_name = " << ikp.sensor_name << std::endl;
std::cerr << "[" << m_profile.instance_name << "] offset_pos = " << ikp.localp.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[m]" << std::endl;
prev_act_force_z.push_back(0.0);
}
m_contactStates.data.length(num);
m_toeheelRatio.data.length(num);
m_will_fall_counter.resize(num);
}
std::vector<std::pair<hrp::Link*, hrp::Link*> > interlocking_joints;
readInterlockingJointsParamFromProperties(interlocking_joints, m_robot, prop["interlocking_joints"], std::string(m_profile.instance_name));
if (interlocking_joints.size() > 0) {
for (size_t i = 0; i < jpe_v.size(); i++) {
std::cerr << "[" << m_profile.instance_name << "] Interlocking Joints for [" << stikp[i].ee_name << "]" << std::endl;
jpe_v[i]->setInterlockingJointPairIndices(interlocking_joints, std::string(m_profile.instance_name));
}
}
// parameters for TPCC
act_zmp = hrp::Vector3::Zero();
for (int i = 0; i < 2; i++) {
k_tpcc_p[i] = 0.2;
k_tpcc_x[i] = 4.0;
k_brot_p[i] = 0.1;
k_brot_tc[i] = 1.5;
}
// parameters for EEFM
double k_ratio = 0.9;
for (int i = 0; i < 2; i++) {
eefm_k1[i] = -1.41429*k_ratio;
eefm_k2[i] = -0.404082*k_ratio;
eefm_k3[i] = -0.18*k_ratio;
eefm_body_attitude_control_gain[i] = 0.5;
eefm_body_attitude_control_time_const[i] = 1e5;
}
for (size_t i = 0; i < stikp.size(); i++) {
STIKParam& ikp = stikp[i];
hrp::Link* root = m_robot->link(ikp.target_name);
ikp.eefm_rot_damping_gain = hrp::Vector3(20*5, 20*5, 1e5);
ikp.eefm_rot_time_const = hrp::Vector3(1.5, 1.5, 1.5);
ikp.eefm_rot_compensation_limit = deg2rad(10.0);
ikp.eefm_swing_rot_spring_gain = hrp::Vector3(0.0, 0.0, 0.0);
ikp.eefm_swing_rot_time_const = hrp::Vector3(1.5, 1.5, 1.5);
ikp.eefm_pos_damping_gain = hrp::Vector3(3500*10, 3500*10, 3500);
ikp.eefm_pos_time_const_support = hrp::Vector3(1.5, 1.5, 1.5);
ikp.eefm_pos_compensation_limit = 0.025;
ikp.eefm_swing_pos_spring_gain = hrp::Vector3(0.0, 0.0, 0.0);
ikp.eefm_swing_pos_time_const = hrp::Vector3(1.5, 1.5, 1.5);
ikp.eefm_ee_moment_limit = hrp::Vector3(1e4, 1e4, 1e4); // Default limit [Nm] is too large. Same as no limit.
if (ikp.ee_name.find("leg") == std::string::npos) { // Arm default
ikp.eefm_ee_forcemoment_distribution_weight = Eigen::Matrix<double, 6,1>::Zero();
} else { // Leg default
for (size_t j = 0; j < 3; j++) {
ikp.eefm_ee_forcemoment_distribution_weight[j] = 1; // Force
ikp.eefm_ee_forcemoment_distribution_weight[j+3] = 1e-2; // Moment
}
}
ikp.max_limb_length = 0.0;
while (!root->isRoot()) {
ikp.max_limb_length += root->b.norm();
ikp.parent_name = root->name;
root = root->parent;
}
ikp.limb_length_margin = 0.13;
ikp.support_time = 0.0;
}
eefm_swing_rot_damping_gain = hrp::Vector3(20*5, 20*5, 1e5);
eefm_swing_pos_damping_gain = hrp::Vector3(33600, 33600, 7000);
eefm_pos_time_const_swing = 0.08;
eefm_pos_transition_time = 0.01;
eefm_pos_margin_time = 0.02;
eefm_zmp_delay_time_const[0] = eefm_zmp_delay_time_const[1] = 0.055;
//eefm_leg_inside_margin = 0.065; // [m]
//eefm_leg_front_margin = 0.05;
//eefm_leg_rear_margin = 0.05;
//fm_wrench_alpha_blending = 1.0; // fz_alpha
eefm_gravitational_acceleration = 9.80665; // [m/s^2]
cop_check_margin = 20.0*1e-3; // [m]
cp_check_margin.resize(4, 30*1e-3); // [m]
cp_offset = hrp::Vector3(0.0, 0.0, 0.0); // [m]
tilt_margin.resize(2, 30 * M_PI / 180); // [rad]
contact_decision_threshold = 50; // [N]
eefm_use_force_difference_control = true;
eefm_use_swing_damping = false;
eefm_swing_damping_force_thre.resize(3, 300);
eefm_swing_damping_moment_thre.resize(3, 15);
initial_cp_too_large_error = true;
is_walking = false;
is_estop_while_walking = false;
sbp_cog_offset = hrp::Vector3(0.0, 0.0, 0.0);
use_limb_stretch_avoidance = false;
use_zmp_truncation = false;
limb_stretch_avoidance_time_const = 1.5;
limb_stretch_avoidance_vlimit[0] = -100 * 1e-3 * dt; // lower limit
limb_stretch_avoidance_vlimit[1] = 50 * 1e-3 * dt; // upper limit
root_rot_compensation_limit[0] = root_rot_compensation_limit[1] = deg2rad(90.0);
detection_count_to_air = static_cast<int>(0.0 / dt);
// parameters for RUNST
double ke = 0, tc = 0;
for (int i = 0; i < 2; i++) {
m_tau_x[i].setup(ke, tc, dt);
m_tau_x[i].setErrorPrefix(std::string(m_profile.instance_name));
m_tau_y[i].setup(ke, tc, dt);
m_tau_y[i].setErrorPrefix(std::string(m_profile.instance_name));
m_f_z.setup(ke, tc, dt);
m_f_z.setErrorPrefix(std::string(m_profile.instance_name));
}
pangx_ref = pangy_ref = pangx = pangy = 0;
rdx = rdy = rx = ry = 0;
pdr = hrp::Vector3::Zero();
// Check is legged robot or not
is_legged_robot = false;
for (size_t i = 0; i < stikp.size(); i++) {
if (stikp[i].ee_name.find("leg") == std::string::npos) continue;
hrp::Sensor* sen= m_robot->sensor<hrp::ForceSensor>(stikp[i].sensor_name);
if ( sen != NULL ) is_legged_robot = true;
}
is_emergency = false;
reset_emergency_flag = false;
m_qCurrent.data.length(m_robot->numJoints());
m_qRef.data.length(m_robot->numJoints());
m_tau.data.length(m_robot->numJoints());
transition_joint_q.resize(m_robot->numJoints());
qorg.resize(m_robot->numJoints());
qrefv.resize(m_robot->numJoints());
transition_count = 0;
loop = 0;
m_is_falling_counter = 0;
is_air_counter = 0;
total_mass = m_robot->totalMass();
ref_zmp_aux = hrp::Vector3::Zero();
m_actContactStates.data.length(m_contactStates.data.length());
for (size_t i = 0; i < m_contactStates.data.length(); i++) {
ref_contact_states.push_back(true);
prev_ref_contact_states.push_back(true);
m_actContactStates.data[i] = false;
act_contact_states.push_back(false);
toeheel_ratio.push_back(1.0);
}
m_COPInfo.data.length(m_contactStates.data.length()*3); // nx, ny, fz for each end-effectors
for (size_t i = 0; i < m_COPInfo.data.length(); i++) {
m_COPInfo.data[i] = 0.0;
}
transition_time = 2.0;
foot_origin_offset[0] = hrp::Vector3::Zero();
foot_origin_offset[1] = hrp::Vector3::Zero();
//
act_cogvel_filter = boost::shared_ptr<FirstOrderLowPassFilter<hrp::Vector3> >(new FirstOrderLowPassFilter<hrp::Vector3>(4.0, dt, hrp::Vector3::Zero())); // [Hz]
// for debug output
m_originRefZmp.data.x = m_originRefZmp.data.y = m_originRefZmp.data.z = 0.0;
m_originRefCog.data.x = m_originRefCog.data.y = m_originRefCog.data.z = 0.0;
m_originRefCogVel.data.x = m_originRefCogVel.data.y = m_originRefCogVel.data.z = 0.0;
m_originNewZmp.data.x = m_originNewZmp.data.y = m_originNewZmp.data.z = 0.0;
m_originActZmp.data.x = m_originActZmp.data.y = m_originActZmp.data.z = 0.0;
m_originActCog.data.x = m_originActCog.data.y = m_originActCog.data.z = 0.0;
m_originActCogVel.data.x = m_originActCogVel.data.y = m_originActCogVel.data.z = 0.0;
m_allRefWrench.data.length(stikp.size() * 6); // 6 is wrench dim
m_allEEComp.data.length(stikp.size() * 6); // 6 is pos+rot dim
m_debugData.data.length(1); m_debugData.data[0] = 0.0;
//
szd = new SimpleZMPDistributor(dt);
std::vector<std::vector<Eigen::Vector2d> > support_polygon_vec;
for (size_t i = 0; i < stikp.size(); i++) {
support_polygon_vec.push_back(std::vector<Eigen::Vector2d>(1,Eigen::Vector2d::Zero()));
}
szd->set_vertices(support_polygon_vec);
rel_ee_pos.reserve(stikp.size());
rel_ee_rot.reserve(stikp.size());
rel_ee_name.reserve(stikp.size());
hrp::Sensor* sen = m_robot->sensor<hrp::RateGyroSensor>("gyrometer");
if (sen == NULL) {
std::cerr << "[" << m_profile.instance_name << "] WARNING! This robot model has no GyroSensor named 'gyrometer'! " << std::endl;
}
return RTC::RTC_OK;
}
RTC::ReturnCode_t Stabilizer::onFinalize()
{
if (szd == NULL) {
delete szd;
szd = NULL;
}
return RTC::RTC_OK;
}
/*
RTC::ReturnCode_t Stabilizer::onStartup(RTC::UniqueId ec_id)
{
return RTC::RTC_OK;
}
*/
/*
RTC::ReturnCode_t Stabilizer::onShutdown(RTC::UniqueId ec_id)
{
return RTC::RTC_OK;
}
*/
RTC::ReturnCode_t Stabilizer::onActivated(RTC::UniqueId ec_id)
{
std::cerr << "[" << m_profile.instance_name<< "] onActivated(" << ec_id << ")" << std::endl;
return RTC::RTC_OK;
}
RTC::ReturnCode_t Stabilizer::onDeactivated(RTC::UniqueId ec_id)
{
Guard guard(m_mutex);
std::cerr << "[" << m_profile.instance_name<< "] onDeactivated(" << ec_id << ")" << std::endl;
if ( (control_mode == MODE_ST || control_mode == MODE_AIR) ) {
sync_2_idle ();
control_mode = MODE_IDLE;
transition_count = 1; // sync in one controller loop
}
return RTC::RTC_OK;
}
#define DEBUGP ((m_debugLevel==1 && loop%200==0) || m_debugLevel > 1 )
#define DEBUGP2 (loop%10==0)
RTC::ReturnCode_t Stabilizer::onExecute(RTC::UniqueId ec_id)
{
loop++;
// std::cout << m_profile.instance_name<< ": onExecute(" << ec_id << ")" << std::endl;
if (m_qRefIn.isNew()) {
m_qRefIn.read();
}
if (m_qCurrentIn.isNew()) {
m_qCurrentIn.read();
}
if (m_rpyIn.isNew()) {
m_rpyIn.read();
}
if (m_zmpRefIn.isNew()) {
m_zmpRefIn.read();
}
if (m_basePosIn.isNew()){
m_basePosIn.read();
}
if (m_baseRpyIn.isNew()){
m_baseRpyIn.read();
}
if (m_contactStatesIn.isNew()){
m_contactStatesIn.read();
for (size_t i = 0; i < m_contactStates.data.length(); i++) {
ref_contact_states[i] = m_contactStates.data[i];
}
}
if (m_toeheelRatioIn.isNew()){
m_toeheelRatioIn.read();
for (size_t i = 0; i < m_toeheelRatio.data.length(); i++) {
toeheel_ratio[i] = m_toeheelRatio.data[i];
}
}
if (m_controlSwingSupportTimeIn.isNew()){
m_controlSwingSupportTimeIn.read();
}
for (size_t i = 0; i < m_wrenchesIn.size(); ++i) {
if ( m_wrenchesIn[i]->isNew() ) {
m_wrenchesIn[i]->read();
}
}
for (size_t i = 0; i < m_ref_wrenchesIn.size(); ++i) {
if ( m_ref_wrenchesIn[i]->isNew() ) {
m_ref_wrenchesIn[i]->read();
}
}
Guard guard(m_mutex);
for (size_t i = 0; i < m_limbCOPOffsetIn.size(); ++i) {
if ( m_limbCOPOffsetIn[i]->isNew() ) {
m_limbCOPOffsetIn[i]->read();
//stikp[i].localCOPPos = stikp[i].localp + stikp[i].localR * hrp::Vector3(m_limbCOPOffset[i].data.x, m_limbCOPOffset[i].data.y, m_limbCOPOffset[i].data.z);
stikp[i].localCOPPos = stikp[i].localp + stikp[i].localR * hrp::Vector3(m_limbCOPOffset[i].data.x, 0, m_limbCOPOffset[i].data.z);
}
}
if (m_qRefSeqIn.isNew()) {
m_qRefSeqIn.read();
is_seq_interpolating = true;
} else {
is_seq_interpolating = false;
}
if (m_walkingStatesIn.isNew()){
m_walkingStatesIn.read();
is_walking = m_walkingStates.data;
}
if (m_sbpCogOffsetIn.isNew()){
m_sbpCogOffsetIn.read();
sbp_cog_offset(0) = m_sbpCogOffset.data.x;
sbp_cog_offset(1) = m_sbpCogOffset.data.y;
sbp_cog_offset(2) = m_sbpCogOffset.data.z;
}
if (is_legged_robot) {
getCurrentParameters();
getTargetParameters();
getActualParameters();
calcStateForEmergencySignal();
switch (control_mode) {
case MODE_IDLE:
break;
case MODE_AIR:
if ( transition_count == 0 && on_ground ) sync_2_st();
break;
case MODE_ST:
if (st_algorithm != OpenHRP::StabilizerService::TPCC) {
calcEEForceMomentControl();
} else {
calcTPCC();
}
if ( transition_count == 0 && !on_ground ) {
if (is_air_counter < detection_count_to_air) ++is_air_counter;
else control_mode = MODE_SYNC_TO_AIR;
} else is_air_counter = 0;
break;
case MODE_SYNC_TO_IDLE:
sync_2_idle();
control_mode = MODE_IDLE;
break;
case MODE_SYNC_TO_AIR:
sync_2_idle();
control_mode = MODE_AIR;
break;
}
}
if ( m_robot->numJoints() == m_qRef.data.length() ) {
if (is_legged_robot) {
for ( int i = 0; i < m_robot->numJoints(); i++ ){
m_qRef.data[i] = m_robot->joint(i)->q;
//m_tau.data[i] = m_robot->joint(i)->u;
}
m_zmp.data.x = rel_act_zmp(0);
m_zmp.data.y = rel_act_zmp(1);
m_zmp.data.z = rel_act_zmp(2);
m_zmp.tm = m_qRef.tm;
m_zmpOut.write();
m_refCP.data.x = rel_ref_cp(0);
m_refCP.data.y = rel_ref_cp(1);
m_refCP.data.z = rel_ref_cp(2);
m_refCP.tm = m_qRef.tm;
m_refCPOut.write();
m_actCP.data.x = rel_act_cp(0);
m_actCP.data.y = rel_act_cp(1);
m_actCP.data.z = rel_act_cp(2);
m_actCP.tm = m_qRef.tm;
m_actCPOut.write();
{
hrp::Vector3 tmp_diff_cp = ref_foot_origin_rot * (ref_cp - act_cp - cp_offset);
m_diffCP.data.x = tmp_diff_cp(0);
m_diffCP.data.y = tmp_diff_cp(1);
m_diffCP.data.z = tmp_diff_cp(2);
m_diffCP.tm = m_qRef.tm;
m_diffCPOut.write();
}
m_diffFootOriginExtMoment.data.x = diff_foot_origin_ext_moment(0);
m_diffFootOriginExtMoment.data.y = diff_foot_origin_ext_moment(1);
m_diffFootOriginExtMoment.data.z = diff_foot_origin_ext_moment(2);
m_diffFootOriginExtMoment.tm = m_qRef.tm;
m_diffFootOriginExtMomentOut.write();
m_actContactStates.tm = m_qRef.tm;
m_actContactStatesOut.write();
m_COPInfo.tm = m_qRef.tm;
m_COPInfoOut.write();
//m_tauOut.write();
// for debug output
m_originRefZmp.data.x = ref_zmp(0); m_originRefZmp.data.y = ref_zmp(1); m_originRefZmp.data.z = ref_zmp(2);
m_originRefCog.data.x = ref_cog(0); m_originRefCog.data.y = ref_cog(1); m_originRefCog.data.z = ref_cog(2);
m_originRefCogVel.data.x = ref_cogvel(0); m_originRefCogVel.data.y = ref_cogvel(1); m_originRefCogVel.data.z = ref_cogvel(2);
m_originNewZmp.data.x = new_refzmp(0); m_originNewZmp.data.y = new_refzmp(1); m_originNewZmp.data.z = new_refzmp(2);
m_originActZmp.data.x = act_zmp(0); m_originActZmp.data.y = act_zmp(1); m_originActZmp.data.z = act_zmp(2);
m_originActCog.data.x = act_cog(0); m_originActCog.data.y = act_cog(1); m_originActCog.data.z = act_cog(2);
m_originActCogVel.data.x = act_cogvel(0); m_originActCogVel.data.y = act_cogvel(1); m_originActCogVel.data.z = act_cogvel(2);
m_originRefZmp.tm = m_qRef.tm;
m_originRefZmpOut.write();
m_originRefCog.tm = m_qRef.tm;
m_originRefCogOut.write();
m_originRefCogVel.tm = m_qRef.tm;
m_originRefCogVelOut.write();
m_originNewZmp.tm = m_qRef.tm;
m_originNewZmpOut.write();
m_originActZmp.tm = m_qRef.tm;
m_originActZmpOut.write();
m_originActCog.tm = m_qRef.tm;
m_originActCogOut.write();
m_originActCogVel.tm = m_qRef.tm;
m_originActCogVelOut.write();
for (size_t i = 0; i < stikp.size(); i++) {
for (size_t j = 0; j < 3; j++) {
m_allRefWrench.data[6*i+j] = stikp[i].ref_force(j);
m_allRefWrench.data[6*i+j+3] = stikp[i].ref_moment(j);
m_allEEComp.data[6*i+j] = stikp[i].d_foot_pos(j);
m_allEEComp.data[6*i+j+3] = stikp[i].d_foot_rpy(j);
}
}
m_allRefWrench.tm = m_qRef.tm;
m_allRefWrenchOut.write();
m_allEEComp.tm = m_qRef.tm;
m_allEECompOut.write();
m_actBaseRpy.data.r = act_base_rpy(0);
m_actBaseRpy.data.p = act_base_rpy(1);
m_actBaseRpy.data.y = act_base_rpy(2);
m_actBaseRpy.tm = m_qRef.tm;
m_currentBaseRpy.data.r = current_base_rpy(0);
m_currentBaseRpy.data.p = current_base_rpy(1);
m_currentBaseRpy.data.y = current_base_rpy(2);
m_currentBaseRpy.tm = m_qRef.tm;
m_currentBasePos.data.x = current_base_pos(0);
m_currentBasePos.data.y = current_base_pos(1);
m_currentBasePos.data.z = current_base_pos(2);
m_currentBasePos.tm = m_qRef.tm;
m_actBaseRpyOut.write();
m_currentBaseRpyOut.write();
m_currentBasePosOut.write();
m_debugData.tm = m_qRef.tm;
m_debugDataOut.write();
}
m_qRefOut.write();
// emergencySignal
if (reset_emergency_flag) {
m_emergencySignal.data = 0;
m_emergencySignalOut.write();
reset_emergency_flag = false;
} else if (is_emergency) {
m_emergencySignal.data = 1;
m_emergencySignalOut.write();
}
}
return RTC::RTC_OK;
}
void Stabilizer::getCurrentParameters ()
{
current_root_p = m_robot->rootLink()->p;
current_root_R = m_robot->rootLink()->R;
for ( int i = 0; i < m_robot->numJoints(); i++ ){
qorg[i] = m_robot->joint(i)->q;
}
}
void Stabilizer::calcFootOriginCoords (hrp::Vector3& foot_origin_pos, hrp::Matrix33& foot_origin_rot)
{
rats::coordinates leg_c[2], tmpc;
hrp::Vector3 ez = hrp::Vector3::UnitZ();
hrp::Vector3 ex = hrp::Vector3::UnitX();
for (size_t i = 0; i < stikp.size(); i++) {
if (stikp[i].ee_name.find("leg") == std::string::npos) continue;
hrp::Link* target = m_robot->sensor<hrp::ForceSensor>(stikp[i].sensor_name)->link;
leg_c[i].pos = target->p + target->R * foot_origin_offset[i];
hrp::Vector3 xv1(target->R * ex);
xv1(2)=0.0;
xv1.normalize();
hrp::Vector3 yv1(ez.cross(xv1));
leg_c[i].rot(0,0) = xv1(0); leg_c[i].rot(1,0) = xv1(1); leg_c[i].rot(2,0) = xv1(2);
leg_c[i].rot(0,1) = yv1(0); leg_c[i].rot(1,1) = yv1(1); leg_c[i].rot(2,1) = yv1(2);
leg_c[i].rot(0,2) = ez(0); leg_c[i].rot(1,2) = ez(1); leg_c[i].rot(2,2) = ez(2);
}
if (ref_contact_states[contact_states_index_map["rleg"]] &&
ref_contact_states[contact_states_index_map["lleg"]]) {
rats::mid_coords(tmpc, 0.5, leg_c[0], leg_c[1]);
foot_origin_pos = tmpc.pos;
foot_origin_rot = tmpc.rot;
} else if (ref_contact_states[contact_states_index_map["rleg"]]) {
foot_origin_pos = leg_c[contact_states_index_map["rleg"]].pos;
foot_origin_rot = leg_c[contact_states_index_map["rleg"]].rot;
} else {
foot_origin_pos = leg_c[contact_states_index_map["lleg"]].pos;
foot_origin_rot = leg_c[contact_states_index_map["lleg"]].rot;
}
}
void Stabilizer::getActualParameters ()
{
// Actual world frame =>
hrp::Vector3 foot_origin_pos;
hrp::Matrix33 foot_origin_rot;
if (st_algorithm != OpenHRP::StabilizerService::TPCC) {
// update by current joint angles
for ( int i = 0; i < m_robot->numJoints(); i++ ){
m_robot->joint(i)->q = m_qCurrent.data[i];
}
// tempolary
m_robot->rootLink()->p = hrp::Vector3::Zero();
m_robot->calcForwardKinematics();
hrp::Sensor* sen = m_robot->sensor<hrp::RateGyroSensor>("gyrometer");
hrp::Matrix33 senR = sen->link->R * sen->localR;
hrp::Matrix33 act_Rs(hrp::rotFromRpy(m_rpy.data.r, m_rpy.data.p, m_rpy.data.y));
//hrp::Matrix33 act_Rs(hrp::rotFromRpy(m_rpy.data.r*0.5, m_rpy.data.p*0.5, m_rpy.data.y*0.5));
m_robot->rootLink()->R = act_Rs * (senR.transpose() * m_robot->rootLink()->R);
m_robot->calcForwardKinematics();
act_base_rpy = hrp::rpyFromRot(m_robot->rootLink()->R);
calcFootOriginCoords (foot_origin_pos, foot_origin_rot);
} else {
for ( int i = 0; i < m_robot->numJoints(); i++ ) {
m_robot->joint(i)->q = qorg[i];
}
m_robot->rootLink()->p = current_root_p;
m_robot->rootLink()->R = current_root_R;
m_robot->calcForwardKinematics();
}
// cog
act_cog = m_robot->calcCM();
// zmp
on_ground = false;
if (st_algorithm != OpenHRP::StabilizerService::TPCC) {
on_ground = calcZMP(act_zmp, zmp_origin_off+foot_origin_pos(2));
} else {
on_ground = calcZMP(act_zmp, ref_zmp(2));
}
// set actual contact states
for (size_t i = 0; i < stikp.size(); i++) {
std::string limb_name = stikp[i].ee_name;
size_t idx = contact_states_index_map[limb_name];
act_contact_states[idx] = isContact(idx);
m_actContactStates.data[idx] = act_contact_states[idx];
}
// <= Actual world frame
// convert absolute (in st) -> root-link relative
rel_act_zmp = m_robot->rootLink()->R.transpose() * (act_zmp - m_robot->rootLink()->p);
if (st_algorithm != OpenHRP::StabilizerService::TPCC) {
// Actual foot_origin frame =>
act_zmp = foot_origin_rot.transpose() * (act_zmp - foot_origin_pos);
act_cog = foot_origin_rot.transpose() * (act_cog - foot_origin_pos);
//act_cogvel = foot_origin_rot.transpose() * act_cogvel;
if (ref_contact_states != prev_ref_contact_states) {
act_cogvel = (foot_origin_rot.transpose() * prev_act_foot_origin_rot) * act_cogvel;
} else {
act_cogvel = (act_cog - prev_act_cog)/dt;
}
prev_act_foot_origin_rot = foot_origin_rot;
act_cogvel = act_cogvel_filter->passFilter(act_cogvel);
prev_act_cog = act_cog;
//act_root_rot = m_robot->rootLink()->R;
for (size_t i = 0; i < stikp.size(); i++) {
hrp::Link* target = m_robot->link(stikp[i].target_name);
//hrp::Vector3 act_ee_p = target->p + target->R * stikp[i].localCOPPos;
hrp::Vector3 _act_ee_p = target->p + target->R * stikp[i].localp;
act_ee_p[i] = foot_origin_rot.transpose() * (_act_ee_p - foot_origin_pos);
act_ee_R[i] = foot_origin_rot.transpose() * (target->R * stikp[i].localR);
}
// capture point
act_cp = act_cog + act_cogvel / std::sqrt(eefm_gravitational_acceleration / (act_cog - act_zmp)(2));
rel_act_cp = hrp::Vector3(act_cp(0), act_cp(1), act_zmp(2));
rel_act_cp = m_robot->rootLink()->R.transpose() * ((foot_origin_pos + foot_origin_rot * rel_act_cp) - m_robot->rootLink()->p);
// <= Actual foot_origin frame
// Actual world frame =>
// new ZMP calculation
// Kajita's feedback law
// Basically Equation (26) in the paper [1].
hrp::Vector3 dcog=foot_origin_rot * (ref_cog - act_cog);
hrp::Vector3 dcogvel=foot_origin_rot * (ref_cogvel - act_cogvel);
hrp::Vector3 dzmp=foot_origin_rot * (ref_zmp - act_zmp);
new_refzmp = foot_origin_rot * new_refzmp + foot_origin_pos;
for (size_t i = 0; i < 2; i++) {
new_refzmp(i) += eefm_k1[i] * transition_smooth_gain * dcog(i) + eefm_k2[i] * transition_smooth_gain * dcogvel(i) + eefm_k3[i] * transition_smooth_gain * dzmp(i) + ref_zmp_aux(i);
}
if (DEBUGP) {
// All state variables are foot_origin coords relative
std::cerr << "[" << m_profile.instance_name << "] state values" << std::endl;
std::cerr << "[" << m_profile.instance_name << "] "
<< "ref_cog = " << hrp::Vector3(ref_cog*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]"))
<< ", act_cog = " << hrp::Vector3(act_cog*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[mm]" << std::endl;
std::cerr << "[" << m_profile.instance_name << "] "
<< "ref_cogvel = " << hrp::Vector3(ref_cogvel*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]"))
<< ", act_cogvel = " << hrp::Vector3(act_cogvel*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[mm/s]" << std::endl;
std::cerr << "[" << m_profile.instance_name << "] "
<< "ref_zmp = " << hrp::Vector3(ref_zmp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]"))
<< ", act_zmp = " << hrp::Vector3(act_zmp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[mm]" << std::endl;
hrp::Vector3 tmpnew_refzmp;
tmpnew_refzmp = foot_origin_rot.transpose()*(new_refzmp-foot_origin_pos); // Actual world -> foot origin relative
std::cerr << "[" << m_profile.instance_name << "] "
<< "new_zmp = " << hrp::Vector3(tmpnew_refzmp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]"))
<< ", dif_zmp = " << hrp::Vector3((tmpnew_refzmp-ref_zmp)*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[mm]" << std::endl;
}
std::vector<std::string> ee_name;
// distribute new ZMP into foot force & moment
std::vector<hrp::Vector3> tmp_ref_force, tmp_ref_moment;
std::vector<double> limb_gains;
std::vector<hrp::dvector6> ee_forcemoment_distribution_weight;
std::vector<double> tmp_toeheel_ratio;
if (control_mode == MODE_ST) {
std::vector<hrp::Vector3> ee_pos, cop_pos;
std::vector<hrp::Matrix33> ee_rot;
std::vector<bool> is_contact_list;
is_contact_list.reserve(stikp.size());
for (size_t i = 0; i < stikp.size(); i++) {
STIKParam& ikp = stikp[i];
if (!is_feedback_control_enable[i]) continue;
hrp::Link* target = m_robot->link(ikp.target_name);
ee_pos.push_back(target->p + target->R * ikp.localp);
cop_pos.push_back(target->p + target->R * ikp.localCOPPos);
ee_rot.push_back(target->R * ikp.localR);
ee_name.push_back(ikp.ee_name);
limb_gains.push_back(ikp.swing_support_gain);
tmp_ref_force.push_back(hrp::Vector3(foot_origin_rot * ref_force[i]));
tmp_ref_moment.push_back(hrp::Vector3(foot_origin_rot * ref_moment[i]));
rel_ee_pos.push_back(foot_origin_rot.transpose() * (ee_pos.back() - foot_origin_pos));
rel_ee_rot.push_back(foot_origin_rot.transpose() * ee_rot.back());
rel_ee_name.push_back(ee_name.back());
is_contact_list.push_back(act_contact_states[i]);
// std::cerr << ee_forcemoment_distribution_weight[i] << std::endl;
ee_forcemoment_distribution_weight.push_back(hrp::dvector6::Zero(6,1));
for (size_t j = 0; j < 6; j++) {
ee_forcemoment_distribution_weight[i][j] = ikp.eefm_ee_forcemoment_distribution_weight[j];
}
tmp_toeheel_ratio.push_back(toeheel_ratio[i]);
}
// All state variables are foot_origin coords relative
if (DEBUGP) {
std::cerr << "[" << m_profile.instance_name << "] ee values" << std::endl;
hrp::Vector3 tmpp;
for (size_t i = 0; i < ee_name.size(); i++) {
tmpp = foot_origin_rot.transpose()*(ee_pos[i]-foot_origin_pos);
std::cerr << "[" << m_profile.instance_name << "] "
<< "ee_pos (" << ee_name[i] << ") = " << hrp::Vector3(tmpp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]"));
tmpp = foot_origin_rot.transpose()*(cop_pos[i]-foot_origin_pos);
std::cerr << ", cop_pos (" << ee_name[i] << ") = " << hrp::Vector3(tmpp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[mm]" << std::endl;
}
}
// truncate ZMP
if (use_zmp_truncation) {
Eigen::Vector2d tmp_new_refzmp(new_refzmp.head(2));
szd->get_vertices(support_polygon_vetices);
szd->calc_convex_hull(support_polygon_vetices, ref_contact_states, ee_pos, ee_rot);
if (!szd->is_inside_support_polygon(tmp_new_refzmp, hrp::Vector3::Zero(), true, std::string(m_profile.instance_name))) new_refzmp.head(2) = tmp_new_refzmp;
}
// Distribute ZMP into each EE force/moment at each COP
if (st_algorithm == OpenHRP::StabilizerService::EEFM) {
// Modified version of distribution in Equation (4)-(6) and (10)-(13) in the paper [1].
szd->distributeZMPToForceMoments(tmp_ref_force, tmp_ref_moment,
ee_pos, cop_pos, ee_rot, ee_name, limb_gains, tmp_toeheel_ratio,
new_refzmp, hrp::Vector3(foot_origin_rot * ref_zmp + foot_origin_pos),
eefm_gravitational_acceleration * total_mass, dt,
DEBUGP, std::string(m_profile.instance_name));
} else if (st_algorithm == OpenHRP::StabilizerService::EEFMQP) {
szd->distributeZMPToForceMomentsQP(tmp_ref_force, tmp_ref_moment,
ee_pos, cop_pos, ee_rot, ee_name, limb_gains, tmp_toeheel_ratio,
new_refzmp, hrp::Vector3(foot_origin_rot * ref_zmp + foot_origin_pos),
eefm_gravitational_acceleration * total_mass, dt,
DEBUGP, std::string(m_profile.instance_name),
(st_algorithm == OpenHRP::StabilizerService::EEFMQPCOP));
} else if (st_algorithm == OpenHRP::StabilizerService::EEFMQPCOP) {
szd->distributeZMPToForceMomentsPseudoInverse(tmp_ref_force, tmp_ref_moment,
ee_pos, cop_pos, ee_rot, ee_name, limb_gains, tmp_toeheel_ratio,
new_refzmp, hrp::Vector3(foot_origin_rot * ref_zmp + foot_origin_pos),
eefm_gravitational_acceleration * total_mass, dt,
DEBUGP, std::string(m_profile.instance_name),
(st_algorithm == OpenHRP::StabilizerService::EEFMQPCOP), is_contact_list);
} else if (st_algorithm == OpenHRP::StabilizerService::EEFMQPCOP2) {
szd->distributeZMPToForceMomentsPseudoInverse2(tmp_ref_force, tmp_ref_moment,
ee_pos, cop_pos, ee_rot, ee_name, limb_gains, tmp_toeheel_ratio,
new_refzmp, hrp::Vector3(foot_origin_rot * ref_zmp + foot_origin_pos),
foot_origin_rot * ref_total_force, foot_origin_rot * ref_total_moment,
ee_forcemoment_distribution_weight,
eefm_gravitational_acceleration * total_mass, dt,
DEBUGP, std::string(m_profile.instance_name));
}
// for debug output
new_refzmp = foot_origin_rot.transpose() * (new_refzmp - foot_origin_pos);
}
// foor modif
if (control_mode == MODE_ST) {
hrp::Vector3 f_diff(hrp::Vector3::Zero());
std::vector<bool> large_swing_f_diff(3, false);
// moment control
act_total_foot_origin_moment = hrp::Vector3::Zero();