-
Notifications
You must be signed in to change notification settings - Fork 28
/
HumanStateProvider.cpp
2682 lines (2281 loc) · 113 KB
/
HumanStateProvider.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
/*
* Copyright (C) 2018 Istituto Italiano di Tecnologia (IIT)
* All rights reserved.
*
* This software may be modified and distributed under the terms of the
* GNU Lesser General Public License v2.1 or any later version.
*/
#include "HumanStateProvider.h"
#include "IKWorkerPool.h"
#include <hde/algorithms/DynamicalInverseKinematics.hpp>
#include <hde/algorithms/InverseVelocityKinematics.hpp>
#include <hde/utils/iDynTreeUtils.hpp>
#include <Wearable/IWear/IWear.h>
#include <iDynTree/InverseKinematics.h>
#include <iDynTree/Model/Model.h>
#include <iDynTree/ModelIO/ModelLoader.h>
#include <yarp/os/LogStream.h>
#include <yarp/os/ResourceFinder.h>
#include <yarp/os/RpcServer.h>
#include <yarp/os/Vocab.h>
#include <iDynTree/Core/EigenHelpers.h>
#include <iDynTree/Model/Traversal.h>
#include <array>
#include <atomic>
#include <chrono>
#include <mutex>
#include <stack>
#include <string>
#include <thread>
#include <unordered_map>
#include <numeric>
/*!
* @brief analyze model and list of segments to create all possible segment pairs
*
* @param[in] model the full model
* @param[in] humanSegments list of segments on which look for the possible pairs
* @param[out] framePairs resulting list of all possible pairs. First element is parent, second is
* child
* @param[out] framePairIndeces indeces in the humanSegments list of the pairs in framePairs
*/
static void createEndEffectorsPairs(
const iDynTree::Model& model,
std::vector<SegmentInfo>& humanSegments,
std::vector<std::pair<std::string, std::string>>& framePairs,
std::vector<std::pair<iDynTree::FrameIndex, iDynTree::FrameIndex>>& framePairIndeces);
static bool getReducedModel(const iDynTree::Model& modelInput,
const std::string& parentFrame,
const std::string& endEffectorFrame,
iDynTree::Model& modelOutput);
const std::string DeviceName = "HumanStateProvider";
const std::string LogPrefix = DeviceName + " :";
constexpr double DefaultPeriod = 0.01;
using namespace hde::devices;
using namespace wearable;
// ==============
// IMPL AND UTILS
// ==============
using ModelJointName = std::string;
using ModelLinkName = std::string;
using WearableLinkName = std::string;
using WearableJointName = std::string;
using InverseVelocityKinematicsSolverName = std::string;
using FloatingBaseName = std::string;
struct WearableJointInfo
{
WearableJointName name;
size_t index;
};
// Struct that contains all the data exposed by the HumanState interface
struct SolutionIK
{
std::vector<double> jointPositions;
std::vector<double> jointVelocities;
std::array<double, 3> basePosition;
std::array<double, 4> baseOrientation;
std::array<double, 6> baseVelocity;
std::array<double, 3> CoMPosition;
std::array<double, 3> CoMVelocity;
void clear()
{
jointPositions.clear();
jointVelocities.clear();
}
};
enum SolverIK
{
global,
pairwised,
dynamical
};
enum rpcCommand
{
empty,
calibrate,
calibrateAll,
calibrateAllWithWorld,
calibrateSubTree,
calibrateRelativeLink,
setRotationOffset,
resetCalibration,
};
// Container of data coming from the wearable interface
struct WearableStorage
{
// Maps [model joint / link name] ==> [wearable virtual sensor name]
//
// E.g. [Pelvis] ==> [XsensSuit::vLink::Pelvis]. Read from the configuration.
//
std::unordered_map<ModelLinkName, WearableLinkName> modelToWearable_LinkName;
// Maps [wearable virtual sensor name] ==> [virtual sensor]
std::unordered_map<WearableLinkName, SensorPtr<const sensor::IVirtualLinkKinSensor>>
linkSensorsMap;
};
class HumanStateProvider::impl
{
public:
// Attached interface
wearable::IWear* iWear = nullptr;
bool allowIKFailures;
float period;
mutable std::mutex mutex;
// Rpc
class CmdParser;
std::unique_ptr<CmdParser> commandPro;
yarp::os::RpcServer rpcPort;
bool applyRpcCommand();
// Wearable variables
WearableStorage wearableStorage;
// Model variables
iDynTree::Model humanModel;
FloatingBaseName floatingBaseFrame;
std::vector<std::string> jointList;
std::vector<SegmentInfo> segments;
std::vector<LinkPairInfo> linkPairs;
// Buffers
std::unordered_map<std::string, iDynTree::Transform> linkTransformMatrices;
std::unordered_map<std::string, iDynTree::Transform> linkTransformMatricesRaw;
std::unordered_map<std::string, iDynTree::Twist> linkVelocities;
iDynTree::VectorDynSize jointConfigurationSolution;
iDynTree::VectorDynSize jointVelocitiesSolution;
iDynTree::Transform baseTransformSolution;
iDynTree::Twist baseVelocitySolution;
std::unordered_map<std::string, hde::utils::idyntree::rotation::RotationDistance>
linkErrorOrientations;
std::unordered_map<std::string, iDynTree::Vector3> linkErrorAngularVelocities;
// IK parameters
int ikPoolSize{1};
int maxIterationsIK;
double costTolerance;
std::string linearSolverName;
yarp::os::Value ikPoolOption;
std::unique_ptr<IKWorkerPool> ikPool;
SolutionIK solution;
InverseVelocityKinematicsSolverName inverseVelocityKinematicsSolver;
double posTargetWeight;
double rotTargetWeight;
double linVelTargetWeight;
double angVelTargetWeight;
double costRegularization;
double dynamicalIKMeasuredLinearVelocityGain;
double dynamicalIKMeasuredAngularVelocityGain;
double dynamicalIKLinearCorrectionGain;
double dynamicalIKAngularCorrectionGain;
double dynamicalIKJointVelocityLimit;
std::vector<std::string> custom_jointsVelocityLimitsNames;
std::vector<iDynTree::JointIndex> custom_jointsVelocityLimitsIndexes;
iDynTree::VectorDynSize custom_jointsVelocityLimitsValues;
// Custom Constraint Form: lowerBound<=A*X<=upperBuond
iDynTree::MatrixDynSize
customConstraintMatrix; // A, CxN matrix; C: number of Constraints, N: number of
// system states: Dofs+6 in floating-based robot
std::vector<std::string> customConstraintVariables; // X, Nx1 Vector : variables names
std::vector<iDynTree::JointIndex>
customConstraintVariablesIndex; // X, Nx1 Vector : variables index
iDynTree::VectorDynSize customConstraintUpperBound; // upperBuond, Cx1 Vector
iDynTree::VectorDynSize customConstraintLowerBound; // lowerBound, Cx1 Vector
iDynTree::VectorDynSize baseVelocityUpperLimit;
iDynTree::VectorDynSize baseVelocityLowerLimit;
double k_u, k_l;
// Secondary calibration
std::unordered_map<std::string, iDynTree::Rotation> secondaryCalibrationRotations;
std::unordered_map<std::string, iDynTree::Rotation> fixedSensorRotation;
iDynTree::Transform secondaryCalibrationWorld;
void eraseSecondaryCalibration(const std::string& linkName);
void selectChainJointsAndLinksForSecondaryCalibration(const std::string& linkName, const std::string& childLinkName,
std::vector<iDynTree::JointIndex>& jointZeroIndices, std::vector<iDynTree::LinkIndex>& linkToCalibrateIndices);
void computeSecondaryCalibrationRotationsForChain(const std::vector<iDynTree::JointIndex>& jointZeroIndices, const iDynTree::Transform &refLinkForCalibrationTransform, const std::vector<iDynTree::LinkIndex>& linkToCalibrateIndices, const std::string& refLinkForCalibrationName);
SolverIK ikSolver;
// flags
bool useDirectBaseMeasurement;
bool useFixedBase;
iDynTree::InverseKinematics globalIK;
hde::algorithms::InverseVelocityKinematics inverseVelocityKinematics; // used for computing joint velocity in global IK solution
hde::algorithms::DynamicalInverseKinematics dynamicalInverseKinematics;
hde::utils::idyntree::state::Integrator stateIntegrator;
// clock
double lastTime{-1.0};
// kinDynComputation
std::unique_ptr<iDynTree::KinDynComputations> kinDynComputations;
iDynTree::Vector3 worldGravity;
// get input data
bool getLinkTransformFromInputData(std::unordered_map<std::string, iDynTree::Transform>& t);
bool computeRelativeTransformForInputData(std::unordered_map<std::string, iDynTree::Transform>& t);
bool applyFixedRightRotationForInputTransformData(std::unordered_map<std::string, iDynTree::Transform>& t);
bool getLinkVelocityFromInputData(std::unordered_map<std::string, iDynTree::Twist>& t);
// calibrate data
bool applySecondaryCalibration(const std::unordered_map<std::string, iDynTree::Transform>& t_in, std::unordered_map<std::string, iDynTree::Transform>& t_out);
// solver initialization and update
bool createLinkPairs();
bool initializePairwisedInverseKinematicsSolver();
bool initializeGlobalInverseKinematicsSolver();
bool initializeDynamicalInverseKinematicsSolver();
bool solvePairwisedInverseKinematicsSolver();
bool solveGlobalInverseKinematicsSolver();
bool solveDynamicalInverseKinematics();
// optimization targets
bool updateInverseKinematicTargets();
bool addInverseKinematicTargets();
bool updateInverseVelocityKinematicTargets();
bool addInverseVelocityKinematicsTargets();
bool addDynamicalInverseKinematicsTargets();
bool computeLinksOrientationErrors(
std::unordered_map<std::string, iDynTree::Transform> linkDesiredOrientations,
iDynTree::VectorDynSize jointConfigurations,
iDynTree::Transform floatingBasePose,
std::unordered_map<std::string, hde::utils::idyntree::rotation::RotationDistance>&
linkErrorOrientations);
bool computeLinksAngularVelocityErrors(
std::unordered_map<std::string, iDynTree::Twist> linkDesiredVelocities,
iDynTree::VectorDynSize jointConfigurations,
iDynTree::Transform floatingBasePose,
iDynTree::VectorDynSize jointVelocities,
iDynTree::Twist baseVelocity,
std::unordered_map<std::string, iDynTree::Vector3>& linkAngularVelocityError);
// constructor
impl();
};
// ===============
// RPC PORT PARSER
// ===============
class HumanStateProvider::impl::CmdParser : public yarp::os::PortReader
{
public:
std::atomic<rpcCommand> cmdStatus{rpcCommand::empty};
std::string parentLinkName;
std::string childLinkName;
std::string refLinkName;
// variables for manual calibration
std::atomic<double> roll; // [deg]
std::atomic<double> pitch; // [deg]
std::atomic<double> yaw; // [deg]
void resetInternalVariables()
{
parentLinkName = "";
childLinkName = "";
cmdStatus = rpcCommand::empty;
}
bool read(yarp::os::ConnectionReader& connection) override
{
yarp::os::Bottle command, response;
if (command.read(connection)) {
if (command.get(0).asString() == "help") {
response.addVocab32(yarp::os::Vocab32::encode("many"));
response.addString("The following commands can be used to apply a secondary calibration assuming the subject is in the zero configuration of the model for the calibrated links. \n");
response.addString("Enter <calibrateAll> to apply a secondary calibration for all the links using the measured base pose \n");
response.addString("Enter <calibrateAllWithWorld <refLink>> to apply a secondary calibration for all the links assuming the <refLink> to be in the world origin \n");
response.addString("Enter <calibrate <linkName>> to apply a secondary calibration for the given link \n");
response.addString("Enter <setRotationOffset <linkName> <r p y [deg]>> to apply a secondary calibration for the given link using the given rotation offset (defined using rpy)\n");
response.addString("Enter <calibrateSubTree <parentLinkName> <childLinkName>> to apply a secondary calibration for the given chain \n");
response.addString("Enter <calibrateRelativeLink <parentLinkName> <childLinkName>> to apply a secondary calibration for the child link using the parent link as reference \n");
response.addString("Enter <reset <linkName>> to remove secondary calibration for the given link \n");
response.addString("Enter <resetAll> to remove all the secondary calibrations");
}
else if (command.get(0).asString() == "calibrateRelativeLink" && !command.get(1).isNull() && !command.get(2).isNull()) {
this->parentLinkName = command.get(1).asString();
this->childLinkName = command.get(2).asString();
response.addString("Entered command <calibrateRelativeLink> is correct, trying to set offset of " + this->childLinkName + " using " + this->parentLinkName + " as reference");
this->cmdStatus = rpcCommand::calibrateRelativeLink;
}
else if (command.get(0).asString() == "calibrateSubTree" && !command.get(1).isNull() && !command.get(2).isNull()) {
this->parentLinkName = command.get(1).asString();
this->childLinkName = command.get(2).asString();
response.addString("Entered command <calibrateSubTree> is correct, trying to set offset for the chain from " + this->parentLinkName + " to " + this->childLinkName);
this->cmdStatus = rpcCommand::calibrateSubTree;
}
else if (command.get(0).asString() == "calibrateAll") {
this->parentLinkName = "";
response.addString("Entered command <calibrateAll> is correct, trying to set offset calibration for all the links");
this->cmdStatus = rpcCommand::calibrateAll;
}
else if (command.get(0).asString() == "calibrateAllWithWorld") {
this->parentLinkName = "";
this->refLinkName = command.get(1).asString();
response.addString("Entered command <calibrateAllWithWorld> is correct, trying to set offset calibration for all the links, and setting base link " + this->refLinkName + " to the origin");
this->cmdStatus = rpcCommand::calibrateAllWithWorld;
}
else if (command.get(0).asString() == "calibrate" && !(command.get(1).isNull())) {
this->parentLinkName = command.get(1).asString();
response.addString("Entered command <calibrate> is correct, trying to set offset calibration for the link " + this->parentLinkName);
this->cmdStatus = rpcCommand::calibrate;
}
else if (command.get(0).asString() == "setRotationOffset" && !command.get(1).isNull() && command.get(2).isFloat64() && command.get(3).isFloat64() && command.get(4).isFloat64()) {
this->parentLinkName = command.get(1).asString();
this->roll = command.get(2).asFloat64();
this->pitch = command.get(3).asFloat64();
this->yaw = command.get(4).asFloat64();
response.addString("Entered command <calibrate> is correct, trying to set rotation offset for the link " + this->parentLinkName);
this->cmdStatus = rpcCommand::setRotationOffset;
}
else if (command.get(0).asString() == "resetAll") {
response.addString("Entered command <resetAll> is correct, removing all the secondary calibrations ");
this->cmdStatus = rpcCommand::resetCalibration;
}
else if (command.get(0).asString() == "reset" && !command.get(1).isNull()) {
this->parentLinkName = command.get(1).asString();
response.addString("Entered command <reset> is correct, trying to remove secondaty calibration for the link " + this->parentLinkName);
this->cmdStatus = rpcCommand::resetCalibration;
}
else {
response.addString(
"Entered command is incorrect. Enter help to know available commands");
}
}
else {
resetInternalVariables();
return false;
}
yarp::os::ConnectionWriter* reply = connection.getWriter();
if (reply != NULL) {
response.write(*reply);
}
else
return false;
return true;
}
};
// ===========
// CONSTRUCTOR
// ===========
HumanStateProvider::impl::impl()
: commandPro(new CmdParser())
{}
// =========================
// HUMANSTATEPROVIDER DEVICE
// =========================
HumanStateProvider::HumanStateProvider()
: PeriodicThread(DefaultPeriod)
, pImpl{new impl()}
{}
HumanStateProvider::~HumanStateProvider() {}
bool HumanStateProvider::open(yarp::os::Searchable& config)
{
// ===============================
// CHECK THE CONFIGURATION OPTIONS
// ===============================
if (!(config.check("period") && config.find("period").isFloat64())) {
yInfo() << LogPrefix << "Using default period:" << DefaultPeriod << "s";
}
if (!(config.check("urdf") && config.find("urdf").isString())) {
yError() << LogPrefix << "urdf option not found or not valid";
return false;
}
if (!(config.check("ikSolver") && config.find("ikSolver").isString())) {
yError() << LogPrefix << "ikSolver option not found or not valid";
return false;
}
if (!(config.check("jointList") && config.find("jointList").isList())) {
yInfo() << LogPrefix << "jointList option not found or not valid, all the model joints are selected.";
pImpl->jointList.clear();
}
else
{
auto jointListBottle = config.find("jointList").asList();
for (size_t it = 0; it < jointListBottle->size(); it++)
{
pImpl->jointList.push_back(jointListBottle->get(it).asString());
}
}
std::string baseFrameName;
if(config.check("floatingBaseFrame") && config.find("floatingBaseFrame").isList() ) {
baseFrameName = config.find("floatingBaseFrame").asList()->get(0).asString();
pImpl->useFixedBase = false;
yWarning() << LogPrefix << "'floatingBaseFrame' configuration option as list is deprecated. Please use a string with the model base name only.";
}
else if(config.check("floatingBaseFrame") && config.find("floatingBaseFrame").isString() ) {
baseFrameName = config.find("floatingBaseFrame").asString();
pImpl->useFixedBase = false;
}
else if(config.check("fixedBaseFrame") && config.find("fixedBaseFrame").isList() ) {
baseFrameName = config.find("fixedBaseFrame").asList()->get(0).asString();
pImpl->useFixedBase = true;
yWarning() << LogPrefix << "'fixedBaseFrame' configuration option as list is deprecated. Please use a string with the model base name only.";
}
else if(config.check("fixedBaseFrame") && config.find("fixedBaseFrame").isString() ) {
baseFrameName = config.find("fixedBaseFrame").asString();
pImpl->useFixedBase = true;
}
else {
yError() << LogPrefix << "BaseFrame option not found or not valid";
return false;
}
yarp::os::Bottle& linksGroup = config.findGroup("MODEL_TO_DATA_LINK_NAMES");
if (linksGroup.isNull()) {
yError() << LogPrefix << "Failed to find group MODEL_TO_DATA_LINK_NAMES";
return false;
}
for (size_t i = 1; i < linksGroup.size(); ++i) {
if (!(linksGroup.get(i).isList() && linksGroup.get(i).asList()->size() == 2)) {
yError() << LogPrefix
<< "Childs of MODEL_TO_DATA_LINK_NAMES must be lists of two elements";
return false;
}
yarp::os::Bottle* list = linksGroup.get(i).asList();
std::string key = list->get(0).asString();
yarp::os::Bottle* listContent = list->get(1).asList();
if (!((listContent->size() == 2) && (listContent->get(0).isString())
&& (listContent->get(1).isString()))) {
yError() << LogPrefix << "Link list must have two strings";
return false;
}
}
yarp::os::Bottle& fixedRotationGroup = config.findGroup("FIXED_SENSOR_ROTATION");
if (!fixedRotationGroup.isNull()) {
for (size_t i = 1; i < fixedRotationGroup.size(); ++i) {
if (!(fixedRotationGroup.get(i).isList() && fixedRotationGroup.get(i).asList()->size() == 2)) {
yError() << LogPrefix
<< "Childs of FIXED_SENSOR_ROTATION must be lists of 2 elements";
return false;
}
yarp::os::Bottle* list = fixedRotationGroup.get(i).asList();
std::string linkName = list->get(0).asString();
yarp::os::Bottle* listContent = list->get(1).asList();
// check if FIXED_SENSOR_ROTATION matrix is passed (9 elements)
if (!( (listContent->size() == 9)
&& (listContent->get(0).isFloat64())
&& (listContent->get(1).isFloat64())
&& (listContent->get(2).isFloat64())
&& (listContent->get(3).isFloat64())
&& (listContent->get(4).isFloat64())
&& (listContent->get(5).isFloat64())
&& (listContent->get(6).isFloat64())
&& (listContent->get(7).isFloat64())
&& (listContent->get(8).isFloat64()) )) {
yError() << LogPrefix << "FIXED_SENSOR_ROTATION " << linkName << " must have 9 double values describing the rotation matrix";
return false;
}
yInfo() << LogPrefix << "FIXED_SENSOR_ROTATION added for link " << linkName;
}
}
// =======================================
// PARSE THE GENERAL CONFIGURATION OPTIONS
// =======================================
std::string solverName = config.find("ikSolver").asString();
if (solverName == "global")
pImpl->ikSolver = SolverIK::global;
else if (solverName == "pairwised")
pImpl->ikSolver = SolverIK::pairwised;
else if (solverName == "dynamical")
pImpl->ikSolver = SolverIK::dynamical;
else {
yError() << LogPrefix << "ikSolver " << solverName << " not found";
return false;
}
const std::string urdfFileName = config.find("urdf").asString();
pImpl->floatingBaseFrame = baseFrameName;
pImpl->period = config.check("period", yarp::os::Value(DefaultPeriod)).asFloat64();
setPeriod(pImpl->period);
for (size_t i = 1; i < linksGroup.size(); ++i) {
yarp::os::Bottle* listContent = linksGroup.get(i).asList()->get(1).asList();
std::string modelLinkName = listContent->get(0).asString();
std::string wearableLinkName = listContent->get(1).asString();
yInfo() << LogPrefix << "Read link map:" << modelLinkName << "==>" << wearableLinkName;
pImpl->wearableStorage.modelToWearable_LinkName[modelLinkName] = wearableLinkName;
}
pImpl->fixedSensorRotation.clear();
for (size_t i = 1; i < fixedRotationGroup.size(); ++i) {
std::string modelLinkName = fixedRotationGroup.get(i).asList()->get(0).asString();
yarp::os::Bottle* fixedRotationMatrixValues = fixedRotationGroup.get(i).asList()->get(1).asList();
iDynTree::Rotation fixedRotation = iDynTree::Rotation( fixedRotationMatrixValues->get(0).asFloat64(),
fixedRotationMatrixValues->get(1).asFloat64(),
fixedRotationMatrixValues->get(2).asFloat64(),
fixedRotationMatrixValues->get(3).asFloat64(),
fixedRotationMatrixValues->get(4).asFloat64(),
fixedRotationMatrixValues->get(5).asFloat64(),
fixedRotationMatrixValues->get(6).asFloat64(),
fixedRotationMatrixValues->get(7).asFloat64(),
fixedRotationMatrixValues->get(8).asFloat64());
pImpl->fixedSensorRotation.emplace(modelLinkName, fixedRotation);
yInfo() << LogPrefix << "Adding Fixed Rotation for " << modelLinkName << "==>" << fixedRotation.toString();
}
// ==========================================
// PARSE THE DEPENDENDT CONFIGURATION OPTIONS
// ==========================================
if (pImpl->ikSolver == SolverIK::pairwised || pImpl->ikSolver == SolverIK::global) {
if (!(config.check("allowIKFailures") && config.find("allowIKFailures").isBool())) {
yError() << LogPrefix << "allowFailures option not found or not valid";
return false;
}
if (!(config.check("maxIterationsIK") && config.find("maxIterationsIK").isInt32())) {
yError() << LogPrefix << "maxIterationsIK option not found or not valid";
return false;
}
if (!(config.check("costTolerance") && config.find("costTolerance").isFloat64())) {
yError() << LogPrefix << "costTolerance option not found or not valid";
return false;
}
if (!(config.check("ikLinearSolver") && config.find("ikLinearSolver").isString())) {
yError() << LogPrefix << "ikLinearSolver option not found or not valid";
return false;
}
if (!(config.check("posTargetWeight") && config.find("posTargetWeight").isFloat64())) {
yError() << LogPrefix << "posTargetWeight option not found or not valid";
return false;
}
if (!(config.check("rotTargetWeight") && config.find("rotTargetWeight").isFloat64())) {
yError() << LogPrefix << "rotTargetWeight option not found or not valid";
return false;
}
if (!(config.check("costRegularization") && config.find("costRegularization").isFloat64())) {
yError() << LogPrefix << "costRegularization option not found or not valid";
return false;
}
pImpl->allowIKFailures = config.find("allowIKFailures").asBool();
pImpl->maxIterationsIK = config.find("maxIterationsIK").asInt32();
pImpl->costTolerance = config.find("costTolerance").asFloat64();
pImpl->linearSolverName = config.find("ikLinearSolver").asString();
pImpl->posTargetWeight = config.find("posTargetWeight").asFloat64();
pImpl->rotTargetWeight = config.find("rotTargetWeight").asFloat64();
pImpl->costRegularization = config.find("costRegularization").asFloat64();
}
if (pImpl->ikSolver == SolverIK::global || pImpl->ikSolver == SolverIK::dynamical) {
if (!(config.check("useDirectBaseMeasurement")
&& config.find("useDirectBaseMeasurement").isBool())) {
yError() << LogPrefix << "useDirectBaseMeasurement option not found or not valid";
return false;
}
if (!(config.check("linVelTargetWeight")
&& config.find("linVelTargetWeight").isFloat64())) {
yError() << LogPrefix << "linVelTargetWeight option not found or not valid";
return false;
}
if (!(config.check("angVelTargetWeight")
&& config.find("angVelTargetWeight").isFloat64())) {
yError() << LogPrefix << "angVelTargetWeight option not found or not valid";
return false;
}
if (config.check("inverseVelocityKinematicsSolver")
&& config.find("inverseVelocityKinematicsSolver").isString()) {
pImpl->inverseVelocityKinematicsSolver =
config.find("inverseVelocityKinematicsSolver").asString();
}
else {
pImpl->inverseVelocityKinematicsSolver = "moorePenrose";
yInfo() << LogPrefix << "Using default inverse velocity kinematics solver";
}
pImpl->useDirectBaseMeasurement = config.find("useDirectBaseMeasurement").asBool();
pImpl->linVelTargetWeight = config.find("linVelTargetWeight").asFloat64();
pImpl->angVelTargetWeight = config.find("angVelTargetWeight").asFloat64();
pImpl->costRegularization = config.find("costRegularization").asFloat64();
}
if (pImpl->ikSolver == SolverIK::pairwised) {
if (!(config.check("ikPoolSizeOption")
&& (config.find("ikPoolSizeOption").isString()
|| config.find("ikPoolSizeOption").isInt32()))) {
yError() << LogPrefix << "ikPoolOption option not found or not valid";
return false;
}
// Get ikPoolSizeOption
if (config.find("ikPoolSizeOption").isString()
&& config.find("ikPoolSizeOption").asString() == "auto") {
yInfo() << LogPrefix << "Using " << std::thread::hardware_concurrency()
<< " available logical threads for ik pool";
pImpl->ikPoolSize = static_cast<int>(std::thread::hardware_concurrency());
}
else if (config.find("ikPoolSizeOption").isInt32()) {
pImpl->ikPoolSize = config.find("ikPoolSizeOption").asInt32();
}
// The pairwised IK will always use the measured base pose and velocity for the base link
if (config.check("useDirectBaseMeasurement")
&& config.find("useDirectBaseMeasurement").isBool()
&& !config.find("useDirectBaseMeasurement").asBool()) {
yWarning() << LogPrefix
<< "useDirectBaseMeasurement is required from Pair-Wised IK. Assuming its "
"value to be true";
}
pImpl->useDirectBaseMeasurement = true;
}
if (pImpl->ikSolver == SolverIK::dynamical) {
if (!(config.check("dynamicalIKMeasuredVelocityGainLinRot")
&& config.find("dynamicalIKMeasuredVelocityGainLinRot").isList()
&& config.find("dynamicalIKMeasuredVelocityGainLinRot").asList()->size()
== 2)) {
yError()
<< LogPrefix
<< "dynamicalIKMeasuredVelocityGainLinRot option not found or not valid";
return false;
}
if (!(config.check("dynamicalIKCorrectionGainsLinRot")
&& config.find("dynamicalIKCorrectionGainsLinRot").isList()
&& config.find("dynamicalIKCorrectionGainsLinRot").asList()->size() == 2)) {
yError() << LogPrefix
<< "dynamicalIKCorrectionGainsLinRot option not found or not valid";
return false;
}
if (config.check("dynamicalIKJointVelocityLimit")
&& config.find("dynamicalIKJointVelocityLimit").isFloat64()) {
pImpl->dynamicalIKJointVelocityLimit =
config.find("dynamicalIKJointVelocityLimit").asFloat64();
}
else {
pImpl->dynamicalIKJointVelocityLimit =
1000.0; // if no limits given for a joint we put 1000.0 rad/sec, which is very high
}
yarp::os::Bottle* dynamicalIKMeasuredVelocityGainLinRot =
config.find("dynamicalIKMeasuredVelocityGainLinRot").asList();
yarp::os::Bottle* dynamicalIKCorrectionGainsLinRot =
config.find("dynamicalIKCorrectionGainsLinRot").asList();
pImpl->dynamicalIKMeasuredLinearVelocityGain =
dynamicalIKMeasuredVelocityGainLinRot->get(0).asFloat64();
pImpl->dynamicalIKMeasuredAngularVelocityGain =
dynamicalIKMeasuredVelocityGainLinRot->get(1).asFloat64();
pImpl->dynamicalIKLinearCorrectionGain =
dynamicalIKCorrectionGainsLinRot->get(0).asFloat64();
pImpl->dynamicalIKAngularCorrectionGain =
dynamicalIKCorrectionGainsLinRot->get(1).asFloat64();
}
// ===================================
// PRINT CURRENT CONFIGURATION OPTIONS
// ===================================
yInfo() << LogPrefix << "*** ===================================";
yInfo() << LogPrefix << "*** Period :" << pImpl->period;
yInfo() << LogPrefix << "*** Urdf file name :" << urdfFileName;
yInfo() << LogPrefix << "*** Ik solver :" << solverName;
yInfo() << LogPrefix
<< "*** Use Directly base measurement :" << pImpl->useDirectBaseMeasurement;
if (pImpl->ikSolver == SolverIK::pairwised || pImpl->ikSolver == SolverIK::global) {
yInfo() << LogPrefix << "*** Allow IK failures :" << pImpl->allowIKFailures;
yInfo() << LogPrefix << "*** Max IK iterations :" << pImpl->maxIterationsIK;
yInfo() << LogPrefix << "*** Cost Tolerance :" << pImpl->costTolerance;
yInfo() << LogPrefix
<< "*** IK Solver Name :" << pImpl->linearSolverName;
yInfo() << LogPrefix << "*** Position target weight :" << pImpl->posTargetWeight;
yInfo() << LogPrefix << "*** Rotation target weight :" << pImpl->rotTargetWeight;
yInfo() << LogPrefix
<< "*** Cost regularization :" << pImpl->costRegularization;
yInfo() << LogPrefix << "*** Size of thread pool :" << pImpl->ikPoolSize;
}
if (pImpl->ikSolver == SolverIK::dynamical) {
yInfo() << LogPrefix << "*** Measured Linear velocity gain :"
<< pImpl->dynamicalIKMeasuredLinearVelocityGain;
yInfo() << LogPrefix << "*** Measured Angular velocity gain :"
<< pImpl->dynamicalIKMeasuredAngularVelocityGain;
yInfo() << LogPrefix << "*** Linear correction gain :"
<< pImpl->dynamicalIKLinearCorrectionGain;
yInfo() << LogPrefix << "*** Angular correction gain :"
<< pImpl->dynamicalIKAngularCorrectionGain;
yInfo() << LogPrefix
<< "*** Cost regularization :" << pImpl->costRegularization;
yInfo() << LogPrefix << "*** Joint velocity limit :"
<< pImpl->dynamicalIKJointVelocityLimit;
}
if (pImpl->ikSolver == SolverIK::dynamical || pImpl->ikSolver == SolverIK::global) {
yInfo() << LogPrefix << "*** Inverse Velocity Kinematics solver:"
<< pImpl->inverseVelocityKinematicsSolver;
}
yInfo() << LogPrefix << "*** ===================================";
// ==========================
// INITIALIZE THE HUMAN MODEL
// ==========================
auto& rf = yarp::os::ResourceFinder::getResourceFinderSingleton();
std::string urdfFilePath = rf.findFile(urdfFileName);
if (urdfFilePath.empty()) {
yError() << LogPrefix << "Failed to find file" << config.find("urdf").asString();
return false;
}
iDynTree::ModelLoader modelLoader;
if ( pImpl->jointList.empty())
{
if (!modelLoader.loadModelFromFile(urdfFilePath) || !modelLoader.isValid()) {
yError() << LogPrefix << "Failed to load model" << urdfFilePath;
return false;
}
}
else
{
if (!modelLoader.loadReducedModelFromFile(urdfFilePath, pImpl->jointList) || !modelLoader.isValid()) {
yError() << LogPrefix << "Failed to load model" << urdfFilePath;
return false;
}
}
yInfo() << LogPrefix << "----------------------------------------" << modelLoader.isValid();
yInfo() << LogPrefix << modelLoader.model().toString();
yInfo() << LogPrefix << modelLoader.model().getNrOfLinks()
<< " , joints: " << modelLoader.model().getNrOfJoints();
yInfo() << LogPrefix << "base link: "
<< modelLoader.model().getLinkName(modelLoader.model().getDefaultBaseLink());
// ====================
// INITIALIZE VARIABLES
// ====================
// Get the model from the loader
pImpl->humanModel = modelLoader.model();
// Set gravity
pImpl->worldGravity.zero();
pImpl->worldGravity(2) = -9.81;
// Initialize kinDyn computation
pImpl->kinDynComputations =
std::unique_ptr<iDynTree::KinDynComputations>(new iDynTree::KinDynComputations());
pImpl->kinDynComputations->loadRobotModel(modelLoader.model());
pImpl->kinDynComputations->setFloatingBase(pImpl->floatingBaseFrame);
// Initialize World Secondary Calibration
pImpl->secondaryCalibrationWorld = iDynTree::Transform::Identity();
// =========================
// INITIALIZE JOINTS BUFFERS
// =========================
// Get the number of joints accordingly to the model
const size_t nrOfDOFs = pImpl->humanModel.getNrOfDOFs();
pImpl->solution.jointPositions.resize(nrOfDOFs);
pImpl->solution.jointVelocities.resize(nrOfDOFs);
pImpl->jointConfigurationSolution.resize(nrOfDOFs);
pImpl->jointConfigurationSolution.zero();
pImpl->jointVelocitiesSolution.resize(nrOfDOFs);
pImpl->jointVelocitiesSolution.zero();
// =======================
// INITIALIZE BASE BUFFERS
// =======================
pImpl->baseTransformSolution = iDynTree::Transform::Identity();
pImpl->baseVelocitySolution.zero();
// ================================================
// INITIALIZE CUSTOM CONSTRAINTS FOR INTEGRATION-IK
// ================================================
pImpl->customConstraintMatrix.resize(0, 0);
pImpl->customConstraintVariables.resize(0);
pImpl->customConstraintLowerBound.resize(0);
pImpl->customConstraintUpperBound.resize(0);
pImpl->customConstraintVariablesIndex.resize(0);
pImpl->custom_jointsVelocityLimitsNames.resize(0);
pImpl->custom_jointsVelocityLimitsValues.resize(0);
pImpl->custom_jointsVelocityLimitsIndexes.resize(0);
pImpl->k_u = 0.5;
pImpl->k_l = 0.5;
if (config.check("CUSTOM_CONSTRAINTS")) {
yarp::os::Bottle& constraintGroup = config.findGroup("CUSTOM_CONSTRAINTS");
if (constraintGroup.isNull()) {
yError() << LogPrefix << "Failed to find group CUSTOM_CONSTRAINTS";
return false;
}
if (pImpl->inverseVelocityKinematicsSolver != "QP"
|| pImpl->ikSolver != SolverIK::dynamical) {
yWarning()
<< LogPrefix
<< "'CUSTOM_CONSTRAINTS' group option is available only if "
"'ikSolver==dynamical' & 'inverseVelocityKinematicsSolver==QP'. \n "
"Currently, you are NOT using the customized constraint group.";
}
yInfo() << "==================>>>>>>> constraint group: " << constraintGroup.size();
for (size_t i = 1; i < constraintGroup.size(); i++) {
yInfo() << "group " << i;
if (!(constraintGroup.get(i).isList()
&& constraintGroup.get(i).asList()->size() == 2)) {
yError() << LogPrefix
<< "Childs of CUSTOM_CONSTRAINTS must be lists of two elements";
return false;
}
else {
yInfo() << "Everything is fine...";
}
yarp::os::Bottle* constraintList = constraintGroup.get(i).asList();
std::string constraintKey = constraintList->get(0).asString();
yarp::os::Bottle* constraintListContent = constraintList->get(1).asList();
yInfo() << constraintKey;
if (constraintKey == "custom_joints_velocity_limits_names") {
for (size_t i = 0; i < constraintListContent->size(); i++) {
pImpl->custom_jointsVelocityLimitsNames.push_back(
constraintListContent->get(i).asString());
}
yInfo() << "custom_joints_velocity_limits_names: ";
for (size_t i = 0; i < pImpl->custom_jointsVelocityLimitsNames.size(); i++) {
yInfo() << pImpl->custom_jointsVelocityLimitsNames[i];
}
} // another option
else if (constraintKey == "custom_joints_velocity_limits_values") {
pImpl->custom_jointsVelocityLimitsValues.resize(constraintListContent->size());
for (size_t i = 0; i < constraintListContent->size(); i++) {
pImpl->custom_jointsVelocityLimitsValues.setVal(
i, constraintListContent->get(i).asFloat64());
}
yInfo() << "custom_joints_velocity_limits_values: ";
for (size_t i = 0; i < pImpl->custom_jointsVelocityLimitsValues.size(); i++) {
yInfo() << pImpl->custom_jointsVelocityLimitsValues.getVal(i);
}
} // another option
else if (constraintKey == "custom_constraint_variables") {
for (size_t i = 0; i < constraintListContent->size(); i++) {
pImpl->customConstraintVariables.push_back(
constraintListContent->get(i).asString());
}
yInfo() << "custom_constraint_variables: ";
for (size_t i = 0; i < pImpl->customConstraintVariables.size(); i++) {
yInfo() << pImpl->customConstraintVariables[i];
}
} // another option
else if (constraintKey == "custom_constraint_matrix") {
// pImpl->customConstraintMatrix.resize(constraintListContent->size());
for (size_t i = 0; i < constraintListContent->size(); i++) {
yarp::os::Bottle* innerLoop = constraintListContent->get(i).asList();
if (i == 0) {
pImpl->customConstraintMatrix.resize(constraintListContent->size(),
innerLoop->size());
}
for (size_t j = 0; j < innerLoop->size(); j++) {
pImpl->customConstraintMatrix.setVal(i, j, innerLoop->get(j).asFloat64());
}
}
yInfo() << "Constraint matrix: ";
for (size_t i = 0; i < pImpl->customConstraintMatrix.rows(); i++) {
for (size_t j = 0; j < pImpl->customConstraintMatrix.cols(); j++) {
std::cout << pImpl->customConstraintMatrix.getVal(i, j) << " ";
}
std::cout << std::endl;
}
} // another option
else if (constraintKey == "custom_constraint_upper_bound") {
pImpl->customConstraintUpperBound.resize(constraintListContent->size());
for (size_t i = 0; i < constraintListContent->size(); i++) {
pImpl->customConstraintUpperBound.setVal(
i, constraintListContent->get(i).asFloat64());
}
yInfo() << "custom_constraint_upper_bound: ";
for (size_t i = 0; i < pImpl->customConstraintUpperBound.size(); i++) {
yInfo() << pImpl->customConstraintUpperBound.getVal(i);
}
} // another option
else if (constraintKey == "custom_constraint_lower_bound") {
pImpl->customConstraintLowerBound.resize(constraintListContent->size());
for (size_t i = 0; i < constraintListContent->size(); i++) {
pImpl->customConstraintLowerBound.setVal(
i, constraintListContent->get(i).asFloat64());
}
yInfo() << "custom_constraint_lower_bound: ";
for (size_t i = 0; i < pImpl->customConstraintLowerBound.size(); i++) {
yInfo() << pImpl->customConstraintLowerBound.getVal(i);
}
} // another option
else if (constraintKey == "base_velocity_limit_upper_buond") {
if (constraintListContent->size() != 6) {
yError() << "the base velocity limit should have size of 6.";
return false;
}
pImpl->baseVelocityUpperLimit.resize(6);
for (size_t i = 0; i < constraintListContent->size(); i++) {
pImpl->baseVelocityUpperLimit.setVal(i,
constraintListContent->get(i).asFloat64());
}
yInfo() << "base_velocity_limit_upper_buond: ";
for (size_t i = 0; i < pImpl->baseVelocityUpperLimit.size(); i++) {
yInfo() << pImpl->baseVelocityUpperLimit.getVal(i);
}
} // another option
else if (constraintKey == "base_velocity_limit_lower_buond") {
if (constraintListContent->size() != 6) {
yError() << "the base velocity limit should have size of 6.";
return false;
}
pImpl->baseVelocityLowerLimit.resize(6);
for (size_t i = 0; i < constraintListContent->size(); i++) {
pImpl->baseVelocityLowerLimit.setVal(i,
constraintListContent->get(i).asFloat64());