forked from fkanehiro/hrpsys-base
-
Notifications
You must be signed in to change notification settings - Fork 0
/
AutoBalancer.cpp
1568 lines (1469 loc) · 70.9 KB
/
AutoBalancer.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 AutoBalancer.cpp
* @brief autobalancer component
* $Date$
*
* $Id$
*/
#include <rtm/CorbaNaming.h>
#include <hrpModel/Link.h>
#include <hrpModel/Sensor.h>
#include <hrpModel/ModelLoaderUtil.h>
#include "AutoBalancer.h"
#include <hrpModel/JointPath.h>
#include <hrpUtil/MatrixSolvers.h>
#include "util/Hrpsys.h"
typedef coil::Guard<coil::Mutex> Guard;
using namespace rats;
// Module specification
// <rtc-template block="module_spec">
static const char* autobalancer_spec[] =
{
"implementation_id", "AutoBalancer",
"type_name", "AutoBalancer",
"description", "autobalancer component",
"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>
AutoBalancer::AutoBalancer(RTC::Manager* manager)
: RTC::DataFlowComponentBase(manager),
// <rtc-template block="initializer">
m_qRefIn("qRef", m_qRef),
m_basePosIn("basePosIn", m_basePos),
m_baseRpyIn("baseRpyIn", m_baseRpy),
m_zmpIn("zmpIn", m_zmp),
m_optionalDataIn("optionalData", m_optionalData),
m_emergencySignalIn("emergencySignal", m_emergencySignal),
m_qOut("q", m_qRef),
m_zmpOut("zmpOut", m_zmp),
m_basePosOut("basePosOut", m_basePos),
m_baseRpyOut("baseRpyOut", m_baseRpy),
m_baseTformOut("baseTformOut", m_baseTform),
m_basePoseOut("basePoseOut", m_basePose),
m_accRefOut("accRef", m_accRef),
m_contactStatesOut("contactStates", m_contactStates),
m_controlSwingSupportTimeOut("controlSwingSupportTime", m_controlSwingSupportTime),
m_cogOut("cogOut", m_cog),
m_AutoBalancerServicePort("AutoBalancerService"),
// </rtc-template>
move_base_gain(0.8),
m_robot(hrp::BodyPtr()),
m_debugLevel(0)
{
m_service0.autobalancer(this);
}
AutoBalancer::~AutoBalancer()
{
}
RTC::ReturnCode_t AutoBalancer::onInitialize()
{
std::cerr << "[" << m_profile.instance_name << "] onInitialize()" << std::endl;
bindParameter("debugLevel", m_debugLevel, "0");
// Registration: InPort/OutPort/Service
// <rtc-template block="registration">
// Set InPort buffers
addInPort("qRef", m_qRefIn);
addInPort("basePosIn", m_basePosIn);
addInPort("baseRpyIn", m_baseRpyIn);
addInPort("zmpIn", m_zmpIn);
addInPort("optionalData", m_optionalDataIn);
addInPort("emergencySignal", m_emergencySignalIn);
// Set OutPort buffer
addOutPort("q", m_qOut);
addOutPort("zmpOut", m_zmpOut);
addOutPort("basePosOut", m_basePosOut);
addOutPort("baseRpyOut", m_baseRpyOut);
addOutPort("baseTformOut", m_baseTformOut);
addOutPort("basePoseOut", m_basePoseOut);
addOutPort("accRef", m_accRefOut);
addOutPort("contactStates", m_contactStatesOut);
addOutPort("controlSwingSupportTime", m_controlSwingSupportTimeOut);
addOutPort("cogOut", m_cogOut);
// Set service provider to Ports
m_AutoBalancerServicePort.registerProvider("service0", "AutoBalancerService", m_service0);
// Set service consumers to Ports
// Set CORBA Service Ports
addPort(m_AutoBalancerServicePort);
// </rtc-template>
// <rtc-template block="bind_config">
// Bind variables and configuration variable
// </rtc-template>
RTC::Properties& prop = getProperties();
coil::stringTo(m_dt, prop["dt"].c_str());
m_robot = hrp::BodyPtr(new hrp::Body());
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());
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;
}
// allocate memory for outPorts
m_qRef.data.length(m_robot->numJoints());
qorg.resize(m_robot->numJoints());
qrefv.resize(m_robot->numJoints());
m_baseTform.data.length(12);
control_mode = MODE_IDLE;
loop = 0;
// setting from conf file
// GaitGenerator requires abc_leg_offset and abc_stride_parameter in robot conf file
// setting leg_pos from conf file
coil::vstring leg_offset_str = coil::split(prop["abc_leg_offset"], ",");
std::vector<hrp::Vector3> leg_pos;
if (leg_offset_str.size() > 0) {
hrp::Vector3 leg_offset;
for (size_t i = 0; i < 3; i++) coil::stringTo(leg_offset(i), leg_offset_str[i].c_str());
std::cerr << "[" << m_profile.instance_name << "] abc_leg_offset = " << leg_offset.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[m]" << std::endl;
leg_pos.push_back(hrp::Vector3(-1*leg_offset));
leg_pos.push_back(hrp::Vector3(leg_offset));
}
leg_names.push_back("rleg");
leg_names.push_back("lleg");
// setting from conf file
// rleg,TARGET_LINK,BASE_LINK
coil::vstring end_effectors_str = coil::split(prop["end_effectors"], ",");
size_t prop_num = 10;
if (end_effectors_str.size() > 0) {
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());
ABCIKparam tp;
for (size_t j = 0; j < 3; j++) {
coil::stringTo(tp.localPos(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());
}
tp.localR = Eigen::AngleAxis<double>(tmpv[3], hrp::Vector3(tmpv[0], tmpv[1], tmpv[2])).toRotationMatrix(); // rotation in VRML is represented by axis + angle
tp.manip = hrp::JointPathExPtr(new hrp::JointPathEx(m_robot, m_robot->link(ee_base), m_robot->link(ee_target), m_dt, false));
// Fix for toe joint
if (ee_name.find("leg") != std::string::npos && tp.manip->numJoints() == 7) { // leg and 7dof joint (6dof leg +1dof toe)
std::vector<double> optw;
for (int j = 0; j < tp.manip->numJoints(); j++ ) {
if ( j == tp.manip->numJoints()-1 ) optw.push_back(0.0);
else optw.push_back(1.0);
}
tp.manip->setOptionalWeightVector(optw);
}
ikp.insert(std::pair<std::string, ABCIKparam>(ee_name , tp));
ikp[ee_name].target_link = m_robot->link(ee_target);
std::cerr << "[" << m_profile.instance_name << "] End Effector [" << ee_name << "]" << std::endl;
std::cerr << "[" << m_profile.instance_name << "] target = " << ikp[ee_name].target_link->name << ", base = " << ee_base << std::endl;
std::cerr << "[" << m_profile.instance_name << "] offset_pos = " << tp.localPos.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[m]" << std::endl;
contact_states_index_map.insert(std::pair<std::string, size_t>(ee_name, i));
}
m_contactStates.data.length(num);
if (ikp.find("rleg") != ikp.end() && ikp.find("lleg") != ikp.end()) {
m_contactStates.data[contact_states_index_map["rleg"]] = true;
m_contactStates.data[contact_states_index_map["lleg"]] = true;
}
if (ikp.find("rarm") != ikp.end() && ikp.find("larm") != ikp.end()) {
m_contactStates.data[contact_states_index_map["rarm"]] = false;
m_contactStates.data[contact_states_index_map["larm"]] = false;
}
m_controlSwingSupportTime.data.length(num);
for (size_t i = 0; i < num; i++) m_controlSwingSupportTime.data[i] = 0.0;
}
zmp_offset_interpolator = new interpolator(ikp.size()*3, m_dt);
zmp_transition_time = 1.0;
transition_interpolator = new interpolator(1, m_dt, interpolator::HOFFARBIB, 1);
transition_interpolator_ratio = 1.0;
adjust_footstep_interpolator = new interpolator(1, m_dt, interpolator::HOFFARBIB, 1);
transition_time = 2.0;
adjust_footstep_transition_time = 2.0;
// setting stride limitations from conf file
double stride_fwd_x_limit = 0.15;
double stride_y_limit = 0.05;
double stride_th_limit = 10;
double stride_bwd_x_limit = 0.05;
std::cerr << "[" << m_profile.instance_name << "] abc_stride_parameter : " << stride_fwd_x_limit << "[m], " << stride_y_limit << "[m], " << stride_th_limit << "[deg], " << stride_bwd_x_limit << "[m]" << std::endl;
if (default_zmp_offsets.size() == 0) {
for (size_t i = 0; i < ikp.size(); i++) default_zmp_offsets.push_back(hrp::Vector3::Zero());
}
if (leg_offset_str.size() > 0) {
gg = ggPtr(new rats::gait_generator(m_dt, leg_pos, leg_names, stride_fwd_x_limit/*[m]*/, stride_y_limit/*[m]*/, stride_th_limit/*[deg]*/, stride_bwd_x_limit/*[m]*/));
gg->set_default_zmp_offsets(default_zmp_offsets);
}
gg_is_walking = gg_solved = false;
fix_leg_coords = coordinates();
// load virtual force sensors
readVirtualForceSensorParamFromProperties(m_vfs, m_robot, prop["virtual_force_sensor"], std::string(m_profile.instance_name));
// ref force port
int npforce = m_robot->numSensors(hrp::Sensor::FORCE);
int nvforce = m_vfs.size();
int nforce = npforce + nvforce;
m_ref_force.resize(nforce);
m_ref_forceIn.resize(nforce);
m_limbCOPOffset.resize(nforce);
m_limbCOPOffsetOut.resize(nforce);
for (unsigned int i=0; i<npforce; i++){
sensor_names.push_back(m_robot->sensor(hrp::Sensor::FORCE, i)->name);
}
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) sensor_names.push_back(it->first);
}
}
// set ref force port
std::cerr << "[" << m_profile.instance_name << "] force sensor ports (" << nforce << ")" << std::endl;
for (unsigned int i=0; i<nforce; i++){
m_ref_forceIn[i] = new InPort<TimedDoubleSeq>(std::string("ref_"+sensor_names[i]).c_str(), m_ref_force[i]);
m_ref_force[i].data.length(6);
registerInPort(std::string("ref_"+sensor_names[i]).c_str(), *m_ref_forceIn[i]);
std::cerr << "[" << m_profile.instance_name << "] name = " << std::string("ref_"+sensor_names[i]) << std::endl;
ref_forces.push_back(hrp::Vector3(0,0,0));
}
// set limb cop offset port
std::cerr << "[" << m_profile.instance_name << "] limbCOPOffset ports (" << nforce << ")" << std::endl;
for (unsigned int i=0; i<nforce; i++){
std::string nm("limbCOPOffset_"+sensor_names[i]);
m_limbCOPOffsetOut[i] = new OutPort<TimedPoint3D>(nm.c_str(), m_limbCOPOffset[i]);
registerOutPort(nm.c_str(), *m_limbCOPOffsetOut[i]);
m_limbCOPOffset[i].data.x = m_limbCOPOffset[i].data.y = m_limbCOPOffset[i].data.z = 0.0;
std::cerr << "[" << m_profile.instance_name << "] name = " << nm << std::endl;
}
sbp_offset = hrp::Vector3(0,0,0);
sbp_cog_offset = hrp::Vector3(0,0,0);
//use_force = MODE_NO_FORCE;
use_force = MODE_REF_FORCE;
if (ikp.find("rleg") != ikp.end() && ikp.find("lleg") != ikp.end()) {
is_legged_robot = true;
} else {
is_legged_robot = false;
}
m_accRef.data.ax = m_accRef.data.ay = m_accRef.data.az = 0.0;
prev_imu_sensor_vel = hrp::Vector3::Zero();
graspless_manip_mode = false;
graspless_manip_arm = "arms";
graspless_manip_p_gain = hrp::Vector3::Zero();
is_stop_mode = false;
return RTC::RTC_OK;
}
RTC::ReturnCode_t AutoBalancer::onFinalize()
{
delete zmp_offset_interpolator;
delete transition_interpolator;
delete adjust_footstep_interpolator;
return RTC::RTC_OK;
}
/*
RTC::ReturnCode_t AutoBalancer::onStartup(RTC::UniqueId ec_id)
{
return RTC::RTC_OK;
}
*/
/*
RTC::ReturnCode_t AutoBalancer::onShutdown(RTC::UniqueId ec_id)
{
return RTC::RTC_OK;
}
*/
RTC::ReturnCode_t AutoBalancer::onActivated(RTC::UniqueId ec_id)
{
std::cerr << "[" << m_profile.instance_name<< "] onActivated(" << ec_id << ")" << std::endl;
return RTC::RTC_OK;
}
RTC::ReturnCode_t AutoBalancer::onDeactivated(RTC::UniqueId ec_id)
{
std::cerr << "[" << m_profile.instance_name<< "] onDeactivated(" << ec_id << ")" << std::endl;
Guard guard(m_mutex);
if (control_mode == MODE_ABC) {
control_mode = MODE_SYNC_TO_IDLE;
double tmp_ratio = 0.0;
transition_interpolator->go(&tmp_ratio, m_dt, true); // sync in one controller loop
}
return RTC::RTC_OK;
}
#define DEBUGP ((m_debugLevel==1 && loop%200==0) || m_debugLevel > 1 )
//#define DEBUGP2 ((loop%200==0))
#define DEBUGP2 (false)
RTC::ReturnCode_t AutoBalancer::onExecute(RTC::UniqueId ec_id)
{
// std::cerr << "AutoBalancer::onExecute(" << ec_id << ")" << std::endl;
loop ++;
if (m_qRefIn.isNew()) {
m_qRefIn.read();
}
if (m_basePosIn.isNew()) {
m_basePosIn.read();
input_basePos(0) = m_basePos.data.x;
input_basePos(1) = m_basePos.data.y;
input_basePos(2) = m_basePos.data.z;
}
if (m_baseRpyIn.isNew()) {
m_baseRpyIn.read();
input_baseRot = hrp::rotFromRpy(m_baseRpy.data.r, m_baseRpy.data.p, m_baseRpy.data.y);
}
if (m_zmpIn.isNew()) {
m_zmpIn.read();
input_zmp(0) = m_zmp.data.x;
input_zmp(1) = m_zmp.data.y;
input_zmp(2) = m_zmp.data.z;
}
for (unsigned int i=0; i<m_ref_forceIn.size(); i++){
if ( m_ref_forceIn[i]->isNew() ) {
m_ref_forceIn[i]->read();
}
}
if (m_optionalDataIn.isNew()) {
m_optionalDataIn.read();
if (is_legged_robot) {
if (m_optionalData.data.length() >= contact_states_index_map.size()*2) {
// current optionalData is contactstates x limb and controlSwingSupportTime x limb
// If contactStates in optionalData is 1.0, m_contactStates is true. Otherwise, false.
m_contactStates.data[contact_states_index_map["rleg"]] = (std::fabs(m_optionalData.data[contact_states_index_map["rleg"]]-1.0)<0.1)?true:false;
m_contactStates.data[contact_states_index_map["lleg"]] = (std::fabs(m_optionalData.data[contact_states_index_map["lleg"]]-1.0)<0.1)?true:false;
m_controlSwingSupportTime.data[contact_states_index_map["rleg"]] = m_optionalData.data[contact_states_index_map["rleg"]+contact_states_index_map.size()];
m_controlSwingSupportTime.data[contact_states_index_map["lleg"]] = m_optionalData.data[contact_states_index_map["lleg"]+contact_states_index_map.size()];
if ( !m_contactStates.data[contact_states_index_map["rleg"]] && !m_contactStates.data[contact_states_index_map["lleg"]] ) { // If two feet have no contact, force set double support contact
m_contactStates.data[contact_states_index_map["rleg"]] = true;
m_contactStates.data[contact_states_index_map["lleg"]] = true;
}
}
}
}
if (m_emergencySignalIn.isNew()){
m_emergencySignalIn.read();
// if (!is_stop_mode) {
// std::cerr << "[" << m_profile.instance_name << "] emergencySignal is set!" << std::endl;
// is_stop_mode = true;
// }
}
Guard guard(m_mutex);
hrp::Vector3 ref_basePos;
hrp::Matrix33 ref_baseRot;
hrp::Vector3 rel_ref_zmp; // ref zmp in base frame
if ( is_legged_robot ) {
getCurrentParameters();
getTargetParameters();
bool is_transition_interpolator_empty = transition_interpolator->isEmpty();
if (!is_transition_interpolator_empty) {
transition_interpolator->get(&transition_interpolator_ratio, true);
} else {
transition_interpolator_ratio = 1.0;
}
if (control_mode != MODE_IDLE ) {
solveLimbIK();
rel_ref_zmp = m_robot->rootLink()->R.transpose() * (ref_zmp - m_robot->rootLink()->p);
} else {
for ( std::map<std::string, ABCIKparam>::iterator it = ikp.begin(); it != ikp.end(); it++ ) {
if (std::find(leg_names.begin(), leg_names.end(), it->first) != leg_names.end() ) {
it->second.current_p0 = it->second.target_link->p;
it->second.current_r0 = it->second.target_link->R;
}
}
rel_ref_zmp = input_zmp;
}
// transition
if (!is_transition_interpolator_empty) {
// transition_interpolator_ratio 0=>1 : IDLE => ABC
// transition_interpolator_ratio 1=>0 : ABC => IDLE
ref_basePos = (1-transition_interpolator_ratio) * input_basePos + transition_interpolator_ratio * m_robot->rootLink()->p;
rel_ref_zmp = (1-transition_interpolator_ratio) * input_zmp + transition_interpolator_ratio * rel_ref_zmp;
rats::mid_rot(ref_baseRot, transition_interpolator_ratio, input_baseRot, m_robot->rootLink()->R);
for ( int i = 0; i < m_robot->numJoints(); i++ ) {
m_robot->joint(i)->q = (1-transition_interpolator_ratio) * m_qRef.data[i] + transition_interpolator_ratio * m_robot->joint(i)->q;
}
} else {
ref_basePos = m_robot->rootLink()->p;
ref_baseRot = m_robot->rootLink()->R;
}
// mode change for sync
if (control_mode == MODE_SYNC_TO_ABC) {
control_mode = MODE_ABC;
} else if (control_mode == MODE_SYNC_TO_IDLE && transition_interpolator->isEmpty() ) {
std::cerr << "[" << m_profile.instance_name << "] Finished cleanup" << std::endl;
control_mode = MODE_IDLE;
}
}
if ( m_qRef.data.length() != 0 ) { // initialized
if (is_legged_robot) {
for ( int i = 0; i < m_robot->numJoints(); i++ ){
m_qRef.data[i] = m_robot->joint(i)->q;
}
}
m_qOut.write();
}
if (is_legged_robot) {
// basePos
m_basePos.data.x = ref_basePos(0);
m_basePos.data.y = ref_basePos(1);
m_basePos.data.z = ref_basePos(2);
m_basePos.tm = m_qRef.tm;
// baseRpy
hrp::Vector3 baseRpy = hrp::rpyFromRot(ref_baseRot);
m_baseRpy.data.r = baseRpy(0);
m_baseRpy.data.p = baseRpy(1);
m_baseRpy.data.y = baseRpy(2);
m_baseRpy.tm = m_qRef.tm;
// baseTform
double *tform_arr = m_baseTform.data.get_buffer();
tform_arr[0] = m_basePos.data.x;
tform_arr[1] = m_basePos.data.y;
tform_arr[2] = m_basePos.data.z;
hrp::setMatrix33ToRowMajorArray(ref_baseRot, tform_arr, 3);
m_baseTform.tm = m_qRef.tm;
// basePose
m_basePose.data.position.x = m_basePos.data.x;
m_basePose.data.position.y = m_basePos.data.y;
m_basePose.data.position.z = m_basePos.data.z;
m_basePose.data.orientation.r = m_baseRpy.data.r;
m_basePose.data.orientation.p = m_baseRpy.data.p;
m_basePose.data.orientation.y = m_baseRpy.data.y;
m_basePose.tm = m_qRef.tm;
// zmp
m_zmp.data.x = rel_ref_zmp(0);
m_zmp.data.y = rel_ref_zmp(1);
m_zmp.data.z = rel_ref_zmp(2);
m_zmp.tm = m_qRef.tm;
// cog
m_cog.data.x = ref_cog(0);
m_cog.data.y = ref_cog(1);
m_cog.data.z = ref_cog(2);
m_cog.tm = m_qRef.tm;
}
m_basePosOut.write();
m_baseRpyOut.write();
m_baseTformOut.write();
m_basePoseOut.write();
m_zmpOut.write();
m_cogOut.write();
// reference acceleration
hrp::Sensor* sen = m_robot->sensor<hrp::RateGyroSensor>("gyrometer");
if (sen != NULL) {
hrp::Vector3 imu_sensor_pos = sen->link->p + sen->link->R * sen->localPos;
hrp::Vector3 imu_sensor_vel = (imu_sensor_pos - prev_imu_sensor_pos)/m_dt;
// convert to imu sensor local acceleration
hrp::Vector3 acc = (sen->link->R * sen->localR).transpose() * (imu_sensor_vel - prev_imu_sensor_vel)/m_dt;
m_accRef.data.ax = acc(0); m_accRef.data.ay = acc(1); m_accRef.data.az = acc(2);
m_accRefOut.write();
prev_imu_sensor_pos = imu_sensor_pos;
prev_imu_sensor_vel = imu_sensor_vel;
}
// control parameters
m_contactStates.tm = m_qRef.tm;
m_contactStatesOut.write();
m_controlSwingSupportTime.tm = m_qRef.tm;
m_controlSwingSupportTimeOut.write();
for (unsigned int i=0; i<m_limbCOPOffsetOut.size(); i++){
m_limbCOPOffset[i].tm = m_qRef.tm;
m_limbCOPOffsetOut[i]->write();
}
return RTC::RTC_OK;
}
void AutoBalancer::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 AutoBalancer::getTargetParameters()
{
// joint angles
for ( int i = 0; i < m_robot->numJoints(); i++ ){
m_robot->joint(i)->q = m_qRef.data[i];
qrefv[i] = m_robot->joint(i)->q;
}
// basepos, rot, zmp
m_robot->rootLink()->p = input_basePos;
m_robot->rootLink()->R = input_baseRot;
m_robot->calcForwardKinematics();
//
if (control_mode != MODE_IDLE) {
coordinates tmp_fix_coords;
if (!zmp_offset_interpolator->isEmpty()) {
double *default_zmp_offsets_output = new double[ikp.size()*3];
zmp_offset_interpolator->get(default_zmp_offsets_output, true);
for (size_t i = 0; i < ikp.size(); i++)
for (size_t j = 0; j < 3; j++)
default_zmp_offsets[i](j) = default_zmp_offsets_output[i*3+j];
delete[] default_zmp_offsets_output;
if (DEBUGP) {
std::cerr << "[" << m_profile.instance_name << "] default_zmp_offsets (interpolated)" << std::endl;
std::map<leg_type, std::string> leg_type_map = gg->get_leg_type_map();
for (size_t i = 0; i < leg_names.size(); i++) {
std::map<leg_type, std::string>::const_iterator dst = std::find_if(leg_type_map.begin(), leg_type_map.end(), (&boost::lambda::_1->* &std::map<leg_type, std::string>::value_type::second == leg_names[i]));
std::cerr << "[" << m_profile.instance_name << "] " << leg_names[i] << " = " << default_zmp_offsets[dst->first].format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[m]" << std::endl;
}
}
}
if ( gg_is_walking ) {
gg->set_default_zmp_offsets(default_zmp_offsets);
gg_solved = gg->proc_one_tick();
{
std::map<leg_type, std::string> leg_type_map = gg->get_leg_type_map();
coordinates tmpc;
// for support leg
for (std::vector<step_node>::const_iterator it = gg->get_support_leg_steps().begin(); it != gg->get_support_leg_steps().end(); it++) {
coordinates sp_coords = it->worldcoords;
coordinates(ikp[leg_type_map[it->l_r]].localPos,
ikp[leg_type_map[it->l_r]].localR).inverse_transformation(tmpc);
sp_coords.transform(tmpc);
ikp[leg_type_map[it->l_r]].target_p0 = sp_coords.pos;
ikp[leg_type_map[it->l_r]].target_r0 = sp_coords.rot;
}
// for swing leg
for (std::vector<step_node>::const_iterator it = gg->get_swing_leg_steps().begin(); it != gg->get_swing_leg_steps().end(); it++) {
coordinates sw_coords = it->worldcoords;
coordinates(ikp[leg_type_map[it->l_r]].localPos,
ikp[leg_type_map[it->l_r]].localR).inverse_transformation(tmpc);
sw_coords.transform(tmpc);
ikp[leg_type_map[it->l_r]].target_p0 = sw_coords.pos;
ikp[leg_type_map[it->l_r]].target_r0 = sw_coords.rot;
}
}
gg->get_swing_support_mid_coords(tmp_fix_coords);
// TODO : assume biped
switch (gg->get_current_support_states().front()) {
case BOTH:
m_contactStates.data[contact_states_index_map["rleg"]] = true;
m_contactStates.data[contact_states_index_map["lleg"]] = true;
break;
case RLEG:
m_contactStates.data[contact_states_index_map["rleg"]] = true;
m_contactStates.data[contact_states_index_map["lleg"]] = false;
break;
case LLEG:
m_contactStates.data[contact_states_index_map["rleg"]] = false;
m_contactStates.data[contact_states_index_map["lleg"]] = true;
break;
default:
if (DEBUGP) std::cerr << "not implemented yet " << std::endl;
break;
}
m_controlSwingSupportTime.data[contact_states_index_map["rleg"]] = gg->get_current_swing_time(0);
m_controlSwingSupportTime.data[contact_states_index_map["lleg"]] = gg->get_current_swing_time(1);
m_limbCOPOffset[contact_states_index_map[gg->get_swing_leg_names().front()]].data.x = gg->get_swing_foot_zmp_offsets().front()(0);
m_limbCOPOffset[contact_states_index_map[gg->get_swing_leg_names().front()]].data.y = gg->get_swing_foot_zmp_offsets().front()(1);
m_limbCOPOffset[contact_states_index_map[gg->get_swing_leg_names().front()]].data.z = gg->get_swing_foot_zmp_offsets().front()(2);
m_limbCOPOffset[contact_states_index_map[gg->get_support_leg_names().front()]].data.x = gg->get_support_foot_zmp_offsets().front()(0);
m_limbCOPOffset[contact_states_index_map[gg->get_support_leg_names().front()]].data.y = gg->get_support_foot_zmp_offsets().front()(1);
m_limbCOPOffset[contact_states_index_map[gg->get_support_leg_names().front()]].data.z = gg->get_support_foot_zmp_offsets().front()(2);
} else {
tmp_fix_coords = fix_leg_coords;
// double support by default
m_contactStates.data[contact_states_index_map["rleg"]] = true;
m_contactStates.data[contact_states_index_map["lleg"]] = true;
// controlSwingSupportTime is not used while double support period, 1.0 is neglected
m_controlSwingSupportTime.data[contact_states_index_map["rleg"]] = 1.0;
m_controlSwingSupportTime.data[contact_states_index_map["lleg"]] = 1.0;
m_limbCOPOffset[contact_states_index_map["rleg"]].data.x = default_zmp_offsets[0](0);
m_limbCOPOffset[contact_states_index_map["rleg"]].data.y = default_zmp_offsets[0](1);
m_limbCOPOffset[contact_states_index_map["rleg"]].data.z = default_zmp_offsets[0](2);
m_limbCOPOffset[contact_states_index_map["lleg"]].data.x = default_zmp_offsets[1](0);
m_limbCOPOffset[contact_states_index_map["lleg"]].data.y = default_zmp_offsets[1](1);
m_limbCOPOffset[contact_states_index_map["lleg"]].data.z = default_zmp_offsets[1](2);
}
if (!adjust_footstep_interpolator->isEmpty()) {
double tmp = 0.0;
adjust_footstep_interpolator->get(&tmp, true);
//std::cerr << "[" << m_profile.instance_name << "] adjust ratio " << tmp << std::endl;
ikp["rleg"].target_p0 = (1-tmp) * ikp["rleg"].adjust_interpolation_org_p0 + tmp*ikp["rleg"].adjust_interpolation_target_p0;
ikp["lleg"].target_p0 = (1-tmp) * ikp["lleg"].adjust_interpolation_org_p0 + tmp*ikp["lleg"].adjust_interpolation_target_p0;
rats::mid_rot(ikp["rleg"].target_r0, tmp, ikp["rleg"].adjust_interpolation_org_r0, ikp["rleg"].adjust_interpolation_target_r0);
rats::mid_rot(ikp["lleg"].target_r0, tmp, ikp["lleg"].adjust_interpolation_org_r0, ikp["lleg"].adjust_interpolation_target_r0);
coordinates tmprc, tmplc;
tmprc.pos = ikp["rleg"].target_p0 + ikp["rleg"].target_r0 * ikp["rleg"].localPos;
tmprc.rot = ikp["rleg"].target_r0 * ikp["rleg"].localR;
tmplc.pos = ikp["lleg"].target_p0 + ikp["lleg"].target_r0 * ikp["lleg"].localPos;
tmplc.rot = ikp["lleg"].target_r0 * ikp["lleg"].localR;
rats::mid_coords(fix_leg_coords, 0.5, tmprc, tmplc);
tmp_fix_coords = fix_leg_coords;
}
// Tempolarily modify tmp_fix_coords
// This will be removed after seq outputs adequate waistRPY discussed in https://github.com/fkanehiro/hrpsys-base/issues/272
{
hrp::Vector3 ex = hrp::Vector3::UnitX();
hrp::Vector3 ez = hrp::Vector3::UnitZ();
hrp::Vector3 xv1 (tmp_fix_coords.rot * ex);
xv1(2) = 0.0;
xv1.normalize();
hrp::Vector3 yv1(ez.cross(xv1));
tmp_fix_coords.rot(0,0) = xv1(0); tmp_fix_coords.rot(1,0) = xv1(1); tmp_fix_coords.rot(2,0) = xv1(2);
tmp_fix_coords.rot(0,1) = yv1(0); tmp_fix_coords.rot(1,1) = yv1(1); tmp_fix_coords.rot(2,1) = yv1(2);
tmp_fix_coords.rot(0,2) = ez(0); tmp_fix_coords.rot(1,2) = ez(1); tmp_fix_coords.rot(2,2) = ez(2);
}
fixLegToCoords(tmp_fix_coords.pos, tmp_fix_coords.rot);
/* update ref_forces ;; sp's absolute -> rmc's absolute */
for (size_t i = 0; i < m_ref_forceIn.size(); i++) {
hrp::Matrix33 eeR;
hrp::Link* parentlink;
hrp::ForceSensor* sensor = m_robot->sensor<hrp::ForceSensor>(sensor_names[i]);
if (sensor) parentlink = sensor->link;
else parentlink = m_vfs[sensor_names[i]].link;
for ( std::map<std::string, ABCIKparam>::iterator it = ikp.begin(); it != ikp.end(); it++ ) {
if (it->second.target_link->name == parentlink->name) eeR = parentlink->R * it->second.localR;
}
// End effector frame
//ref_forces[i] = eeR * hrp::Vector3(m_ref_force[i].data[0], m_ref_force[i].data[1], m_ref_force[i].data[2]);
// world frame
ref_forces[i] = tmp_fix_coords.rot * hrp::Vector3(m_ref_force[i].data[0], m_ref_force[i].data[1], m_ref_force[i].data[2]);
}
sbp_offset = tmp_fix_coords.rot * hrp::Vector3(sbp_offset);
target_root_p = m_robot->rootLink()->p;
target_root_R = m_robot->rootLink()->R;
for ( std::map<std::string, ABCIKparam>::iterator it = ikp.begin(); it != ikp.end(); it++ ) {
if ( control_mode == MODE_IDLE || std::find(leg_names.begin(), leg_names.end(), it->first) == leg_names.end() ) {
it->second.target_p0 = it->second.target_link->p;
it->second.target_r0 = it->second.target_link->R;
}
}
hrp::Vector3 tmp_foot_mid_pos(hrp::Vector3::Zero());
{
std::map<leg_type, std::string> leg_type_map = gg->get_leg_type_map();
std::map<leg_type, double> zmp_weight_map = gg->get_zmp_weight_map();
double sum_of_weight = 0.0;
for (size_t i = 0; i < leg_names.size(); i++) {
ABCIKparam& tmpikp = ikp[leg_names[i]];
// get target_end_coords
tmpikp.target_end_coords.pos = tmpikp.target_p0 + tmpikp.target_r0 * tmpikp.localPos;
tmpikp.target_end_coords.rot = tmpikp.target_r0 * tmpikp.localR;
// for foot_mid_pos
std::map<leg_type, std::string>::const_iterator dst = std::find_if(leg_type_map.begin(), leg_type_map.end(), (&boost::lambda::_1->* &std::map<leg_type, std::string>::value_type::second == leg_names[i]));
tmp_foot_mid_pos += (tmpikp.target_link->p + tmpikp.target_link->R * tmpikp.localPos + tmpikp.target_link->R * tmpikp.localR * default_zmp_offsets[i]) * zmp_weight_map[dst->first];
sum_of_weight += zmp_weight_map[dst->first];
}
tmp_foot_mid_pos *= (1.0 / sum_of_weight);
}
//
{
if ( gg_is_walking && gg->get_lcg_count() == static_cast<size_t>(gg->get_default_step_time()/(2*m_dt))-1) {
hrp::Vector3 vel_htc(calc_vel_from_hand_error(tmp_fix_coords));
gg->set_offset_velocity_param(vel_htc(0), vel_htc(1) ,vel_htc(2));
}// else {
// if ( gg_is_walking && gg->get_lcg_count() == static_cast<size_t>(gg->get_default_step_time()/(2*m_dt))-1) {
// gg->set_offset_velocity_param(0,0,0);
// }
// }
}
//
hrp::Vector3 tmp_ref_cog(m_robot->calcCM());
if (gg_is_walking) {
ref_cog = gg->get_cog();
} else {
ref_cog = tmp_foot_mid_pos;
}
ref_cog(2) = tmp_ref_cog(2);
if (gg_is_walking) {
ref_zmp = gg->get_refzmp();
} else {
ref_zmp(0) = ref_cog(0);
ref_zmp(1) = ref_cog(1);
ref_zmp(2) = tmp_foot_mid_pos(2);
}
}
// Just for ik initial value
if (control_mode == MODE_SYNC_TO_ABC) {
current_root_p = target_root_p;
current_root_R = target_root_R;
for ( std::map<std::string, ABCIKparam>::iterator it = ikp.begin(); it != ikp.end(); it++ ) {
if ( std::find(leg_names.begin(), leg_names.end(), it->first) != leg_names.end() ) {
it->second.target_p0 = it->second.target_link->p;
it->second.target_r0 = it->second.target_link->R;
}
}
}
};
hrp::Matrix33 AutoBalancer::OrientRotationMatrix (const hrp::Matrix33& rot, const hrp::Vector3& axis1, const hrp::Vector3& axis2)
{
hrp::Vector3 vv = axis1.cross(axis2);
if (fabs(vv.norm()-0.0) < 1e-5) {
return rot;
} else {
Eigen::AngleAxis<double> tmpr(std::asin(vv.norm()), vv.normalized());
return tmpr.toRotationMatrix() * rot;
}
}
void AutoBalancer::fixLegToCoords (const hrp::Vector3& fix_pos, const hrp::Matrix33& fix_rot)
{
// get current foot mid pos + rot
std::vector<coordinates> foot_coords;
for (size_t i = 0; i < leg_names.size(); i++) {
ABCIKparam& tmpikp = ikp[leg_names[i]];
foot_coords.push_back(coordinates((tmpikp.target_link->p + tmpikp.target_link->R * tmpikp.localPos),
(tmpikp.target_link->R * tmpikp.localR)));
}
coordinates current_foot_mid_coords;
multi_mid_coords(current_foot_mid_coords, foot_coords);
hrp::Vector3 current_foot_mid_pos = current_foot_mid_coords.pos;
hrp::Matrix33 current_foot_mid_rot = current_foot_mid_coords.rot;
// fix root pos + rot to fix "coords" = "current_foot_mid_xx"
hrp::Matrix33 tmpR (fix_rot * current_foot_mid_rot.transpose());
m_robot->rootLink()->p = fix_pos + tmpR * (m_robot->rootLink()->p - current_foot_mid_pos);
rats::rotm3times(m_robot->rootLink()->R, tmpR, m_robot->rootLink()->R);
m_robot->calcForwardKinematics();
}
bool AutoBalancer::solveLimbIKforLimb (ABCIKparam& param)
{
param.current_p0 = param.target_link->p;
param.current_r0 = param.target_link->R;
hrp::Vector3 vel_p, vel_r;
vel_p = param.target_p0 - param.current_p0;
rats::difference_rotation(vel_r, param.current_r0, param.target_r0);
vel_p *= transition_interpolator_ratio;
vel_r *= transition_interpolator_ratio;
param.manip->calcInverseKinematics2Loop(vel_p, vel_r, 1.0, 0.001, 0.01, &qrefv);
return true;
}
void AutoBalancer::solveLimbIK ()
{
for ( std::map<std::string, ABCIKparam>::iterator it = ikp.begin(); it != ikp.end(); it++ ) {
if (it->second.is_active) {
for ( int j = 0; j < it->second.manip->numJoints(); j++ ){
int i = it->second.manip->joint(j)->jointId;
m_robot->joint(i)->q = qorg[i];
}
}
}
m_robot->rootLink()->p = current_root_p;
m_robot->rootLink()->R = current_root_R;
m_robot->calcForwardKinematics();
hrp::Vector3 tmp_input_sbp = hrp::Vector3(0,0,0);
static_balance_point_proc_one(tmp_input_sbp, ref_zmp(2));
hrp::Vector3 dif_cog = tmp_input_sbp - ref_cog;
dif_cog(2) = m_robot->rootLink()->p(2) - target_root_p(2);
m_robot->rootLink()->p = m_robot->rootLink()->p + -1 * move_base_gain * dif_cog;
m_robot->rootLink()->R = target_root_R;
// Fix for toe joint
for ( std::map<std::string, ABCIKparam>::iterator it = ikp.begin(); it != ikp.end(); it++ ) {
if (it->second.is_active && (it->first.find("leg") != std::string::npos) && it->second.manip->numJoints() == 7) {
int i = it->second.target_link->jointId;
if (gg->get_swing_leg_names().front() == it->first) {
m_robot->joint(i)->q = qrefv[i] + -1 * gg->get_foot_dif_rot_angle();
} else {
m_robot->joint(i)->q = qrefv[i];
}
}
}
m_robot->calcForwardKinematics();
for ( std::map<std::string, ABCIKparam>::iterator it = ikp.begin(); it != ikp.end(); it++ ) {
if (it->second.is_active) solveLimbIKforLimb(it->second);
}
if (gg_is_walking && !gg_solved) stopWalking ();
}
/*
RTC::ReturnCode_t AutoBalancer::onAborting(RTC::UniqueId ec_id)
{
return RTC::RTC_OK;
}
*/
/*
RTC::ReturnCode_t AutoBalancer::onError(RTC::UniqueId ec_id)
{
return RTC::RTC_OK;
}
*/
/*
RTC::ReturnCode_t AutoBalancer::onReset(RTC::UniqueId ec_id)
{
return RTC::RTC_OK;
}
*/
/*
RTC::ReturnCode_t AutoBalancer::onStateUpdate(RTC::UniqueId ec_id)
{
return RTC::RTC_OK;
}
*/
/*
RTC::ReturnCode_t AutoBalancer::onRateChanged(RTC::UniqueId ec_id)
{
return RTC::RTC_OK;
}
*/
void AutoBalancer::startABCparam(const OpenHRP::AutoBalancerService::StrSequence& limbs)
{
std::cerr << "[" << m_profile.instance_name << "] start auto balancer mode" << std::endl;
Guard guard(m_mutex);
double tmp_ratio = 0.0;
transition_interpolator->clear();
transition_interpolator->set(&tmp_ratio);
tmp_ratio = 1.0;
transition_interpolator->go(&tmp_ratio, transition_time, true);
for ( std::map<std::string, ABCIKparam>::iterator it = ikp.begin(); it != ikp.end(); it++ ) {
it->second.is_active = false;
}
for (size_t i = 0; i < limbs.length(); i++) {
ABCIKparam& tmp = ikp[std::string(limbs[i])];
tmp.is_active = true;
std::cerr << "[" << m_profile.instance_name << "] limb [" << std::string(limbs[i]) << "]" << std::endl;
}
control_mode = MODE_SYNC_TO_ABC;
}
void AutoBalancer::stopABCparam()
{
std::cerr << "[" << m_profile.instance_name << "] stop auto balancer mode" << std::endl;
//Guard guard(m_mutex);
double tmp_ratio = 1.0;
transition_interpolator->clear();
transition_interpolator->set(&tmp_ratio);
tmp_ratio = 0.0;
transition_interpolator->go(&tmp_ratio, transition_time, true);
control_mode = MODE_SYNC_TO_IDLE;
}
void AutoBalancer::startWalking ()
{
if ( control_mode != MODE_ABC ) {
return_control_mode = control_mode;
OpenHRP::AutoBalancerService::StrSequence fix_limbs;
fix_limbs.length(2);
fix_limbs[0] = "rleg";
fix_limbs[1] = "lleg";
startABCparam(fix_limbs);
waitABCTransition();
}
{
Guard guard(m_mutex);
std::vector<std::string> init_swing_leg_names(gg->get_footstep_front_leg_names());
std::vector<std::string> tmp_all_limbs(leg_names);
std::vector<std::string> init_support_leg_names;
std::sort(tmp_all_limbs.begin(), tmp_all_limbs.end());
std::sort(init_swing_leg_names.begin(), init_swing_leg_names.end());
std::set_difference(tmp_all_limbs.begin(), tmp_all_limbs.end(),
init_swing_leg_names.begin(), init_swing_leg_names.end(),
std::back_inserter(init_support_leg_names));
std::vector<step_node> init_support_leg_steps, init_swing_leg_dst_steps;
for (std::vector<std::string>::iterator it = init_support_leg_names.begin(); it != init_support_leg_names.end(); it++)
init_support_leg_steps.push_back(step_node(*it, ikp[*it].target_end_coords, 0, 0, 0, 0));
for (std::vector<std::string>::iterator it = init_swing_leg_names.begin(); it != init_swing_leg_names.end(); it++)
init_swing_leg_dst_steps.push_back(step_node(*it, ikp[*it].target_end_coords, 0, 0, 0, 0));
gg->set_default_zmp_offsets(default_zmp_offsets);
gg->initialize_gait_parameter(ref_cog, init_support_leg_steps, init_swing_leg_dst_steps);
}
while ( !gg->proc_one_tick() );
{
Guard guard(m_mutex);
gg_is_walking = gg_solved = true;
}
}
void AutoBalancer::stopWalking ()
{
std::vector<coordinates> tmp_end_coords_list;
for (std::vector<string>::iterator it = leg_names.begin(); it != leg_names.end(); it++) {
tmp_end_coords_list.push_back(ikp[*it].target_end_coords);
}
multi_mid_coords(fix_leg_coords, tmp_end_coords_list);
fixLegToCoords(fix_leg_coords.pos, fix_leg_coords.rot);
gg->clear_footstep_nodes_list();
if (return_control_mode == MODE_IDLE) stopABCparam();
gg_is_walking = false;
}
bool AutoBalancer::startAutoBalancer (const OpenHRP::AutoBalancerService::StrSequence& limbs)
{
if (control_mode == MODE_IDLE) {
startABCparam(limbs);
waitABCTransition();
return_control_mode = MODE_ABC;
return true;
} else {
return false;
}
}
bool AutoBalancer::stopAutoBalancer ()
{
if (control_mode == MODE_ABC) {
stopABCparam();
waitABCTransition();
return true;
} else {
return false;
}
}
void AutoBalancer::waitABCTransition()
{
while (!transition_interpolator->isEmpty()) usleep(1000);
usleep(1000);
}
bool AutoBalancer::goPos(const double& x, const double& y, const double& th)
{
if ( !gg_is_walking && !is_stop_mode) {
gg->set_all_limbs(leg_names);
coordinates start_ref_coords;
mid_coords(start_ref_coords, 0.5, ikp["rleg"].target_end_coords, ikp["lleg"].target_end_coords);
gg->go_pos_param_2_footstep_nodes_list(x, y, th,
(y > 0 ? boost::assign::list_of(ikp["rleg"].target_end_coords) : boost::assign::list_of(ikp["lleg"].target_end_coords)),
start_ref_coords,
(y > 0 ? boost::assign::list_of(RLEG) : boost::assign::list_of(LLEG)));
startWalking();
return true;
} else {
std::cerr << "[" << m_profile.instance_name << "] Cannot goPos while walking." << std::endl;
return false;
}
}
bool AutoBalancer::goVelocity(const double& vx, const double& vy, const double& vth)
{
if (gg_is_walking && gg_solved) {
gg->set_velocity_param(vx, vy, vth);
} else {
coordinates ref_coords;
mid_coords(ref_coords, 0.5, ikp["rleg"].target_end_coords, ikp["lleg"].target_end_coords);
gg->initialize_velocity_mode(ref_coords, vx, vy, vth);
startWalking();
}
return true;
}