-
Notifications
You must be signed in to change notification settings - Fork 12
/
WholeBodyDynamicsDevice.cpp
3708 lines (3075 loc) · 140 KB
/
WholeBodyDynamicsDevice.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
#include <yarp/os/Log.h>
#define SKIN_EVENTS_TIMEOUT 0.2
#include "WholeBodyDynamicsDevice.h"
#include <yarp/os/LogStream.h>
#include <yarp/os/Property.h>
#include <yarp/os/ResourceFinder.h>
#include <yarp/os/Time.h>
#include <yarp/os/PeriodicThread.h>
#include <yarp/dev/IAnalogSensor.h>
#include <yarp/dev/IGenericSensor.h>
#include <iDynTree/yarp/YARPConversions.h>
#include <iDynTree/Core/Utils.h>
#include <iDynTree/Core/EigenHelpers.h>
#include <cassert>
#include <cmath>
namespace yarp
{
namespace dev
{
const size_t wholeBodyDynamics_nrOfChannelsOfYARPFTSensor = 6;
const size_t wholeBodyDynamics_nrOfChannelsOfAYARPIMUSensor = 12;
const double wholeBodyDynamics_sensorTimeoutInSeconds = 2.0;
constexpr double defaultWholeBodyDynamicsPeriod = 0.01;
WholeBodyDynamicsDevice::WholeBodyDynamicsDevice(): yarp::os::PeriodicThread(defaultWholeBodyDynamicsPeriod),
portPrefix("/wholeBodyDynamics"),
correctlyConfigured(false),
sensorReadCorrectly(false),
estimationWentWell(false),
validOffsetAvailable(false),
lastReadingSkinContactListStamp(0.0),
streamFilteredFT(false),
checkTemperatureEvery_seconds(0.55),
useSkinForContacts{true},
isIMUAttached{false},
settingsEditor(settings)
{
// Calibration quantities
calibrationBuffers.ongoingCalibration = false;
calibrationBuffers.calibratingFTsensor.resize(0);
calibrationBuffers.offsetSumBuffer.resize(0);
ftProcessors.resize(0);
calibrationBuffers.estimationSumBuffer.resize(0);
calibrationBuffers.measurementSumBuffer.resize(0);
calibrationBuffers.nrOfSamplesToUseForCalibration = 0;
calibrationBuffers.nrOfSamplesUsedUntilNowForCalibration = 0;
// temperature measuremnts vector
tempMeasurements.resize(0);
ftTempMapping.resize(0);
prevFTTempTimeStamp=0;
}
WholeBodyDynamicsDevice::~WholeBodyDynamicsDevice()
{
}
bool WholeBodyDynamicsDevice::openSettingsPort()
{
settingsPort.setReader(settingsEditor);
bool ok = settingsPort.open(portPrefix+"/settings");
if( !ok )
{
yError() << "WholeBodyDynamicsDevice: Impossible to open port " << portPrefix+"/settings";
return false;
}
return true;
}
bool WholeBodyDynamicsDevice::openRPCPort()
{
this->wholeBodyDynamics_IDLServer::yarp().attachAsServer(rpcPort);
bool ok = rpcPort.open(portPrefix+"/rpc");
if( !ok )
{
yError() << "WholeBodyDynamicsDevice: Impossible to open port " << portPrefix+"/rpc";
return false;
}
return true;
}
bool WholeBodyDynamicsDevice::closeSettingsPort()
{
settingsPort.close();
return true;
}
bool WholeBodyDynamicsDevice::closeRPCPort()
{
rpcPort.close();
return true;
}
bool WholeBodyDynamicsDevice::closeSkinContactListsPorts()
{
this->portContactsInput.close();
this->portContactsOutput.close();
return true;
}
bool WholeBodyDynamicsDevice::closeExternalWrenchesPorts()
{
for(unsigned int i = 0; i < outputWrenchPorts.size(); i++ )
{
if( outputWrenchPorts[i].output_port )
{
outputWrenchPorts[i].output_port->close();
delete outputWrenchPorts[i].output_port;
outputWrenchPorts[i].output_port = 0;
}
}
netExternalWrenchesPort.close();
return true;
}
bool WholeBodyDynamicsDevice::closeFilteredFTPorts()
{
for(unsigned int i = 0; i < outputFTPorts.size(); i++ )
{
if( outputFTPorts[i] )
{
outputFTPorts[i]->close();
outputFTPorts[i].reset();
}
}
return true;
}
void addVectorOfStringToProperty(yarp::os::Property& prop, std::string key, std::vector<std::string> & list)
{
prop.addGroup(key);
yarp::os::Bottle & bot = prop.findGroup(key).addList();
for(size_t i=0; i < list.size(); i++)
{
bot.addString(list[i].c_str());
}
return;
}
bool getConfigParamsAsList(os::Searchable& config,std::string propertyName , std::vector<std::string> & list, bool isRequired)
{
yarp::os::Property prop;
prop.fromString(config.toString().c_str());
yarp::os::Bottle *propNames=prop.find(propertyName).asList();
if(propNames==nullptr)
{
if(isRequired)
{
yError() <<"WholeBodyDynamicsDevice: Error parsing parameters: \" "<<propertyName<<" \" should be followed by a list\n";
}
return false;
}
list.resize(propNames->size());
for(auto elem=0u; elem < propNames->size(); elem++)
{
list[elem] = propNames->get(elem).asString().c_str();
}
return true;
}
bool getConfigParamsAsList(const yarp::os::Searchable& config,std::string propertyName , iDynTree::VectorDynSize & list, bool isRequired)
{
yarp::os::Property prop;
prop.fromString(config.toString().c_str());
yarp::os::Bottle *propNames=prop.find(propertyName).asList();
if(propNames==nullptr)
{
if(isRequired)
{
yError() <<"WholeBodyDynamicsDevice: Error parsing parameters: \" "<<propertyName<<" \" should be followed by a list\n";
}
return false;
}
list.resize(propNames->size());
for(auto elem=0u; elem < propNames->size(); elem++)
{
const auto value = propNames->get(elem);
if( !value.isFloat64() && !value.isInt32() )
{
yError() << "WholeBodyDynamicsDevice: Error parsing parameters: \" "<<propertyName<<" \". Expected double or integer array.\n";
return false;
}
list(elem) = value.asFloat64();
}
return true;
}
bool getUsedDOFsList(os::Searchable& config, std::vector<std::string> & usedDOFs)
{
bool required{true};
return getConfigParamsAsList(config,"axesNames",usedDOFs, required);
}
bool getAdditionalConsideredFixedJointsList(os::Searchable& config, std::vector<std::string> & additionalFixedJoints)
{
bool notRequired{false};
return getConfigParamsAsList(config,"additionalConsideredFixedJoints",additionalFixedJoints, notRequired);
}
bool getGravityCompensationDOFsList(os::Searchable& config, std::vector<std::string> & gravityCompensationDOFs)
{
bool required{true};
return getConfigParamsAsList(config,"gravityCompensationAxesNames",gravityCompensationDOFs, required);
}
bool WholeBodyDynamicsDevice::openRemapperControlBoard(os::Searchable& config)
{
// Pass to the remapper just the relevant parameters (axesList)
yarp::os::Property propRemapper;
propRemapper.put("device","controlboardremapper");
bool ok = getUsedDOFsList(config,estimationJointNames);
if(!ok) return false;
addVectorOfStringToProperty(propRemapper,"axesNames",estimationJointNames);
ok = remappedControlBoard.open(propRemapper);
if( !ok )
{
return ok;
}
// View relevant interfaces for the remappedControlBoard
ok = ok && remappedControlBoard.view(remappedControlBoardInterfaces.encs);
ok = ok && remappedControlBoard.view(remappedControlBoardInterfaces.multwrap);
ok = ok && remappedControlBoard.view(remappedControlBoardInterfaces.impctrl);
ok = ok && remappedControlBoard.view(remappedControlBoardInterfaces.ctrlmode);
ok = ok && remappedControlBoard.view(remappedControlBoardInterfaces.intmode);
if( !ok )
{
yError() << "wholeBodyDynamics : open impossible to use the necessary interfaces in remappedControlBoard";
return ok;
}
// Check if the controlboard and the estimator have a consistent number of joints
int axes = 0;
remappedControlBoardInterfaces.encs->getAxes(&axes);
if( axes != (int) estimator.model().getNrOfDOFs() )
{
yError() << "wholeBodyDynamics : open estimator model and the remappedControlBoard has an inconsistent number of joints";
return false;
}
return true;
}
bool WholeBodyDynamicsDevice::openRemapperVirtualSensors(os::Searchable& config)
{
// Pass to the remapper just the relevant parameters (axesList)
yarp::os::Property propRemapper;
propRemapper.put("device","virtualAnalogRemapper");
bool ok = getUsedDOFsList(config,estimationJointNames);
if(!ok) return false;
addVectorOfStringToProperty(propRemapper,"axesNames",estimationJointNames);
ok = remappedVirtualAnalogSensors.open(propRemapper);
if( !ok )
{
return ok;
}
// View relevant interfaces for the remappedVirtualAnalogSensors
ok = ok && remappedVirtualAnalogSensors.view(remappedVirtualAnalogSensorsInterfaces.ivirtsens);
ok = ok && remappedVirtualAnalogSensors.view(remappedVirtualAnalogSensorsInterfaces.multwrap);
if( !ok )
{
yError() << "wholeBodyDynamics : open impossible to use the necessary interfaces in remappedControlBoard";
return ok;
}
// Check if the controlboard and the estimator have a consistent number of joints
int axes = remappedVirtualAnalogSensorsInterfaces.ivirtsens->getVirtualAnalogSensorChannels();
if( axes != (int) estimator.model().getNrOfDOFs() )
{
yError() << "wholeBodyDynamics : open estimator model and the remapperVirtualAnalogSensor has an inconsistent number of joints";
return false;
}
return true;
}
bool WholeBodyDynamicsDevice::openEstimator(os::Searchable& config)
{
// get the list of considered dofs from config
bool ok = getUsedDOFsList(config,estimationJointNames);
if(!ok) return false;
yarp::os::ResourceFinder & rf = yarp::os::ResourceFinder::getResourceFinderSingleton();
std::string modelFileName = "model.urdf";
if( config.check("modelFile") && config.find("modelFile").isString() )
{
modelFileName = config.find("modelFile").asString();
}
std::string modelFileFullPath = rf.findFileByName(modelFileName);
yInfo() << "wholeBodyDynamics : Loading model from " << modelFileFullPath;
// Add additional fixed joints listed with the parameter `additionalConsideredFixedJoints`
std::vector<std::string> additionalConsideredJoints;
bool additionalFixedJointsExist = getAdditionalConsideredFixedJointsList(config,additionalConsideredJoints);
if(additionalFixedJointsExist)
{
yInfo() << "wholeBodyDynamics: Loading additional fixed joints from the config file: " << additionalConsideredJoints;
// Append additionalConsideredJoints to estimationJointNames
estimationJointNames.insert(estimationJointNames.end(), additionalConsideredJoints.begin(), additionalConsideredJoints.end());
}
ok = estimator.loadModelAndSensorsFromFileWithSpecifiedDOFs(modelFileFullPath,estimationJointNames);
if( !ok )
{
yInfo() << "wholeBodyDynamics : impossible to create ExtWrenchesAndJointTorquesEstimator from file "
<< modelFileName << " ( full path: " << modelFileFullPath << " ) ";
return false;
}
if( estimator.sensors().getNrOfSensors(iDynTree::SIX_AXIS_FORCE_TORQUE) == 0 )
{
yWarning() << "wholeBodyDynamics : the loaded model has 0 FT sensors, so the estimation will use just the model.";
yWarning() << "wholeBodyDynamics : If you instead want to add the FT sensors to your model, please check iDynTree documentation on how to add sensors to models.";
}
return true;
}
bool WholeBodyDynamicsDevice::openContactFrames(os::Searchable& config)
{
yarp::os::Property prop;
prop.fromString(config.toString().c_str());
yarp::os::Bottle *propDefaultContactFrames=prop.find("defaultContactFrames").asList();
yarp::os::Bottle *propOverrideContactFrames=prop.find("overrideContactFrames").asList();
yarp::os::Bottle *propContactWrenchType=prop.find("contactWrenchType").asList();
yarp::os::Bottle *propContactWrenchDirection=prop.find("contactWrenchDirection").asList();
yarp::os::Bottle *propContactWrenchPosition=prop.find("contactWrenchPosition").asList();
if(propOverrideContactFrames==0)
{
//overrideContactFrames don't exist -> considering defaultContactFrames
if(propDefaultContactFrames==0)
{
yError() << "wholeBodyDynamics : openContactFrames : Error parsing parameters: \"defaultContactFrames\" should be followed by a list\n";
return false;
}
else
{
//fill the variable `contactFramesNames` and build objects "iDynTree::UnknownWrenchContact" for each default contact frame
contactFramesNames.resize(propDefaultContactFrames->size());
unknownExtWrench.resize(contactFramesNames.size());
nrUnknownsInExtWrench.resize(contactFramesNames.size());
for(int ax=0; ax < propDefaultContactFrames->size(); ax++)
{
contactFramesNames[ax] = propDefaultContactFrames->get(ax).asString().c_str();
unknownExtWrench[ax].contactPoint = iDynTree::Position::Zero();
unknownExtWrench[ax].unknownType = iDynTree::FULL_WRENCH;
unknownExtWrench[ax].forceDirection = iDynTree::Direction::Default();
nrUnknownsInExtWrench[ax] = 6;
}
}
}
else
{
//overrideContactFrames exist -> they are parsed instead of defaultContactFrames
overrideContactFramesSelected = true;
bool OverrideFrameParsedOK = parseOverrideContactFramesData(propOverrideContactFrames, propContactWrenchType, propContactWrenchDirection, propContactWrenchPosition);
if(!OverrideFrameParsedOK)
{
yError() << "wholeBodyDynamics : openContactFrames : parameters 'overrideContactFrames', 'contactWrenchType', 'contactWrenchDirection' and 'contactWrenchPosition' contain some problems.";
return false;
}
}
// We build the contactFramesIdx vector
std::vector<iDynTree::FrameIndex> contactFramesIdx;
contactFramesIdx.clear();
std::vector<int> indexesToDiscard;
indexesToDiscard.clear();
for(size_t i=0; i < contactFramesNames.size(); i++)
{
iDynTree::FrameIndex idx = estimator.model().getFrameIndex(contactFramesNames[i]);
if( idx == iDynTree::FRAME_INVALID_INDEX )
{
yWarning() << "Frame " << contactFramesNames[i] << " not found in the model, discarding it";
indexesToDiscard.push_back(i);
}
else
{
contactFramesIdx.push_back(idx);
}
}
sort(indexesToDiscard.begin(), indexesToDiscard.end());
//remove the variables that correspond to invalid frames
for(int i=indexesToDiscard.size()-1; i>=0; i-- )
{
contactFramesNames.erase(contactFramesNames.begin() + indexesToDiscard[i]);
unknownExtWrench.erase(unknownExtWrench.begin() + indexesToDiscard[i]);
nrUnknownsInExtWrench.erase(nrUnknownsInExtWrench.begin() + indexesToDiscard[i]);
}
// The frames from in 1 submodel should be no more than 1 if the type is FULL_WRENCH, no more than 2 if the type is PURE_FORCE, and no more than 6 if the type is PURE_FORCE_WITH_KNOWN_DIRECTION.
// Refer to section 3 of the theory paper https://www.researchgate.net/publication/236152161_Contact_Force_Estimations_Using_Tactile_Sensors_and_Force_Torque_Sensors
// For each submodel, we find the first suitable contact frame
// This is a n^2 algorithm, but given that is just used in
// configuration it should be ok
size_t nrOfSubModels = estimator.submodels().getNrOfSubModels();
// We indicate with FRAME_INVALID_INDEX the fact that we still don't have a default/override contact for the given submodel
contactFramesIdxValidForSubModel.resize(contactFramesIdx.size(),iDynTree::FRAME_INVALID_INDEX);
//create a vector to store the submodel indexes that will have contact points
std::vector<size_t> validSubModelsIndexes;
validSubModelsIndexes.resize(contactFramesIdx.size(),iDynTree::FRAME_INVALID_INDEX);
nrUnknownsInSubModel.resize(nrOfSubModels,0);
for(size_t i=0; i < contactFramesIdx.size(); i++)
{
size_t subModelIdx = estimator.submodels().getSubModelOfFrame(estimator.model(),contactFramesIdx[i]);
//check if adding the current contact to this subModel will increase the no of variable to more than 6
if(nrUnknownsInSubModel[subModelIdx]+nrUnknownsInExtWrench[i] > 6)
{
yWarning() << "subModel no " << subModelIdx << " has the maximum number of variables (6). The frame " << contactFramesNames[i] << " will not be added to it.";
}
else
{
//add the contact frame
contactFramesIdxValidForSubModel[i] = contactFramesIdx[i];
//add the submodel index to the valid submodel indexes group
validSubModelsIndexes[i] = subModelIdx;
nrUnknownsInSubModel[subModelIdx] += nrUnknownsInExtWrench[i];
}
}
//after filling the valid submodels vector, we sort it to be able to use "std::binary_search"
std::sort(validSubModelsIndexes.begin(), validSubModelsIndexes.end());
// Let's check that every submodel has a default/override contact position
std::vector<iDynTree::FrameIndex> invalidFrameIndexVector(nrOfSubModels,iDynTree::FRAME_INVALID_INDEX);
for(size_t subModelIdx = 0; subModelIdx < nrOfSubModels; subModelIdx++)
{
//check if the submodel is not in the list
if(!std::binary_search(validSubModelsIndexes.begin(), validSubModelsIndexes.end(), subModelIdx))
{
yError() << "wholeBodyDynamics : openContactFrames : missing default/override contact for submodel composed by the links: ";
const iDynTree::Traversal & subModelTraversal = estimator.submodels().getTraversal(subModelIdx);
for(iDynTree::TraversalIndex i = 0; i < (iDynTree::TraversalIndex) subModelTraversal.getNrOfVisitedLinks(); i++)
{
iDynTree::LinkIndex linkIdx = subModelTraversal.getLink(i)->getIndex();
yError() << "wholeBodyDynamics : openContactFrames :" << estimator.model().getLinkName(linkIdx);
}
return false;
}
}
return true;
}
bool WholeBodyDynamicsDevice::parseOverrideContactFramesData(yarp::os::Bottle *_propOverrideContactFrames, yarp::os::Bottle *_propContactWrenchType, yarp::os::Bottle *_propContactWrenchDirection, yarp::os::Bottle *_propContactWrenchPosition)
{
//fill the variable `contactFramesNames`
contactFramesNames.resize(_propOverrideContactFrames->size());
for(int ax=0; ax < _propOverrideContactFrames->size(); ax++)
{
contactFramesNames[ax] = _propOverrideContactFrames->get(ax).asString().c_str();
}
//Check if the parameters `propcontactWrenchType`, `contactWrenchDirection` and `contactWrenchPosition` exist in the configuration file
if(_propContactWrenchType==0 || _propContactWrenchDirection==0 || _propContactWrenchPosition==0)
{
yError() << "wholeBodyDynamics : openContactFrames : missing necessary parameters for the overrideContactFrames.";
return false;
}
else
{
//fill the other variables from the prop objects
contactWrenchType.resize(_propContactWrenchType->size());
for(int ax=0; ax < _propContactWrenchType->size(); ax++)
{
contactWrenchType[ax] = _propContactWrenchType->get(ax).asString().c_str();
}
//Check if the size of propContactWrenchDirection is a multiple of 3
if(_propContactWrenchDirection->size()%3 == 0)
{
contactWrenchDirection.resize(_propContactWrenchDirection->size()/3);
for(int ax=0; ax < contactWrenchDirection.size(); ax++)
{
contactWrenchDirection[ax].resize(3);
//put every 3 elements of `propContactWrenchDirection` in one raw of `contactWrenchDirection`
for(int ay=0; ay < 3; ay++)
{
int index = 3*ax+ay;
contactWrenchDirection[ax][ay] = _propContactWrenchDirection->get(index).asFloat64();
}
}
}
else
{
yError() << "wholeBodyDynamics : openContactFrames : parameter 'contactWrenchDirection' size is not consistent.";
return false;
}
//Check if the size of propContactWrenchPosition is a mulitple of 3
if(_propContactWrenchPosition->size()%3 == 0)
{
contactWrenchPosition.resize(_propContactWrenchPosition->size()/3);
for(int ax=0; ax < contactWrenchPosition.size(); ax++)
{
contactWrenchPosition[ax].resize(3);
//put every 3 elements of `propContactWrenchPosition` in one raw of `contactWrenchPosition`
for(int ay=0; ay < 3; ay++)
{
int index = 3*ax+ay;
contactWrenchPosition[ax][ay] = _propContactWrenchPosition->get(index).asFloat64();
}
}
}
else
{
yError() << "wholeBodyDynamics : openContactFrames : parameter 'contactWrenchPosition' size is not consistent.";
return false;
}
//check full size of the lists `contactWrenchType`, `contactWrenchDirection` and `contactWrenchPosition` to verify it's consistent with number of frames in `overrideContactFrames`
if(contactWrenchType.size() == contactFramesNames.size() && contactWrenchDirection.size() == contactFramesNames.size() && contactWrenchPosition.size() == contactFramesNames.size())
{
yInfo() << "wholeBodyDynamics : openContactFrames : parsing the values from the parameters 'overrideContactFrames', 'contactWrenchType', 'contactWrenchDirection' and 'contactWrenchPosition'.";
}
else
{
yError() << "wholeBodyDynamics : openContactFrames : parameters 'overrideContactFrames', 'contactWrenchType', 'contactWrenchDirection' and 'contactWrenchPosition' sizes are not consistent.";
return false;
}
}
//build objects "iDynTree::UnknownWrenchContact" for each override contact frame
unknownExtWrench.resize(contactFramesNames.size());
nrUnknownsInExtWrench.resize(contactFramesNames.size());
// check if the parameter `contactWrenchType` contains only the values "full", "pure" or "pureKnown"
for(int i=0; i<contactFramesNames.size(); i++)
{
unknownExtWrench[i].contactPoint = iDynTree::Position(contactWrenchPosition[i][0], contactWrenchPosition[i][1], contactWrenchPosition[i][2]);
if(contactWrenchType[i]=="full")
{
nrUnknownsInExtWrench[i] = 6;
unknownExtWrench[i].unknownType = iDynTree::FULL_WRENCH;
unknownExtWrench[i].forceDirection = iDynTree::Direction::Default();
}
else if(contactWrenchType[i]=="pure")
{
nrUnknownsInExtWrench[i] = 3;
unknownExtWrench[i].unknownType = iDynTree::PURE_FORCE;
unknownExtWrench[i].forceDirection = iDynTree::Direction::Default();
}
else if(contactWrenchType[i]=="pureKnown")
{
nrUnknownsInExtWrench[i] = 1;
unknownExtWrench[i].unknownType = iDynTree::PURE_FORCE_WITH_KNOWN_DIRECTION;
unknownExtWrench[i].forceDirection = iDynTree::Direction(contactWrenchDirection[i][0], contactWrenchDirection[i][1], contactWrenchDirection[i][2]);
}
else
{
yError() << "wholeBodyDynamics : openContactFrames : parameter 'contactWrenchType' contains some errors/inconsistencies.";
return false;
}
}
return true;
}
bool WholeBodyDynamicsDevice::openSkinContactListPorts(os::Searchable& config)
{
bool ok = this->portContactsInput.open(portPrefix+"/skin_contacts:i");
if(!ok) return ok;
ok = this->portContactsOutput.open(portPrefix+"/contacts:o");
if(!ok) return ok;
// Configure the conversion helper to read/publish data on this ports
yarp::os::Bottle & bot = config.findGroup("IDYNTREE_SKINDYNLIB_LINKS");
for(int i=1; i < bot.size(); i++ )
{
yarp::os::Bottle * map_bot = bot.get(i).asList();
if( map_bot->size() != 2 || map_bot->get(1).asList() == NULL ||
map_bot->get(1).asList()->size() != 3 )
{
yError() << "WholeBodyDynamicsDevice: IDYNTREE_SKINDYNLIB_LINKS group is malformed (" << map_bot->toString() << ")";
return false;
}
std::string iDynTree_link_name = map_bot->get(0).asString();
std::string iDynTree_skinFrame_name = map_bot->get(1).asList()->get(0).asString();
int skinDynLib_body_part = map_bot->get(1).asList()->get(1).asInt32();
int skinDynLib_link_index = map_bot->get(1).asList()->get(2).asInt32();
bool ret_sdl = conversionHelper.addSkinDynLibAlias(estimator.model(),
iDynTree_link_name,iDynTree_skinFrame_name,
skinDynLib_body_part,skinDynLib_link_index);
if( !ret_sdl )
{
yError() << "WholeBodyDynamicsDevice: IDYNTREE_SKINDYNLIB_LINKS link " << iDynTree_link_name
<< " and frame " << iDynTree_skinFrame_name << " and not found in urdf model";
return false;
}
}
return ok;
}
bool WholeBodyDynamicsDevice::openExternalWrenchesPorts(os::Searchable& config)
{
// Read ports info from config
// Load output external wrenches ports informations
yarp::os::Bottle & output_wrench_bot = config.findGroup("WBD_OUTPUT_EXTERNAL_WRENCH_PORTS");
if( output_wrench_bot.isNull() )
{
// The WBD_OUTPUT_EXTERNAL_WRENCH_PORTS is optional
return true;
}
for(int output_wrench_port = 1; output_wrench_port < output_wrench_bot.size(); output_wrench_port++)
{
outputWrenchPortInformation wrench_port_struct;
yarp::os::Bottle *wrench_port = output_wrench_bot.get(output_wrench_port).asList();
if( wrench_port == NULL || wrench_port->isNull() || wrench_port->size() != 2
|| wrench_port->get(1).asList() == NULL
|| !(wrench_port->get(1).asList()->size() == 2 || wrench_port->get(1).asList()->size() == 3 ) )
{
yError() << "wholeBodyDynamics : malformed WBD_OUTPUT_EXTERNAL_WRENCH_PORTS group found in configuration, exiting";
if( wrench_port )
{
yError() << "wholeBodyDynamics : malformed line " << wrench_port->toString();
}
else
{
yError() << "wholeBodyDynamics : malformed line " << output_wrench_bot.get(output_wrench_port).toString();
yError() << "wholeBodyDynamics : malformed group " << output_wrench_bot.toString();
}
return false;
}
wrench_port_struct.port_name = wrench_port->get(0).asString();
wrench_port_struct.link = wrench_port->get(1).asList()->get(0).asString();
if( wrench_port->get(1).asList()->size() == 2 )
{
// Simple configuration, both the origin and the orientation of the
// force belong to the same frame
wrench_port_struct.orientation_frame = wrench_port->get(1).asList()->get(1).asString();
wrench_port_struct.origin_frame = wrench_port_struct.orientation_frame;
}
else
{
assert( wrench_port->get(1).asList()->size() == 3 );
// Complex configuration: the first parameter is the frame of the point of expression,
// the second parameter is the frame of orientation
wrench_port_struct.origin_frame = wrench_port->get(1).asList()->get(1).asString();
wrench_port_struct.orientation_frame = wrench_port->get(1).asList()->get(2).asString();
}
outputWrenchPorts.push_back(wrench_port_struct);
}
// Load indeces for specified links and frame
for(unsigned i=0; i < outputWrenchPorts.size(); i++ )
{
outputWrenchPorts[i].link_index =
kinDynComp.getRobotModel().getLinkIndex(outputWrenchPorts[i].link);
if( outputWrenchPorts[i].link_index < 0 )
{
yError() << "wholeBodyDynamics : Link " << outputWrenchPorts[i].link << " not found in the model.";
return false;
}
outputWrenchPorts[i].origin_frame_index =
kinDynComp.getRobotModel().getFrameIndex(outputWrenchPorts[i].origin_frame);
if( outputWrenchPorts[i].origin_frame_index < 0 )
{
yError() << "wholeBodyDynamics : Frame " << outputWrenchPorts[i].origin_frame << " not found in the model.";
return false;
}
outputWrenchPorts[i].orientation_frame_index =
kinDynComp.getRobotModel().getFrameIndex(outputWrenchPorts[i].orientation_frame);
if( outputWrenchPorts[i].orientation_frame_index < 0 )
{
yError() << "wholeBodyDynamics : Frame " << outputWrenchPorts[i].orientation_frame_index << " not found in the model.";
return false;
}
}
// Open ports
bool ok = true;
for(unsigned int i = 0; i < outputWrenchPorts.size(); i++ )
{
std::string port_name = outputWrenchPorts[i].port_name;
outputWrenchPorts[i].output_port = new yarp::os::BufferedPort<yarp::sig::Vector>;
ok = ok && outputWrenchPorts[i].output_port->open(port_name);
outputWrenchPorts[i].output_vector.resize(wholeBodyDynamics_nrOfChannelsOfYARPFTSensor);
}
if( !ok )
{
yError() << "wholeBodyDynamics impossible to open port for publishing external wrenches";
return false;
}
std::string outputWrenchPortInfoType = config.find("outputWrenchPortInfoType").asString();
if(outputWrenchPortInfoType == "contactWrenches")
{
m_outputWrenchPortInfoType = contactWrenches;
}
else
{
m_outputWrenchPortInfoType = netWrench;
}
enablePublishNetExternalWrenches = config.check("publishNetExternalWrenches", yarp::os::Value(false)).asBool();
if (enablePublishNetExternalWrenches)
{
if (!netExternalWrenchesPort.open(portPrefix +"/netExternalWrenches:o"))
{
yError() << "wholeBodyDynamics impossible to open port for publishing net external wrenches";
return false;
}
}
return ok;
}
bool WholeBodyDynamicsDevice::openMultipleAnalogSensorRemapper(os::Searchable &config)
{
// Pass to the remapper just the relevant parameters (sensorList)
yarp::os::Property prop;
prop.fromString(config.toString().c_str());
yarp::os::Property propMASRemapper;
yarp::os::Bottle & propMasNames=prop.findGroup("multipleAnalogSensorsNames");
propMASRemapper.put("device","multipleanalogsensorsremapper");
bool ok=false;
for (auto types=1u;types<propMasNames.size();types++){
yarp::os::Bottle * mas_type = propMasNames.get(types).asList();
if( mas_type->size() != 2 || mas_type->get(1).asList() == nullptr )
{
yError() << "wholeBodyDynamics: multipleAnalogSensorsNames group is malformed (" << mas_type->toString() << "). ";
return false;
}
else {
ok=true;
}
propMASRemapper.addGroup(mas_type->get(0).asString());
yarp::os::Bottle MASnames;
yarp::os::Bottle & MASnamesList= MASnames.addList();
for(auto i=0u; i < mas_type->get(1).asList()->size(); i++)
{
MASnamesList.addString(mas_type->get(1).asList()->get(i).asString());
}
propMASRemapper.put(mas_type->get(0).asString(),MASnames.get(0));
}
ok = multipleAnalogRemappedDevice.open(propMASRemapper);
if( !ok )
{
return ok;
}
// View relevant interfaces for the multipleAnalogRemappedDevice
ok = ok && multipleAnalogRemappedDevice.view(remappedMASInterfaces.temperatureSensors);
ok = ok && multipleAnalogRemappedDevice.view(remappedMASInterfaces.ftMultiSensors);
ok = ok && multipleAnalogRemappedDevice.view(remappedMASInterfaces.multwrap);
if( !ok )
{
yError() << "wholeBodyDynamics : openMultipleAnalogSensorRemapper : error while opening the necessary interfaces in multipleAnalogRemappedDevice";
return ok;
}
return true;
}
bool WholeBodyDynamicsDevice::openFilteredFTPorts(os::Searchable& config)
{
bool ok = true;
// create port names
std::string sensorName;
std::string portName;
outputFTPorts.resize(estimator.sensors().getNrOfSensors(iDynTree::SIX_AXIS_FORCE_TORQUE));
for(int ft=0; ft < estimator.sensors().getNrOfSensors(iDynTree::SIX_AXIS_FORCE_TORQUE); ft++ )
{
sensorName= estimator.sensors().getSensor(iDynTree::SIX_AXIS_FORCE_TORQUE,ft)->getName() ;
yInfo() << "wholeBodyDynamics: creating port name and opening port for " << sensorName;
portName=(portPrefix+"/filteredFT/"+sensorName);
outputFTPorts[ft]=std::make_unique<yarp::os::BufferedPort<yarp::sig::Vector> >();
ok = ok && outputFTPorts[ft]->open(portName);
}
if( !ok )
{
yError() << "wholeBodyDynamics impossible to open port for publishing filtered ft wrenches";
return false;
}
return ok;
}
void WholeBodyDynamicsDevice::resizeBuffers()
{
this->jointPos.resize(estimator.model());
this->jointVel.resize(estimator.model());
this->jointAcc.resize(estimator.model());
this->measuredContactLocations.resize(estimator.model());
this->ftMeasurement.resize(wholeBodyDynamics_nrOfChannelsOfYARPFTSensor);
this->imuMeasurement.resize(wholeBodyDynamics_nrOfChannelsOfAYARPIMUSensor);
this->rawSensorsMeasurements.resize(estimator.sensors());
this->filteredSensorMeasurements.resize(estimator.sensors());
this->estimatedJointTorques.resize(estimator.model());
this->estimatedJointTorquesYARP.resize(this->estimatedJointTorques.size(),0.0);
this->estimateExternalContactWrenches.resize(estimator.model());
this->jointPosKF.resize(estimator.model());
this->jointVelKF.resize(estimator.model());
this->jointAccKF.resize(estimator.model());
jointVelKF.zero();
jointAccKF.zero();
// Resize F/T stuff
size_t nrOfFTSensors = estimator.sensors().getNrOfSensors(iDynTree::SIX_AXIS_FORCE_TORQUE);
calibrationBuffers.calibratingFTsensor.resize(nrOfFTSensors,false);
iDynTree::Wrench zeroWrench;
zeroWrench.zero();
calibrationBuffers.offsetSumBuffer.resize(nrOfFTSensors,zeroWrench.asVector());
calibrationBuffers.measurementSumBuffer.resize(nrOfFTSensors,zeroWrench.asVector());
calibrationBuffers.estimationSumBuffer.resize(nrOfFTSensors,zeroWrench.asVector());
calibrationBuffers.assumedContactLocationsForCalibration.resize(estimator.model());
calibrationBuffers.predictedExternalContactWrenchesForCalibration.resize(estimator.model());
calibrationBuffers.predictedJointTorquesForCalibration.resize(estimator.model());
calibrationBuffers.predictedSensorMeasurementsForCalibration.resize(estimator.sensors());
ftProcessors.resize(nrOfFTSensors);
// Resize temperature sensor inside F/T sensors
this->tempMeasurements.resize(nrOfFTSensors,0.0);
this->ftTempMapping.resize(nrOfFTSensors,-1);
// Resize filters
filters.init(nrOfFTSensors,
settings.forceTorqueFilterCutoffInHz,
settings.imuFilterCutoffInHz,
estimator.model().getNrOfDOFs(),
settings.jointVelFilterCutoffInHz,
settings.jointAccFilterCutoffInHz,
getPeriod());
// Resize external wrenches publishing software
this->netExternalWrenchesExertedByTheEnviroment.resize(estimator.model());
bool ok = this->kinDynComp.loadRobotModel(estimator.model());
if( !ok )
{
yError() << "wholeBodyDynamics : error in opening KinDynComputation class";
}
for (iDynTree::LinkIndex link = 0;
link < static_cast<iDynTree::LinkIndex>(netExternalWrenchesExertedByTheEnviroment.getNrOfLinks());
++link)
{
netExternalWrenches.vectors[estimator.model().getLinkName(link)].resize(6);
std::fill(netExternalWrenches.vectors[estimator.model().getLinkName(link)].begin(),
netExternalWrenches.vectors[estimator.model().getLinkName(link)].end(),
0.0);
}
}
bool WholeBodyDynamicsDevice::loadSettingsFromConfig(os::Searchable& config)
{
// Fill setting with their default values
settings.kinematicSource = IMU;
yarp::os::Property prop;
prop.fromString(config.toString().c_str());
if (prop.check("devicePeriodInSeconds"))
{
if(!prop.find("devicePeriodInSeconds").isFloat64())
{
yError() << "wholeBodyDynamics : The devicePeriodInSeconds must be a double";
return false;
}
this->setPeriod(prop.find("devicePeriodInSeconds").asFloat64());
}
else
{
yWarning() << "wholeBodyDynamics : The devicePeriodInSeconds parameter is not found. The default one is used. Period:" << this->getPeriod() << "seconds.";
}
// Check the assumeFixed parameter
if( prop.check("assume_fixed") )
{
if( ! prop.find("assume_fixed").isString() )
{
yError() << "wholeBodyDynamics : assume_fixed is present, but it is not a string";
return false;
}
std::string fixedFrameName = prop.find("assume_fixed").asString();
iDynTree::FrameIndex fixedFrameIndex = estimator.model().getFrameIndex(fixedFrameName);
if( fixedFrameIndex == iDynTree::FRAME_INVALID_INDEX )
{
yError() << "wholeBodyDynamics : assume_fixed is present, but " << fixedFrameName << " is not a frame in the model";
return false;
}
// Add a hardcoded warning, ugly but I think that in the short term is useful
if( fixedFrameName != "root_link" &&
fixedFrameName != "l_sole" &&
fixedFrameName != "r_sole" )
{
yWarning() << "wholeBodyDynamics : assume_fixed is set to " << fixedFrameName << " that is not root_link, l_sole or r_sole, so pay attention to correctly set the gravity vector";
}
settings.kinematicSource = FIXED_FRAME;
settings.fixedFrameName = fixedFrameName;
}
if (settings.kinematicSource != FIXED_FRAME)
{
// Check for the imu frame
if( prop.check("imuFrameName") &&
prop.find("imuFrameName").isString() )
{
settings.imuFrameName = prop.find("imuFrameName").asString();
}
else
{
yError() << "wholeBodyDynamics : missing required string parameter imuFrameName";
return false;
}
}
// fixedFrameGravity is always required even if you
// use the IMU because the estimation could switch in use a fixed frame
// via RPC, so we should have a valid gravity to use
if( prop.check("fixedFrameGravity") &&
prop.find("fixedFrameGravity").isList() &&
prop.find("fixedFrameGravity").asList()->size() == 3 )
{
settings.fixedFrameGravity.x = prop.find("fixedFrameGravity").asList()->get(0).asFloat64();
settings.fixedFrameGravity.y = prop.find("fixedFrameGravity").asList()->get(1).asFloat64();
settings.fixedFrameGravity.z = prop.find("fixedFrameGravity").asList()->get(2).asFloat64();
}
else
{
yError() << "wholeBodyDynamics : missing required parameter fixedFrameGravity";
return false;
}
// Set the port prefix. The default value "/wholeBodyDynamics"
// is set in the device constructor
if( prop.check("portPrefix") &&
prop.find("portPrefix").isString())